From bf190f541dab38250c1d3e44921235fdb1227bf3 Mon Sep 17 00:00:00 2001 From: Sedith Date: Thu, 19 Mar 2020 19:50:44 +0100 Subject: [PATCH 1/3] update cppmpc to be usable with casadi_src file generated by MATMPC@299a4d8 add gitignore file ; udpate casadi_src.cpp and .h ; update casadi_wrapper accordingly (Ji->Hi, JN->HN) ; remove now unused qp_workspace class ; add qp_problem::info method computing OBJ value (cost function value among all shooting points) ; add OBJ double field in rti_step_workspace, also add ::info method ; considere weights as vector as in MATMPC model generation : WN is a vector, W is a matrix where the ith collumn is the weight for the ith shooting point ; generate control bounds for the nbu_idx (similar to state bounds) use exported casadi symbols to compute hessians instead of using intermediate jacobians ; modify InvertedPendulum.cpp according to all these changes, and add display of OBJective function in output file --- .gitignore | 4 + examples/InvertedPendulum.cpp | 70 +- include/casadi_wrapper.hpp | 4 +- include/qp_problem.hpp | 25 +- include/rti_step.hpp | 10 +- model/casadi_src.cpp | 2319 ++++++++++++--------------------- model/casadi_src.h | 40 +- src/casadi_wrapper.cpp | 108 +- src/full_condensing.cpp | 44 +- src/qp_problem.cpp | 155 ++- src/qpsolver.cpp | 18 +- src/rti_step.cpp | 20 +- 12 files changed, 1114 insertions(+), 1703 deletions(-) create mode 100644 .gitignore diff --git a/.gitignore b/.gitignore new file mode 100644 index 0000000..3c8cfe4 --- /dev/null +++ b/.gitignore @@ -0,0 +1,4 @@ +lib/ +**/*.o +data.txt +examples/*_d* diff --git a/examples/InvertedPendulum.cpp b/examples/InvertedPendulum.cpp index e33019c..bc42f20 100644 --- a/examples/InvertedPendulum.cpp +++ b/examples/InvertedPendulum.cpp @@ -1,53 +1,55 @@ #include #include -#include #include "mpc_common.hpp" #include "rti_step.hpp" #include "casadi_wrapper.hpp" using namespace std; -int main() -{ +int main() +{ // define problem size model_size size; size.nx = 4; size.nu = 1; size.ny = 5; - size.nyN= 4; + size.nyN = 4; size.np = 0; size.nbu = 1; size.nbx = 1; size.nbg = 0; size.nbgN = 0; size.N = 40; - size.nbx_idx = new int[size.nbx]; - size.nbx_idx[0]=0; - + size.nbx_idx = new int[size.nbx]; + size.nbx_idx[0] = 0; + size.nbu_idx = new int[size.nbu]; + size.nbu_idx[0] = 0; + // create a RTI controller rti_step_workspace rti_work(size); // initial condition and parameters rti_work.x0(1) = M_PI; - int i; - for(i=0;i +#include #include "mpc_common.hpp" using namespace Eigen; @@ -9,7 +9,7 @@ using namespace Eigen; class qp_in{ public: MatrixXd x; - MatrixXd u; + MatrixXd u; MatrixXd y; VectorXd yN; MatrixXd W; @@ -42,27 +42,18 @@ class qp_data{ MatrixXd Cgx; MatrixXd CgN; MatrixXd Cgu; - VectorXd lb_u; - VectorXd ub_u; VectorXd lb_x; VectorXd ub_x; + VectorXd lb_u; + VectorXd ub_u; VectorXd lb_g; VectorXd ub_g; - - qp_data& init(model_size& size); -}; - -class qp_workspace{ - public: - MatrixXd Jx; - MatrixXd Ju; - MatrixXd JxN; - qp_workspace& init(model_size& size); + qp_data& init(model_size& size); }; class qp_out{ - public: + public: MatrixXd dx; MatrixXd du; MatrixXd lam; @@ -77,12 +68,12 @@ class qp_problem{ public: qp_in in; qp_data data; - qp_workspace work; qp_out out; qp_problem& init(model_size& size); qp_problem& generateQP(model_size& size); qp_problem& expandSol(model_size& size, VectorXd& x0); + qp_problem& info(model_size& size, double& OBJ); }; -#endif \ No newline at end of file +#endif diff --git a/include/rti_step.hpp b/include/rti_step.hpp index 0fe3019..5046a3c 100644 --- a/include/rti_step.hpp +++ b/include/rti_step.hpp @@ -17,16 +17,16 @@ class rti_step_workspace{ VectorXd x0; // current state int sample; // current sample double CPT; // computation time - + double OBJ; rti_step_workspace& init(model_size& size); rti_step_workspace& step(); rti_step_workspace& free(); + rti_step_workspace& info(); private: - Timer timer; + Timer timer; full_condensing_workspace cond_work; - qpoases_workspace qpoases_work; - + qpoases_workspace qpoases_work; }; -#endif \ No newline at end of file +#endif diff --git a/model/casadi_src.cpp b/model/casadi_src.cpp index e518b49..39e259e 100644 --- a/model/casadi_src.cpp +++ b/model/casadi_src.cpp @@ -71,8 +71,6 @@ casadi_real if_else(casadi_real c, casadi_real x, casadi_real y) { return c!=0 ? #define casadi_s4 CASADI_PREFIX(s4) #define casadi_s5 CASADI_PREFIX(s5) #define casadi_s6 CASADI_PREFIX(s6) -#define casadi_s7 CASADI_PREFIX(s7) -#define casadi_s8 CASADI_PREFIX(s8) /* Printing routine */ #define PRINTF printf @@ -98,9 +96,7 @@ static const int casadi_s2[4] = {0, 1, 0, 0}; static const int casadi_s3[23] = {4, 4, 0, 4, 8, 12, 16, 0, 1, 2, 3, 0, 1, 2, 3, 0, 1, 2, 3, 0, 1, 2, 3}; static const int casadi_s4[9] = {5, 1, 0, 5, 0, 1, 2, 3, 4}; static const int casadi_s5[3] = {0, 0, 0}; -static const int casadi_s6[33] = {5, 5, 0, 5, 10, 15, 20, 25, 0, 1, 2, 3, 4, 0, 1, 2, 3, 4, 0, 1, 2, 3, 4, 0, 1, 2, 3, 4, 0, 1, 2, 3, 4}; -static const int casadi_s7[27] = {5, 4, 0, 5, 10, 15, 20, 0, 1, 2, 3, 4, 0, 1, 2, 3, 4, 0, 1, 2, 3, 4, 0, 1, 2, 3, 4}; -static const int casadi_s8[7] = {0, 4, 0, 0, 0, 0, 0}; +static const int casadi_s6[7] = {0, 4, 0, 0, 0, 0, 0}; /* f_fun:(states[4],controls,params[0])->(xdot[4]) */ static int casadi_f0(const casadi_real** arg, casadi_real** res, int* iw, casadi_real* w, void* mem) { @@ -108,13 +104,13 @@ static int casadi_f0(const casadi_real** arg, casadi_real** res, int* iw, casadi if (res[0]!=0) res[0][0]=a0; a0=arg[0] ? arg[0][3] : 0; if (res[0]!=0) res[0][1]=a0; - casadi_real a1=-8.0000000000000016e-002; + casadi_real a1=-8.0000000000000016e-02; casadi_real a2=arg[0] ? arg[0][1] : 0; casadi_real a3=sin(a2); a3=(a1*a3); casadi_real a4=sq(a0); a3=(a3*a4); - a4=9.8100000000000009e-001; + a4=9.8100000000000009e-01; casadi_real a5=cos(a2); a4=(a4*a5); a5=sin(a2); @@ -122,8 +118,8 @@ static int casadi_f0(const casadi_real** arg, casadi_real** res, int* iw, casadi a3=(a3+a4); a4=arg[1] ? arg[1][0] : 0; a3=(a3+a4); - a5=1.1000000000000001e+000; - casadi_real a6=1.0000000000000001e-001; + a5=1.1000000000000001e+00; + casadi_real a6=1.0000000000000001e-01; casadi_real a7=cos(a2); a7=sq(a7); a6=(a6*a7); @@ -139,11 +135,11 @@ static int casadi_f0(const casadi_real** arg, casadi_real** res, int* iw, casadi a0=cos(a2); a4=(a4*a0); a1=(a1+a4); - a4=1.0791000000000002e+001; + a4=1.0791000000000002e+01; a2=sin(a2); a4=(a4*a2); a1=(a1+a4); - a4=8.0000000000000004e-001; + a4=8.0000000000000004e-01; a4=(a4*a5); a1=(a1/a4); if (res[0]!=0) res[0][3]=a1; @@ -212,7 +208,7 @@ static int casadi_f1(const casadi_real** arg, casadi_real** res, int* iw, casadi if (res[0]!=0) res[0][1]=a0; casadi_real a1=arg[0] ? arg[0][3] : 0; casadi_real a2=sq(a1); - casadi_real a3=-8.0000000000000016e-002; + casadi_real a3=-8.0000000000000016e-02; casadi_real a4=arg[0] ? arg[0][1] : 0; casadi_real a5=cos(a4); casadi_real a6=arg[3] ? arg[3][1] : 0; @@ -225,7 +221,7 @@ static int casadi_f1(const casadi_real** arg, casadi_real** res, int* iw, casadi casadi_real a10=(a9*a0); a10=(a8*a10); a7=(a7+a10); - a10=9.8100000000000009e-001; + a10=9.8100000000000009e-01; casadi_real a11=cos(a4); a11=(a10*a11); casadi_real a12=cos(a4); @@ -238,8 +234,8 @@ static int casadi_f1(const casadi_real** arg, casadi_real** res, int* iw, casadi a16=(a14*a16); a13=(a13-a16); a7=(a7+a13); - a13=1.1000000000000001e+000; - a16=1.0000000000000001e-001; + a13=1.1000000000000001e+00; + a16=1.0000000000000001e-01; casadi_real a17=cos(a4); casadi_real a18=sq(a17); a18=(a16*a18); @@ -282,12 +278,12 @@ static int casadi_f1(const casadi_real** arg, casadi_real** res, int* iw, casadi casadi_real a31=(a0*a6); a31=(a19*a31); a26=(a26-a31); - a31=1.0791000000000002e+001; + a31=1.0791000000000002e+01; casadi_real a32=cos(a4); a6=(a32*a6); a6=(a31*a6); a26=(a26+a6); - a6=8.0000000000000004e-001; + a6=8.0000000000000004e-01; casadi_real a33=(a6*a13); a26=(a26/a33); casadi_real a34=(a29*a7); @@ -578,13 +574,13 @@ static int casadi_f2(const casadi_real** arg, casadi_real** res, int* iw, casadi a0=(a0-a1); if (res[0]!=0) res[0][1]=a0; a0=arg[3] ? arg[3][2] : 0; - casadi_real a2=-8.0000000000000016e-002; + casadi_real a2=-8.0000000000000016e-02; casadi_real a3=arg[0] ? arg[0][1] : 0; casadi_real a4=sin(a3); a4=(a2*a4); casadi_real a5=sq(a1); a4=(a4*a5); - a5=9.8100000000000009e-001; + a5=9.8100000000000009e-01; casadi_real a6=cos(a3); a5=(a5*a6); a6=sin(a3); @@ -592,8 +588,8 @@ static int casadi_f2(const casadi_real** arg, casadi_real** res, int* iw, casadi a4=(a4+a5); a5=arg[1] ? arg[1][0] : 0; a4=(a4+a5); - a6=1.1000000000000001e+000; - casadi_real a7=1.0000000000000001e-001; + a6=1.1000000000000001e+00; + casadi_real a7=1.0000000000000001e-01; casadi_real a8=cos(a3); a8=sq(a8); a7=(a7*a8); @@ -611,11 +607,11 @@ static int casadi_f2(const casadi_real** arg, casadi_real** res, int* iw, casadi a1=cos(a3); a5=(a5*a1); a2=(a2+a5); - a5=1.0791000000000002e+001; + a5=1.0791000000000002e+01; a3=sin(a3); a5=(a5*a3); a2=(a2+a5); - a5=8.0000000000000004e-001; + a5=8.0000000000000004e-01; a5=(a5*a6); a2=(a2/a5); a0=(a0-a2); @@ -690,12 +686,12 @@ static int casadi_f3(const casadi_real** arg, casadi_real** res, int* iw, casadi if (res[0]!=0) res[0][5]=a0; casadi_real a1=arg[0] ? arg[0][3] : 0; casadi_real a2=sq(a1); - casadi_real a3=-8.0000000000000016e-002; + casadi_real a3=-8.0000000000000016e-02; casadi_real a4=arg[0] ? arg[0][1] : 0; casadi_real a5=cos(a4); a5=(a3*a5); a5=(a2*a5); - casadi_real a6=9.8100000000000009e-001; + casadi_real a6=9.8100000000000009e-01; casadi_real a7=cos(a4); a7=(a6*a7); casadi_real a8=cos(a4); @@ -706,8 +702,8 @@ static int casadi_f3(const casadi_real** arg, casadi_real** res, int* iw, casadi a6=(a9*a6); a8=(a8-a6); a5=(a5+a8); - a8=1.1000000000000001e+000; - a6=1.0000000000000001e-001; + a8=1.1000000000000001e+00; + a6=1.0000000000000001e-01; a10=cos(a4); casadi_real a11=sq(a10); a11=(a6*a11); @@ -744,11 +740,11 @@ static int casadi_f3(const casadi_real** arg, casadi_real** res, int* iw, casadi a3=sin(a4); a3=(a7*a3); a10=(a10-a3); - a3=1.0791000000000002e+001; + a3=1.0791000000000002e+01; a12=cos(a4); a12=(a3*a12); a10=(a10+a12); - a12=8.0000000000000004e-001; + a12=8.0000000000000004e-01; casadi_real a13=(a12*a8); a10=(a10/a13); a2=(a2*a9); @@ -847,8 +843,8 @@ static int casadi_f4(const casadi_real** arg, casadi_real** res, int* iw, casadi casadi_real a0=0.; if (res[0]!=0) res[0][0]=a0; if (res[0]!=0) res[0][1]=a0; - a0=1.1000000000000001e+000; - casadi_real a1=1.0000000000000001e-001; + a0=1.1000000000000001e+00; + casadi_real a1=1.0000000000000001e-01; casadi_real a2=arg[0] ? arg[0][1] : 0; casadi_real a3=cos(a2); a3=sq(a3); @@ -858,7 +854,7 @@ static int casadi_f4(const casadi_real** arg, casadi_real** res, int* iw, casadi a1=(-a1); if (res[0]!=0) res[0][2]=a1; a2=cos(a2); - a1=8.0000000000000004e-001; + a1=8.0000000000000004e-01; a1=(a1*a0); a2=(a2/a1); a2=(-a2); @@ -1004,18 +1000,18 @@ CASADI_SYMBOL_EXPORT int impl_jac_xdot_fun_work(int *sz_arg, int* sz_res, int *s /* F:(i0[4],i1,i2[0])->(o0[4]) */ static int casadi_f6(const casadi_real** arg, casadi_real** res, int* iw, casadi_real* w, void* mem) { casadi_real a0=arg[0] ? arg[0][0] : 0; - casadi_real a1=8.3333333333333332e-003; + casadi_real a1=8.3333333333333332e-03; casadi_real a2=arg[0] ? arg[0][2] : 0; casadi_real a3=2.; - casadi_real a4=2.5000000000000001e-002; - casadi_real a5=-8.0000000000000016e-002; + casadi_real a4=2.5000000000000001e-02; + casadi_real a5=-8.0000000000000016e-02; casadi_real a6=arg[0] ? arg[0][1] : 0; casadi_real a7=sin(a6); a7=(a5*a7); casadi_real a8=arg[0] ? arg[0][3] : 0; casadi_real a9=sq(a8); a7=(a7*a9); - a9=9.8100000000000009e-001; + a9=9.8100000000000009e-01; casadi_real a10=cos(a6); a10=(a9*a10); casadi_real a11=sin(a6); @@ -1023,8 +1019,8 @@ static int casadi_f6(const casadi_real** arg, casadi_real** res, int* iw, casadi a7=(a7+a10); a10=arg[1] ? arg[1][0] : 0; a7=(a7+a10); - a11=1.1000000000000001e+000; - casadi_real a12=1.0000000000000001e-001; + a11=1.1000000000000001e+00; + casadi_real a12=1.0000000000000001e-01; casadi_real a13=cos(a6); a13=sq(a13); a13=(a12*a13); @@ -1047,11 +1043,11 @@ static int casadi_f6(const casadi_real** arg, casadi_real** res, int* iw, casadi a18=cos(a6); a18=(a10*a18); a17=(a17+a18); - a18=1.0791000000000002e+001; + a18=1.0791000000000002e+01; casadi_real a19=sin(a6); a19=(a18*a19); a17=(a17+a19); - a19=8.0000000000000004e-001; + a19=8.0000000000000004e-01; a13=(a19*a13); a17=(a17/a13); a13=(a4*a17); @@ -1073,7 +1069,7 @@ static int casadi_f6(const casadi_real** arg, casadi_real** res, int* iw, casadi a21=(a2+a21); a21=(a3*a21); a14=(a14+a21); - a21=5.0000000000000003e-002; + a21=5.0000000000000003e-02; casadi_real a22=(a4*a13); a22=(a6+a22); casadi_real a23=sin(a22); @@ -1249,17 +1245,17 @@ static int casadi_f7(const casadi_real** arg, casadi_real** res, int* iw, casadi if (res[0]!=0) res[0][1]=a1; if (res[0]!=0) res[0][2]=a1; if (res[0]!=0) res[0][3]=a1; - casadi_real a2=8.3333333333333332e-003; + casadi_real a2=8.3333333333333332e-03; casadi_real a3=2.; - casadi_real a4=2.5000000000000001e-002; + casadi_real a4=2.5000000000000001e-02; casadi_real a5=arg[0] ? arg[0][3] : 0; casadi_real a6=sq(a5); - casadi_real a7=-8.0000000000000016e-002; + casadi_real a7=-8.0000000000000016e-02; casadi_real a8=arg[0] ? arg[0][1] : 0; casadi_real a9=cos(a8); a9=(a7*a9); a9=(a6*a9); - casadi_real a10=9.8100000000000009e-001; + casadi_real a10=9.8100000000000009e-01; casadi_real a11=cos(a8); a11=(a10*a11); casadi_real a12=cos(a8); @@ -1270,8 +1266,8 @@ static int casadi_f7(const casadi_real** arg, casadi_real** res, int* iw, casadi a14=(a13*a14); a12=(a12-a14); a9=(a9+a12); - a12=1.1000000000000001e+000; - a14=1.0000000000000001e-001; + a12=1.1000000000000001e+00; + a14=1.0000000000000001e-01; casadi_real a15=cos(a8); casadi_real a16=sq(a15); a16=(a14*a16); @@ -1303,11 +1299,11 @@ static int casadi_f7(const casadi_real** arg, casadi_real** res, int* iw, casadi casadi_real a22=cos(a8); casadi_real a23=(a11*a22); a21=(a21+a23); - a23=1.0791000000000002e+001; + a23=1.0791000000000002e+01; casadi_real a24=sin(a8); a24=(a23*a24); a21=(a21+a24); - a24=8.0000000000000004e-001; + a24=8.0000000000000004e-01; casadi_real a25=(a24*a16); a21=(a21/a25); casadi_real a26=(a4*a21); @@ -1373,7 +1369,7 @@ static int casadi_f7(const casadi_real** arg, casadi_real** res, int* iw, casadi a39=(a4*a30); a39=(a3*a39); a6=(a6+a39); - a39=5.0000000000000003e-002; + a39=5.0000000000000003e-02; casadi_real a40=cos(a28); a40=(a7*a40); casadi_real a41=sin(a28); @@ -2175,114 +2171,54 @@ CASADI_SYMBOL_EXPORT int path_con_N_fun_work(int *sz_arg, int* sz_res, int *sz_i return 0; } -/* obji_fun:(i0[4],i1,i2[0],i3[5],i4[5x5])->(o0) */ +/* obji_fun:(i0[4],i1,i2[0],i3[5],i4[5])->(o0) */ static int casadi_f11(const casadi_real** arg, casadi_real** res, int* iw, casadi_real* w, void* mem) { - casadi_real a0=5.0000000000000000e-001; + casadi_real a0=5.0000000000000000e-01; casadi_real a1=arg[0] ? arg[0][0] : 0; casadi_real a2=arg[3] ? arg[3][0] : 0; casadi_real a3=(a1-a2); a3=(a0*a3); casadi_real a4=arg[4] ? arg[4][0] : 0; - a4=(a3*a4); - casadi_real a5=arg[0] ? arg[0][1] : 0; - casadi_real a6=arg[3] ? arg[3][1] : 0; - casadi_real a7=(a5-a6); - a7=(a0*a7); - casadi_real a8=arg[4] ? arg[4][1] : 0; - a8=(a7*a8); - a4=(a4+a8); - a8=arg[0] ? arg[0][2] : 0; - casadi_real a9=arg[3] ? arg[3][2] : 0; - casadi_real a10=(a8-a9); - a10=(a0*a10); - casadi_real a11=arg[4] ? arg[4][2] : 0; - a11=(a10*a11); - a4=(a4+a11); - a11=arg[0] ? arg[0][3] : 0; - casadi_real a12=arg[3] ? arg[3][3] : 0; - casadi_real a13=(a11-a12); - a13=(a0*a13); - casadi_real a14=arg[4] ? arg[4][3] : 0; - a14=(a13*a14); - a4=(a4+a14); - a14=arg[1] ? arg[1][0] : 0; - casadi_real a15=arg[3] ? arg[3][4] : 0; - casadi_real a16=(a14-a15); - a0=(a0*a16); - a16=arg[4] ? arg[4][4] : 0; - a16=(a0*a16); - a4=(a4+a16); + a3=(a3*a4); + a1=(a1-a2); + a3=(a3*a1); + a1=arg[0] ? arg[0][1] : 0; + a2=arg[3] ? arg[3][1] : 0; + a4=(a1-a2); + a4=(a0*a4); + casadi_real a5=arg[4] ? arg[4][1] : 0; + a4=(a4*a5); a1=(a1-a2); a4=(a4*a1); - a1=arg[4] ? arg[4][5] : 0; - a1=(a3*a1); - a2=arg[4] ? arg[4][6] : 0; - a2=(a7*a2); - a1=(a1+a2); - a2=arg[4] ? arg[4][7] : 0; - a2=(a10*a2); - a1=(a1+a2); - a2=arg[4] ? arg[4][8] : 0; - a2=(a13*a2); - a1=(a1+a2); - a2=arg[4] ? arg[4][9] : 0; + a3=(a3+a4); + a4=arg[0] ? arg[0][2] : 0; + a1=arg[3] ? arg[3][2] : 0; + a2=(a4-a1); a2=(a0*a2); - a1=(a1+a2); - a5=(a5-a6); + a5=arg[4] ? arg[4][2] : 0; + a2=(a2*a5); + a4=(a4-a1); + a2=(a2*a4); + a3=(a3+a2); + a2=arg[0] ? arg[0][3] : 0; + a4=arg[3] ? arg[3][3] : 0; + a1=(a2-a4); + a1=(a0*a1); + a5=arg[4] ? arg[4][3] : 0; a1=(a1*a5); - a4=(a4+a1); - a1=arg[4] ? arg[4][10] : 0; - a1=(a3*a1); - a5=arg[4] ? arg[4][11] : 0; - a5=(a7*a5); - a1=(a1+a5); - a5=arg[4] ? arg[4][12] : 0; - a5=(a10*a5); - a1=(a1+a5); - a5=arg[4] ? arg[4][13] : 0; - a5=(a13*a5); - a1=(a1+a5); - a5=arg[4] ? arg[4][14] : 0; - a5=(a0*a5); - a1=(a1+a5); - a8=(a8-a9); - a1=(a1*a8); - a4=(a4+a1); - a1=arg[4] ? arg[4][15] : 0; - a1=(a3*a1); - a8=arg[4] ? arg[4][16] : 0; - a8=(a7*a8); - a1=(a1+a8); - a8=arg[4] ? arg[4][17] : 0; - a8=(a10*a8); - a1=(a1+a8); - a8=arg[4] ? arg[4][18] : 0; - a8=(a13*a8); - a1=(a1+a8); - a8=arg[4] ? arg[4][19] : 0; - a8=(a0*a8); - a1=(a1+a8); - a11=(a11-a12); - a1=(a1*a11); - a4=(a4+a1); - a1=arg[4] ? arg[4][20] : 0; - a3=(a3*a1); - a1=arg[4] ? arg[4][21] : 0; - a7=(a7*a1); - a3=(a3+a7); - a7=arg[4] ? arg[4][22] : 0; - a10=(a10*a7); - a3=(a3+a10); - a10=arg[4] ? arg[4][23] : 0; - a13=(a13*a10); - a3=(a3+a13); - a13=arg[4] ? arg[4][24] : 0; - a0=(a0*a13); + a2=(a2-a4); + a1=(a1*a2); + a3=(a3+a1); + a1=arg[1] ? arg[1][0] : 0; + a2=arg[3] ? arg[3][4] : 0; + a4=(a1-a2); + a0=(a0*a4); + a4=arg[4] ? arg[4][4] : 0; + a0=(a0*a4); + a1=(a1-a2); + a0=(a0*a1); a3=(a3+a0); - a14=(a14-a15); - a3=(a3*a14); - a4=(a4+a3); - if (res[0]!=0) res[0][0]=a4; + if (res[0]!=0) res[0][0]=a3; return 0; } @@ -2324,7 +2260,7 @@ CASADI_SYMBOL_EXPORT const int* obji_fun_sparsity_in(int i) { case 1: return casadi_s1; case 2: return casadi_s2; case 3: return casadi_s4; - case 4: return casadi_s6; + case 4: return casadi_s4; default: return 0; } } @@ -2340,85 +2276,49 @@ CASADI_SYMBOL_EXPORT int obji_fun_work(int *sz_arg, int* sz_res, int *sz_iw, int if (sz_arg) *sz_arg = 5; if (sz_res) *sz_res = 1; if (sz_iw) *sz_iw = 0; - if (sz_w) *sz_w = 17; + if (sz_w) *sz_w = 6; return 0; } -/* objN_fun:(i0[4],i1[0],i2[4],i3[4x4])->(o0) */ +/* objN_fun:(i0[4],i1[0],i2[4],i3[4])->(o0) */ static int casadi_f12(const casadi_real** arg, casadi_real** res, int* iw, casadi_real* w, void* mem) { - casadi_real a0=5.0000000000000000e-001; + casadi_real a0=5.0000000000000000e-01; casadi_real a1=arg[0] ? arg[0][0] : 0; casadi_real a2=arg[2] ? arg[2][0] : 0; casadi_real a3=(a1-a2); a3=(a0*a3); casadi_real a4=arg[3] ? arg[3][0] : 0; - a4=(a3*a4); - casadi_real a5=arg[0] ? arg[0][1] : 0; - casadi_real a6=arg[2] ? arg[2][1] : 0; - casadi_real a7=(a5-a6); - a7=(a0*a7); - casadi_real a8=arg[3] ? arg[3][1] : 0; - a8=(a7*a8); - a4=(a4+a8); - a8=arg[0] ? arg[0][2] : 0; - casadi_real a9=arg[2] ? arg[2][2] : 0; - casadi_real a10=(a8-a9); - a10=(a0*a10); - casadi_real a11=arg[3] ? arg[3][2] : 0; - a11=(a10*a11); - a4=(a4+a11); - a11=arg[0] ? arg[0][3] : 0; - casadi_real a12=arg[2] ? arg[2][3] : 0; - casadi_real a13=(a11-a12); - a0=(a0*a13); - a13=arg[3] ? arg[3][3] : 0; - a13=(a0*a13); - a4=(a4+a13); + a3=(a3*a4); + a1=(a1-a2); + a3=(a3*a1); + a1=arg[0] ? arg[0][1] : 0; + a2=arg[2] ? arg[2][1] : 0; + a4=(a1-a2); + a4=(a0*a4); + casadi_real a5=arg[3] ? arg[3][1] : 0; + a4=(a4*a5); a1=(a1-a2); a4=(a4*a1); - a1=arg[3] ? arg[3][4] : 0; - a1=(a3*a1); - a2=arg[3] ? arg[3][5] : 0; - a2=(a7*a2); - a1=(a1+a2); - a2=arg[3] ? arg[3][6] : 0; - a2=(a10*a2); - a1=(a1+a2); - a2=arg[3] ? arg[3][7] : 0; + a3=(a3+a4); + a4=arg[0] ? arg[0][2] : 0; + a1=arg[2] ? arg[2][2] : 0; + a2=(a4-a1); a2=(a0*a2); - a1=(a1+a2); - a5=(a5-a6); - a1=(a1*a5); - a4=(a4+a1); - a1=arg[3] ? arg[3][8] : 0; - a1=(a3*a1); - a5=arg[3] ? arg[3][9] : 0; - a5=(a7*a5); - a1=(a1+a5); - a5=arg[3] ? arg[3][10] : 0; - a5=(a10*a5); - a1=(a1+a5); - a5=arg[3] ? arg[3][11] : 0; - a5=(a0*a5); - a1=(a1+a5); - a8=(a8-a9); - a1=(a1*a8); - a4=(a4+a1); - a1=arg[3] ? arg[3][12] : 0; - a3=(a3*a1); - a1=arg[3] ? arg[3][13] : 0; - a7=(a7*a1); - a3=(a3+a7); - a7=arg[3] ? arg[3][14] : 0; - a10=(a10*a7); - a3=(a3+a10); - a10=arg[3] ? arg[3][15] : 0; - a0=(a0*a10); + a5=arg[3] ? arg[3][2] : 0; + a2=(a2*a5); + a4=(a4-a1); + a2=(a2*a4); + a3=(a3+a2); + a2=arg[0] ? arg[0][3] : 0; + a4=arg[2] ? arg[2][3] : 0; + a1=(a2-a4); + a0=(a0*a1); + a1=arg[3] ? arg[3][3] : 0; + a0=(a0*a1); + a2=(a2-a4); + a0=(a0*a2); a3=(a3+a0); - a11=(a11-a12); - a3=(a3*a11); - a4=(a4+a3); - if (res[0]!=0) res[0][0]=a4; + if (res[0]!=0) res[0][0]=a3; return 0; } @@ -2458,7 +2358,7 @@ CASADI_SYMBOL_EXPORT const int* objN_fun_sparsity_in(int i) { case 0: return casadi_s0; case 1: return casadi_s2; case 2: return casadi_s0; - case 3: return casadi_s3; + case 3: return casadi_s0; default: return 0; } } @@ -2474,172 +2374,68 @@ CASADI_SYMBOL_EXPORT int objN_fun_work(int *sz_arg, int* sz_res, int *sz_iw, int if (sz_arg) *sz_arg = 4; if (sz_res) *sz_res = 1; if (sz_iw) *sz_iw = 0; - if (sz_w) *sz_w = 14; + if (sz_w) *sz_w = 6; return 0; } -/* gi_fun:(i0[4],i1,i2[0],i3[5],i4[5x5])->(o0[4],o1) */ +/* gi_fun:(i0[4],i1,i2[0],i3[5],i4[5])->(o0[4],o1) */ static int casadi_f13(const casadi_real** arg, casadi_real** res, int* iw, casadi_real* w, void* mem) { - casadi_real a0=5.0000000000000000e-001; + casadi_real a0=5.0000000000000000e-01; casadi_real a1=arg[0] ? arg[0][0] : 0; casadi_real a2=arg[3] ? arg[3][0] : 0; casadi_real a3=(a1-a2); a3=(a0*a3); casadi_real a4=arg[4] ? arg[4][0] : 0; - casadi_real a5=(a3*a4); - casadi_real a6=arg[0] ? arg[0][1] : 0; - casadi_real a7=arg[3] ? arg[3][1] : 0; - casadi_real a8=(a6-a7); - a8=(a0*a8); - casadi_real a9=arg[4] ? arg[4][1] : 0; - casadi_real a10=(a8*a9); - a5=(a5+a10); - a10=arg[0] ? arg[0][2] : 0; - casadi_real a11=arg[3] ? arg[3][2] : 0; - casadi_real a12=(a10-a11); - a12=(a0*a12); - casadi_real a13=arg[4] ? arg[4][2] : 0; - casadi_real a14=(a12*a13); - a5=(a5+a14); - a14=arg[0] ? arg[0][3] : 0; - casadi_real a15=arg[3] ? arg[3][3] : 0; - casadi_real a16=(a14-a15); - a16=(a0*a16); - casadi_real a17=arg[4] ? arg[4][3] : 0; - casadi_real a18=(a16*a17); - a5=(a5+a18); - a18=arg[1] ? arg[1][0] : 0; - casadi_real a19=arg[3] ? arg[3][4] : 0; - casadi_real a20=(a18-a19); - a20=(a0*a20); - casadi_real a21=arg[4] ? arg[4][4] : 0; - casadi_real a22=(a20*a21); - a5=(a5+a22); - a22=arg[4] ? arg[4][20] : 0; - a18=(a18-a19); - a19=(a22*a18); - casadi_real a23=arg[4] ? arg[4][15] : 0; - a14=(a14-a15); - a15=(a23*a14); - a19=(a19+a15); - a15=arg[4] ? arg[4][10] : 0; - a10=(a10-a11); - a11=(a15*a10); - a19=(a19+a11); - a11=arg[4] ? arg[4][5] : 0; - a6=(a6-a7); - a7=(a11*a6); - a19=(a19+a7); + a3=(a3*a4); a1=(a1-a2); a4=(a4*a1); - a19=(a19+a4); - a19=(a0*a19); - a5=(a5+a19); - if (res[0]!=0) res[0][0]=a5; - a11=(a3*a11); - a5=arg[4] ? arg[4][6] : 0; - a19=(a8*a5); - a11=(a11+a19); - a19=arg[4] ? arg[4][7] : 0; - a4=(a12*a19); - a11=(a11+a4); - a4=arg[4] ? arg[4][8] : 0; - a2=(a16*a4); - a11=(a11+a2); - a2=arg[4] ? arg[4][9] : 0; - a7=(a20*a2); - a11=(a11+a7); - a7=arg[4] ? arg[4][21] : 0; - casadi_real a24=(a7*a18); - casadi_real a25=arg[4] ? arg[4][16] : 0; - casadi_real a26=(a25*a14); - a24=(a24+a26); - a26=arg[4] ? arg[4][11] : 0; - casadi_real a27=(a26*a10); - a24=(a24+a27); - a5=(a5*a6); - a24=(a24+a5); - a9=(a9*a1); - a24=(a24+a9); - a24=(a0*a24); - a11=(a11+a24); - if (res[0]!=0) res[0][1]=a11; - a15=(a3*a15); - a26=(a8*a26); - a15=(a15+a26); - a26=arg[4] ? arg[4][12] : 0; - a11=(a12*a26); - a15=(a15+a11); - a11=arg[4] ? arg[4][13] : 0; - a24=(a16*a11); - a15=(a15+a24); - a24=arg[4] ? arg[4][14] : 0; - a9=(a20*a24); - a15=(a15+a9); - a9=arg[4] ? arg[4][22] : 0; - a5=(a9*a18); - a27=arg[4] ? arg[4][17] : 0; - casadi_real a28=(a27*a14); - a5=(a5+a28); - a26=(a26*a10); - a5=(a5+a26); - a19=(a19*a6); - a5=(a5+a19); - a13=(a13*a1); - a5=(a5+a13); - a5=(a0*a5); - a15=(a15+a5); - if (res[0]!=0) res[0][2]=a15; - a23=(a3*a23); - a25=(a8*a25); - a23=(a23+a25); - a27=(a12*a27); - a23=(a23+a27); - a27=arg[4] ? arg[4][18] : 0; - a25=(a16*a27); - a23=(a23+a25); - a25=arg[4] ? arg[4][19] : 0; - a15=(a20*a25); - a23=(a23+a15); - a15=arg[4] ? arg[4][23] : 0; - a5=(a15*a18); - a27=(a27*a14); - a5=(a5+a27); - a11=(a11*a10); - a5=(a5+a11); - a4=(a4*a6); - a5=(a5+a4); - a17=(a17*a1); - a5=(a5+a17); - a5=(a0*a5); - a23=(a23+a5); - if (res[0]!=0) res[0][3]=a23; - a21=(a0*a21); - a1=(a1*a21); + a4=(a0*a4); + a3=(a3+a4); + if (res[0]!=0) res[0][0]=a3; + a3=arg[0] ? arg[0][1] : 0; + a4=arg[3] ? arg[3][1] : 0; + a1=(a3-a4); + a1=(a0*a1); + a2=arg[4] ? arg[4][1] : 0; + a1=(a1*a2); + a3=(a3-a4); + a2=(a2*a3); a2=(a0*a2); - a6=(a6*a2); - a1=(a1+a6); - a24=(a0*a24); - a10=(a10*a24); - a1=(a1+a10); - a25=(a0*a25); - a14=(a14*a25); - a1=(a1+a14); - a14=arg[4] ? arg[4][24] : 0; - a0=(a0*a14); - a18=(a18*a0); - a3=(a3*a22); - a8=(a8*a7); - a3=(a3+a8); - a12=(a12*a9); - a3=(a3+a12); - a16=(a16*a15); - a3=(a3+a16); - a20=(a20*a14); - a3=(a3+a20); - a18=(a18+a3); - a1=(a1+a18); - if (res[1]!=0) res[1][0]=a1; + a1=(a1+a2); + if (res[0]!=0) res[0][1]=a1; + a1=arg[0] ? arg[0][2] : 0; + a2=arg[3] ? arg[3][2] : 0; + a3=(a1-a2); + a3=(a0*a3); + a4=arg[4] ? arg[4][2] : 0; + a3=(a3*a4); + a1=(a1-a2); + a4=(a4*a1); + a4=(a0*a4); + a3=(a3+a4); + if (res[0]!=0) res[0][2]=a3; + a3=arg[0] ? arg[0][3] : 0; + a4=arg[3] ? arg[3][3] : 0; + a1=(a3-a4); + a1=(a0*a1); + a2=arg[4] ? arg[4][3] : 0; + a1=(a1*a2); + a3=(a3-a4); + a2=(a2*a3); + a2=(a0*a2); + a1=(a1+a2); + if (res[0]!=0) res[0][3]=a1; + a1=arg[1] ? arg[1][0] : 0; + a2=arg[3] ? arg[3][4] : 0; + a3=(a1-a2); + a4=arg[4] ? arg[4][4] : 0; + casadi_real a5=(a0*a4); + a3=(a3*a5); + a1=(a1-a2); + a0=(a0*a1); + a0=(a0*a4); + a3=(a3+a0); + if (res[1]!=0) res[1][0]=a3; return 0; } @@ -2682,7 +2478,7 @@ CASADI_SYMBOL_EXPORT const int* gi_fun_sparsity_in(int i) { case 1: return casadi_s1; case 2: return casadi_s2; case 3: return casadi_s4; - case 4: return casadi_s6; + case 4: return casadi_s4; default: return 0; } } @@ -2699,117 +2495,57 @@ CASADI_SYMBOL_EXPORT int gi_fun_work(int *sz_arg, int* sz_res, int *sz_iw, int * if (sz_arg) *sz_arg = 5; if (sz_res) *sz_res = 2; if (sz_iw) *sz_iw = 0; - if (sz_w) *sz_w = 29; + if (sz_w) *sz_w = 6; return 0; } -/* gN_fun:(i0[4],i1[0],i2[4],i3[4x4])->(o0[4]) */ +/* gN_fun:(i0[4],i1[0],i2[4],i3[4])->(o0[4]) */ static int casadi_f14(const casadi_real** arg, casadi_real** res, int* iw, casadi_real* w, void* mem) { - casadi_real a0=5.0000000000000000e-001; + casadi_real a0=5.0000000000000000e-01; casadi_real a1=arg[0] ? arg[0][0] : 0; casadi_real a2=arg[2] ? arg[2][0] : 0; casadi_real a3=(a1-a2); a3=(a0*a3); casadi_real a4=arg[3] ? arg[3][0] : 0; - casadi_real a5=(a3*a4); - casadi_real a6=arg[0] ? arg[0][1] : 0; - casadi_real a7=arg[2] ? arg[2][1] : 0; - casadi_real a8=(a6-a7); - a8=(a0*a8); - casadi_real a9=arg[3] ? arg[3][1] : 0; - casadi_real a10=(a8*a9); - a5=(a5+a10); - a10=arg[0] ? arg[0][2] : 0; - casadi_real a11=arg[2] ? arg[2][2] : 0; - casadi_real a12=(a10-a11); - a12=(a0*a12); - casadi_real a13=arg[3] ? arg[3][2] : 0; - casadi_real a14=(a12*a13); - a5=(a5+a14); - a14=arg[0] ? arg[0][3] : 0; - casadi_real a15=arg[2] ? arg[2][3] : 0; - casadi_real a16=(a14-a15); - a16=(a0*a16); - casadi_real a17=arg[3] ? arg[3][3] : 0; - casadi_real a18=(a16*a17); - a5=(a5+a18); - a18=arg[3] ? arg[3][12] : 0; - a14=(a14-a15); - a15=(a18*a14); - casadi_real a19=arg[3] ? arg[3][8] : 0; - a10=(a10-a11); - a11=(a19*a10); - a15=(a15+a11); - a11=arg[3] ? arg[3][4] : 0; - a6=(a6-a7); - a7=(a11*a6); - a15=(a15+a7); + a3=(a3*a4); a1=(a1-a2); a4=(a4*a1); - a15=(a15+a4); - a15=(a0*a15); - a5=(a5+a15); - if (res[0]!=0) res[0][0]=a5; - a11=(a3*a11); - a5=arg[3] ? arg[3][5] : 0; - a15=(a8*a5); - a11=(a11+a15); - a15=arg[3] ? arg[3][6] : 0; - a4=(a12*a15); - a11=(a11+a4); - a4=arg[3] ? arg[3][7] : 0; - a2=(a16*a4); - a11=(a11+a2); - a2=arg[3] ? arg[3][13] : 0; - a7=(a2*a14); - casadi_real a20=arg[3] ? arg[3][9] : 0; - casadi_real a21=(a20*a10); - a7=(a7+a21); - a5=(a5*a6); - a7=(a7+a5); - a9=(a9*a1); - a7=(a7+a9); - a7=(a0*a7); - a11=(a11+a7); - if (res[0]!=0) res[0][1]=a11; - a19=(a3*a19); - a20=(a8*a20); - a19=(a19+a20); - a20=arg[3] ? arg[3][10] : 0; - a11=(a12*a20); - a19=(a19+a11); - a11=arg[3] ? arg[3][11] : 0; - a7=(a16*a11); - a19=(a19+a7); - a7=arg[3] ? arg[3][14] : 0; - a9=(a7*a14); - a20=(a20*a10); - a9=(a9+a20); - a15=(a15*a6); - a9=(a9+a15); - a13=(a13*a1); - a9=(a9+a13); - a9=(a0*a9); - a19=(a19+a9); - if (res[0]!=0) res[0][2]=a19; - a3=(a3*a18); - a8=(a8*a2); - a3=(a3+a8); - a12=(a12*a7); - a3=(a3+a12); - a12=arg[3] ? arg[3][15] : 0; - a16=(a16*a12); - a3=(a3+a16); - a12=(a12*a14); - a11=(a11*a10); - a12=(a12+a11); - a4=(a4*a6); - a12=(a12+a4); - a17=(a17*a1); - a12=(a12+a17); - a0=(a0*a12); - a3=(a3+a0); - if (res[0]!=0) res[0][3]=a3; + a4=(a0*a4); + a3=(a3+a4); + if (res[0]!=0) res[0][0]=a3; + a3=arg[0] ? arg[0][1] : 0; + a4=arg[2] ? arg[2][1] : 0; + a1=(a3-a4); + a1=(a0*a1); + a2=arg[3] ? arg[3][1] : 0; + a1=(a1*a2); + a3=(a3-a4); + a2=(a2*a3); + a2=(a0*a2); + a1=(a1+a2); + if (res[0]!=0) res[0][1]=a1; + a1=arg[0] ? arg[0][2] : 0; + a2=arg[2] ? arg[2][2] : 0; + a3=(a1-a2); + a3=(a0*a3); + a4=arg[3] ? arg[3][2] : 0; + a3=(a3*a4); + a1=(a1-a2); + a4=(a4*a1); + a4=(a0*a4); + a3=(a3+a4); + if (res[0]!=0) res[0][2]=a3; + a3=arg[0] ? arg[0][3] : 0; + a4=arg[2] ? arg[2][3] : 0; + a1=(a3-a4); + a1=(a0*a1); + a2=arg[3] ? arg[3][3] : 0; + a1=(a1*a2); + a3=(a3-a4); + a2=(a2*a3); + a0=(a0*a2); + a1=(a1+a0); + if (res[0]!=0) res[0][3]=a1; return 0; } @@ -2849,7 +2585,7 @@ CASADI_SYMBOL_EXPORT const int* gN_fun_sparsity_in(int i) { case 0: return casadi_s0; case 1: return casadi_s2; case 2: return casadi_s0; - case 3: return casadi_s3; + case 3: return casadi_s0; default: return 0; } } @@ -2865,105 +2601,57 @@ CASADI_SYMBOL_EXPORT int gN_fun_work(int *sz_arg, int* sz_res, int *sz_iw, int * if (sz_arg) *sz_arg = 4; if (sz_res) *sz_res = 1; if (sz_iw) *sz_iw = 0; - if (sz_w) *sz_w = 22; + if (sz_w) *sz_w = 5; return 0; } -/* Ji_fun:(i0[4],i1,i2[0],i3[5],i4[5x5])->(o0[5x4],o1[5]) */ +/* Hi_fun:(i0[4],i1,i2[0],i3[5],i4[5])->(o0[4x4],o1,o2[4]) */ static int casadi_f15(const casadi_real** arg, casadi_real** res, int* iw, casadi_real* w, void* mem) { casadi_real a0=arg[4] ? arg[4][0] : 0; - a0=sqrt(a0); if (res[0]!=0) res[0][0]=a0; - a0=arg[4] ? arg[4][1] : 0; - a0=sqrt(a0); + a0=0.; if (res[0]!=0) res[0][1]=a0; - a0=arg[4] ? arg[4][2] : 0; - a0=sqrt(a0); if (res[0]!=0) res[0][2]=a0; - a0=arg[4] ? arg[4][3] : 0; - a0=sqrt(a0); if (res[0]!=0) res[0][3]=a0; - a0=arg[4] ? arg[4][4] : 0; - a0=sqrt(a0); if (res[0]!=0) res[0][4]=a0; - a0=arg[4] ? arg[4][5] : 0; - a0=sqrt(a0); - if (res[0]!=0) res[0][5]=a0; - a0=arg[4] ? arg[4][6] : 0; - a0=sqrt(a0); + casadi_real a1=arg[4] ? arg[4][1] : 0; + if (res[0]!=0) res[0][5]=a1; if (res[0]!=0) res[0][6]=a0; - a0=arg[4] ? arg[4][7] : 0; - a0=sqrt(a0); if (res[0]!=0) res[0][7]=a0; - a0=arg[4] ? arg[4][8] : 0; - a0=sqrt(a0); if (res[0]!=0) res[0][8]=a0; - a0=arg[4] ? arg[4][9] : 0; - a0=sqrt(a0); if (res[0]!=0) res[0][9]=a0; - a0=arg[4] ? arg[4][10] : 0; - a0=sqrt(a0); - if (res[0]!=0) res[0][10]=a0; - a0=arg[4] ? arg[4][11] : 0; - a0=sqrt(a0); + a1=arg[4] ? arg[4][2] : 0; + if (res[0]!=0) res[0][10]=a1; if (res[0]!=0) res[0][11]=a0; - a0=arg[4] ? arg[4][12] : 0; - a0=sqrt(a0); if (res[0]!=0) res[0][12]=a0; - a0=arg[4] ? arg[4][13] : 0; - a0=sqrt(a0); if (res[0]!=0) res[0][13]=a0; - a0=arg[4] ? arg[4][14] : 0; - a0=sqrt(a0); if (res[0]!=0) res[0][14]=a0; - a0=arg[4] ? arg[4][15] : 0; - a0=sqrt(a0); - if (res[0]!=0) res[0][15]=a0; - a0=arg[4] ? arg[4][16] : 0; - a0=sqrt(a0); - if (res[0]!=0) res[0][16]=a0; - a0=arg[4] ? arg[4][17] : 0; - a0=sqrt(a0); - if (res[0]!=0) res[0][17]=a0; - a0=arg[4] ? arg[4][18] : 0; - a0=sqrt(a0); - if (res[0]!=0) res[0][18]=a0; - a0=arg[4] ? arg[4][19] : 0; - a0=sqrt(a0); - if (res[0]!=0) res[0][19]=a0; - a0=arg[4] ? arg[4][20] : 0; - a0=sqrt(a0); - if (res[1]!=0) res[1][0]=a0; - a0=arg[4] ? arg[4][21] : 0; - a0=sqrt(a0); - if (res[1]!=0) res[1][1]=a0; - a0=arg[4] ? arg[4][22] : 0; - a0=sqrt(a0); - if (res[1]!=0) res[1][2]=a0; - a0=arg[4] ? arg[4][23] : 0; - a0=sqrt(a0); - if (res[1]!=0) res[1][3]=a0; - a0=arg[4] ? arg[4][24] : 0; - a0=sqrt(a0); - if (res[1]!=0) res[1][4]=a0; + a1=arg[4] ? arg[4][3] : 0; + if (res[0]!=0) res[0][15]=a1; + a1=arg[4] ? arg[4][4] : 0; + if (res[1]!=0) res[1][0]=a1; + if (res[2]!=0) res[2][0]=a0; + if (res[2]!=0) res[2][1]=a0; + if (res[2]!=0) res[2][2]=a0; + if (res[2]!=0) res[2][3]=a0; return 0; } -CASADI_SYMBOL_EXPORT int Ji_fun(const casadi_real** arg, casadi_real** res, int* iw, casadi_real* w, void* mem){ +CASADI_SYMBOL_EXPORT int Hi_fun(const casadi_real** arg, casadi_real** res, int* iw, casadi_real* w, void* mem){ return casadi_f15(arg, res, iw, w, mem); } -CASADI_SYMBOL_EXPORT void Ji_fun_incref(void) { +CASADI_SYMBOL_EXPORT void Hi_fun_incref(void) { } -CASADI_SYMBOL_EXPORT void Ji_fun_decref(void) { +CASADI_SYMBOL_EXPORT void Hi_fun_decref(void) { } -CASADI_SYMBOL_EXPORT int Ji_fun_n_in(void) { return 5;} +CASADI_SYMBOL_EXPORT int Hi_fun_n_in(void) { return 5;} -CASADI_SYMBOL_EXPORT int Ji_fun_n_out(void) { return 2;} +CASADI_SYMBOL_EXPORT int Hi_fun_n_out(void) { return 3;} -CASADI_SYMBOL_EXPORT const char* Ji_fun_name_in(int i){ +CASADI_SYMBOL_EXPORT const char* Hi_fun_name_in(int i){ switch (i) { case 0: return "i0"; case 1: return "i1"; @@ -2974,109 +2662,84 @@ CASADI_SYMBOL_EXPORT const char* Ji_fun_name_in(int i){ } } -CASADI_SYMBOL_EXPORT const char* Ji_fun_name_out(int i){ +CASADI_SYMBOL_EXPORT const char* Hi_fun_name_out(int i){ switch (i) { case 0: return "o0"; case 1: return "o1"; + case 2: return "o2"; default: return 0; } } -CASADI_SYMBOL_EXPORT const int* Ji_fun_sparsity_in(int i) { +CASADI_SYMBOL_EXPORT const int* Hi_fun_sparsity_in(int i) { switch (i) { case 0: return casadi_s0; case 1: return casadi_s1; case 2: return casadi_s2; case 3: return casadi_s4; - case 4: return casadi_s6; + case 4: return casadi_s4; default: return 0; } } -CASADI_SYMBOL_EXPORT const int* Ji_fun_sparsity_out(int i) { +CASADI_SYMBOL_EXPORT const int* Hi_fun_sparsity_out(int i) { switch (i) { - case 0: return casadi_s7; - case 1: return casadi_s4; + case 0: return casadi_s3; + case 1: return casadi_s1; + case 2: return casadi_s0; default: return 0; } } -CASADI_SYMBOL_EXPORT int Ji_fun_work(int *sz_arg, int* sz_res, int *sz_iw, int *sz_w) { +CASADI_SYMBOL_EXPORT int Hi_fun_work(int *sz_arg, int* sz_res, int *sz_iw, int *sz_w) { if (sz_arg) *sz_arg = 5; - if (sz_res) *sz_res = 2; + if (sz_res) *sz_res = 3; if (sz_iw) *sz_iw = 0; - if (sz_w) *sz_w = 1; + if (sz_w) *sz_w = 2; return 0; } -/* JN_fun:(i0[4],i1[0],i2[4],i3[4x4])->(o0[4x4]) */ +/* HN_fun:(i0[4],i1[0],i2[4],i3[4])->(o0[4x4]) */ static int casadi_f16(const casadi_real** arg, casadi_real** res, int* iw, casadi_real* w, void* mem) { casadi_real a0=arg[3] ? arg[3][0] : 0; - a0=sqrt(a0); if (res[0]!=0) res[0][0]=a0; - a0=arg[3] ? arg[3][1] : 0; - a0=sqrt(a0); + a0=0.; if (res[0]!=0) res[0][1]=a0; - a0=arg[3] ? arg[3][2] : 0; - a0=sqrt(a0); if (res[0]!=0) res[0][2]=a0; - a0=arg[3] ? arg[3][3] : 0; - a0=sqrt(a0); if (res[0]!=0) res[0][3]=a0; - a0=arg[3] ? arg[3][4] : 0; - a0=sqrt(a0); if (res[0]!=0) res[0][4]=a0; - a0=arg[3] ? arg[3][5] : 0; - a0=sqrt(a0); - if (res[0]!=0) res[0][5]=a0; - a0=arg[3] ? arg[3][6] : 0; - a0=sqrt(a0); + casadi_real a1=arg[3] ? arg[3][1] : 0; + if (res[0]!=0) res[0][5]=a1; if (res[0]!=0) res[0][6]=a0; - a0=arg[3] ? arg[3][7] : 0; - a0=sqrt(a0); if (res[0]!=0) res[0][7]=a0; - a0=arg[3] ? arg[3][8] : 0; - a0=sqrt(a0); if (res[0]!=0) res[0][8]=a0; - a0=arg[3] ? arg[3][9] : 0; - a0=sqrt(a0); if (res[0]!=0) res[0][9]=a0; - a0=arg[3] ? arg[3][10] : 0; - a0=sqrt(a0); - if (res[0]!=0) res[0][10]=a0; - a0=arg[3] ? arg[3][11] : 0; - a0=sqrt(a0); + a1=arg[3] ? arg[3][2] : 0; + if (res[0]!=0) res[0][10]=a1; if (res[0]!=0) res[0][11]=a0; - a0=arg[3] ? arg[3][12] : 0; - a0=sqrt(a0); if (res[0]!=0) res[0][12]=a0; - a0=arg[3] ? arg[3][13] : 0; - a0=sqrt(a0); if (res[0]!=0) res[0][13]=a0; - a0=arg[3] ? arg[3][14] : 0; - a0=sqrt(a0); if (res[0]!=0) res[0][14]=a0; - a0=arg[3] ? arg[3][15] : 0; - a0=sqrt(a0); + a0=arg[3] ? arg[3][3] : 0; if (res[0]!=0) res[0][15]=a0; return 0; } -CASADI_SYMBOL_EXPORT int JN_fun(const casadi_real** arg, casadi_real** res, int* iw, casadi_real* w, void* mem){ +CASADI_SYMBOL_EXPORT int HN_fun(const casadi_real** arg, casadi_real** res, int* iw, casadi_real* w, void* mem){ return casadi_f16(arg, res, iw, w, mem); } -CASADI_SYMBOL_EXPORT void JN_fun_incref(void) { +CASADI_SYMBOL_EXPORT void HN_fun_incref(void) { } -CASADI_SYMBOL_EXPORT void JN_fun_decref(void) { +CASADI_SYMBOL_EXPORT void HN_fun_decref(void) { } -CASADI_SYMBOL_EXPORT int JN_fun_n_in(void) { return 4;} +CASADI_SYMBOL_EXPORT int HN_fun_n_in(void) { return 4;} -CASADI_SYMBOL_EXPORT int JN_fun_n_out(void) { return 1;} +CASADI_SYMBOL_EXPORT int HN_fun_n_out(void) { return 1;} -CASADI_SYMBOL_EXPORT const char* JN_fun_name_in(int i){ +CASADI_SYMBOL_EXPORT const char* HN_fun_name_in(int i){ switch (i) { case 0: return "i0"; case 1: return "i1"; @@ -3086,35 +2749,35 @@ CASADI_SYMBOL_EXPORT const char* JN_fun_name_in(int i){ } } -CASADI_SYMBOL_EXPORT const char* JN_fun_name_out(int i){ +CASADI_SYMBOL_EXPORT const char* HN_fun_name_out(int i){ switch (i) { case 0: return "o0"; default: return 0; } } -CASADI_SYMBOL_EXPORT const int* JN_fun_sparsity_in(int i) { +CASADI_SYMBOL_EXPORT const int* HN_fun_sparsity_in(int i) { switch (i) { case 0: return casadi_s0; case 1: return casadi_s2; case 2: return casadi_s0; - case 3: return casadi_s3; + case 3: return casadi_s0; default: return 0; } } -CASADI_SYMBOL_EXPORT const int* JN_fun_sparsity_out(int i) { +CASADI_SYMBOL_EXPORT const int* HN_fun_sparsity_out(int i) { switch (i) { case 0: return casadi_s3; default: return 0; } } -CASADI_SYMBOL_EXPORT int JN_fun_work(int *sz_arg, int* sz_res, int *sz_iw, int *sz_w) { +CASADI_SYMBOL_EXPORT int HN_fun_work(int *sz_arg, int* sz_res, int *sz_iw, int *sz_w) { if (sz_arg) *sz_arg = 4; if (sz_res) *sz_res = 1; if (sz_iw) *sz_iw = 0; - if (sz_w) *sz_w = 1; + if (sz_w) *sz_w = 2; return 0; } @@ -3165,7 +2828,7 @@ CASADI_SYMBOL_EXPORT const int* Ci_fun_sparsity_in(int i) { CASADI_SYMBOL_EXPORT const int* Ci_fun_sparsity_out(int i) { switch (i) { - case 0: return casadi_s8; + case 0: return casadi_s6; case 1: return casadi_s2; default: return 0; } @@ -3223,7 +2886,7 @@ CASADI_SYMBOL_EXPORT const int* CN_fun_sparsity_in(int i) { CASADI_SYMBOL_EXPORT const int* CN_fun_sparsity_out(int i) { switch (i) { - case 0: return casadi_s8; + case 0: return casadi_s6; default: return 0; } } @@ -3236,262 +2899,158 @@ CASADI_SYMBOL_EXPORT int CN_fun_work(int *sz_arg, int* sz_res, int *sz_iw, int * return 0; } -/* adj_fun:(i0[4],i1,i2[0],i3[5],i4[5x5],i5[4],i6,i7,i8[0])->(o0[5],o1[5],o2[5]) */ +/* adj_fun:(i0[4],i1,i2[0],i3[5],i4[5],i5[4],i6,i7,i8[0])->(o0[5],o1[5],o2[5]) */ static int casadi_f19(const casadi_real** arg, casadi_real** res, int* iw, casadi_real* w, void* mem) { - casadi_real a0=5.0000000000000000e-001; + casadi_real a0=5.0000000000000000e-01; casadi_real a1=arg[0] ? arg[0][0] : 0; casadi_real a2=arg[3] ? arg[3][0] : 0; casadi_real a3=(a1-a2); a3=(a0*a3); casadi_real a4=arg[4] ? arg[4][0] : 0; - casadi_real a5=(a3*a4); - casadi_real a6=arg[0] ? arg[0][1] : 0; - casadi_real a7=arg[3] ? arg[3][1] : 0; - casadi_real a8=(a6-a7); - a8=(a0*a8); - casadi_real a9=arg[4] ? arg[4][1] : 0; - casadi_real a10=(a8*a9); - a5=(a5+a10); - a10=arg[0] ? arg[0][2] : 0; - casadi_real a11=arg[3] ? arg[3][2] : 0; - casadi_real a12=(a10-a11); - a12=(a0*a12); - casadi_real a13=arg[4] ? arg[4][2] : 0; - casadi_real a14=(a12*a13); - a5=(a5+a14); - a14=arg[0] ? arg[0][3] : 0; - casadi_real a15=arg[3] ? arg[3][3] : 0; - casadi_real a16=(a14-a15); - a16=(a0*a16); - casadi_real a17=arg[4] ? arg[4][3] : 0; - casadi_real a18=(a16*a17); - a5=(a5+a18); - a18=arg[1] ? arg[1][0] : 0; - casadi_real a19=arg[3] ? arg[3][4] : 0; - casadi_real a20=(a18-a19); - a20=(a0*a20); - casadi_real a21=arg[4] ? arg[4][4] : 0; - casadi_real a22=(a20*a21); - a5=(a5+a22); - a22=arg[4] ? arg[4][20] : 0; - a19=(a18-a19); - casadi_real a23=(a22*a19); - casadi_real a24=arg[4] ? arg[4][15] : 0; - a15=(a14-a15); - casadi_real a25=(a24*a15); - a23=(a23+a25); - a25=arg[4] ? arg[4][10] : 0; - a10=(a10-a11); - a11=(a25*a10); - a23=(a23+a11); - a11=arg[4] ? arg[4][5] : 0; - a7=(a6-a7); - casadi_real a26=(a11*a7); - a23=(a23+a26); + a3=(a3*a4); a1=(a1-a2); a4=(a4*a1); - a23=(a23+a4); - a23=(a0*a23); - a5=(a5+a23); - if (res[0]!=0) res[0][0]=a5; - a11=(a3*a11); - a5=arg[4] ? arg[4][6] : 0; - a23=(a8*a5); - a11=(a11+a23); - a23=arg[4] ? arg[4][7] : 0; - a4=(a12*a23); - a11=(a11+a4); - a4=arg[4] ? arg[4][8] : 0; - a2=(a16*a4); - a11=(a11+a2); - a2=arg[4] ? arg[4][9] : 0; - a26=(a20*a2); - a11=(a11+a26); - a26=arg[4] ? arg[4][21] : 0; - casadi_real a27=(a26*a19); - casadi_real a28=arg[4] ? arg[4][16] : 0; - casadi_real a29=(a28*a15); - a27=(a27+a29); - a29=arg[4] ? arg[4][11] : 0; - casadi_real a30=(a29*a10); - a27=(a27+a30); - a5=(a5*a7); - a27=(a27+a5); - a9=(a9*a1); - a27=(a27+a9); - a27=(a0*a27); - a11=(a11+a27); - if (res[0]!=0) res[0][1]=a11; - a25=(a3*a25); - a29=(a8*a29); - a25=(a25+a29); - a29=arg[4] ? arg[4][12] : 0; - a11=(a12*a29); - a25=(a25+a11); - a11=arg[4] ? arg[4][13] : 0; - a27=(a16*a11); - a25=(a25+a27); - a27=arg[4] ? arg[4][14] : 0; - a9=(a20*a27); - a25=(a25+a9); - a9=arg[4] ? arg[4][22] : 0; - a5=(a9*a19); - a30=arg[4] ? arg[4][17] : 0; - casadi_real a31=(a30*a15); - a5=(a5+a31); - a29=(a29*a10); - a5=(a5+a29); - a23=(a23*a7); - a5=(a5+a23); - a13=(a13*a1); - a5=(a5+a13); - a5=(a0*a5); - a25=(a25+a5); - if (res[0]!=0) res[0][2]=a25; - a24=(a3*a24); - a28=(a8*a28); - a24=(a24+a28); - a30=(a12*a30); - a24=(a24+a30); - a30=arg[4] ? arg[4][18] : 0; - a28=(a16*a30); - a24=(a24+a28); - a28=arg[4] ? arg[4][19] : 0; - a25=(a20*a28); - a24=(a24+a25); - a25=arg[4] ? arg[4][23] : 0; - a5=(a25*a19); - a30=(a30*a15); - a5=(a5+a30); - a11=(a11*a10); - a5=(a5+a11); - a4=(a4*a7); - a5=(a5+a4); - a17=(a17*a1); - a5=(a5+a17); + a4=(a0*a4); + a3=(a3+a4); + if (res[0]!=0) res[0][0]=a3; + a3=arg[0] ? arg[0][1] : 0; + a4=arg[3] ? arg[3][1] : 0; + a1=(a3-a4); + a1=(a0*a1); + a2=arg[4] ? arg[4][1] : 0; + a1=(a1*a2); + a4=(a3-a4); + a2=(a2*a4); + a2=(a0*a2); + a1=(a1+a2); + if (res[0]!=0) res[0][1]=a1; + a1=arg[0] ? arg[0][2] : 0; + a2=arg[3] ? arg[3][2] : 0; + a4=(a1-a2); + a4=(a0*a4); + casadi_real a5=arg[4] ? arg[4][2] : 0; + a4=(a4*a5); + a1=(a1-a2); + a5=(a5*a1); a5=(a0*a5); - a24=(a24+a5); - if (res[0]!=0) res[0][3]=a24; - a21=(a0*a21); - a1=(a1*a21); + a4=(a4+a5); + if (res[0]!=0) res[0][2]=a4; + a4=arg[0] ? arg[0][3] : 0; + a5=arg[3] ? arg[3][3] : 0; + a1=(a4-a5); + a1=(a0*a1); + a2=arg[4] ? arg[4][3] : 0; + a1=(a1*a2); + a5=(a4-a5); + a2=(a2*a5); a2=(a0*a2); - a7=(a7*a2); - a1=(a1+a7); - a27=(a0*a27); - a10=(a10*a27); - a1=(a1+a10); - a28=(a0*a28); - a15=(a15*a28); - a1=(a1+a15); - a15=arg[4] ? arg[4][24] : 0; - a0=(a0*a15); - a19=(a19*a0); - a3=(a3*a22); - a8=(a8*a26); - a3=(a3+a8); - a12=(a12*a9); - a3=(a3+a12); - a16=(a16*a25); - a3=(a3+a16); - a20=(a20*a15); - a3=(a3+a20); - a19=(a19+a3); - a1=(a1+a19); - if (res[0]!=0) res[0][4]=a1; - a1=arg[5] ? arg[5][0] : 0; - if (res[1]!=0) res[1][0]=a1; - a19=5.0000000000000003e-002; - a3=2.5000000000000001e-002; - a20=-8.0000000000000016e-002; - a15=(a3*a14); - a15=(a6+a15); - a16=cos(a15); - a16=(a20*a16); - a25=sin(a15); - a12=(a16*a25); - a9=cos(a6); - a9=(a20*a9); - a8=sin(a6); - a26=(a9*a8); - a22=sq(a14); - a0=(a26*a22); - a28=cos(a6); - a10=(a18*a28); - a0=(a0+a10); - a10=1.0791000000000002e+001; - a27=sin(a6); - a27=(a10*a27); - a0=(a0+a27); - a27=8.0000000000000004e-001; - a7=1.1000000000000001e+000; - a2=1.0000000000000001e-001; - a21=cos(a6); - a24=sq(a21); - a24=(a2*a24); - a24=(a7-a24); - a5=(a27*a24); - a0=(a0/a5); - a17=(a3*a0); - a17=(a14+a17); - a4=sq(a17); - a11=(a12*a4); - a30=cos(a15); - a13=(a18*a30); - a11=(a11+a13); - a13=sin(a15); - a13=(a10*a13); - a11=(a11+a13); - a13=cos(a15); - a23=sq(a13); - a23=(a2*a23); - a23=(a7-a23); - a29=(a27*a23); - a11=(a11/a29); - a31=(a3*a11); - a31=(a14+a31); - casadi_real a32=(a19*a31); - a32=(a6+a32); + a1=(a1+a2); + if (res[0]!=0) res[0][3]=a1; + a1=arg[1] ? arg[1][0] : 0; + a2=arg[3] ? arg[3][4] : 0; + a5=(a1-a2); + casadi_real a6=arg[4] ? arg[4][4] : 0; + casadi_real a7=(a0*a6); + a5=(a5*a7); + a2=(a1-a2); + a0=(a0*a2); + a0=(a0*a6); + a5=(a5+a0); + if (res[0]!=0) res[0][4]=a5; + a5=arg[5] ? arg[5][0] : 0; + if (res[1]!=0) res[1][0]=a5; + a0=5.0000000000000003e-02; + a6=2.5000000000000001e-02; + a2=-8.0000000000000016e-02; + a7=(a6*a4); + a7=(a3+a7); + casadi_real a8=cos(a7); + a8=(a2*a8); + casadi_real a9=sin(a7); + casadi_real a10=(a8*a9); + casadi_real a11=cos(a3); + a11=(a2*a11); + casadi_real a12=sin(a3); + casadi_real a13=(a11*a12); + casadi_real a14=sq(a4); + casadi_real a15=(a13*a14); + casadi_real a16=cos(a3); + casadi_real a17=(a1*a16); + a15=(a15+a17); + a17=1.0791000000000002e+01; + casadi_real a18=sin(a3); + a18=(a17*a18); + a15=(a15+a18); + a18=8.0000000000000004e-01; + casadi_real a19=1.1000000000000001e+00; + casadi_real a20=1.0000000000000001e-01; + casadi_real a21=cos(a3); + casadi_real a22=sq(a21); + a22=(a20*a22); + a22=(a19-a22); + casadi_real a23=(a18*a22); + a15=(a15/a23); + casadi_real a24=(a6*a15); + a24=(a4+a24); + casadi_real a25=sq(a24); + casadi_real a26=(a10*a25); + casadi_real a27=cos(a7); + casadi_real a28=(a1*a27); + a26=(a26+a28); + a28=sin(a7); + a28=(a17*a28); + a26=(a26+a28); + a28=cos(a7); + casadi_real a29=sq(a28); + a29=(a20*a29); + a29=(a19-a29); + casadi_real a30=(a18*a29); + a26=(a26/a30); + casadi_real a31=(a6*a26); + a31=(a4+a31); + casadi_real a32=(a0*a31); + a32=(a3+a32); casadi_real a33=cos(a32); - casadi_real a34=8.3333333333333332e-003; + casadi_real a34=8.3333333333333332e-03; casadi_real a35=arg[5] ? arg[5][3] : 0; casadi_real a36=(a34*a35); casadi_real a37=cos(a32); casadi_real a38=sq(a37); - a38=(a2*a38); - a38=(a7-a38); - casadi_real a39=(a27*a38); + a38=(a20*a38); + a38=(a19-a38); + casadi_real a39=(a18*a38); casadi_real a40=(a36/a39); - casadi_real a41=(a10*a40); + casadi_real a41=(a17*a40); a33=(a33*a41); a41=sin(a32); - casadi_real a42=(a18*a40); + casadi_real a42=(a1*a40); a41=(a41*a42); a33=(a33-a41); a41=cos(a32); a42=cos(a32); - a42=(a20*a42); - casadi_real a43=(a3*a17); - a43=(a6+a43); + a42=(a2*a42); + casadi_real a43=(a6*a24); + a43=(a3+a43); casadi_real a44=cos(a43); - a44=(a20*a44); + a44=(a2*a44); casadi_real a45=sin(a43); casadi_real a46=(a44*a45); casadi_real a47=sq(a31); casadi_real a48=(a46*a47); casadi_real a49=cos(a43); - casadi_real a50=(a18*a49); + casadi_real a50=(a1*a49); a48=(a48+a50); a50=sin(a43); - a50=(a10*a50); + a50=(a17*a50); a48=(a48+a50); a50=cos(a43); casadi_real a51=sq(a50); - a51=(a2*a51); - a7=(a7-a51); - a51=(a27*a7); + a51=(a20*a51); + a19=(a19-a51); + a51=(a18*a19); a48=(a48/a51); - casadi_real a52=(a19*a48); - a52=(a14+a52); + casadi_real a52=(a0*a48); + a52=(a4+a52); casadi_real a53=sq(a52); casadi_real a54=(a53*a40); casadi_real a55=(a42*a54); @@ -3500,7 +3059,7 @@ static int casadi_f19(const casadi_real** arg, casadi_real** res, int* iw, casad a41=sin(a32); a55=sin(a32); a54=(a55*a54); - a54=(a20*a54); + a54=(a2*a54); a41=(a41*a54); a33=(a33-a41); a41=sin(a32); @@ -3508,33 +3067,33 @@ static int casadi_f19(const casadi_real** arg, casadi_real** res, int* iw, casad a42=(a42*a55); a53=(a42*a53); a55=cos(a32); - a54=(a18*a55); + a54=(a1*a55); a53=(a53+a54); a54=sin(a32); - a54=(a10*a54); + a54=(a17*a54); a53=(a53+a54); a53=(a53/a39); a53=(a53/a39); a53=(a53*a36); - a53=(a27*a53); + a53=(a18*a53); a39=sin(a32); - a39=(a20*a39); + a39=(a2*a39); a54=sq(a52); casadi_real a56=(a39*a54); - casadi_real a57=9.8100000000000009e-001; + casadi_real a57=9.8100000000000009e-01; casadi_real a58=cos(a32); a58=(a57*a58); casadi_real a59=sin(a32); casadi_real a60=(a58*a59); a56=(a56+a60); - a56=(a56+a18); + a56=(a56+a1); a56=(a56/a38); a56=(a56/a38); a60=arg[5] ? arg[5][2] : 0; casadi_real a61=(a34*a60); a56=(a56*a61); a53=(a53+a56); - a53=(a2*a53); + a53=(a20*a53); a37=(a37*a53); a41=(a41*a37); a33=(a33-a41); @@ -3550,7 +3109,7 @@ static int casadi_f19(const casadi_real** arg, casadi_real** res, int* iw, casad a33=(a33-a41); a32=cos(a32); a54=(a54*a38); - a54=(a20*a54); + a54=(a2*a54); a32=(a32*a54); a33=(a33+a32); a32=arg[5] ? arg[5][1] : 0; @@ -3567,13 +3126,13 @@ static int casadi_f19(const casadi_real** arg, casadi_real** res, int* iw, casad a37=(a37+a52); a32=(a34*a32); a37=(a37+a32); - a52=(a19*a37); + a52=(a0*a37); a58=(a58+a52); a52=(a58/a51); - a39=(a10*a52); + a39=(a17*a52); a41=(a41*a39); a39=sin(a43); - a42=(a18*a52); + a42=(a1*a52); a39=(a39*a42); a41=(a41-a39); a39=cos(a43); @@ -3583,16 +3142,16 @@ static int casadi_f19(const casadi_real** arg, casadi_real** res, int* iw, casad a41=(a41+a39); a39=sin(a43); a45=(a45*a47); - a45=(a20*a45); + a45=(a2*a45); a39=(a39*a45); a41=(a41-a39); a39=sin(a43); a50=(a50+a50); a48=(a48/a51); a48=(a48*a58); - a48=(a27*a48); + a48=(a18*a48); a58=sin(a43); - a58=(a20*a58); + a58=(a2*a58); a51=sq(a31); a45=(a58*a51); a47=cos(a43); @@ -3600,21 +3159,21 @@ static int casadi_f19(const casadi_real** arg, casadi_real** res, int* iw, casad a44=sin(a43); a42=(a47*a44); a45=(a45+a42); - a45=(a45+a18); - a45=(a45/a7); - a45=(a45/a7); + a45=(a45+a1); + a45=(a45/a19); + a45=(a45/a19); a42=(a59*a61); - a34=(a34*a1); - a1=(a19*a34); - a42=(a42+a1); + a34=(a34*a5); + a5=(a0*a34); + a42=(a42+a5); a45=(a45*a42); a48=(a48+a45); - a48=(a2*a48); + a48=(a20*a48); a50=(a50*a48); a39=(a39*a50); a41=(a41-a39); a39=cos(a43); - a42=(a42/a7); + a42=(a42/a19); a47=(a47*a42); a39=(a39*a47); a41=(a41+a39); @@ -3625,158 +3184,158 @@ static int casadi_f19(const casadi_real** arg, casadi_real** res, int* iw, casad a41=(a41-a39); a43=cos(a43); a51=(a51*a42); - a51=(a20*a51); + a51=(a2*a51); a43=(a43*a51); a41=(a41+a43); a54=(a54+a41); - a43=cos(a6); + a43=cos(a3); a51=(a59*a32); - a39=(a17+a17); + a39=(a24+a24); a44=(a59*a36); - a19=(a19*a33); + a0=(a0*a33); a33=(a31+a31); a46=(a46*a52); a33=(a33*a46); - a19=(a19+a33); + a0=(a0+a33); a33=(a59*a32); - a19=(a19+a33); + a0=(a0+a33); a31=(a31+a31); a58=(a58*a42); a31=(a31*a58); - a19=(a19+a31); - a31=(a3*a19); + a0=(a0+a31); + a31=(a6*a0); a44=(a44+a31); - a31=(a44/a29); - a12=(a12*a31); - a39=(a39*a12); + a31=(a44/a30); + a10=(a10*a31); + a39=(a39*a10); a51=(a51+a39); - a41=(a3*a41); + a41=(a6*a41); a51=(a51+a41); - a41=(a17+a17); - a39=sin(a15); - a39=(a20*a39); - a12=(a59*a61); + a41=(a24+a24); + a39=sin(a7); + a39=(a2*a39); + a10=(a59*a61); a58=(a59*a34); - a33=(a3*a58); - a12=(a12+a33); - a33=(a12/a23); + a33=(a6*a58); + a10=(a10+a33); + a33=(a10/a29); a46=(a39*a33); a41=(a41*a46); a51=(a51+a41); - a41=(a3*a51); + a41=(a6*a51); a36=(a36+a41); - a41=(a36/a5); - a46=(a10*a41); + a41=(a36/a23); + a46=(a17*a41); a43=(a43*a46); a54=(a54+a43); - a43=sin(a6); - a46=(a18*a41); + a43=sin(a3); + a46=(a1*a41); a43=(a43*a46); a54=(a54-a43); - a43=cos(a6); - a22=(a22*a41); - a9=(a9*a22); - a43=(a43*a9); + a43=cos(a3); + a14=(a14*a41); + a11=(a11*a14); + a43=(a43*a11); a54=(a54+a43); - a43=sin(a6); - a8=(a8*a22); - a8=(a20*a8); - a43=(a43*a8); + a43=sin(a3); + a12=(a12*a14); + a12=(a2*a12); + a43=(a43*a12); a54=(a54-a43); - a43=cos(a15); - a10=(a10*a31); - a43=(a43*a10); - a10=sin(a15); - a8=(a18*a31); - a10=(a10*a8); - a43=(a43-a10); - a10=cos(a15); - a4=(a4*a31); - a16=(a16*a4); - a10=(a10*a16); - a43=(a43+a10); - a10=sin(a15); - a25=(a25*a4); - a25=(a20*a25); - a10=(a10*a25); - a43=(a43-a10); - a10=sin(a15); - a13=(a13+a13); - a11=(a11/a29); - a11=(a11*a44); - a11=(a27*a11); - a17=sq(a17); - a39=(a39*a17); - a44=cos(a15); + a43=cos(a7); + a17=(a17*a31); + a43=(a43*a17); + a17=sin(a7); + a12=(a1*a31); + a17=(a17*a12); + a43=(a43-a17); + a17=cos(a7); + a25=(a25*a31); + a8=(a8*a25); + a17=(a17*a8); + a43=(a43+a17); + a17=sin(a7); + a9=(a9*a25); + a9=(a2*a9); + a17=(a17*a9); + a43=(a43-a17); + a17=sin(a7); + a28=(a28+a28); + a26=(a26/a30); + a26=(a26*a44); + a26=(a18*a26); + a24=sq(a24); + a39=(a39*a24); + a44=cos(a7); a44=(a57*a44); - a29=sin(a15); - a25=(a44*a29); - a39=(a39+a25); - a39=(a39+a18); - a39=(a39/a23); - a39=(a39/a23); - a39=(a39*a12); - a11=(a11+a39); - a11=(a2*a11); - a13=(a13*a11); - a10=(a10*a13); - a43=(a43-a10); - a10=cos(a15); + a30=sin(a7); + a9=(a44*a30); + a39=(a39+a9); + a39=(a39+a1); + a39=(a39/a29); + a39=(a39/a29); + a39=(a39*a10); + a26=(a26+a39); + a26=(a20*a26); + a28=(a28*a26); + a17=(a17*a28); + a43=(a43-a17); + a17=cos(a7); a44=(a44*a33); - a10=(a10*a44); - a43=(a43+a10); - a10=sin(a15); - a29=(a29*a33); - a29=(a57*a29); - a10=(a10*a29); - a43=(a43-a10); - a15=cos(a15); - a17=(a17*a33); - a17=(a20*a17); - a15=(a15*a17); - a43=(a43+a15); + a17=(a17*a44); + a43=(a43+a17); + a17=sin(a7); + a30=(a30*a33); + a30=(a57*a30); + a17=(a17*a30); + a43=(a43-a17); + a7=cos(a7); + a24=(a24*a33); + a24=(a2*a24); + a7=(a7*a24); + a43=(a43+a7); a54=(a54+a43); - a15=sin(a6); + a7=sin(a3); a21=(a21+a21); - a0=(a0/a5); - a0=(a0*a36); - a27=(a27*a0); - a0=sin(a6); - a0=(a20*a0); - a36=sq(a14); - a5=(a0*a36); - a17=cos(a6); - a17=(a57*a17); - a10=sin(a6); - a29=(a17*a10); - a5=(a5+a29); - a5=(a5+a18); - a5=(a5/a24); - a5=(a5/a24); + a15=(a15/a23); + a15=(a15*a36); + a18=(a18*a15); + a15=sin(a3); + a15=(a2*a15); + a36=sq(a4); + a23=(a15*a36); + a24=cos(a3); + a24=(a57*a24); + a17=sin(a3); + a30=(a24*a17); + a23=(a23+a30); + a23=(a23+a1); + a23=(a23/a22); + a23=(a23/a22); a59=(a59*a34); - a18=(a3*a59); - a61=(a61+a18); - a5=(a5*a61); - a27=(a27+a5); - a2=(a2*a27); - a21=(a21*a2); - a15=(a15*a21); - a54=(a54-a15); - a15=cos(a6); - a61=(a61/a24); + a1=(a6*a59); + a61=(a61+a1); + a23=(a23*a61); + a18=(a18+a23); + a20=(a20*a18); + a21=(a21*a20); + a7=(a7*a21); + a54=(a54-a7); + a7=cos(a3); + a61=(a61/a22); + a24=(a24*a61); + a7=(a7*a24); + a54=(a54+a7); + a7=sin(a3); a17=(a17*a61); - a15=(a15*a17); - a54=(a54+a15); - a15=sin(a6); - a10=(a10*a61); - a57=(a57*a10); - a15=(a15*a57); - a54=(a54-a15); - a6=cos(a6); + a57=(a57*a17); + a7=(a7*a57); + a54=(a54-a7); + a3=cos(a3); a36=(a36*a61); - a20=(a20*a36); - a6=(a6*a20); - a54=(a54+a6); + a2=(a2*a36); + a3=(a3*a2); + a54=(a54+a3); if (res[1]!=0) res[1][1]=a54; a60=(a60+a34); a60=(a60+a58); @@ -3785,29 +3344,29 @@ static int casadi_f19(const casadi_real** arg, casadi_real** res, int* iw, casad if (res[1]!=0) res[1][2]=a60; a35=(a35+a37); a35=(a35+a32); - a35=(a35+a19); + a35=(a35+a0); a35=(a35+a51); - a51=(a14+a14); - a26=(a26*a41); - a51=(a51*a26); + a51=(a4+a4); + a13=(a13*a41); + a51=(a51*a13); a35=(a35+a51); - a3=(a3*a43); - a35=(a35+a3); - a14=(a14+a14); - a0=(a0*a61); - a14=(a14*a0); - a35=(a35+a14); + a6=(a6*a43); + a35=(a35+a6); + a4=(a4+a4); + a15=(a15*a61); + a4=(a4*a15); + a35=(a35+a4); if (res[1]!=0) res[1][3]=a35; a55=(a55*a40); a55=(a55+a38); a49=(a49*a52); a55=(a55+a49); a55=(a55+a42); - a30=(a30*a31); - a55=(a55+a30); + a27=(a27*a31); + a55=(a55+a27); a55=(a55+a33); - a28=(a28*a41); - a55=(a55+a28); + a16=(a16*a41); + a55=(a55+a16); a55=(a55+a61); if (res[1]!=0) res[1][4]=a55; a55=arg[6] ? arg[6][0] : 0; @@ -3865,7 +3424,7 @@ CASADI_SYMBOL_EXPORT const int* adj_fun_sparsity_in(int i) { case 1: return casadi_s1; case 2: return casadi_s2; case 3: return casadi_s4; - case 4: return casadi_s6; + case 4: return casadi_s4; case 5: return casadi_s0; case 6: return casadi_s1; case 7: return casadi_s1; @@ -3891,119 +3450,59 @@ CASADI_SYMBOL_EXPORT int adj_fun_work(int *sz_arg, int* sz_res, int *sz_iw, int return 0; } -/* adjN_fun:(i0[4],i1[0],i2[4],i3[4x4],i4,i5[0])->(o0[4],o1[4]) */ +/* adjN_fun:(i0[4],i1[0],i2[4],i3[4],i4,i5[0])->(o0[4],o1[4]) */ static int casadi_f20(const casadi_real** arg, casadi_real** res, int* iw, casadi_real* w, void* mem) { - casadi_real a0=5.0000000000000000e-001; + casadi_real a0=5.0000000000000000e-01; casadi_real a1=arg[0] ? arg[0][0] : 0; casadi_real a2=arg[2] ? arg[2][0] : 0; casadi_real a3=(a1-a2); a3=(a0*a3); casadi_real a4=arg[3] ? arg[3][0] : 0; - casadi_real a5=(a3*a4); - casadi_real a6=arg[0] ? arg[0][1] : 0; - casadi_real a7=arg[2] ? arg[2][1] : 0; - casadi_real a8=(a6-a7); - a8=(a0*a8); - casadi_real a9=arg[3] ? arg[3][1] : 0; - casadi_real a10=(a8*a9); - a5=(a5+a10); - a10=arg[0] ? arg[0][2] : 0; - casadi_real a11=arg[2] ? arg[2][2] : 0; - casadi_real a12=(a10-a11); - a12=(a0*a12); - casadi_real a13=arg[3] ? arg[3][2] : 0; - casadi_real a14=(a12*a13); - a5=(a5+a14); - a14=arg[0] ? arg[0][3] : 0; - casadi_real a15=arg[2] ? arg[2][3] : 0; - casadi_real a16=(a14-a15); - a16=(a0*a16); - casadi_real a17=arg[3] ? arg[3][3] : 0; - casadi_real a18=(a16*a17); - a5=(a5+a18); - a18=arg[3] ? arg[3][12] : 0; - a14=(a14-a15); - a15=(a18*a14); - casadi_real a19=arg[3] ? arg[3][8] : 0; - a10=(a10-a11); - a11=(a19*a10); - a15=(a15+a11); - a11=arg[3] ? arg[3][4] : 0; - a6=(a6-a7); - a7=(a11*a6); - a15=(a15+a7); + a3=(a3*a4); a1=(a1-a2); a4=(a4*a1); - a15=(a15+a4); - a15=(a0*a15); - a5=(a5+a15); - if (res[0]!=0) res[0][0]=a5; - a11=(a3*a11); - a5=arg[3] ? arg[3][5] : 0; - a15=(a8*a5); - a11=(a11+a15); - a15=arg[3] ? arg[3][6] : 0; - a4=(a12*a15); - a11=(a11+a4); - a4=arg[3] ? arg[3][7] : 0; - a2=(a16*a4); - a11=(a11+a2); - a2=arg[3] ? arg[3][13] : 0; - a7=(a2*a14); - casadi_real a20=arg[3] ? arg[3][9] : 0; - casadi_real a21=(a20*a10); - a7=(a7+a21); - a5=(a5*a6); - a7=(a7+a5); - a9=(a9*a1); - a7=(a7+a9); - a7=(a0*a7); - a11=(a11+a7); - if (res[0]!=0) res[0][1]=a11; - a19=(a3*a19); - a20=(a8*a20); - a19=(a19+a20); - a20=arg[3] ? arg[3][10] : 0; - a11=(a12*a20); - a19=(a19+a11); - a11=arg[3] ? arg[3][11] : 0; - a7=(a16*a11); - a19=(a19+a7); - a7=arg[3] ? arg[3][14] : 0; - a9=(a7*a14); - a20=(a20*a10); - a9=(a9+a20); - a15=(a15*a6); - a9=(a9+a15); - a13=(a13*a1); - a9=(a9+a13); - a9=(a0*a9); - a19=(a19+a9); - if (res[0]!=0) res[0][2]=a19; - a3=(a3*a18); - a8=(a8*a2); - a3=(a3+a8); - a12=(a12*a7); - a3=(a3+a12); - a12=arg[3] ? arg[3][15] : 0; - a16=(a16*a12); - a3=(a3+a16); - a12=(a12*a14); - a11=(a11*a10); - a12=(a12+a11); - a4=(a4*a6); - a12=(a12+a4); - a17=(a17*a1); - a12=(a12+a17); - a0=(a0*a12); - a3=(a3+a0); - if (res[0]!=0) res[0][3]=a3; - a3=arg[4] ? arg[4][0] : 0; - if (res[1]!=0) res[1][0]=a3; - a3=0.; - if (res[1]!=0) res[1][1]=a3; - if (res[1]!=0) res[1][2]=a3; - if (res[1]!=0) res[1][3]=a3; + a4=(a0*a4); + a3=(a3+a4); + if (res[0]!=0) res[0][0]=a3; + a3=arg[0] ? arg[0][1] : 0; + a4=arg[2] ? arg[2][1] : 0; + a1=(a3-a4); + a1=(a0*a1); + a2=arg[3] ? arg[3][1] : 0; + a1=(a1*a2); + a3=(a3-a4); + a2=(a2*a3); + a2=(a0*a2); + a1=(a1+a2); + if (res[0]!=0) res[0][1]=a1; + a1=arg[0] ? arg[0][2] : 0; + a2=arg[2] ? arg[2][2] : 0; + a3=(a1-a2); + a3=(a0*a3); + a4=arg[3] ? arg[3][2] : 0; + a3=(a3*a4); + a1=(a1-a2); + a4=(a4*a1); + a4=(a0*a4); + a3=(a3+a4); + if (res[0]!=0) res[0][2]=a3; + a3=arg[0] ? arg[0][3] : 0; + a4=arg[2] ? arg[2][3] : 0; + a1=(a3-a4); + a1=(a0*a1); + a2=arg[3] ? arg[3][3] : 0; + a1=(a1*a2); + a3=(a3-a4); + a2=(a2*a3); + a0=(a0*a2); + a1=(a1+a0); + if (res[0]!=0) res[0][3]=a1; + a1=arg[4] ? arg[4][0] : 0; + if (res[1]!=0) res[1][0]=a1; + a1=0.; + if (res[1]!=0) res[1][1]=a1; + if (res[1]!=0) res[1][2]=a1; + if (res[1]!=0) res[1][3]=a1; return 0; } @@ -4046,7 +3545,7 @@ CASADI_SYMBOL_EXPORT const int* adjN_fun_sparsity_in(int i) { case 0: return casadi_s0; case 1: return casadi_s2; case 2: return casadi_s0; - case 3: return casadi_s3; + case 3: return casadi_s0; case 4: return casadi_s1; case 5: return casadi_s2; default: return 0; @@ -4065,266 +3564,162 @@ CASADI_SYMBOL_EXPORT int adjN_fun_work(int *sz_arg, int* sz_res, int *sz_iw, int if (sz_arg) *sz_arg = 6; if (sz_res) *sz_res = 2; if (sz_iw) *sz_iw = 0; - if (sz_w) *sz_w = 22; + if (sz_w) *sz_w = 5; return 0; } -/* adj_dG_fun:(i0[4],i1,i2[0],i3[5],i4[5x5],i5[4])->(o0[5],o1[5]) */ +/* adj_dG_fun:(i0[4],i1,i2[0],i3[5],i4[5],i5[4])->(o0[5],o1[5]) */ static int casadi_f21(const casadi_real** arg, casadi_real** res, int* iw, casadi_real* w, void* mem) { - casadi_real a0=5.0000000000000000e-001; + casadi_real a0=5.0000000000000000e-01; casadi_real a1=arg[0] ? arg[0][0] : 0; casadi_real a2=arg[3] ? arg[3][0] : 0; casadi_real a3=(a1-a2); a3=(a0*a3); casadi_real a4=arg[4] ? arg[4][0] : 0; - casadi_real a5=(a3*a4); - casadi_real a6=arg[0] ? arg[0][1] : 0; - casadi_real a7=arg[3] ? arg[3][1] : 0; - casadi_real a8=(a6-a7); - a8=(a0*a8); - casadi_real a9=arg[4] ? arg[4][1] : 0; - casadi_real a10=(a8*a9); - a5=(a5+a10); - a10=arg[0] ? arg[0][2] : 0; - casadi_real a11=arg[3] ? arg[3][2] : 0; - casadi_real a12=(a10-a11); - a12=(a0*a12); - casadi_real a13=arg[4] ? arg[4][2] : 0; - casadi_real a14=(a12*a13); - a5=(a5+a14); - a14=arg[0] ? arg[0][3] : 0; - casadi_real a15=arg[3] ? arg[3][3] : 0; - casadi_real a16=(a14-a15); - a16=(a0*a16); - casadi_real a17=arg[4] ? arg[4][3] : 0; - casadi_real a18=(a16*a17); - a5=(a5+a18); - a18=arg[1] ? arg[1][0] : 0; - casadi_real a19=arg[3] ? arg[3][4] : 0; - casadi_real a20=(a18-a19); - a20=(a0*a20); - casadi_real a21=arg[4] ? arg[4][4] : 0; - casadi_real a22=(a20*a21); - a5=(a5+a22); - a22=arg[4] ? arg[4][20] : 0; - a19=(a18-a19); - casadi_real a23=(a22*a19); - casadi_real a24=arg[4] ? arg[4][15] : 0; - a15=(a14-a15); - casadi_real a25=(a24*a15); - a23=(a23+a25); - a25=arg[4] ? arg[4][10] : 0; - a10=(a10-a11); - a11=(a25*a10); - a23=(a23+a11); - a11=arg[4] ? arg[4][5] : 0; - a7=(a6-a7); - casadi_real a26=(a11*a7); - a23=(a23+a26); + a3=(a3*a4); a1=(a1-a2); a4=(a4*a1); - a23=(a23+a4); - a23=(a0*a23); - a5=(a5+a23); - if (res[0]!=0) res[0][0]=a5; - a11=(a3*a11); - a5=arg[4] ? arg[4][6] : 0; - a23=(a8*a5); - a11=(a11+a23); - a23=arg[4] ? arg[4][7] : 0; - a4=(a12*a23); - a11=(a11+a4); - a4=arg[4] ? arg[4][8] : 0; - a2=(a16*a4); - a11=(a11+a2); - a2=arg[4] ? arg[4][9] : 0; - a26=(a20*a2); - a11=(a11+a26); - a26=arg[4] ? arg[4][21] : 0; - casadi_real a27=(a26*a19); - casadi_real a28=arg[4] ? arg[4][16] : 0; - casadi_real a29=(a28*a15); - a27=(a27+a29); - a29=arg[4] ? arg[4][11] : 0; - casadi_real a30=(a29*a10); - a27=(a27+a30); - a5=(a5*a7); - a27=(a27+a5); - a9=(a9*a1); - a27=(a27+a9); - a27=(a0*a27); - a11=(a11+a27); - if (res[0]!=0) res[0][1]=a11; - a25=(a3*a25); - a29=(a8*a29); - a25=(a25+a29); - a29=arg[4] ? arg[4][12] : 0; - a11=(a12*a29); - a25=(a25+a11); - a11=arg[4] ? arg[4][13] : 0; - a27=(a16*a11); - a25=(a25+a27); - a27=arg[4] ? arg[4][14] : 0; - a9=(a20*a27); - a25=(a25+a9); - a9=arg[4] ? arg[4][22] : 0; - a5=(a9*a19); - a30=arg[4] ? arg[4][17] : 0; - casadi_real a31=(a30*a15); - a5=(a5+a31); - a29=(a29*a10); - a5=(a5+a29); - a23=(a23*a7); - a5=(a5+a23); - a13=(a13*a1); - a5=(a5+a13); - a5=(a0*a5); - a25=(a25+a5); - if (res[0]!=0) res[0][2]=a25; - a24=(a3*a24); - a28=(a8*a28); - a24=(a24+a28); - a30=(a12*a30); - a24=(a24+a30); - a30=arg[4] ? arg[4][18] : 0; - a28=(a16*a30); - a24=(a24+a28); - a28=arg[4] ? arg[4][19] : 0; - a25=(a20*a28); - a24=(a24+a25); - a25=arg[4] ? arg[4][23] : 0; - a5=(a25*a19); - a30=(a30*a15); - a5=(a5+a30); - a11=(a11*a10); - a5=(a5+a11); - a4=(a4*a7); - a5=(a5+a4); - a17=(a17*a1); - a5=(a5+a17); + a4=(a0*a4); + a3=(a3+a4); + if (res[0]!=0) res[0][0]=a3; + a3=arg[0] ? arg[0][1] : 0; + a4=arg[3] ? arg[3][1] : 0; + a1=(a3-a4); + a1=(a0*a1); + a2=arg[4] ? arg[4][1] : 0; + a1=(a1*a2); + a4=(a3-a4); + a2=(a2*a4); + a2=(a0*a2); + a1=(a1+a2); + if (res[0]!=0) res[0][1]=a1; + a1=arg[0] ? arg[0][2] : 0; + a2=arg[3] ? arg[3][2] : 0; + a4=(a1-a2); + a4=(a0*a4); + casadi_real a5=arg[4] ? arg[4][2] : 0; + a4=(a4*a5); + a1=(a1-a2); + a5=(a5*a1); a5=(a0*a5); - a24=(a24+a5); - if (res[0]!=0) res[0][3]=a24; - a21=(a0*a21); - a1=(a1*a21); + a4=(a4+a5); + if (res[0]!=0) res[0][2]=a4; + a4=arg[0] ? arg[0][3] : 0; + a5=arg[3] ? arg[3][3] : 0; + a1=(a4-a5); + a1=(a0*a1); + a2=arg[4] ? arg[4][3] : 0; + a1=(a1*a2); + a5=(a4-a5); + a2=(a2*a5); a2=(a0*a2); - a7=(a7*a2); - a1=(a1+a7); - a27=(a0*a27); - a10=(a10*a27); - a1=(a1+a10); - a28=(a0*a28); - a15=(a15*a28); - a1=(a1+a15); - a15=arg[4] ? arg[4][24] : 0; - a0=(a0*a15); - a19=(a19*a0); - a3=(a3*a22); - a8=(a8*a26); - a3=(a3+a8); - a12=(a12*a9); - a3=(a3+a12); - a16=(a16*a25); - a3=(a3+a16); - a20=(a20*a15); - a3=(a3+a20); - a19=(a19+a3); - a1=(a1+a19); - if (res[0]!=0) res[0][4]=a1; - a1=arg[5] ? arg[5][0] : 0; - if (res[1]!=0) res[1][0]=a1; - a19=5.0000000000000003e-002; - a3=2.5000000000000001e-002; - a20=-8.0000000000000016e-002; - a15=(a3*a14); - a15=(a6+a15); - a16=cos(a15); - a16=(a20*a16); - a25=sin(a15); - a12=(a16*a25); - a9=cos(a6); - a9=(a20*a9); - a8=sin(a6); - a26=(a9*a8); - a22=sq(a14); - a0=(a26*a22); - a28=cos(a6); - a10=(a18*a28); - a0=(a0+a10); - a10=1.0791000000000002e+001; - a27=sin(a6); - a27=(a10*a27); - a0=(a0+a27); - a27=8.0000000000000004e-001; - a7=1.1000000000000001e+000; - a2=1.0000000000000001e-001; - a21=cos(a6); - a24=sq(a21); - a24=(a2*a24); - a24=(a7-a24); - a5=(a27*a24); - a0=(a0/a5); - a17=(a3*a0); - a17=(a14+a17); - a4=sq(a17); - a11=(a12*a4); - a30=cos(a15); - a13=(a18*a30); - a11=(a11+a13); - a13=sin(a15); - a13=(a10*a13); - a11=(a11+a13); - a13=cos(a15); - a23=sq(a13); - a23=(a2*a23); - a23=(a7-a23); - a29=(a27*a23); - a11=(a11/a29); - a31=(a3*a11); - a31=(a14+a31); - casadi_real a32=(a19*a31); - a32=(a6+a32); + a1=(a1+a2); + if (res[0]!=0) res[0][3]=a1; + a1=arg[1] ? arg[1][0] : 0; + a2=arg[3] ? arg[3][4] : 0; + a5=(a1-a2); + casadi_real a6=arg[4] ? arg[4][4] : 0; + casadi_real a7=(a0*a6); + a5=(a5*a7); + a2=(a1-a2); + a0=(a0*a2); + a0=(a0*a6); + a5=(a5+a0); + if (res[0]!=0) res[0][4]=a5; + a5=arg[5] ? arg[5][0] : 0; + if (res[1]!=0) res[1][0]=a5; + a0=5.0000000000000003e-02; + a6=2.5000000000000001e-02; + a2=-8.0000000000000016e-02; + a7=(a6*a4); + a7=(a3+a7); + casadi_real a8=cos(a7); + a8=(a2*a8); + casadi_real a9=sin(a7); + casadi_real a10=(a8*a9); + casadi_real a11=cos(a3); + a11=(a2*a11); + casadi_real a12=sin(a3); + casadi_real a13=(a11*a12); + casadi_real a14=sq(a4); + casadi_real a15=(a13*a14); + casadi_real a16=cos(a3); + casadi_real a17=(a1*a16); + a15=(a15+a17); + a17=1.0791000000000002e+01; + casadi_real a18=sin(a3); + a18=(a17*a18); + a15=(a15+a18); + a18=8.0000000000000004e-01; + casadi_real a19=1.1000000000000001e+00; + casadi_real a20=1.0000000000000001e-01; + casadi_real a21=cos(a3); + casadi_real a22=sq(a21); + a22=(a20*a22); + a22=(a19-a22); + casadi_real a23=(a18*a22); + a15=(a15/a23); + casadi_real a24=(a6*a15); + a24=(a4+a24); + casadi_real a25=sq(a24); + casadi_real a26=(a10*a25); + casadi_real a27=cos(a7); + casadi_real a28=(a1*a27); + a26=(a26+a28); + a28=sin(a7); + a28=(a17*a28); + a26=(a26+a28); + a28=cos(a7); + casadi_real a29=sq(a28); + a29=(a20*a29); + a29=(a19-a29); + casadi_real a30=(a18*a29); + a26=(a26/a30); + casadi_real a31=(a6*a26); + a31=(a4+a31); + casadi_real a32=(a0*a31); + a32=(a3+a32); casadi_real a33=cos(a32); - casadi_real a34=8.3333333333333332e-003; + casadi_real a34=8.3333333333333332e-03; casadi_real a35=arg[5] ? arg[5][3] : 0; casadi_real a36=(a34*a35); casadi_real a37=cos(a32); casadi_real a38=sq(a37); - a38=(a2*a38); - a38=(a7-a38); - casadi_real a39=(a27*a38); + a38=(a20*a38); + a38=(a19-a38); + casadi_real a39=(a18*a38); casadi_real a40=(a36/a39); - casadi_real a41=(a10*a40); + casadi_real a41=(a17*a40); a33=(a33*a41); a41=sin(a32); - casadi_real a42=(a18*a40); + casadi_real a42=(a1*a40); a41=(a41*a42); a33=(a33-a41); a41=cos(a32); a42=cos(a32); - a42=(a20*a42); - casadi_real a43=(a3*a17); - a43=(a6+a43); + a42=(a2*a42); + casadi_real a43=(a6*a24); + a43=(a3+a43); casadi_real a44=cos(a43); - a44=(a20*a44); + a44=(a2*a44); casadi_real a45=sin(a43); casadi_real a46=(a44*a45); casadi_real a47=sq(a31); casadi_real a48=(a46*a47); casadi_real a49=cos(a43); - casadi_real a50=(a18*a49); + casadi_real a50=(a1*a49); a48=(a48+a50); a50=sin(a43); - a50=(a10*a50); + a50=(a17*a50); a48=(a48+a50); a50=cos(a43); casadi_real a51=sq(a50); - a51=(a2*a51); - a7=(a7-a51); - a51=(a27*a7); + a51=(a20*a51); + a19=(a19-a51); + a51=(a18*a19); a48=(a48/a51); - casadi_real a52=(a19*a48); - a52=(a14+a52); + casadi_real a52=(a0*a48); + a52=(a4+a52); casadi_real a53=sq(a52); casadi_real a54=(a53*a40); casadi_real a55=(a42*a54); @@ -4333,7 +3728,7 @@ static int casadi_f21(const casadi_real** arg, casadi_real** res, int* iw, casad a41=sin(a32); a55=sin(a32); a54=(a55*a54); - a54=(a20*a54); + a54=(a2*a54); a41=(a41*a54); a33=(a33-a41); a41=sin(a32); @@ -4341,33 +3736,33 @@ static int casadi_f21(const casadi_real** arg, casadi_real** res, int* iw, casad a42=(a42*a55); a53=(a42*a53); a55=cos(a32); - a54=(a18*a55); + a54=(a1*a55); a53=(a53+a54); a54=sin(a32); - a54=(a10*a54); + a54=(a17*a54); a53=(a53+a54); a53=(a53/a39); a53=(a53/a39); a53=(a53*a36); - a53=(a27*a53); + a53=(a18*a53); a39=sin(a32); - a39=(a20*a39); + a39=(a2*a39); a54=sq(a52); casadi_real a56=(a39*a54); - casadi_real a57=9.8100000000000009e-001; + casadi_real a57=9.8100000000000009e-01; casadi_real a58=cos(a32); a58=(a57*a58); casadi_real a59=sin(a32); casadi_real a60=(a58*a59); a56=(a56+a60); - a56=(a56+a18); + a56=(a56+a1); a56=(a56/a38); a56=(a56/a38); a60=arg[5] ? arg[5][2] : 0; casadi_real a61=(a34*a60); a56=(a56*a61); a53=(a53+a56); - a53=(a2*a53); + a53=(a20*a53); a37=(a37*a53); a41=(a41*a37); a33=(a33-a41); @@ -4383,7 +3778,7 @@ static int casadi_f21(const casadi_real** arg, casadi_real** res, int* iw, casad a33=(a33-a41); a32=cos(a32); a54=(a54*a38); - a54=(a20*a54); + a54=(a2*a54); a32=(a32*a54); a33=(a33+a32); a32=arg[5] ? arg[5][1] : 0; @@ -4400,13 +3795,13 @@ static int casadi_f21(const casadi_real** arg, casadi_real** res, int* iw, casad a37=(a37+a52); a32=(a34*a32); a37=(a37+a32); - a52=(a19*a37); + a52=(a0*a37); a58=(a58+a52); a52=(a58/a51); - a39=(a10*a52); + a39=(a17*a52); a41=(a41*a39); a39=sin(a43); - a42=(a18*a52); + a42=(a1*a52); a39=(a39*a42); a41=(a41-a39); a39=cos(a43); @@ -4416,16 +3811,16 @@ static int casadi_f21(const casadi_real** arg, casadi_real** res, int* iw, casad a41=(a41+a39); a39=sin(a43); a45=(a45*a47); - a45=(a20*a45); + a45=(a2*a45); a39=(a39*a45); a41=(a41-a39); a39=sin(a43); a50=(a50+a50); a48=(a48/a51); a48=(a48*a58); - a48=(a27*a48); + a48=(a18*a48); a58=sin(a43); - a58=(a20*a58); + a58=(a2*a58); a51=sq(a31); a45=(a58*a51); a47=cos(a43); @@ -4433,21 +3828,21 @@ static int casadi_f21(const casadi_real** arg, casadi_real** res, int* iw, casad a44=sin(a43); a42=(a47*a44); a45=(a45+a42); - a45=(a45+a18); - a45=(a45/a7); - a45=(a45/a7); + a45=(a45+a1); + a45=(a45/a19); + a45=(a45/a19); a42=(a59*a61); - a34=(a34*a1); - a1=(a19*a34); - a42=(a42+a1); + a34=(a34*a5); + a5=(a0*a34); + a42=(a42+a5); a45=(a45*a42); a48=(a48+a45); - a48=(a2*a48); + a48=(a20*a48); a50=(a50*a48); a39=(a39*a50); a41=(a41-a39); a39=cos(a43); - a42=(a42/a7); + a42=(a42/a19); a47=(a47*a42); a39=(a39*a47); a41=(a41+a39); @@ -4458,158 +3853,158 @@ static int casadi_f21(const casadi_real** arg, casadi_real** res, int* iw, casad a41=(a41-a39); a43=cos(a43); a51=(a51*a42); - a51=(a20*a51); + a51=(a2*a51); a43=(a43*a51); a41=(a41+a43); a54=(a54+a41); - a43=cos(a6); + a43=cos(a3); a51=(a59*a32); - a39=(a17+a17); + a39=(a24+a24); a44=(a59*a36); - a19=(a19*a33); + a0=(a0*a33); a33=(a31+a31); a46=(a46*a52); a33=(a33*a46); - a19=(a19+a33); + a0=(a0+a33); a33=(a59*a32); - a19=(a19+a33); + a0=(a0+a33); a31=(a31+a31); a58=(a58*a42); a31=(a31*a58); - a19=(a19+a31); - a31=(a3*a19); + a0=(a0+a31); + a31=(a6*a0); a44=(a44+a31); - a31=(a44/a29); - a12=(a12*a31); - a39=(a39*a12); + a31=(a44/a30); + a10=(a10*a31); + a39=(a39*a10); a51=(a51+a39); - a41=(a3*a41); + a41=(a6*a41); a51=(a51+a41); - a41=(a17+a17); - a39=sin(a15); - a39=(a20*a39); - a12=(a59*a61); + a41=(a24+a24); + a39=sin(a7); + a39=(a2*a39); + a10=(a59*a61); a58=(a59*a34); - a33=(a3*a58); - a12=(a12+a33); - a33=(a12/a23); + a33=(a6*a58); + a10=(a10+a33); + a33=(a10/a29); a46=(a39*a33); a41=(a41*a46); a51=(a51+a41); - a41=(a3*a51); + a41=(a6*a51); a36=(a36+a41); - a41=(a36/a5); - a46=(a10*a41); + a41=(a36/a23); + a46=(a17*a41); a43=(a43*a46); a54=(a54+a43); - a43=sin(a6); - a46=(a18*a41); + a43=sin(a3); + a46=(a1*a41); a43=(a43*a46); a54=(a54-a43); - a43=cos(a6); - a22=(a22*a41); - a9=(a9*a22); - a43=(a43*a9); + a43=cos(a3); + a14=(a14*a41); + a11=(a11*a14); + a43=(a43*a11); a54=(a54+a43); - a43=sin(a6); - a8=(a8*a22); - a8=(a20*a8); - a43=(a43*a8); + a43=sin(a3); + a12=(a12*a14); + a12=(a2*a12); + a43=(a43*a12); a54=(a54-a43); - a43=cos(a15); - a10=(a10*a31); - a43=(a43*a10); - a10=sin(a15); - a8=(a18*a31); - a10=(a10*a8); - a43=(a43-a10); - a10=cos(a15); - a4=(a4*a31); - a16=(a16*a4); - a10=(a10*a16); - a43=(a43+a10); - a10=sin(a15); - a25=(a25*a4); - a25=(a20*a25); - a10=(a10*a25); - a43=(a43-a10); - a10=sin(a15); - a13=(a13+a13); - a11=(a11/a29); - a11=(a11*a44); - a11=(a27*a11); - a17=sq(a17); - a39=(a39*a17); - a44=cos(a15); + a43=cos(a7); + a17=(a17*a31); + a43=(a43*a17); + a17=sin(a7); + a12=(a1*a31); + a17=(a17*a12); + a43=(a43-a17); + a17=cos(a7); + a25=(a25*a31); + a8=(a8*a25); + a17=(a17*a8); + a43=(a43+a17); + a17=sin(a7); + a9=(a9*a25); + a9=(a2*a9); + a17=(a17*a9); + a43=(a43-a17); + a17=sin(a7); + a28=(a28+a28); + a26=(a26/a30); + a26=(a26*a44); + a26=(a18*a26); + a24=sq(a24); + a39=(a39*a24); + a44=cos(a7); a44=(a57*a44); - a29=sin(a15); - a25=(a44*a29); - a39=(a39+a25); - a39=(a39+a18); - a39=(a39/a23); - a39=(a39/a23); - a39=(a39*a12); - a11=(a11+a39); - a11=(a2*a11); - a13=(a13*a11); - a10=(a10*a13); - a43=(a43-a10); - a10=cos(a15); + a30=sin(a7); + a9=(a44*a30); + a39=(a39+a9); + a39=(a39+a1); + a39=(a39/a29); + a39=(a39/a29); + a39=(a39*a10); + a26=(a26+a39); + a26=(a20*a26); + a28=(a28*a26); + a17=(a17*a28); + a43=(a43-a17); + a17=cos(a7); a44=(a44*a33); - a10=(a10*a44); - a43=(a43+a10); - a10=sin(a15); - a29=(a29*a33); - a29=(a57*a29); - a10=(a10*a29); - a43=(a43-a10); - a15=cos(a15); - a17=(a17*a33); - a17=(a20*a17); - a15=(a15*a17); - a43=(a43+a15); + a17=(a17*a44); + a43=(a43+a17); + a17=sin(a7); + a30=(a30*a33); + a30=(a57*a30); + a17=(a17*a30); + a43=(a43-a17); + a7=cos(a7); + a24=(a24*a33); + a24=(a2*a24); + a7=(a7*a24); + a43=(a43+a7); a54=(a54+a43); - a15=sin(a6); + a7=sin(a3); a21=(a21+a21); - a0=(a0/a5); - a0=(a0*a36); - a27=(a27*a0); - a0=sin(a6); - a0=(a20*a0); - a36=sq(a14); - a5=(a0*a36); - a17=cos(a6); - a17=(a57*a17); - a10=sin(a6); - a29=(a17*a10); - a5=(a5+a29); - a5=(a5+a18); - a5=(a5/a24); - a5=(a5/a24); + a15=(a15/a23); + a15=(a15*a36); + a18=(a18*a15); + a15=sin(a3); + a15=(a2*a15); + a36=sq(a4); + a23=(a15*a36); + a24=cos(a3); + a24=(a57*a24); + a17=sin(a3); + a30=(a24*a17); + a23=(a23+a30); + a23=(a23+a1); + a23=(a23/a22); + a23=(a23/a22); a59=(a59*a34); - a18=(a3*a59); - a61=(a61+a18); - a5=(a5*a61); - a27=(a27+a5); - a2=(a2*a27); - a21=(a21*a2); - a15=(a15*a21); - a54=(a54-a15); - a15=cos(a6); - a61=(a61/a24); + a1=(a6*a59); + a61=(a61+a1); + a23=(a23*a61); + a18=(a18+a23); + a20=(a20*a18); + a21=(a21*a20); + a7=(a7*a21); + a54=(a54-a7); + a7=cos(a3); + a61=(a61/a22); + a24=(a24*a61); + a7=(a7*a24); + a54=(a54+a7); + a7=sin(a3); a17=(a17*a61); - a15=(a15*a17); - a54=(a54+a15); - a15=sin(a6); - a10=(a10*a61); - a57=(a57*a10); - a15=(a15*a57); - a54=(a54-a15); - a6=cos(a6); + a57=(a57*a17); + a7=(a7*a57); + a54=(a54-a7); + a3=cos(a3); a36=(a36*a61); - a20=(a20*a36); - a6=(a6*a20); - a54=(a54+a6); + a2=(a2*a36); + a3=(a3*a2); + a54=(a54+a3); if (res[1]!=0) res[1][1]=a54; a60=(a60+a34); a60=(a60+a58); @@ -4618,29 +4013,29 @@ static int casadi_f21(const casadi_real** arg, casadi_real** res, int* iw, casad if (res[1]!=0) res[1][2]=a60; a35=(a35+a37); a35=(a35+a32); - a35=(a35+a19); + a35=(a35+a0); a35=(a35+a51); - a51=(a14+a14); - a26=(a26*a41); - a51=(a51*a26); + a51=(a4+a4); + a13=(a13*a41); + a51=(a51*a13); a35=(a35+a51); - a3=(a3*a43); - a35=(a35+a3); - a14=(a14+a14); - a0=(a0*a61); - a14=(a14*a0); - a35=(a35+a14); + a6=(a6*a43); + a35=(a35+a6); + a4=(a4+a4); + a15=(a15*a61); + a4=(a4*a15); + a35=(a35+a4); if (res[1]!=0) res[1][3]=a35; a55=(a55*a40); a55=(a55+a38); a49=(a49*a52); a55=(a55+a49); a55=(a55+a42); - a30=(a30*a31); - a55=(a55+a30); + a27=(a27*a31); + a55=(a55+a27); a55=(a55+a33); - a28=(a28*a41); - a55=(a55+a28); + a16=(a16*a41); + a55=(a55+a16); a55=(a55+a61); if (res[1]!=0) res[1][4]=a55; return 0; @@ -4686,7 +4081,7 @@ CASADI_SYMBOL_EXPORT const int* adj_dG_fun_sparsity_in(int i) { case 1: return casadi_s1; case 2: return casadi_s2; case 3: return casadi_s4; - case 4: return casadi_s6; + case 4: return casadi_s4; case 5: return casadi_s0; default: return 0; } diff --git a/model/casadi_src.h b/model/casadi_src.h index 5d83d5e..d38005e 100644 --- a/model/casadi_src.h +++ b/model/casadi_src.h @@ -158,26 +158,26 @@ const char* gN_fun_name_out(int i); const int* gN_fun_sparsity_in(int i); const int* gN_fun_sparsity_out(int i); int gN_fun_work(int *sz_arg, int* sz_res, int *sz_iw, int *sz_w); -int Ji_fun(const casadi_real** arg, casadi_real** res, int* iw, casadi_real* w, void* mem); -void Ji_fun_incref(void); -void Ji_fun_decref(void); -int Ji_fun_n_out(void); -int Ji_fun_n_in(void); -const char* Ji_fun_name_in(int i); -const char* Ji_fun_name_out(int i); -const int* Ji_fun_sparsity_in(int i); -const int* Ji_fun_sparsity_out(int i); -int Ji_fun_work(int *sz_arg, int* sz_res, int *sz_iw, int *sz_w); -int JN_fun(const casadi_real** arg, casadi_real** res, int* iw, casadi_real* w, void* mem); -void JN_fun_incref(void); -void JN_fun_decref(void); -int JN_fun_n_out(void); -int JN_fun_n_in(void); -const char* JN_fun_name_in(int i); -const char* JN_fun_name_out(int i); -const int* JN_fun_sparsity_in(int i); -const int* JN_fun_sparsity_out(int i); -int JN_fun_work(int *sz_arg, int* sz_res, int *sz_iw, int *sz_w); +int Hi_fun(const casadi_real** arg, casadi_real** res, int* iw, casadi_real* w, void* mem); +void Hi_fun_incref(void); +void Hi_fun_decref(void); +int Hi_fun_n_out(void); +int Hi_fun_n_in(void); +const char* Hi_fun_name_in(int i); +const char* Hi_fun_name_out(int i); +const int* Hi_fun_sparsity_in(int i); +const int* Hi_fun_sparsity_out(int i); +int Hi_fun_work(int *sz_arg, int* sz_res, int *sz_iw, int *sz_w); +int HN_fun(const casadi_real** arg, casadi_real** res, int* iw, casadi_real* w, void* mem); +void HN_fun_incref(void); +void HN_fun_decref(void); +int HN_fun_n_out(void); +int HN_fun_n_in(void); +const char* HN_fun_name_in(int i); +const char* HN_fun_name_out(int i); +const int* HN_fun_sparsity_in(int i); +const int* HN_fun_sparsity_out(int i); +int HN_fun_work(int *sz_arg, int* sz_res, int *sz_iw, int *sz_w); int Ci_fun(const casadi_real** arg, casadi_real** res, int* iw, casadi_real* w, void* mem); void Ci_fun_incref(void); void Ci_fun_decref(void); diff --git a/src/casadi_wrapper.cpp b/src/casadi_wrapper.cpp index dfb6458..f13b452 100644 --- a/src/casadi_wrapper.cpp +++ b/src/casadi_wrapper.cpp @@ -6,9 +6,9 @@ void f_Fun(double **in, double **out){ const double *x = in[0]; const double *u = in[1]; const double *p = in[2]; - + double *xn = out[0]; - + void *casadi_mem = NULL; int *casadi_iw = NULL; double *casadi_w = NULL; @@ -31,10 +31,10 @@ void vde_Fun(double **in, double **out){ const double *p = in[2]; const double *Sx = in[3]; const double *Su = in[4]; - + double *jac_x = out[0]; double *jac_u = out[1]; - + void *casadi_mem = NULL; int *casadi_iw = NULL; double *casadi_w = NULL; @@ -59,9 +59,9 @@ void impl_f_Fun(double **in, double **out){ const double *u = in[1]; const double *p = in[2]; const double *xdot = in[3]; - + double *res = out[0]; - + void *casadi_mem = NULL; int *casadi_iw = NULL; double *casadi_w = NULL; @@ -75,7 +75,7 @@ void impl_f_Fun(double **in, double **out){ casadi_arg[3] = xdot; casadi_res[0] = res; - + impl_f_fun(casadi_arg, casadi_res, casadi_iw, casadi_w, casadi_mem); } @@ -84,9 +84,9 @@ void impl_jac_x_Fun(double **in, double **out){ const double *u = in[1]; const double *p = in[2]; const double *xdot = in[3]; - + double *jac_x = out[0]; - + void *casadi_mem = NULL; int *casadi_iw = NULL; double *casadi_w = NULL; @@ -98,9 +98,9 @@ void impl_jac_x_Fun(double **in, double **out){ casadi_arg[1] = u; casadi_arg[2] = p; casadi_arg[3] = xdot; - + casadi_res[0] = jac_x; - + impl_jac_x_fun(casadi_arg, casadi_res, casadi_iw, casadi_w, casadi_mem); } @@ -109,9 +109,9 @@ void impl_jac_u_Fun(double **in, double **out){ const double *u = in[1]; const double *p = in[2]; const double *xdot = in[3]; - + double *jac_u = out[0]; - + void *casadi_mem = NULL; int *casadi_iw = NULL; double *casadi_w = NULL; @@ -134,9 +134,9 @@ void impl_jac_xdot_Fun(double **in, double **out){ const double *u = in[1]; const double *p = in[2]; const double *xdot = in[3]; - + double *jac_xdot = out[0]; - + void *casadi_mem = NULL; int *casadi_iw = NULL; double *casadi_w = NULL; @@ -179,7 +179,7 @@ void F_Fun(double **in, double **out) { } void D_Fun(double **in, double **out) { - + const double *xi = in[0]; const double *ui = in[1]; const double *parai = in[2]; @@ -204,22 +204,23 @@ void D_Fun(double **in, double **out) { D(casadi_arg, casadi_res, casadi_iw, casadi_w, casadi_mem); } -void Ji_Fun(double **in, double **out) { +void Hi_Fun(double **in, double **out) { const double *xi = in[0]; const double *ui = in[1]; const double *parai = in[2]; const double *refi = in[3]; const double *Qi = in[4]; - double *Jx = out[0]; - double *Ju = out[1]; + double *Hx = out[0]; + double *Hu = out[1]; + double *Hxu = out[2]; void *casadi_mem = NULL; int *casadi_iw = NULL; double *casadi_w = NULL; const double *casadi_arg[5]; - double *casadi_res[2]; + double *casadi_res[3]; casadi_arg[0] = xi; casadi_arg[1] = ui; @@ -227,10 +228,36 @@ void Ji_Fun(double **in, double **out) { casadi_arg[3] = refi; casadi_arg[4] = Qi; - casadi_res[0] = Jx; - casadi_res[1] = Ju; + casadi_res[0] = Hx; + casadi_res[1] = Hu; + casadi_res[2] = Hxu; + + Hi_fun(casadi_arg, casadi_res, casadi_iw, casadi_w, casadi_mem); +} + +void HN_Fun(double **in, double **out) { + const double *xN = in[0]; + const double *paraN = in[1] ; + const double *refN = in[2]; + const double *QN = in[3]; + + double *HN = out[0]; + + void *casadi_mem = NULL; + int *casadi_iw = NULL; + double *casadi_w = NULL; + + const double *casadi_arg[4]; + double *casadi_res[1]; + + casadi_arg[0] = xN; + casadi_arg[1] = paraN; + casadi_arg[2] = refN; + casadi_arg[3] = QN; + + casadi_res[0] = HN; - Ji_fun(casadi_arg, casadi_res, casadi_iw, casadi_w, casadi_mem); + HN_fun(casadi_arg, casadi_res, casadi_iw, casadi_w, casadi_mem); } void gi_Fun(double **in, double **out) { @@ -268,7 +295,7 @@ void path_con_Fun(double **in, double **out) { const double *xi = in[0]; const double *ui = in[1]; const double *parai = in[2]; - + double *ci = out[0]; void *casadi_mem = NULL; @@ -281,7 +308,7 @@ void path_con_Fun(double **in, double **out) { casadi_arg[0] = xi; casadi_arg[1] = ui; casadi_arg[2] = parai; - + casadi_res[0] = ci; path_con_fun(casadi_arg, casadi_res, casadi_iw, casadi_w, casadi_mem); @@ -312,31 +339,6 @@ void Ci_Fun(double **in, double **out) { Ci_fun(casadi_arg, casadi_res, casadi_iw, casadi_w, casadi_mem); } -void JN_Fun(double **in, double **out) { - const double *xN = in[0]; - const double *paraN = in[1] ; - const double *refN = in[2]; - const double *QN = in[3]; - - double *JxN = out[0]; - - void *casadi_mem = NULL; - int *casadi_iw = NULL; - double *casadi_w = NULL; - - const double *casadi_arg[4]; - double *casadi_res[1]; - - casadi_arg[0] = xN; - casadi_arg[1] = paraN; - casadi_arg[2] = refN; - casadi_arg[3] = QN; - - casadi_res[0] = JxN; - - JN_fun(casadi_arg, casadi_res, casadi_iw, casadi_w, casadi_mem); -} - void gN_Fun(double **in, double **out) { const double *xN = in[0]; @@ -367,7 +369,7 @@ void path_con_N_Fun(double **in, double **out) { const double *xN = in[0]; const double *paraN = in[1]; - + double *cN = out[0]; void *casadi_mem = NULL; @@ -379,14 +381,14 @@ void path_con_N_Fun(double **in, double **out) { casadi_arg[0] = xN; casadi_arg[1] = paraN; - + casadi_res[0] = cN; path_con_N_fun(casadi_arg, casadi_res, casadi_iw, casadi_w, casadi_mem); } void CN_Fun(double **in, double **out) { - + const double *xN = in[0]; const double *paraN = in[1]; diff --git a/src/full_condensing.cpp b/src/full_condensing.cpp index cda67d0..74f665e 100644 --- a/src/full_condensing.cpp +++ b/src/full_condensing.cpp @@ -34,7 +34,7 @@ full_condensing_workspace& full_condensing_workspace::full_condensing(model_size int nbgN = size.nbgN; int N = size.N; - int idx = N*nbg+nbgN; + int idx = N*nbg+nbgN; int i,j; @@ -48,8 +48,8 @@ full_condensing_workspace& full_condensing_workspace::full_condensing(model_size /* Compute Hc */ for(i=0;ii;j--){ - Hc.block(j*nu,i*nu,nu,nu) = qp.data.S.block(0,j*nu,nx,nu).transpose() * G.block((j-1)*nx,i*nu,nx,nu) + qp.data.B.block(0,j*nu,nx,nu).transpose() * W; + for(j=N-1;j>i;j--){ + Hc.block(j*nu,i*nu,nu,nu) = qp.data.S.block(0,j*nu,nx,nu).transpose() * G.block((j-1)*nx,i*nu,nx,nu) + qp.data.B.block(0,j*nu,nx,nu).transpose() * W; W = qp.data.Q.block(0,j*nx,nx,nx) * G.block((j-1)*nx,i*nu,nx,nu) + qp.data.A.block(0,j*nx,nx,nx).transpose() * W; Hc.block(i*nu,j*nu,nu,nu) = Hc.block(j*nu,i*nu,nu,nu).transpose(); } @@ -57,28 +57,28 @@ full_condensing_workspace& full_condensing_workspace::full_condensing(model_size } /* Compute Ccg */ - if (nbg>0){ + if (nbg>0){ for(i=0;i0){ - for(i=0;i0){ + for(i=0;i0){ + if (nbx>0){ for(i=0;i0){ + if (nbg>0){ for(i=0;i0){ + if (nbgN>0){ lcc.segment(N*nbg,nbgN) = qp.data.CgN * L.tail(nx); - ucc.segment(N*nbg,nbgN) = qp.data.ub_g.segment(N*nbg,nbgN) - lcc.segment(N*nbg,nbgN); - lcc.segment(N*nbg,nbgN) = qp.data.lb_g.segment(N*nbg,nbgN) - lcc.segment(N*nbg,nbgN); + ucc.segment(N*nbg,nbgN) = qp.data.ub_u.segment(N*nbg,nbgN) - lcc.segment(N*nbg,nbgN); + lcc.segment(N*nbg,nbgN) = qp.data.lb_u.segment(N*nbg,nbgN) - lcc.segment(N*nbg,nbgN); } - - if (nbx>0){ + /* Compute ccx */ + if (nbx>0){ for(i=0;i -#include +#include #include "mpc_common.hpp" #include "qp_problem.hpp" #include "casadi_wrapper.hpp" @@ -20,14 +19,14 @@ qp_in& qp_in::init(model_size& size) int nbg = size.nbg; int nbgN = size.nbgN; int N = size.N; - + x = MatrixXd::Zero(nx,N+1); u = MatrixXd::Zero(nu,N); y = MatrixXd::Zero(ny,N); yN = VectorXd::Zero(nyN); p = MatrixXd::Zero(np,N+1); - W = MatrixXd::Zero(ny,ny); - WN = MatrixXd::Zero(nyN,nyN); + W = MatrixXd::Zero(ny,N); + WN = VectorXd::Zero(nyN); lbu = VectorXd::Zero(nbu); ubu = VectorXd::Zero(nbu); lbx = VectorXd::Zero(nbx); @@ -45,25 +44,26 @@ qp_data& qp_data::init(model_size& size) int nx=size.nx; int nu=size.nu; int nbx = size.nbx; + int nbu = size.nbu; int nbg = size.nbg; int nbgN = size.nbgN; int N = size.N; - int *nbx_idx = size.nbx_idx; + int* nbx_idx = size.nbx_idx; Q = MatrixXd::Zero(nx,(N+1)*nx); S = MatrixXd::Zero(nx,N*nu); R = MatrixXd::Zero(nu,N*nu); A = MatrixXd::Zero(nx,N*nx); B = MatrixXd::Zero(nx,N*nu); - a = MatrixXd::Zero(nx,N); Cx = MatrixXd::Zero(nbx,nx); Cgx = MatrixXd::Zero(nbg,N*nx); - CgN = MatrixXd::Zero(nbgN,nx); Cgu = MatrixXd::Zero(nbg,N*nu); + CgN = MatrixXd::Zero(nbgN,nx); gx = MatrixXd::Zero(nx,N+1); gu = MatrixXd::Zero(nu,N); - lb_u = VectorXd::Zero(N*nu); - ub_u = VectorXd::Zero(N*nu); + a = MatrixXd::Zero(nx,N); + lb_u = VectorXd::Zero(N*nbu); + ub_u = VectorXd::Zero(N*nbu); lb_x = VectorXd::Zero(N*nbx); ub_x = VectorXd::Zero(N*nbx); lb_g = VectorXd::Zero(nbg*N+nbgN); @@ -77,34 +77,19 @@ qp_data& qp_data::init(model_size& size) } -qp_workspace& qp_workspace::init(model_size& size) -{ - int nx=size.nx; - int nu=size.nu; - int ny=size.ny; - int nyN=size.nyN; - - Jx = MatrixXd::Zero(ny,nx); - Ju = MatrixXd::Zero(ny,nu); - JxN = MatrixXd::Zero(nyN,nx); - - return *this; - -} - qp_out& qp_out::init(model_size& size) { int nx=size.nx; - int nu=size.nu; + int nu=size.nu; int nbg=size.nbg; - int nbgN=size.nbgN; + int nbgN=size.nbgN; int N = size.N; int nbx = size.nbx; dx = MatrixXd::Zero(nx,N+1); du = MatrixXd::Zero(nu,N); lam = MatrixXd::Zero(nx,N+1); - mu_u = VectorXd::Zero(N*nu); + mu_u = VectorXd::Zero(N*nu); mu_x = VectorXd::Zero(N*nbx); mu_g = VectorXd::Zero(nbg*N+nbgN); @@ -116,7 +101,6 @@ qp_problem& qp_problem::init(model_size& size) { in.init(size); data.init(size); - work.init(size); out.init(size); return *this; @@ -129,91 +113,90 @@ qp_problem& qp_problem::generateQP(model_size& size) int ny = size.ny; int np = size.np; int nbx = size.nbx; + int nbu = size.nbu; int nbg = size.nbg; int nbgN = size.nbgN; int N = size.N; - int *nbx_idx = size.nbx_idx; - - int i=0,j=0; + int* nbx_idx = size.nbx_idx; + int* nbu_idx = size.nbu_idx; - // allocate array of pointers + int i, j; + + // allocate array of pointers double *casadi_in[5]; - double *casadi_out[2]; - casadi_in[4] = in.W.data(); - + double *casadi_out[3]; + // start loop - for(i=0;i0){ + //constraints + if (nbg > 0) + { casadi_out[0] = data.lb_g.data() + i*nbg; path_con_Fun(casadi_in, casadi_out); // constraint residual data.ub_g.segment(i*nbg,nbg) = in.ubg - data.lb_g.segment(i*nbg,nbg); data.lb_g.segment(i*nbg,nbg) = in.lbg - data.lb_g.segment(i*nbg,nbg); - + // constraint Jacobian casadi_out[0] = data.Cgx.data()+i*nbg*nx; casadi_out[1] = data.Cgu.data()+i*nbg*nu; Ci_Fun(casadi_in, casadi_out); } } - // the terminal stage casadi_in[0] = in.x.data()+N*nx; casadi_in[1] = in.p.data()+N*np; casadi_in[2] = in.yN.data(); casadi_in[3] = in.WN.data(); - - casadi_out[0] = work.JxN.data(); - JN_Fun(casadi_in, casadi_out); - data.Q.block(0,N*nx,nx,nx) = work.JxN.transpose() * work.JxN; - + casadi_out[0] = data.Q.data()+N*nx*nx; + HN_Fun(casadi_in, casadi_out); + regularization(nx, data.Q.data()+N*nx*nx, in.reg); + casadi_out[0] = data.gx.data()+N*nx; gN_Fun(casadi_in, casadi_out); - if (nbgN>0){ + if (nbgN > 0) + { casadi_out[0] = data.lb_g.data() + N*nbg; path_con_N_Fun(casadi_in, casadi_out); data.ub_g.segment(N*nbg,nbgN) = in.ubgN - data.lb_g.segment(N*nbg,nbgN); @@ -224,26 +207,54 @@ qp_problem& qp_problem::generateQP(model_size& size) } return *this; - } qp_problem& qp_problem::expandSol(model_size& size, VectorXd& x0) - { +{ int nx = size.nx; int nu = size.nu; int N = size.N; - int i; out.dx.col(0) = x0 - in.x.col(0); - for(i=0;i #include "mpc_common.hpp" #include "qp_problem.hpp" #include "full_condensing.hpp" #include "qpsolver.hpp" #include -USING_NAMESPACE_QPOASES - using namespace std; qpoases_workspace& qpoases_workspace::init(model_size& size) { - int nu=size.nu; - int nbg=size.nbg; - int nbgN=size.nbgN; + int nu = size.nu; + int nbg = size.nbg; + int nbgN = size.nbgN; int N = size.N; int nbx = size.nbx; @@ -28,9 +25,9 @@ qpoases_workspace& qpoases_workspace::init(model_size& size) void qpoases_workspace::solveQP(model_size& size, qp_problem& qp, full_condensing_workspace& cond_work, int sample) { - int nu=size.nu; - int nbg=size.nbg; - int nbgN=size.nbgN; + int nu = size.nu; + int nbg = size.nbg; + int nbgN = size.nbgN; int N = size.N; int nbx = size.nbx; @@ -48,7 +45,6 @@ void qpoases_workspace::solveQP(model_size& size, qp_problem& qp, full_condensin memcpy(qp.out.mu_u.data(),yOpt,N*nu*sizeof(double)); memcpy(qp.out.mu_g.data(),yOpt+N*nu,(N*nbg+nbgN)*sizeof(double)); memcpy(qp.out.mu_x.data(),yOpt+N*nu+N*nbg+nbgN,N*nbx*sizeof(double)); - } qpoases_workspace& qpoases_workspace::free() @@ -57,4 +53,4 @@ qpoases_workspace& qpoases_workspace::free() delete myOptions; return *this; -} \ No newline at end of file +} diff --git a/src/rti_step.cpp b/src/rti_step.cpp index d199824..d345719 100644 --- a/src/rti_step.cpp +++ b/src/rti_step.cpp @@ -4,6 +4,7 @@ #include "qpsolver.hpp" #include "rti_step.hpp" #include "Timer.h" +#include rti_step_workspace& rti_step_workspace::init(model_size& usr_size) { @@ -12,14 +13,13 @@ rti_step_workspace& rti_step_workspace::init(model_size& usr_size) cond_work.init(size); qpoases_work.init(size); x0 = VectorXd::Zero(size.nx); - return *this; } + rti_step_workspace& rti_step_workspace::step() { - timer.start(); - + timer.start(); QP.generateQP(size); cond_work.full_condensing(size, QP, x0); @@ -28,10 +28,9 @@ rti_step_workspace& rti_step_workspace::step() QP.expandSol(size, x0); - timer.stop(); - CPT = timer.getElapsedTimeInMilliSec(); + CPT = timer.getElapsedTimeInMilliSec(); - return *this; + return *this; } rti_step_workspace& rti_step_workspace::free() @@ -39,4 +38,11 @@ rti_step_workspace& rti_step_workspace::free() qpoases_work.free(); return *this; -} \ No newline at end of file +} + +rti_step_workspace& rti_step_workspace::info() +{ + OBJ = 0; + QP.info(size,OBJ); + return *this; +} From fd0bc1aefb0e662f1bd8b593edcf8174cdfb5230 Mon Sep 17 00:00:00 2001 From: Sedith Date: Thu, 19 Mar 2020 20:29:15 +0100 Subject: [PATCH 2/3] revert changes commited to full_condensing.cpp file contained wrong changes, was commited by mistake ; add change Ts in InvertedPendulum.cpp to allow more shooting points --- examples/InvertedPendulum.cpp | 2 +- src/full_condensing.cpp | 67 +++++++++++++++++++---------------- 2 files changed, 37 insertions(+), 32 deletions(-) diff --git a/examples/InvertedPendulum.cpp b/examples/InvertedPendulum.cpp index bc42f20..0514f9a 100644 --- a/examples/InvertedPendulum.cpp +++ b/examples/InvertedPendulum.cpp @@ -56,7 +56,7 @@ int main() // prepare the closed-loop simulation rti_work.sample = 0; - double Tf=4, Ts=0.05,t=0; + double Tf=4, Ts=0.025,t=0; double *simu_in[3]; double *simu_out[1]; diff --git a/src/full_condensing.cpp b/src/full_condensing.cpp index 74f665e..fdcd42f 100644 --- a/src/full_condensing.cpp +++ b/src/full_condensing.cpp @@ -1,5 +1,3 @@ -#include "mpc_common.hpp" -#include "qp_problem.hpp" #include "full_condensing.hpp" full_condensing_workspace& full_condensing_workspace::init(model_size& size) @@ -36,19 +34,22 @@ full_condensing_workspace& full_condensing_workspace::full_condensing(model_size int idx = N*nbg+nbgN; - int i,j; + int i, j; /* compute G */ - for(i=0;ii;j--){ + for (j=N-1; j>i; j--) + { Hc.block(j*nu,i*nu,nu,nu) = qp.data.S.block(0,j*nu,nx,nu).transpose() * G.block((j-1)*nx,i*nu,nx,nu) + qp.data.B.block(0,j*nu,nx,nu).transpose() * W; W = qp.data.Q.block(0,j*nx,nx,nx) * G.block((j-1)*nx,i*nu,nx,nu) + qp.data.A.block(0,j*nx,nx,nx).transpose() * W; Hc.block(i*nu,j*nu,nu,nu) = Hc.block(j*nu,i*nu,nu,nu).transpose(); @@ -57,66 +58,70 @@ full_condensing_workspace& full_condensing_workspace::full_condensing(model_size } /* Compute Ccg */ - if (nbg>0){ - for(i=0;i 0) + for (i=0; i0){ - for(i=0;i 0) + for (i=0; i0){ - for(i=0;i 0) + for (i=0; i0;i--){ + for (i=N-1; i>0; i--) + { gc.segment(i*nu,nu) = qp.data.gu.col(i) + qp.data.S.block(0,i*nu,nx,nu).transpose()*L.segment(i*nx,nx) + qp.data.B.block(0,i*nu,nx,nu).transpose()*w; w = qp.data.gx.col(i) + qp.data.Q.block(0,i*nx,nx,nx)*L.segment(i*nx,nx) + qp.data.A.block(0,i*nx,nx,nx).transpose()*w; } gc.head(nu) = qp.data.gu.col(0) + qp.data.S.leftCols(nu).transpose()*L.head(nx) + qp.data.B.leftCols(nu).transpose()*w; /* Compute cc */ - if (nbg>0){ - for(i=0;i 0) + for (i=0; i0){ + if (nbgN > 0) + { lcc.segment(N*nbg,nbgN) = qp.data.CgN * L.tail(nx); - ucc.segment(N*nbg,nbgN) = qp.data.ub_u.segment(N*nbg,nbgN) - lcc.segment(N*nbg,nbgN); - lcc.segment(N*nbg,nbgN) = qp.data.lb_u.segment(N*nbg,nbgN) - lcc.segment(N*nbg,nbgN); + ucc.segment(N*nbg,nbgN) = qp.data.ub_g.segment(N*nbg,nbgN) - lcc.segment(N*nbg,nbgN); + lcc.segment(N*nbg,nbgN) = qp.data.lb_g.segment(N*nbg,nbgN) - lcc.segment(N*nbg,nbgN); } - /* Compute ccx */ - if (nbx>0){ - for(i=0;i 0) + for (i=0; i Date: Fri, 27 Mar 2020 20:05:10 +0100 Subject: [PATCH 3/3] update casadi wrapper and remove addition of use of nbu in qp_problem casadi 3.5 uses int for mem and long longint for iw ; remove use of nbu, nbu_idx in qp_problem, the non-constrained inputs have to be ficticiously constrained between -inf,inf before passing to the solver --- examples/InvertedPendulum.cpp | 2 +- model/casadi_src.cpp | 8739 +++++++++++++++++---------------- model/casadi_src.h | 595 ++- src/casadi_wrapper.cpp | 80 +- src/qp_problem.cpp | 18 +- 5 files changed, 5040 insertions(+), 4394 deletions(-) diff --git a/examples/InvertedPendulum.cpp b/examples/InvertedPendulum.cpp index 0514f9a..bc42f20 100644 --- a/examples/InvertedPendulum.cpp +++ b/examples/InvertedPendulum.cpp @@ -56,7 +56,7 @@ int main() // prepare the closed-loop simulation rti_work.sample = 0; - double Tf=4, Ts=0.025,t=0; + double Tf=4, Ts=0.05,t=0; double *simu_in[3]; double *simu_out[1]; diff --git a/model/casadi_src.cpp b/model/casadi_src.cpp index 39e259e..c126a54 100644 --- a/model/casadi_src.cpp +++ b/model/casadi_src.cpp @@ -1,4109 +1,4630 @@ -/* This file was automatically generated by CasADi. - The CasADi copyright holders make no ownership claim of its contents. */ -#ifdef __cplusplus -extern "C" { -#endif - -/* How to prefix internal symbols */ -#ifdef CODEGEN_PREFIX - #define NAMESPACE_CONCAT(NS, ID) _NAMESPACE_CONCAT(NS, ID) - #define _NAMESPACE_CONCAT(NS, ID) NS ## ID - #define CASADI_PREFIX(ID) NAMESPACE_CONCAT(CODEGEN_PREFIX, ID) -#else - #define CASADI_PREFIX(ID) casadi_src_ ## ID -#endif - -#include - -#ifndef casadi_real -#define casadi_real double -#endif - -#define to_double(x) (double) x -#define to_int(x) (int) x -#define CASADI_CAST(x,y) (x) y - -/* Pre-c99 compatibility */ -#if __STDC_VERSION__ < 199901L - #define fmin CASADI_PREFIX(fmin) - casadi_real fmin(casadi_real x, casadi_real y) { return xy ? x : y;} -#endif - -/* CasADi extensions */ -#define sq CASADI_PREFIX(sq) -casadi_real sq(casadi_real x) { return x*x;} -#define sign CASADI_PREFIX(sign) -casadi_real CASADI_PREFIX(sign)(casadi_real x) { return x<0 ? -1 : x>0 ? 1 : x;} -#define twice CASADI_PREFIX(twice) -casadi_real twice(casadi_real x) { return x+x;} -#define if_else CASADI_PREFIX(if_else) -casadi_real if_else(casadi_real c, casadi_real x, casadi_real y) { return c!=0 ? x : y;} - -/* Add prefix to internal symbols */ -#define casadi_f0 CASADI_PREFIX(f0) -#define casadi_f1 CASADI_PREFIX(f1) -#define casadi_f10 CASADI_PREFIX(f10) -#define casadi_f11 CASADI_PREFIX(f11) -#define casadi_f12 CASADI_PREFIX(f12) -#define casadi_f13 CASADI_PREFIX(f13) -#define casadi_f14 CASADI_PREFIX(f14) -#define casadi_f15 CASADI_PREFIX(f15) -#define casadi_f16 CASADI_PREFIX(f16) -#define casadi_f17 CASADI_PREFIX(f17) -#define casadi_f18 CASADI_PREFIX(f18) -#define casadi_f19 CASADI_PREFIX(f19) -#define casadi_f2 CASADI_PREFIX(f2) -#define casadi_f20 CASADI_PREFIX(f20) -#define casadi_f21 CASADI_PREFIX(f21) -#define casadi_f3 CASADI_PREFIX(f3) -#define casadi_f4 CASADI_PREFIX(f4) -#define casadi_f5 CASADI_PREFIX(f5) -#define casadi_f6 CASADI_PREFIX(f6) -#define casadi_f7 CASADI_PREFIX(f7) -#define casadi_f8 CASADI_PREFIX(f8) -#define casadi_f9 CASADI_PREFIX(f9) -#define casadi_s0 CASADI_PREFIX(s0) -#define casadi_s1 CASADI_PREFIX(s1) -#define casadi_s2 CASADI_PREFIX(s2) -#define casadi_s3 CASADI_PREFIX(s3) -#define casadi_s4 CASADI_PREFIX(s4) -#define casadi_s5 CASADI_PREFIX(s5) -#define casadi_s6 CASADI_PREFIX(s6) - -/* Printing routine */ -#define PRINTF printf - -/* Symbol visibility in DLLs */ -#ifndef CASADI_SYMBOL_EXPORT - #if defined(_WIN32) || defined(__WIN32__) || defined(__CYGWIN__) - #if defined(STATIC_LINKED) - #define CASADI_SYMBOL_EXPORT - #else - #define CASADI_SYMBOL_EXPORT __declspec(dllexport) - #endif - #elif defined(__GNUC__) && defined(GCC_HASCLASSVISIBILITY) - #define CASADI_SYMBOL_EXPORT __attribute__ ((visibility ("default"))) - #else - #define CASADI_SYMBOL_EXPORT - #endif -#endif - -static const int casadi_s0[8] = {4, 1, 0, 4, 0, 1, 2, 3}; -static const int casadi_s1[5] = {1, 1, 0, 1, 0}; -static const int casadi_s2[4] = {0, 1, 0, 0}; -static const int casadi_s3[23] = {4, 4, 0, 4, 8, 12, 16, 0, 1, 2, 3, 0, 1, 2, 3, 0, 1, 2, 3, 0, 1, 2, 3}; -static const int casadi_s4[9] = {5, 1, 0, 5, 0, 1, 2, 3, 4}; -static const int casadi_s5[3] = {0, 0, 0}; -static const int casadi_s6[7] = {0, 4, 0, 0, 0, 0, 0}; - -/* f_fun:(states[4],controls,params[0])->(xdot[4]) */ -static int casadi_f0(const casadi_real** arg, casadi_real** res, int* iw, casadi_real* w, void* mem) { - casadi_real a0=arg[0] ? arg[0][2] : 0; - if (res[0]!=0) res[0][0]=a0; - a0=arg[0] ? arg[0][3] : 0; - if (res[0]!=0) res[0][1]=a0; - casadi_real a1=-8.0000000000000016e-02; - casadi_real a2=arg[0] ? arg[0][1] : 0; - casadi_real a3=sin(a2); - a3=(a1*a3); - casadi_real a4=sq(a0); - a3=(a3*a4); - a4=9.8100000000000009e-01; - casadi_real a5=cos(a2); - a4=(a4*a5); - a5=sin(a2); - a4=(a4*a5); - a3=(a3+a4); - a4=arg[1] ? arg[1][0] : 0; - a3=(a3+a4); - a5=1.1000000000000001e+00; - casadi_real a6=1.0000000000000001e-01; - casadi_real a7=cos(a2); - a7=sq(a7); - a6=(a6*a7); - a5=(a5-a6); - a3=(a3/a5); - if (res[0]!=0) res[0][2]=a3; - a3=cos(a2); - a1=(a1*a3); - a3=sin(a2); - a1=(a1*a3); - a0=sq(a0); - a1=(a1*a0); - a0=cos(a2); - a4=(a4*a0); - a1=(a1+a4); - a4=1.0791000000000002e+01; - a2=sin(a2); - a4=(a4*a2); - a1=(a1+a4); - a4=8.0000000000000004e-01; - a4=(a4*a5); - a1=(a1/a4); - if (res[0]!=0) res[0][3]=a1; - return 0; -} - -CASADI_SYMBOL_EXPORT int f_fun(const casadi_real** arg, casadi_real** res, int* iw, casadi_real* w, void* mem){ - return casadi_f0(arg, res, iw, w, mem); -} - -CASADI_SYMBOL_EXPORT void f_fun_incref(void) { -} - -CASADI_SYMBOL_EXPORT void f_fun_decref(void) { -} - -CASADI_SYMBOL_EXPORT int f_fun_n_in(void) { return 3;} - -CASADI_SYMBOL_EXPORT int f_fun_n_out(void) { return 1;} - -CASADI_SYMBOL_EXPORT const char* f_fun_name_in(int i){ - switch (i) { - case 0: return "states"; - case 1: return "controls"; - case 2: return "params"; - default: return 0; - } -} - -CASADI_SYMBOL_EXPORT const char* f_fun_name_out(int i){ - switch (i) { - case 0: return "xdot"; - default: return 0; - } -} - -CASADI_SYMBOL_EXPORT const int* f_fun_sparsity_in(int i) { - switch (i) { - case 0: return casadi_s0; - case 1: return casadi_s1; - case 2: return casadi_s2; - default: return 0; - } -} - -CASADI_SYMBOL_EXPORT const int* f_fun_sparsity_out(int i) { - switch (i) { - case 0: return casadi_s0; - default: return 0; - } -} - -CASADI_SYMBOL_EXPORT int f_fun_work(int *sz_arg, int* sz_res, int *sz_iw, int *sz_w) { - if (sz_arg) *sz_arg = 3; - if (sz_res) *sz_res = 1; - if (sz_iw) *sz_iw = 0; - if (sz_w) *sz_w = 8; - return 0; -} - -/* vdeFun:(i0[4],i1,i2[0],i3[4x4],i4[4])->(o0[4x4],o1[4]) */ -static int casadi_f1(const casadi_real** arg, casadi_real** res, int* iw, casadi_real* w, void* mem) { - casadi_real a0=arg[3] ? arg[3][2] : 0; - if (res[0]!=0) res[0][0]=a0; - a0=arg[3] ? arg[3][3] : 0; - if (res[0]!=0) res[0][1]=a0; - casadi_real a1=arg[0] ? arg[0][3] : 0; - casadi_real a2=sq(a1); - casadi_real a3=-8.0000000000000016e-02; - casadi_real a4=arg[0] ? arg[0][1] : 0; - casadi_real a5=cos(a4); - casadi_real a6=arg[3] ? arg[3][1] : 0; - casadi_real a7=(a5*a6); - a7=(a3*a7); - a7=(a2*a7); - casadi_real a8=sin(a4); - a8=(a3*a8); - casadi_real a9=(a1+a1); - casadi_real a10=(a9*a0); - a10=(a8*a10); - a7=(a7+a10); - a10=9.8100000000000009e-01; - casadi_real a11=cos(a4); - a11=(a10*a11); - casadi_real a12=cos(a4); - casadi_real a13=(a12*a6); - a13=(a11*a13); - casadi_real a14=sin(a4); - casadi_real a15=sin(a4); - casadi_real a16=(a15*a6); - a16=(a10*a16); - a16=(a14*a16); - a13=(a13-a16); - a7=(a7+a13); - a13=1.1000000000000001e+00; - a16=1.0000000000000001e-01; - casadi_real a17=cos(a4); - casadi_real a18=sq(a17); - a18=(a16*a18); - a13=(a13-a18); - a7=(a7/a13); - a18=(a8*a2); - casadi_real a19=(a11*a14); - a18=(a18+a19); - a19=arg[1] ? arg[1][0] : 0; - a18=(a18+a19); - a18=(a18/a13); - casadi_real a20=(a18/a13); - casadi_real a21=(a17+a17); - casadi_real a22=sin(a4); - casadi_real a23=(a22*a6); - a23=(a21*a23); - a23=(a16*a23); - casadi_real a24=(a20*a23); - a7=(a7-a24); - if (res[0]!=0) res[0][2]=a7; - a7=sq(a1); - a24=cos(a4); - a24=(a3*a24); - casadi_real a25=cos(a4); - casadi_real a26=(a25*a6); - a26=(a24*a26); - casadi_real a27=sin(a4); - casadi_real a28=sin(a4); - casadi_real a29=(a28*a6); - a29=(a3*a29); - a29=(a27*a29); - a26=(a26-a29); - a26=(a7*a26); - a29=(a24*a27); - casadi_real a30=(a1+a1); - a0=(a30*a0); - a0=(a29*a0); - a26=(a26+a0); - a0=sin(a4); - casadi_real a31=(a0*a6); - a31=(a19*a31); - a26=(a26-a31); - a31=1.0791000000000002e+01; - casadi_real a32=cos(a4); - a6=(a32*a6); - a6=(a31*a6); - a26=(a26+a6); - a6=8.0000000000000004e-01; - casadi_real a33=(a6*a13); - a26=(a26/a33); - casadi_real a34=(a29*a7); - casadi_real a35=cos(a4); - casadi_real a36=(a19*a35); - a34=(a34+a36); - a36=sin(a4); - a36=(a31*a36); - a34=(a34+a36); - a34=(a34/a33); - a36=(a34/a33); - a23=(a6*a23); - a23=(a36*a23); - a26=(a26-a23); - if (res[0]!=0) res[0][3]=a26; - a26=arg[3] ? arg[3][6] : 0; - if (res[0]!=0) res[0][4]=a26; - a26=arg[3] ? arg[3][7] : 0; - if (res[0]!=0) res[0][5]=a26; - a23=arg[3] ? arg[3][5] : 0; - casadi_real a37=(a5*a23); - a37=(a3*a37); - a37=(a2*a37); - casadi_real a38=(a9*a26); - a38=(a8*a38); - a37=(a37+a38); - a38=(a12*a23); - a38=(a11*a38); - casadi_real a39=(a15*a23); - a39=(a10*a39); - a39=(a14*a39); - a38=(a38-a39); - a37=(a37+a38); - a37=(a37/a13); - a38=(a22*a23); - a38=(a21*a38); - a38=(a16*a38); - a39=(a20*a38); - a37=(a37-a39); - if (res[0]!=0) res[0][6]=a37; - a37=(a25*a23); - a37=(a24*a37); - a39=(a28*a23); - a39=(a3*a39); - a39=(a27*a39); - a37=(a37-a39); - a37=(a7*a37); - a26=(a30*a26); - a26=(a29*a26); - a37=(a37+a26); - a26=(a0*a23); - a26=(a19*a26); - a37=(a37-a26); - a23=(a32*a23); - a23=(a31*a23); - a37=(a37+a23); - a37=(a37/a33); - a38=(a6*a38); - a38=(a36*a38); - a37=(a37-a38); - if (res[0]!=0) res[0][7]=a37; - a37=arg[3] ? arg[3][10] : 0; - if (res[0]!=0) res[0][8]=a37; - a37=arg[3] ? arg[3][11] : 0; - if (res[0]!=0) res[0][9]=a37; - a38=arg[3] ? arg[3][9] : 0; - a23=(a5*a38); - a23=(a3*a23); - a23=(a2*a23); - a26=(a9*a37); - a26=(a8*a26); - a23=(a23+a26); - a26=(a12*a38); - a26=(a11*a26); - a39=(a15*a38); - a39=(a10*a39); - a39=(a14*a39); - a26=(a26-a39); - a23=(a23+a26); - a23=(a23/a13); - a26=(a22*a38); - a26=(a21*a26); - a26=(a16*a26); - a39=(a20*a26); - a23=(a23-a39); - if (res[0]!=0) res[0][10]=a23; - a23=(a25*a38); - a23=(a24*a23); - a39=(a28*a38); - a39=(a3*a39); - a39=(a27*a39); - a23=(a23-a39); - a23=(a7*a23); - a37=(a30*a37); - a37=(a29*a37); - a23=(a23+a37); - a37=(a0*a38); - a37=(a19*a37); - a23=(a23-a37); - a38=(a32*a38); - a38=(a31*a38); - a23=(a23+a38); - a23=(a23/a33); - a26=(a6*a26); - a26=(a36*a26); - a23=(a23-a26); - if (res[0]!=0) res[0][11]=a23; - a23=arg[3] ? arg[3][14] : 0; - if (res[0]!=0) res[0][12]=a23; - a23=arg[3] ? arg[3][15] : 0; - if (res[0]!=0) res[0][13]=a23; - a26=arg[3] ? arg[3][13] : 0; - a5=(a5*a26); - a5=(a3*a5); - a5=(a2*a5); - a9=(a9*a23); - a9=(a8*a9); - a5=(a5+a9); - a12=(a12*a26); - a12=(a11*a12); - a15=(a15*a26); - a15=(a10*a15); - a15=(a14*a15); - a12=(a12-a15); - a5=(a5+a12); - a5=(a5/a13); - a22=(a22*a26); - a21=(a21*a22); - a21=(a16*a21); - a20=(a20*a21); - a5=(a5-a20); - if (res[0]!=0) res[0][14]=a5; - a25=(a25*a26); - a25=(a24*a25); - a28=(a28*a26); - a28=(a3*a28); - a28=(a27*a28); - a25=(a25-a28); - a25=(a7*a25); - a30=(a30*a23); - a30=(a29*a30); - a25=(a25+a30); - a0=(a0*a26); - a0=(a19*a0); - a25=(a25-a0); - a32=(a32*a26); - a32=(a31*a32); - a25=(a25+a32); - a25=(a25/a33); - a21=(a6*a21); - a36=(a36*a21); - a25=(a25-a36); - if (res[0]!=0) res[0][15]=a25; - a25=arg[4] ? arg[4][2] : 0; - if (res[1]!=0) res[1][0]=a25; - a25=arg[4] ? arg[4][3] : 0; - if (res[1]!=0) res[1][1]=a25; - a36=(1./a13); - a21=cos(a4); - a32=arg[4] ? arg[4][1] : 0; - a21=(a21*a32); - a21=(a3*a21); - a2=(a2*a21); - a21=(a1+a1); - a21=(a21*a25); - a8=(a8*a21); - a2=(a2+a8); - a8=cos(a4); - a8=(a8*a32); - a11=(a11*a8); - a8=sin(a4); - a8=(a8*a32); - a10=(a10*a8); - a14=(a14*a10); - a11=(a11-a14); - a2=(a2+a11); - a2=(a2/a13); - a18=(a18/a13); - a17=(a17+a17); - a13=sin(a4); - a13=(a13*a32); - a17=(a17*a13); - a16=(a16*a17); - a18=(a18*a16); - a2=(a2-a18); - a36=(a36+a2); - if (res[1]!=0) res[1][2]=a36; - a35=(a35/a33); - a36=cos(a4); - a36=(a36*a32); - a24=(a24*a36); - a36=sin(a4); - a36=(a36*a32); - a3=(a3*a36); - a27=(a27*a3); - a24=(a24-a27); - a7=(a7*a24); - a1=(a1+a1); - a1=(a1*a25); - a29=(a29*a1); - a7=(a7+a29); - a29=sin(a4); - a29=(a29*a32); - a19=(a19*a29); - a7=(a7-a19); - a4=cos(a4); - a4=(a4*a32); - a31=(a31*a4); - a7=(a7+a31); - a7=(a7/a33); - a34=(a34/a33); - a6=(a6*a16); - a34=(a34*a6); - a7=(a7-a34); - a35=(a35+a7); - if (res[1]!=0) res[1][3]=a35; - return 0; -} - -CASADI_SYMBOL_EXPORT int vdeFun(const casadi_real** arg, casadi_real** res, int* iw, casadi_real* w, void* mem){ - return casadi_f1(arg, res, iw, w, mem); -} - -CASADI_SYMBOL_EXPORT void vdeFun_incref(void) { -} - -CASADI_SYMBOL_EXPORT void vdeFun_decref(void) { -} - -CASADI_SYMBOL_EXPORT int vdeFun_n_in(void) { return 5;} - -CASADI_SYMBOL_EXPORT int vdeFun_n_out(void) { return 2;} - -CASADI_SYMBOL_EXPORT const char* vdeFun_name_in(int i){ - switch (i) { - case 0: return "i0"; - case 1: return "i1"; - case 2: return "i2"; - case 3: return "i3"; - case 4: return "i4"; - default: return 0; - } -} - -CASADI_SYMBOL_EXPORT const char* vdeFun_name_out(int i){ - switch (i) { - case 0: return "o0"; - case 1: return "o1"; - default: return 0; - } -} - -CASADI_SYMBOL_EXPORT const int* vdeFun_sparsity_in(int i) { - switch (i) { - case 0: return casadi_s0; - case 1: return casadi_s1; - case 2: return casadi_s2; - case 3: return casadi_s3; - case 4: return casadi_s0; - default: return 0; - } -} - -CASADI_SYMBOL_EXPORT const int* vdeFun_sparsity_out(int i) { - switch (i) { - case 0: return casadi_s3; - case 1: return casadi_s0; - default: return 0; - } -} - -CASADI_SYMBOL_EXPORT int vdeFun_work(int *sz_arg, int* sz_res, int *sz_iw, int *sz_w) { - if (sz_arg) *sz_arg = 5; - if (sz_res) *sz_res = 2; - if (sz_iw) *sz_iw = 0; - if (sz_w) *sz_w = 40; - return 0; -} - -/* impl_f_fun:(i0[4],i1,i2[0],i3[4])->(o0[4]) */ -static int casadi_f2(const casadi_real** arg, casadi_real** res, int* iw, casadi_real* w, void* mem) { - casadi_real a0=arg[3] ? arg[3][0] : 0; - casadi_real a1=arg[0] ? arg[0][2] : 0; - a0=(a0-a1); - if (res[0]!=0) res[0][0]=a0; - a0=arg[3] ? arg[3][1] : 0; - a1=arg[0] ? arg[0][3] : 0; - a0=(a0-a1); - if (res[0]!=0) res[0][1]=a0; - a0=arg[3] ? arg[3][2] : 0; - casadi_real a2=-8.0000000000000016e-02; - casadi_real a3=arg[0] ? arg[0][1] : 0; - casadi_real a4=sin(a3); - a4=(a2*a4); - casadi_real a5=sq(a1); - a4=(a4*a5); - a5=9.8100000000000009e-01; - casadi_real a6=cos(a3); - a5=(a5*a6); - a6=sin(a3); - a5=(a5*a6); - a4=(a4+a5); - a5=arg[1] ? arg[1][0] : 0; - a4=(a4+a5); - a6=1.1000000000000001e+00; - casadi_real a7=1.0000000000000001e-01; - casadi_real a8=cos(a3); - a8=sq(a8); - a7=(a7*a8); - a6=(a6-a7); - a4=(a4/a6); - a0=(a0-a4); - if (res[0]!=0) res[0][2]=a0; - a0=arg[3] ? arg[3][3] : 0; - a4=cos(a3); - a2=(a2*a4); - a4=sin(a3); - a2=(a2*a4); - a1=sq(a1); - a2=(a2*a1); - a1=cos(a3); - a5=(a5*a1); - a2=(a2+a5); - a5=1.0791000000000002e+01; - a3=sin(a3); - a5=(a5*a3); - a2=(a2+a5); - a5=8.0000000000000004e-01; - a5=(a5*a6); - a2=(a2/a5); - a0=(a0-a2); - if (res[0]!=0) res[0][3]=a0; - return 0; -} - -CASADI_SYMBOL_EXPORT int impl_f_fun(const casadi_real** arg, casadi_real** res, int* iw, casadi_real* w, void* mem){ - return casadi_f2(arg, res, iw, w, mem); -} - -CASADI_SYMBOL_EXPORT void impl_f_fun_incref(void) { -} - -CASADI_SYMBOL_EXPORT void impl_f_fun_decref(void) { -} - -CASADI_SYMBOL_EXPORT int impl_f_fun_n_in(void) { return 4;} - -CASADI_SYMBOL_EXPORT int impl_f_fun_n_out(void) { return 1;} - -CASADI_SYMBOL_EXPORT const char* impl_f_fun_name_in(int i){ - switch (i) { - case 0: return "i0"; - case 1: return "i1"; - case 2: return "i2"; - case 3: return "i3"; - default: return 0; - } -} - -CASADI_SYMBOL_EXPORT const char* impl_f_fun_name_out(int i){ - switch (i) { - case 0: return "o0"; - default: return 0; - } -} - -CASADI_SYMBOL_EXPORT const int* impl_f_fun_sparsity_in(int i) { - switch (i) { - case 0: return casadi_s0; - case 1: return casadi_s1; - case 2: return casadi_s2; - case 3: return casadi_s0; - default: return 0; - } -} - -CASADI_SYMBOL_EXPORT const int* impl_f_fun_sparsity_out(int i) { - switch (i) { - case 0: return casadi_s0; - default: return 0; - } -} - -CASADI_SYMBOL_EXPORT int impl_f_fun_work(int *sz_arg, int* sz_res, int *sz_iw, int *sz_w) { - if (sz_arg) *sz_arg = 4; - if (sz_res) *sz_res = 1; - if (sz_iw) *sz_iw = 0; - if (sz_w) *sz_w = 9; - return 0; -} - -/* impl_jac_x_fun:(i0[4],i1,i2[0],i3[4])->(o0[4x4]) */ -static int casadi_f3(const casadi_real** arg, casadi_real** res, int* iw, casadi_real* w, void* mem) { - casadi_real a0=0.; - if (res[0]!=0) res[0][0]=a0; - if (res[0]!=0) res[0][1]=a0; - if (res[0]!=0) res[0][2]=a0; - if (res[0]!=0) res[0][3]=a0; - if (res[0]!=0) res[0][4]=a0; - if (res[0]!=0) res[0][5]=a0; - casadi_real a1=arg[0] ? arg[0][3] : 0; - casadi_real a2=sq(a1); - casadi_real a3=-8.0000000000000016e-02; - casadi_real a4=arg[0] ? arg[0][1] : 0; - casadi_real a5=cos(a4); - a5=(a3*a5); - a5=(a2*a5); - casadi_real a6=9.8100000000000009e-01; - casadi_real a7=cos(a4); - a7=(a6*a7); - casadi_real a8=cos(a4); - a8=(a7*a8); - casadi_real a9=sin(a4); - casadi_real a10=sin(a4); - a6=(a6*a10); - a6=(a9*a6); - a8=(a8-a6); - a5=(a5+a8); - a8=1.1000000000000001e+00; - a6=1.0000000000000001e-01; - a10=cos(a4); - casadi_real a11=sq(a10); - a11=(a6*a11); - a8=(a8-a11); - a5=(a5/a8); - a11=sin(a4); - a11=(a3*a11); - a2=(a11*a2); - a7=(a7*a9); - a2=(a2+a7); - a7=arg[1] ? arg[1][0] : 0; - a2=(a2+a7); - a2=(a2/a8); - a2=(a2/a8); - a10=(a10+a10); - a9=sin(a4); - a10=(a10*a9); - a6=(a6*a10); - a2=(a2*a6); - a5=(a5-a2); - a5=(-a5); - if (res[0]!=0) res[0][6]=a5; - a5=sq(a1); - a2=cos(a4); - a2=(a3*a2); - a10=cos(a4); - a10=(a2*a10); - a9=sin(a4); - casadi_real a12=sin(a4); - a3=(a3*a12); - a3=(a9*a3); - a10=(a10-a3); - a10=(a5*a10); - a3=sin(a4); - a3=(a7*a3); - a10=(a10-a3); - a3=1.0791000000000002e+01; - a12=cos(a4); - a12=(a3*a12); - a10=(a10+a12); - a12=8.0000000000000004e-01; - casadi_real a13=(a12*a8); - a10=(a10/a13); - a2=(a2*a9); - a5=(a2*a5); - a9=cos(a4); - a7=(a7*a9); - a5=(a5+a7); - a4=sin(a4); - a3=(a3*a4); - a5=(a5+a3); - a5=(a5/a13); - a5=(a5/a13); - a12=(a12*a6); - a5=(a5*a12); - a10=(a10-a5); - a10=(-a10); - if (res[0]!=0) res[0][7]=a10; - a10=-1.; - if (res[0]!=0) res[0][8]=a10; - if (res[0]!=0) res[0][9]=a0; - if (res[0]!=0) res[0][10]=a0; - if (res[0]!=0) res[0][11]=a0; - if (res[0]!=0) res[0][12]=a0; - if (res[0]!=0) res[0][13]=a10; - a10=(a1+a1); - a11=(a11*a10); - a11=(a11/a8); - a11=(-a11); - if (res[0]!=0) res[0][14]=a11; - a1=(a1+a1); - a2=(a2*a1); - a2=(a2/a13); - a2=(-a2); - if (res[0]!=0) res[0][15]=a2; - return 0; -} - -CASADI_SYMBOL_EXPORT int impl_jac_x_fun(const casadi_real** arg, casadi_real** res, int* iw, casadi_real* w, void* mem){ - return casadi_f3(arg, res, iw, w, mem); -} - -CASADI_SYMBOL_EXPORT void impl_jac_x_fun_incref(void) { -} - -CASADI_SYMBOL_EXPORT void impl_jac_x_fun_decref(void) { -} - -CASADI_SYMBOL_EXPORT int impl_jac_x_fun_n_in(void) { return 4;} - -CASADI_SYMBOL_EXPORT int impl_jac_x_fun_n_out(void) { return 1;} - -CASADI_SYMBOL_EXPORT const char* impl_jac_x_fun_name_in(int i){ - switch (i) { - case 0: return "i0"; - case 1: return "i1"; - case 2: return "i2"; - case 3: return "i3"; - default: return 0; - } -} - -CASADI_SYMBOL_EXPORT const char* impl_jac_x_fun_name_out(int i){ - switch (i) { - case 0: return "o0"; - default: return 0; - } -} - -CASADI_SYMBOL_EXPORT const int* impl_jac_x_fun_sparsity_in(int i) { - switch (i) { - case 0: return casadi_s0; - case 1: return casadi_s1; - case 2: return casadi_s2; - case 3: return casadi_s0; - default: return 0; - } -} - -CASADI_SYMBOL_EXPORT const int* impl_jac_x_fun_sparsity_out(int i) { - switch (i) { - case 0: return casadi_s3; - default: return 0; - } -} - -CASADI_SYMBOL_EXPORT int impl_jac_x_fun_work(int *sz_arg, int* sz_res, int *sz_iw, int *sz_w) { - if (sz_arg) *sz_arg = 4; - if (sz_res) *sz_res = 1; - if (sz_iw) *sz_iw = 0; - if (sz_w) *sz_w = 14; - return 0; -} - -/* impl_jac_u_fun:(i0[4],i1,i2[0],i3[4])->(o0[4]) */ -static int casadi_f4(const casadi_real** arg, casadi_real** res, int* iw, casadi_real* w, void* mem) { - casadi_real a0=0.; - if (res[0]!=0) res[0][0]=a0; - if (res[0]!=0) res[0][1]=a0; - a0=1.1000000000000001e+00; - casadi_real a1=1.0000000000000001e-01; - casadi_real a2=arg[0] ? arg[0][1] : 0; - casadi_real a3=cos(a2); - a3=sq(a3); - a1=(a1*a3); - a0=(a0-a1); - a1=(1./a0); - a1=(-a1); - if (res[0]!=0) res[0][2]=a1; - a2=cos(a2); - a1=8.0000000000000004e-01; - a1=(a1*a0); - a2=(a2/a1); - a2=(-a2); - if (res[0]!=0) res[0][3]=a2; - return 0; -} - -CASADI_SYMBOL_EXPORT int impl_jac_u_fun(const casadi_real** arg, casadi_real** res, int* iw, casadi_real* w, void* mem){ - return casadi_f4(arg, res, iw, w, mem); -} - -CASADI_SYMBOL_EXPORT void impl_jac_u_fun_incref(void) { -} - -CASADI_SYMBOL_EXPORT void impl_jac_u_fun_decref(void) { -} - -CASADI_SYMBOL_EXPORT int impl_jac_u_fun_n_in(void) { return 4;} - -CASADI_SYMBOL_EXPORT int impl_jac_u_fun_n_out(void) { return 1;} - -CASADI_SYMBOL_EXPORT const char* impl_jac_u_fun_name_in(int i){ - switch (i) { - case 0: return "i0"; - case 1: return "i1"; - case 2: return "i2"; - case 3: return "i3"; - default: return 0; - } -} - -CASADI_SYMBOL_EXPORT const char* impl_jac_u_fun_name_out(int i){ - switch (i) { - case 0: return "o0"; - default: return 0; - } -} - -CASADI_SYMBOL_EXPORT const int* impl_jac_u_fun_sparsity_in(int i) { - switch (i) { - case 0: return casadi_s0; - case 1: return casadi_s1; - case 2: return casadi_s2; - case 3: return casadi_s0; - default: return 0; - } -} - -CASADI_SYMBOL_EXPORT const int* impl_jac_u_fun_sparsity_out(int i) { - switch (i) { - case 0: return casadi_s0; - default: return 0; - } -} - -CASADI_SYMBOL_EXPORT int impl_jac_u_fun_work(int *sz_arg, int* sz_res, int *sz_iw, int *sz_w) { - if (sz_arg) *sz_arg = 4; - if (sz_res) *sz_res = 1; - if (sz_iw) *sz_iw = 0; - if (sz_w) *sz_w = 4; - return 0; -} - -/* impl_jac_xdot_fun:(i0[4],i1,i2[0],i3[4])->(o0[4x4]) */ -static int casadi_f5(const casadi_real** arg, casadi_real** res, int* iw, casadi_real* w, void* mem) { - casadi_real a0=1.; - if (res[0]!=0) res[0][0]=a0; - casadi_real a1=0.; - if (res[0]!=0) res[0][1]=a1; - if (res[0]!=0) res[0][2]=a1; - if (res[0]!=0) res[0][3]=a1; - if (res[0]!=0) res[0][4]=a1; - if (res[0]!=0) res[0][5]=a0; - if (res[0]!=0) res[0][6]=a1; - if (res[0]!=0) res[0][7]=a1; - if (res[0]!=0) res[0][8]=a1; - if (res[0]!=0) res[0][9]=a1; - if (res[0]!=0) res[0][10]=a0; - if (res[0]!=0) res[0][11]=a1; - if (res[0]!=0) res[0][12]=a1; - if (res[0]!=0) res[0][13]=a1; - if (res[0]!=0) res[0][14]=a1; - if (res[0]!=0) res[0][15]=a0; - return 0; -} - -CASADI_SYMBOL_EXPORT int impl_jac_xdot_fun(const casadi_real** arg, casadi_real** res, int* iw, casadi_real* w, void* mem){ - return casadi_f5(arg, res, iw, w, mem); -} - -CASADI_SYMBOL_EXPORT void impl_jac_xdot_fun_incref(void) { -} - -CASADI_SYMBOL_EXPORT void impl_jac_xdot_fun_decref(void) { -} - -CASADI_SYMBOL_EXPORT int impl_jac_xdot_fun_n_in(void) { return 4;} - -CASADI_SYMBOL_EXPORT int impl_jac_xdot_fun_n_out(void) { return 1;} - -CASADI_SYMBOL_EXPORT const char* impl_jac_xdot_fun_name_in(int i){ - switch (i) { - case 0: return "i0"; - case 1: return "i1"; - case 2: return "i2"; - case 3: return "i3"; - default: return 0; - } -} - -CASADI_SYMBOL_EXPORT const char* impl_jac_xdot_fun_name_out(int i){ - switch (i) { - case 0: return "o0"; - default: return 0; - } -} - -CASADI_SYMBOL_EXPORT const int* impl_jac_xdot_fun_sparsity_in(int i) { - switch (i) { - case 0: return casadi_s0; - case 1: return casadi_s1; - case 2: return casadi_s2; - case 3: return casadi_s0; - default: return 0; - } -} - -CASADI_SYMBOL_EXPORT const int* impl_jac_xdot_fun_sparsity_out(int i) { - switch (i) { - case 0: return casadi_s3; - default: return 0; - } -} - -CASADI_SYMBOL_EXPORT int impl_jac_xdot_fun_work(int *sz_arg, int* sz_res, int *sz_iw, int *sz_w) { - if (sz_arg) *sz_arg = 4; - if (sz_res) *sz_res = 1; - if (sz_iw) *sz_iw = 0; - if (sz_w) *sz_w = 2; - return 0; -} - -/* F:(i0[4],i1,i2[0])->(o0[4]) */ -static int casadi_f6(const casadi_real** arg, casadi_real** res, int* iw, casadi_real* w, void* mem) { - casadi_real a0=arg[0] ? arg[0][0] : 0; - casadi_real a1=8.3333333333333332e-03; - casadi_real a2=arg[0] ? arg[0][2] : 0; - casadi_real a3=2.; - casadi_real a4=2.5000000000000001e-02; - casadi_real a5=-8.0000000000000016e-02; - casadi_real a6=arg[0] ? arg[0][1] : 0; - casadi_real a7=sin(a6); - a7=(a5*a7); - casadi_real a8=arg[0] ? arg[0][3] : 0; - casadi_real a9=sq(a8); - a7=(a7*a9); - a9=9.8100000000000009e-01; - casadi_real a10=cos(a6); - a10=(a9*a10); - casadi_real a11=sin(a6); - a10=(a10*a11); - a7=(a7+a10); - a10=arg[1] ? arg[1][0] : 0; - a7=(a7+a10); - a11=1.1000000000000001e+00; - casadi_real a12=1.0000000000000001e-01; - casadi_real a13=cos(a6); - a13=sq(a13); - a13=(a12*a13); - a13=(a11-a13); - a7=(a7/a13); - casadi_real a14=(a4*a7); - a14=(a2+a14); - a14=(a3*a14); - a14=(a2+a14); - casadi_real a15=(a4*a8); - a15=(a6+a15); - casadi_real a16=sin(a15); - a16=(a5*a16); - casadi_real a17=cos(a6); - a17=(a5*a17); - casadi_real a18=sin(a6); - a17=(a17*a18); - a18=sq(a8); - a17=(a17*a18); - a18=cos(a6); - a18=(a10*a18); - a17=(a17+a18); - a18=1.0791000000000002e+01; - casadi_real a19=sin(a6); - a19=(a18*a19); - a17=(a17+a19); - a19=8.0000000000000004e-01; - a13=(a19*a13); - a17=(a17/a13); - a13=(a4*a17); - a13=(a8+a13); - casadi_real a20=sq(a13); - a16=(a16*a20); - a20=cos(a15); - a20=(a9*a20); - casadi_real a21=sin(a15); - a20=(a20*a21); - a16=(a16+a20); - a16=(a16+a10); - a20=cos(a15); - a20=sq(a20); - a20=(a12*a20); - a20=(a11-a20); - a16=(a16/a20); - a21=(a4*a16); - a21=(a2+a21); - a21=(a3*a21); - a14=(a14+a21); - a21=5.0000000000000003e-02; - casadi_real a22=(a4*a13); - a22=(a6+a22); - casadi_real a23=sin(a22); - a23=(a5*a23); - casadi_real a24=cos(a15); - a24=(a5*a24); - casadi_real a25=sin(a15); - a24=(a24*a25); - a25=sq(a13); - a24=(a24*a25); - a25=cos(a15); - a25=(a10*a25); - a24=(a24+a25); - a15=sin(a15); - a15=(a18*a15); - a24=(a24+a15); - a20=(a19*a20); - a24=(a24/a20); - a4=(a4*a24); - a4=(a8+a4); - a20=sq(a4); - a23=(a23*a20); - a20=cos(a22); - a20=(a9*a20); - a15=sin(a22); - a20=(a20*a15); - a23=(a23+a20); - a23=(a23+a10); - a20=cos(a22); - a20=sq(a20); - a20=(a12*a20); - a20=(a11-a20); - a23=(a23/a20); - a15=(a21*a23); - a15=(a2+a15); - a14=(a14+a15); - a14=(a1*a14); - a0=(a0+a14); - if (res[0]!=0) res[0][0]=a0; - a13=(a3*a13); - a13=(a8+a13); - a0=(a3*a4); - a13=(a13+a0); - a0=cos(a22); - a0=(a5*a0); - a14=sin(a22); - a0=(a0*a14); - a14=sq(a4); - a0=(a0*a14); - a14=cos(a22); - a14=(a10*a14); - a0=(a0+a14); - a22=sin(a22); - a22=(a18*a22); - a0=(a0+a22); - a20=(a19*a20); - a0=(a0/a20); - a20=(a21*a0); - a20=(a8+a20); - a13=(a13+a20); - a13=(a1*a13); - a13=(a6+a13); - if (res[0]!=0) res[0][1]=a13; - a16=(a3*a16); - a7=(a7+a16); - a23=(a3*a23); - a7=(a7+a23); - a21=(a21*a4); - a6=(a6+a21); - a21=sin(a6); - a21=(a5*a21); - a4=sq(a20); - a21=(a21*a4); - a4=cos(a6); - a9=(a9*a4); - a4=sin(a6); - a9=(a9*a4); - a21=(a21+a9); - a21=(a21+a10); - a9=cos(a6); - a9=sq(a9); - a12=(a12*a9); - a11=(a11-a12); - a21=(a21/a11); - a7=(a7+a21); - a7=(a1*a7); - a2=(a2+a7); - if (res[0]!=0) res[0][2]=a2; - a24=(a3*a24); - a17=(a17+a24); - a3=(a3*a0); - a17=(a17+a3); - a3=cos(a6); - a5=(a5*a3); - a3=sin(a6); - a5=(a5*a3); - a20=sq(a20); - a5=(a5*a20); - a20=cos(a6); - a10=(a10*a20); - a5=(a5+a10); - a6=sin(a6); - a18=(a18*a6); - a5=(a5+a18); - a19=(a19*a11); - a5=(a5/a19); - a17=(a17+a5); - a1=(a1*a17); - a8=(a8+a1); - if (res[0]!=0) res[0][3]=a8; - return 0; -} - -CASADI_SYMBOL_EXPORT int F(const casadi_real** arg, casadi_real** res, int* iw, casadi_real* w, void* mem){ - return casadi_f6(arg, res, iw, w, mem); -} - -CASADI_SYMBOL_EXPORT void F_incref(void) { -} - -CASADI_SYMBOL_EXPORT void F_decref(void) { -} - -CASADI_SYMBOL_EXPORT int F_n_in(void) { return 3;} - -CASADI_SYMBOL_EXPORT int F_n_out(void) { return 1;} - -CASADI_SYMBOL_EXPORT const char* F_name_in(int i){ - switch (i) { - case 0: return "i0"; - case 1: return "i1"; - case 2: return "i2"; - default: return 0; - } -} - -CASADI_SYMBOL_EXPORT const char* F_name_out(int i){ - switch (i) { - case 0: return "o0"; - default: return 0; - } -} - -CASADI_SYMBOL_EXPORT const int* F_sparsity_in(int i) { - switch (i) { - case 0: return casadi_s0; - case 1: return casadi_s1; - case 2: return casadi_s2; - default: return 0; - } -} - -CASADI_SYMBOL_EXPORT const int* F_sparsity_out(int i) { - switch (i) { - case 0: return casadi_s0; - default: return 0; - } -} - -CASADI_SYMBOL_EXPORT int F_work(int *sz_arg, int* sz_res, int *sz_iw, int *sz_w) { - if (sz_arg) *sz_arg = 3; - if (sz_res) *sz_res = 1; - if (sz_iw) *sz_iw = 0; - if (sz_w) *sz_w = 26; - return 0; -} - -/* D:(i0[4],i1,i2[0])->(o0[4x4],o1[4]) */ -static int casadi_f7(const casadi_real** arg, casadi_real** res, int* iw, casadi_real* w, void* mem) { - casadi_real a0=1.; - if (res[0]!=0) res[0][0]=a0; - casadi_real a1=0.; - if (res[0]!=0) res[0][1]=a1; - if (res[0]!=0) res[0][2]=a1; - if (res[0]!=0) res[0][3]=a1; - casadi_real a2=8.3333333333333332e-03; - casadi_real a3=2.; - casadi_real a4=2.5000000000000001e-02; - casadi_real a5=arg[0] ? arg[0][3] : 0; - casadi_real a6=sq(a5); - casadi_real a7=-8.0000000000000016e-02; - casadi_real a8=arg[0] ? arg[0][1] : 0; - casadi_real a9=cos(a8); - a9=(a7*a9); - a9=(a6*a9); - casadi_real a10=9.8100000000000009e-01; - casadi_real a11=cos(a8); - a11=(a10*a11); - casadi_real a12=cos(a8); - a12=(a11*a12); - casadi_real a13=sin(a8); - casadi_real a14=sin(a8); - a14=(a10*a14); - a14=(a13*a14); - a12=(a12-a14); - a9=(a9+a12); - a12=1.1000000000000001e+00; - a14=1.0000000000000001e-01; - casadi_real a15=cos(a8); - casadi_real a16=sq(a15); - a16=(a14*a16); - a16=(a12-a16); - a9=(a9/a16); - casadi_real a17=sin(a8); - a17=(a7*a17); - a6=(a17*a6); - a11=(a11*a13); - a6=(a6+a11); - a11=arg[1] ? arg[1][0] : 0; - a6=(a6+a11); - a6=(a6/a16); - a6=(a6/a16); - a15=(a15+a15); - a13=sin(a8); - a15=(a15*a13); - a15=(a14*a15); - a6=(a6*a15); - a9=(a9-a6); - a6=(a4*a9); - a6=(a3*a6); - a13=cos(a8); - a13=(a7*a13); - casadi_real a18=sin(a8); - casadi_real a19=(a13*a18); - casadi_real a20=sq(a5); - casadi_real a21=(a19*a20); - casadi_real a22=cos(a8); - casadi_real a23=(a11*a22); - a21=(a21+a23); - a23=1.0791000000000002e+01; - casadi_real a24=sin(a8); - a24=(a23*a24); - a21=(a21+a24); - a24=8.0000000000000004e-01; - casadi_real a25=(a24*a16); - a21=(a21/a25); - casadi_real a26=(a4*a21); - a26=(a5+a26); - casadi_real a27=sq(a26); - casadi_real a28=(a4*a5); - a28=(a8+a28); - casadi_real a29=cos(a28); - casadi_real a30=(a7*a29); - a30=(a27*a30); - casadi_real a31=sin(a28); - a31=(a7*a31); - casadi_real a32=(a26+a26); - casadi_real a33=cos(a8); - a13=(a13*a33); - a33=sin(a8); - a33=(a7*a33); - a18=(a18*a33); - a13=(a13-a18); - a20=(a20*a13); - a13=sin(a8); - a13=(a11*a13); - a20=(a20-a13); - a13=cos(a8); - a13=(a23*a13); - a20=(a20+a13); - a20=(a20/a25); - a21=(a21/a25); - a15=(a24*a15); - a21=(a21*a15); - a20=(a20-a21); - a21=(a4*a20); - a15=(a32*a21); - a15=(a31*a15); - a30=(a30+a15); - a15=cos(a28); - a15=(a10*a15); - a13=cos(a28); - a18=(a15*a13); - a33=sin(a28); - casadi_real a34=sin(a28); - casadi_real a35=(a10*a34); - a35=(a33*a35); - a18=(a18-a35); - a30=(a30+a18); - a18=cos(a28); - a35=sq(a18); - a35=(a14*a35); - a35=(a12-a35); - a30=(a30/a35); - casadi_real a36=(a31*a27); - casadi_real a37=(a15*a33); - a36=(a36+a37); - a36=(a36+a11); - a36=(a36/a35); - a36=(a36/a35); - a18=(a18+a18); - a37=sin(a28); - casadi_real a38=(a18*a37); - a38=(a14*a38); - casadi_real a39=(a36*a38); - a30=(a30-a39); - a39=(a4*a30); - a39=(a3*a39); - a6=(a6+a39); - a39=5.0000000000000003e-02; - casadi_real a40=cos(a28); - a40=(a7*a40); - casadi_real a41=sin(a28); - casadi_real a42=(a40*a41); - casadi_real a43=sq(a26); - casadi_real a44=(a42*a43); - casadi_real a45=cos(a28); - casadi_real a46=(a11*a45); - a44=(a44+a46); - a46=sin(a28); - a46=(a23*a46); - a44=(a44+a46); - a46=(a24*a35); - a44=(a44/a46); - casadi_real a47=(a4*a44); - a47=(a5+a47); - casadi_real a48=sq(a47); - casadi_real a49=(a4*a26); - a49=(a8+a49); - casadi_real a50=cos(a49); - casadi_real a51=(a4*a21); - a51=(a0+a51); - casadi_real a52=(a50*a51); - a52=(a7*a52); - a52=(a48*a52); - casadi_real a53=sin(a49); - a53=(a7*a53); - casadi_real a54=(a47+a47); - casadi_real a55=cos(a28); - casadi_real a56=(a40*a55); - casadi_real a57=sin(a28); - casadi_real a58=(a7*a57); - a58=(a41*a58); - a56=(a56-a58); - a56=(a43*a56); - a58=(a26+a26); - casadi_real a59=(a58*a21); - a59=(a42*a59); - a56=(a56+a59); - a59=sin(a28); - casadi_real a60=(a11*a59); - a56=(a56-a60); - a28=cos(a28); - a60=(a23*a28); - a56=(a56+a60); - a56=(a56/a46); - a44=(a44/a46); - a38=(a24*a38); - a38=(a44*a38); - a56=(a56-a38); - a38=(a4*a56); - a60=(a54*a38); - a60=(a53*a60); - a52=(a52+a60); - a60=cos(a49); - a60=(a10*a60); - casadi_real a61=cos(a49); - casadi_real a62=(a61*a51); - a62=(a60*a62); - casadi_real a63=sin(a49); - casadi_real a64=sin(a49); - casadi_real a65=(a64*a51); - a65=(a10*a65); - a65=(a63*a65); - a62=(a62-a65); - a52=(a52+a62); - a62=cos(a49); - a65=sq(a62); - a65=(a14*a65); - a65=(a12-a65); - a52=(a52/a65); - casadi_real a66=(a53*a48); - casadi_real a67=(a60*a63); - a66=(a66+a67); - a66=(a66+a11); - a66=(a66/a65); - a67=(a66/a65); - casadi_real a68=(a62+a62); - casadi_real a69=sin(a49); - casadi_real a70=(a69*a51); - a70=(a68*a70); - a70=(a14*a70); - casadi_real a71=(a67*a70); - a52=(a52-a71); - a71=(a39*a52); - a6=(a6+a71); - a6=(a2*a6); - if (res[0]!=0) res[0][4]=a6; - a21=(a3*a21); - a6=(a3*a38); - a21=(a21+a6); - a6=sq(a47); - a71=cos(a49); - a71=(a7*a71); - casadi_real a72=cos(a49); - casadi_real a73=(a72*a51); - a73=(a71*a73); - casadi_real a74=sin(a49); - casadi_real a75=sin(a49); - casadi_real a76=(a75*a51); - a76=(a7*a76); - a76=(a74*a76); - a73=(a73-a76); - a73=(a6*a73); - a76=(a71*a74); - casadi_real a77=(a47+a47); - casadi_real a78=(a77*a38); - a78=(a76*a78); - a73=(a73+a78); - a78=sin(a49); - casadi_real a79=(a78*a51); - a79=(a11*a79); - a73=(a73-a79); - a79=cos(a49); - a51=(a79*a51); - a51=(a23*a51); - a73=(a73+a51); - a51=(a24*a65); - a73=(a73/a51); - casadi_real a80=(a76*a6); - casadi_real a81=cos(a49); - casadi_real a82=(a11*a81); - a80=(a80+a82); - a82=sin(a49); - a82=(a23*a82); - a80=(a80+a82); - a80=(a80/a51); - a82=(a80/a51); - a70=(a24*a70); - a70=(a82*a70); - a73=(a73-a70); - a70=(a39*a73); - a21=(a21+a70); - a21=(a2*a21); - a21=(a0+a21); - if (res[0]!=0) res[0][5]=a21; - a30=(a3*a30); - a9=(a9+a30); - a52=(a3*a52); - a9=(a9+a52); - a52=(a39*a80); - a52=(a5+a52); - a30=sq(a52); - a21=(a39*a47); - a8=(a8+a21); - a21=cos(a8); - a38=(a39*a38); - a38=(a0+a38); - casadi_real a83=(a21*a38); - a83=(a7*a83); - a83=(a30*a83); - casadi_real a84=sin(a8); - a84=(a7*a84); - casadi_real a85=(a52+a52); - casadi_real a86=(a85*a70); - a86=(a84*a86); - a83=(a83+a86); - a86=cos(a8); - a86=(a10*a86); - casadi_real a87=cos(a8); - casadi_real a88=(a87*a38); - a88=(a86*a88); - casadi_real a89=sin(a8); - casadi_real a90=sin(a8); - casadi_real a91=(a90*a38); - a91=(a10*a91); - a91=(a89*a91); - a88=(a88-a91); - a83=(a83+a88); - a88=cos(a8); - a91=sq(a88); - a91=(a14*a91); - a12=(a12-a91); - a83=(a83/a12); - a91=(a84*a30); - casadi_real a92=(a86*a89); - a91=(a91+a92); - a91=(a91+a11); - a91=(a91/a12); - a92=(a91/a12); - casadi_real a93=(a88+a88); - casadi_real a94=sin(a8); - casadi_real a95=(a94*a38); - a95=(a93*a95); - a95=(a14*a95); - casadi_real a96=(a92*a95); - a83=(a83-a96); - a9=(a9+a83); - a9=(a2*a9); - if (res[0]!=0) res[0][6]=a9; - a56=(a3*a56); - a20=(a20+a56); - a73=(a3*a73); - a20=(a20+a73); - a73=sq(a52); - a56=cos(a8); - a56=(a7*a56); - a9=cos(a8); - a83=(a9*a38); - a83=(a56*a83); - a96=sin(a8); - casadi_real a97=sin(a8); - casadi_real a98=(a97*a38); - a98=(a7*a98); - a98=(a96*a98); - a83=(a83-a98); - a83=(a73*a83); - a98=(a56*a96); - casadi_real a99=(a52+a52); - a70=(a99*a70); - a70=(a98*a70); - a83=(a83+a70); - a70=sin(a8); - casadi_real a100=(a70*a38); - a100=(a11*a100); - a83=(a83-a100); - a100=cos(a8); - a38=(a100*a38); - a38=(a23*a38); - a83=(a83+a38); - a38=(a24*a12); - a83=(a83/a38); - casadi_real a101=(a98*a73); - casadi_real a102=cos(a8); - casadi_real a103=(a11*a102); - a101=(a101+a103); - a103=sin(a8); - a103=(a23*a103); - a101=(a101+a103); - a101=(a101/a38); - a103=(a101/a38); - a95=(a24*a95); - a95=(a103*a95); - a83=(a83-a95); - a20=(a20+a83); - a20=(a2*a20); - if (res[0]!=0) res[0][7]=a20; - if (res[0]!=0) res[0][8]=a39; - if (res[0]!=0) res[0][9]=a1; - if (res[0]!=0) res[0][10]=a0; - if (res[0]!=0) res[0][11]=a1; - a1=(a5+a5); - a17=(a17*a1); - a17=(a17/a16); - a1=(a4*a17); - a1=(a3*a1); - a29=(a4*a29); - a29=(a7*a29); - a27=(a27*a29); - a5=(a5+a5); - a19=(a19*a5); - a19=(a19/a25); - a5=(a4*a19); - a5=(a0+a5); - a32=(a32*a5); - a32=(a31*a32); - a27=(a27+a32); - a13=(a4*a13); - a15=(a15*a13); - a34=(a4*a34); - a34=(a10*a34); - a33=(a33*a34); - a15=(a15-a33); - a27=(a27+a15); - a27=(a27/a35); - a37=(a4*a37); - a18=(a18*a37); - a18=(a14*a18); - a36=(a36*a18); - a27=(a27-a36); - a36=(a4*a27); - a36=(a3*a36); - a1=(a1+a36); - a36=(a4*a5); - a50=(a50*a36); - a50=(a7*a50); - a50=(a48*a50); - a55=(a4*a55); - a40=(a40*a55); - a57=(a4*a57); - a57=(a7*a57); - a41=(a41*a57); - a40=(a40-a41); - a43=(a43*a40); - a58=(a58*a5); - a58=(a42*a58); - a43=(a43+a58); - a59=(a4*a59); - a59=(a11*a59); - a43=(a43-a59); - a28=(a4*a28); - a28=(a23*a28); - a43=(a43+a28); - a43=(a43/a46); - a18=(a24*a18); - a44=(a44*a18); - a43=(a43-a44); - a44=(a4*a43); - a44=(a0+a44); - a54=(a54*a44); - a54=(a53*a54); - a50=(a50+a54); - a61=(a61*a36); - a61=(a60*a61); - a64=(a64*a36); - a64=(a10*a64); - a64=(a63*a64); - a61=(a61-a64); - a50=(a50+a61); - a50=(a50/a65); - a69=(a69*a36); - a68=(a68*a69); - a68=(a14*a68); - a67=(a67*a68); - a50=(a50-a67); - a67=(a39*a50); - a1=(a1+a67); - a1=(a2*a1); - if (res[0]!=0) res[0][12]=a1; - a5=(a3*a5); - a5=(a0+a5); - a1=(a3*a44); - a5=(a5+a1); - a72=(a72*a36); - a72=(a71*a72); - a75=(a75*a36); - a75=(a7*a75); - a75=(a74*a75); - a72=(a72-a75); - a72=(a6*a72); - a77=(a77*a44); - a77=(a76*a77); - a72=(a72+a77); - a78=(a78*a36); - a78=(a11*a78); - a72=(a72-a78); - a79=(a79*a36); - a79=(a23*a79); - a72=(a72+a79); - a72=(a72/a51); - a68=(a24*a68); - a82=(a82*a68); - a72=(a72-a82); - a82=(a39*a72); - a82=(a0+a82); - a5=(a5+a82); - a5=(a2*a5); - if (res[0]!=0) res[0][13]=a5; - a27=(a3*a27); - a17=(a17+a27); - a50=(a3*a50); - a17=(a17+a50); - a44=(a39*a44); - a21=(a21*a44); - a21=(a7*a21); - a21=(a30*a21); - a85=(a85*a82); - a85=(a84*a85); - a21=(a21+a85); - a87=(a87*a44); - a87=(a86*a87); - a90=(a90*a44); - a90=(a10*a90); - a90=(a89*a90); - a87=(a87-a90); - a21=(a21+a87); - a21=(a21/a12); - a94=(a94*a44); - a93=(a93*a94); - a93=(a14*a93); - a92=(a92*a93); - a21=(a21-a92); - a17=(a17+a21); - a17=(a2*a17); - if (res[0]!=0) res[0][14]=a17; - a43=(a3*a43); - a19=(a19+a43); - a72=(a3*a72); - a19=(a19+a72); - a9=(a9*a44); - a9=(a56*a9); - a97=(a97*a44); - a97=(a7*a97); - a97=(a96*a97); - a9=(a9-a97); - a9=(a73*a9); - a99=(a99*a82); - a99=(a98*a99); - a9=(a9+a99); - a70=(a70*a44); - a70=(a11*a70); - a9=(a9-a70); - a100=(a100*a44); - a100=(a23*a100); - a9=(a9+a100); - a9=(a9/a38); - a93=(a24*a93); - a103=(a103*a93); - a9=(a9-a103); - a19=(a19+a9); - a19=(a2*a19); - a19=(a0+a19); - if (res[0]!=0) res[0][15]=a19; - a19=(a4/a16); - a19=(a3*a19); - a9=(a26+a26); - a22=(a22/a25); - a25=(a4*a22); - a9=(a9*a25); - a31=(a31*a9); - a31=(a31+a0); - a31=(a31/a35); - a35=(a4*a31); - a35=(a3*a35); - a19=(a19+a35); - a35=cos(a49); - a9=(a4*a25); - a35=(a35*a9); - a35=(a7*a35); - a48=(a48*a35); - a35=(a47+a47); - a26=(a26+a26); - a26=(a26*a25); - a42=(a42*a26); - a42=(a42+a45); - a42=(a42/a46); - a4=(a4*a42); - a35=(a35*a4); - a53=(a53*a35); - a48=(a48+a53); - a53=cos(a49); - a53=(a53*a9); - a60=(a60*a53); - a53=sin(a49); - a53=(a53*a9); - a53=(a10*a53); - a63=(a63*a53); - a60=(a60-a63); - a48=(a48+a60); - a48=(a48+a0); - a48=(a48/a65); - a66=(a66/a65); - a62=(a62+a62); - a65=sin(a49); - a65=(a65*a9); - a62=(a62*a65); - a62=(a14*a62); - a66=(a66*a62); - a48=(a48-a66); - a66=(a39*a48); - a19=(a19+a66); - a19=(a2*a19); - if (res[1]!=0) res[1][0]=a19; - a25=(a3*a25); - a19=(a3*a4); - a25=(a25+a19); - a19=cos(a49); - a19=(a19*a9); - a71=(a71*a19); - a19=sin(a49); - a19=(a19*a9); - a19=(a7*a19); - a74=(a74*a19); - a71=(a71-a74); - a6=(a6*a71); - a47=(a47+a47); - a47=(a47*a4); - a76=(a76*a47); - a6=(a6+a76); - a76=sin(a49); - a76=(a76*a9); - a76=(a11*a76); - a81=(a81-a76); - a6=(a6+a81); - a49=cos(a49); - a49=(a49*a9); - a49=(a23*a49); - a6=(a6+a49); - a6=(a6/a51); - a80=(a80/a51); - a62=(a24*a62); - a80=(a80*a62); - a6=(a6-a80); - a80=(a39*a6); - a25=(a25+a80); - a25=(a2*a25); - if (res[1]!=0) res[1][1]=a25; - a16=(1./a16); - a31=(a3*a31); - a16=(a16+a31); - a48=(a3*a48); - a16=(a16+a48); - a48=cos(a8); - a39=(a39*a4); - a48=(a48*a39); - a48=(a7*a48); - a30=(a30*a48); - a48=(a52+a52); - a48=(a48*a80); - a84=(a84*a48); - a30=(a30+a84); - a84=cos(a8); - a84=(a84*a39); - a86=(a86*a84); - a84=sin(a8); - a84=(a84*a39); - a10=(a10*a84); - a89=(a89*a10); - a86=(a86-a89); - a30=(a30+a86); - a30=(a30+a0); - a30=(a30/a12); - a91=(a91/a12); - a88=(a88+a88); - a12=sin(a8); - a12=(a12*a39); - a88=(a88*a12); - a14=(a14*a88); - a91=(a91*a14); - a30=(a30-a91); - a16=(a16+a30); - a16=(a2*a16); - if (res[1]!=0) res[1][2]=a16; - a42=(a3*a42); - a22=(a22+a42); - a3=(a3*a6); - a22=(a22+a3); - a3=cos(a8); - a3=(a3*a39); - a56=(a56*a3); - a3=sin(a8); - a3=(a3*a39); - a7=(a7*a3); - a96=(a96*a7); - a56=(a56-a96); - a73=(a73*a56); - a52=(a52+a52); - a52=(a52*a80); - a98=(a98*a52); - a73=(a73+a98); - a98=sin(a8); - a98=(a98*a39); - a11=(a11*a98); - a102=(a102-a11); - a73=(a73+a102); - a8=cos(a8); - a8=(a8*a39); - a23=(a23*a8); - a73=(a73+a23); - a73=(a73/a38); - a101=(a101/a38); - a24=(a24*a14); - a101=(a101*a24); - a73=(a73-a101); - a22=(a22+a73); - a2=(a2*a22); - if (res[1]!=0) res[1][3]=a2; - return 0; -} - -CASADI_SYMBOL_EXPORT int D(const casadi_real** arg, casadi_real** res, int* iw, casadi_real* w, void* mem){ - return casadi_f7(arg, res, iw, w, mem); -} - -CASADI_SYMBOL_EXPORT void D_incref(void) { -} - -CASADI_SYMBOL_EXPORT void D_decref(void) { -} - -CASADI_SYMBOL_EXPORT int D_n_in(void) { return 3;} - -CASADI_SYMBOL_EXPORT int D_n_out(void) { return 2;} - -CASADI_SYMBOL_EXPORT const char* D_name_in(int i){ - switch (i) { - case 0: return "i0"; - case 1: return "i1"; - case 2: return "i2"; - default: return 0; - } -} - -CASADI_SYMBOL_EXPORT const char* D_name_out(int i){ - switch (i) { - case 0: return "o0"; - case 1: return "o1"; - default: return 0; - } -} - -CASADI_SYMBOL_EXPORT const int* D_sparsity_in(int i) { - switch (i) { - case 0: return casadi_s0; - case 1: return casadi_s1; - case 2: return casadi_s2; - default: return 0; - } -} - -CASADI_SYMBOL_EXPORT const int* D_sparsity_out(int i) { - switch (i) { - case 0: return casadi_s3; - case 1: return casadi_s0; - default: return 0; - } -} - -CASADI_SYMBOL_EXPORT int D_work(int *sz_arg, int* sz_res, int *sz_iw, int *sz_w) { - if (sz_arg) *sz_arg = 3; - if (sz_res) *sz_res = 2; - if (sz_iw) *sz_iw = 0; - if (sz_w) *sz_w = 104; - return 0; -} - -/* h_fun:(states[4],controls,params[0])->(h[5]) */ -static int casadi_f8(const casadi_real** arg, casadi_real** res, int* iw, casadi_real* w, void* mem) { - casadi_real a0=arg[0] ? arg[0][0] : 0; - if (res[0]!=0) res[0][0]=a0; - a0=arg[0] ? arg[0][1] : 0; - if (res[0]!=0) res[0][1]=a0; - a0=arg[0] ? arg[0][2] : 0; - if (res[0]!=0) res[0][2]=a0; - a0=arg[0] ? arg[0][3] : 0; - if (res[0]!=0) res[0][3]=a0; - a0=arg[1] ? arg[1][0] : 0; - if (res[0]!=0) res[0][4]=a0; - return 0; -} - -CASADI_SYMBOL_EXPORT int h_fun(const casadi_real** arg, casadi_real** res, int* iw, casadi_real* w, void* mem){ - return casadi_f8(arg, res, iw, w, mem); -} - -CASADI_SYMBOL_EXPORT void h_fun_incref(void) { -} - -CASADI_SYMBOL_EXPORT void h_fun_decref(void) { -} - -CASADI_SYMBOL_EXPORT int h_fun_n_in(void) { return 3;} - -CASADI_SYMBOL_EXPORT int h_fun_n_out(void) { return 1;} - -CASADI_SYMBOL_EXPORT const char* h_fun_name_in(int i){ - switch (i) { - case 0: return "states"; - case 1: return "controls"; - case 2: return "params"; - default: return 0; - } -} - -CASADI_SYMBOL_EXPORT const char* h_fun_name_out(int i){ - switch (i) { - case 0: return "h"; - default: return 0; - } -} - -CASADI_SYMBOL_EXPORT const int* h_fun_sparsity_in(int i) { - switch (i) { - case 0: return casadi_s0; - case 1: return casadi_s1; - case 2: return casadi_s2; - default: return 0; - } -} - -CASADI_SYMBOL_EXPORT const int* h_fun_sparsity_out(int i) { - switch (i) { - case 0: return casadi_s4; - default: return 0; - } -} - -CASADI_SYMBOL_EXPORT int h_fun_work(int *sz_arg, int* sz_res, int *sz_iw, int *sz_w) { - if (sz_arg) *sz_arg = 3; - if (sz_res) *sz_res = 1; - if (sz_iw) *sz_iw = 0; - if (sz_w) *sz_w = 1; - return 0; -} - -/* path_con_fun:(states[4],controls,params[0])->(general_con[]) */ -static int casadi_f9(const casadi_real** arg, casadi_real** res, int* iw, casadi_real* w, void* mem) { - return 0; -} - -CASADI_SYMBOL_EXPORT int path_con_fun(const casadi_real** arg, casadi_real** res, int* iw, casadi_real* w, void* mem){ - return casadi_f9(arg, res, iw, w, mem); -} - -CASADI_SYMBOL_EXPORT void path_con_fun_incref(void) { -} - -CASADI_SYMBOL_EXPORT void path_con_fun_decref(void) { -} - -CASADI_SYMBOL_EXPORT int path_con_fun_n_in(void) { return 3;} - -CASADI_SYMBOL_EXPORT int path_con_fun_n_out(void) { return 1;} - -CASADI_SYMBOL_EXPORT const char* path_con_fun_name_in(int i){ - switch (i) { - case 0: return "states"; - case 1: return "controls"; - case 2: return "params"; - default: return 0; - } -} - -CASADI_SYMBOL_EXPORT const char* path_con_fun_name_out(int i){ - switch (i) { - case 0: return "general_con"; - default: return 0; - } -} - -CASADI_SYMBOL_EXPORT const int* path_con_fun_sparsity_in(int i) { - switch (i) { - case 0: return casadi_s0; - case 1: return casadi_s1; - case 2: return casadi_s2; - default: return 0; - } -} - -CASADI_SYMBOL_EXPORT const int* path_con_fun_sparsity_out(int i) { - switch (i) { - case 0: return casadi_s5; - default: return 0; - } -} - -CASADI_SYMBOL_EXPORT int path_con_fun_work(int *sz_arg, int* sz_res, int *sz_iw, int *sz_w) { - if (sz_arg) *sz_arg = 3; - if (sz_res) *sz_res = 1; - if (sz_iw) *sz_iw = 0; - if (sz_w) *sz_w = 0; - return 0; -} - -/* path_con_N_fun:(states[4],params[0])->(general_con_N[]) */ -static int casadi_f10(const casadi_real** arg, casadi_real** res, int* iw, casadi_real* w, void* mem) { - return 0; -} - -CASADI_SYMBOL_EXPORT int path_con_N_fun(const casadi_real** arg, casadi_real** res, int* iw, casadi_real* w, void* mem){ - return casadi_f10(arg, res, iw, w, mem); -} - -CASADI_SYMBOL_EXPORT void path_con_N_fun_incref(void) { -} - -CASADI_SYMBOL_EXPORT void path_con_N_fun_decref(void) { -} - -CASADI_SYMBOL_EXPORT int path_con_N_fun_n_in(void) { return 2;} - -CASADI_SYMBOL_EXPORT int path_con_N_fun_n_out(void) { return 1;} - -CASADI_SYMBOL_EXPORT const char* path_con_N_fun_name_in(int i){ - switch (i) { - case 0: return "states"; - case 1: return "params"; - default: return 0; - } -} - -CASADI_SYMBOL_EXPORT const char* path_con_N_fun_name_out(int i){ - switch (i) { - case 0: return "general_con_N"; - default: return 0; - } -} - -CASADI_SYMBOL_EXPORT const int* path_con_N_fun_sparsity_in(int i) { - switch (i) { - case 0: return casadi_s0; - case 1: return casadi_s2; - default: return 0; - } -} - -CASADI_SYMBOL_EXPORT const int* path_con_N_fun_sparsity_out(int i) { - switch (i) { - case 0: return casadi_s5; - default: return 0; - } -} - -CASADI_SYMBOL_EXPORT int path_con_N_fun_work(int *sz_arg, int* sz_res, int *sz_iw, int *sz_w) { - if (sz_arg) *sz_arg = 2; - if (sz_res) *sz_res = 1; - if (sz_iw) *sz_iw = 0; - if (sz_w) *sz_w = 0; - return 0; -} - -/* obji_fun:(i0[4],i1,i2[0],i3[5],i4[5])->(o0) */ -static int casadi_f11(const casadi_real** arg, casadi_real** res, int* iw, casadi_real* w, void* mem) { - casadi_real a0=5.0000000000000000e-01; - casadi_real a1=arg[0] ? arg[0][0] : 0; - casadi_real a2=arg[3] ? arg[3][0] : 0; - casadi_real a3=(a1-a2); - a3=(a0*a3); - casadi_real a4=arg[4] ? arg[4][0] : 0; - a3=(a3*a4); - a1=(a1-a2); - a3=(a3*a1); - a1=arg[0] ? arg[0][1] : 0; - a2=arg[3] ? arg[3][1] : 0; - a4=(a1-a2); - a4=(a0*a4); - casadi_real a5=arg[4] ? arg[4][1] : 0; - a4=(a4*a5); - a1=(a1-a2); - a4=(a4*a1); - a3=(a3+a4); - a4=arg[0] ? arg[0][2] : 0; - a1=arg[3] ? arg[3][2] : 0; - a2=(a4-a1); - a2=(a0*a2); - a5=arg[4] ? arg[4][2] : 0; - a2=(a2*a5); - a4=(a4-a1); - a2=(a2*a4); - a3=(a3+a2); - a2=arg[0] ? arg[0][3] : 0; - a4=arg[3] ? arg[3][3] : 0; - a1=(a2-a4); - a1=(a0*a1); - a5=arg[4] ? arg[4][3] : 0; - a1=(a1*a5); - a2=(a2-a4); - a1=(a1*a2); - a3=(a3+a1); - a1=arg[1] ? arg[1][0] : 0; - a2=arg[3] ? arg[3][4] : 0; - a4=(a1-a2); - a0=(a0*a4); - a4=arg[4] ? arg[4][4] : 0; - a0=(a0*a4); - a1=(a1-a2); - a0=(a0*a1); - a3=(a3+a0); - if (res[0]!=0) res[0][0]=a3; - return 0; -} - -CASADI_SYMBOL_EXPORT int obji_fun(const casadi_real** arg, casadi_real** res, int* iw, casadi_real* w, void* mem){ - return casadi_f11(arg, res, iw, w, mem); -} - -CASADI_SYMBOL_EXPORT void obji_fun_incref(void) { -} - -CASADI_SYMBOL_EXPORT void obji_fun_decref(void) { -} - -CASADI_SYMBOL_EXPORT int obji_fun_n_in(void) { return 5;} - -CASADI_SYMBOL_EXPORT int obji_fun_n_out(void) { return 1;} - -CASADI_SYMBOL_EXPORT const char* obji_fun_name_in(int i){ - switch (i) { - case 0: return "i0"; - case 1: return "i1"; - case 2: return "i2"; - case 3: return "i3"; - case 4: return "i4"; - default: return 0; - } -} - -CASADI_SYMBOL_EXPORT const char* obji_fun_name_out(int i){ - switch (i) { - case 0: return "o0"; - default: return 0; - } -} - -CASADI_SYMBOL_EXPORT const int* obji_fun_sparsity_in(int i) { - switch (i) { - case 0: return casadi_s0; - case 1: return casadi_s1; - case 2: return casadi_s2; - case 3: return casadi_s4; - case 4: return casadi_s4; - default: return 0; - } -} - -CASADI_SYMBOL_EXPORT const int* obji_fun_sparsity_out(int i) { - switch (i) { - case 0: return casadi_s1; - default: return 0; - } -} - -CASADI_SYMBOL_EXPORT int obji_fun_work(int *sz_arg, int* sz_res, int *sz_iw, int *sz_w) { - if (sz_arg) *sz_arg = 5; - if (sz_res) *sz_res = 1; - if (sz_iw) *sz_iw = 0; - if (sz_w) *sz_w = 6; - return 0; -} - -/* objN_fun:(i0[4],i1[0],i2[4],i3[4])->(o0) */ -static int casadi_f12(const casadi_real** arg, casadi_real** res, int* iw, casadi_real* w, void* mem) { - casadi_real a0=5.0000000000000000e-01; - casadi_real a1=arg[0] ? arg[0][0] : 0; - casadi_real a2=arg[2] ? arg[2][0] : 0; - casadi_real a3=(a1-a2); - a3=(a0*a3); - casadi_real a4=arg[3] ? arg[3][0] : 0; - a3=(a3*a4); - a1=(a1-a2); - a3=(a3*a1); - a1=arg[0] ? arg[0][1] : 0; - a2=arg[2] ? arg[2][1] : 0; - a4=(a1-a2); - a4=(a0*a4); - casadi_real a5=arg[3] ? arg[3][1] : 0; - a4=(a4*a5); - a1=(a1-a2); - a4=(a4*a1); - a3=(a3+a4); - a4=arg[0] ? arg[0][2] : 0; - a1=arg[2] ? arg[2][2] : 0; - a2=(a4-a1); - a2=(a0*a2); - a5=arg[3] ? arg[3][2] : 0; - a2=(a2*a5); - a4=(a4-a1); - a2=(a2*a4); - a3=(a3+a2); - a2=arg[0] ? arg[0][3] : 0; - a4=arg[2] ? arg[2][3] : 0; - a1=(a2-a4); - a0=(a0*a1); - a1=arg[3] ? arg[3][3] : 0; - a0=(a0*a1); - a2=(a2-a4); - a0=(a0*a2); - a3=(a3+a0); - if (res[0]!=0) res[0][0]=a3; - return 0; -} - -CASADI_SYMBOL_EXPORT int objN_fun(const casadi_real** arg, casadi_real** res, int* iw, casadi_real* w, void* mem){ - return casadi_f12(arg, res, iw, w, mem); -} - -CASADI_SYMBOL_EXPORT void objN_fun_incref(void) { -} - -CASADI_SYMBOL_EXPORT void objN_fun_decref(void) { -} - -CASADI_SYMBOL_EXPORT int objN_fun_n_in(void) { return 4;} - -CASADI_SYMBOL_EXPORT int objN_fun_n_out(void) { return 1;} - -CASADI_SYMBOL_EXPORT const char* objN_fun_name_in(int i){ - switch (i) { - case 0: return "i0"; - case 1: return "i1"; - case 2: return "i2"; - case 3: return "i3"; - default: return 0; - } -} - -CASADI_SYMBOL_EXPORT const char* objN_fun_name_out(int i){ - switch (i) { - case 0: return "o0"; - default: return 0; - } -} - -CASADI_SYMBOL_EXPORT const int* objN_fun_sparsity_in(int i) { - switch (i) { - case 0: return casadi_s0; - case 1: return casadi_s2; - case 2: return casadi_s0; - case 3: return casadi_s0; - default: return 0; - } -} - -CASADI_SYMBOL_EXPORT const int* objN_fun_sparsity_out(int i) { - switch (i) { - case 0: return casadi_s1; - default: return 0; - } -} - -CASADI_SYMBOL_EXPORT int objN_fun_work(int *sz_arg, int* sz_res, int *sz_iw, int *sz_w) { - if (sz_arg) *sz_arg = 4; - if (sz_res) *sz_res = 1; - if (sz_iw) *sz_iw = 0; - if (sz_w) *sz_w = 6; - return 0; -} - -/* gi_fun:(i0[4],i1,i2[0],i3[5],i4[5])->(o0[4],o1) */ -static int casadi_f13(const casadi_real** arg, casadi_real** res, int* iw, casadi_real* w, void* mem) { - casadi_real a0=5.0000000000000000e-01; - casadi_real a1=arg[0] ? arg[0][0] : 0; - casadi_real a2=arg[3] ? arg[3][0] : 0; - casadi_real a3=(a1-a2); - a3=(a0*a3); - casadi_real a4=arg[4] ? arg[4][0] : 0; - a3=(a3*a4); - a1=(a1-a2); - a4=(a4*a1); - a4=(a0*a4); - a3=(a3+a4); - if (res[0]!=0) res[0][0]=a3; - a3=arg[0] ? arg[0][1] : 0; - a4=arg[3] ? arg[3][1] : 0; - a1=(a3-a4); - a1=(a0*a1); - a2=arg[4] ? arg[4][1] : 0; - a1=(a1*a2); - a3=(a3-a4); - a2=(a2*a3); - a2=(a0*a2); - a1=(a1+a2); - if (res[0]!=0) res[0][1]=a1; - a1=arg[0] ? arg[0][2] : 0; - a2=arg[3] ? arg[3][2] : 0; - a3=(a1-a2); - a3=(a0*a3); - a4=arg[4] ? arg[4][2] : 0; - a3=(a3*a4); - a1=(a1-a2); - a4=(a4*a1); - a4=(a0*a4); - a3=(a3+a4); - if (res[0]!=0) res[0][2]=a3; - a3=arg[0] ? arg[0][3] : 0; - a4=arg[3] ? arg[3][3] : 0; - a1=(a3-a4); - a1=(a0*a1); - a2=arg[4] ? arg[4][3] : 0; - a1=(a1*a2); - a3=(a3-a4); - a2=(a2*a3); - a2=(a0*a2); - a1=(a1+a2); - if (res[0]!=0) res[0][3]=a1; - a1=arg[1] ? arg[1][0] : 0; - a2=arg[3] ? arg[3][4] : 0; - a3=(a1-a2); - a4=arg[4] ? arg[4][4] : 0; - casadi_real a5=(a0*a4); - a3=(a3*a5); - a1=(a1-a2); - a0=(a0*a1); - a0=(a0*a4); - a3=(a3+a0); - if (res[1]!=0) res[1][0]=a3; - return 0; -} - -CASADI_SYMBOL_EXPORT int gi_fun(const casadi_real** arg, casadi_real** res, int* iw, casadi_real* w, void* mem){ - return casadi_f13(arg, res, iw, w, mem); -} - -CASADI_SYMBOL_EXPORT void gi_fun_incref(void) { -} - -CASADI_SYMBOL_EXPORT void gi_fun_decref(void) { -} - -CASADI_SYMBOL_EXPORT int gi_fun_n_in(void) { return 5;} - -CASADI_SYMBOL_EXPORT int gi_fun_n_out(void) { return 2;} - -CASADI_SYMBOL_EXPORT const char* gi_fun_name_in(int i){ - switch (i) { - case 0: return "i0"; - case 1: return "i1"; - case 2: return "i2"; - case 3: return "i3"; - case 4: return "i4"; - default: return 0; - } -} - -CASADI_SYMBOL_EXPORT const char* gi_fun_name_out(int i){ - switch (i) { - case 0: return "o0"; - case 1: return "o1"; - default: return 0; - } -} - -CASADI_SYMBOL_EXPORT const int* gi_fun_sparsity_in(int i) { - switch (i) { - case 0: return casadi_s0; - case 1: return casadi_s1; - case 2: return casadi_s2; - case 3: return casadi_s4; - case 4: return casadi_s4; - default: return 0; - } -} - -CASADI_SYMBOL_EXPORT const int* gi_fun_sparsity_out(int i) { - switch (i) { - case 0: return casadi_s0; - case 1: return casadi_s1; - default: return 0; - } -} - -CASADI_SYMBOL_EXPORT int gi_fun_work(int *sz_arg, int* sz_res, int *sz_iw, int *sz_w) { - if (sz_arg) *sz_arg = 5; - if (sz_res) *sz_res = 2; - if (sz_iw) *sz_iw = 0; - if (sz_w) *sz_w = 6; - return 0; -} - -/* gN_fun:(i0[4],i1[0],i2[4],i3[4])->(o0[4]) */ -static int casadi_f14(const casadi_real** arg, casadi_real** res, int* iw, casadi_real* w, void* mem) { - casadi_real a0=5.0000000000000000e-01; - casadi_real a1=arg[0] ? arg[0][0] : 0; - casadi_real a2=arg[2] ? arg[2][0] : 0; - casadi_real a3=(a1-a2); - a3=(a0*a3); - casadi_real a4=arg[3] ? arg[3][0] : 0; - a3=(a3*a4); - a1=(a1-a2); - a4=(a4*a1); - a4=(a0*a4); - a3=(a3+a4); - if (res[0]!=0) res[0][0]=a3; - a3=arg[0] ? arg[0][1] : 0; - a4=arg[2] ? arg[2][1] : 0; - a1=(a3-a4); - a1=(a0*a1); - a2=arg[3] ? arg[3][1] : 0; - a1=(a1*a2); - a3=(a3-a4); - a2=(a2*a3); - a2=(a0*a2); - a1=(a1+a2); - if (res[0]!=0) res[0][1]=a1; - a1=arg[0] ? arg[0][2] : 0; - a2=arg[2] ? arg[2][2] : 0; - a3=(a1-a2); - a3=(a0*a3); - a4=arg[3] ? arg[3][2] : 0; - a3=(a3*a4); - a1=(a1-a2); - a4=(a4*a1); - a4=(a0*a4); - a3=(a3+a4); - if (res[0]!=0) res[0][2]=a3; - a3=arg[0] ? arg[0][3] : 0; - a4=arg[2] ? arg[2][3] : 0; - a1=(a3-a4); - a1=(a0*a1); - a2=arg[3] ? arg[3][3] : 0; - a1=(a1*a2); - a3=(a3-a4); - a2=(a2*a3); - a0=(a0*a2); - a1=(a1+a0); - if (res[0]!=0) res[0][3]=a1; - return 0; -} - -CASADI_SYMBOL_EXPORT int gN_fun(const casadi_real** arg, casadi_real** res, int* iw, casadi_real* w, void* mem){ - return casadi_f14(arg, res, iw, w, mem); -} - -CASADI_SYMBOL_EXPORT void gN_fun_incref(void) { -} - -CASADI_SYMBOL_EXPORT void gN_fun_decref(void) { -} - -CASADI_SYMBOL_EXPORT int gN_fun_n_in(void) { return 4;} - -CASADI_SYMBOL_EXPORT int gN_fun_n_out(void) { return 1;} - -CASADI_SYMBOL_EXPORT const char* gN_fun_name_in(int i){ - switch (i) { - case 0: return "i0"; - case 1: return "i1"; - case 2: return "i2"; - case 3: return "i3"; - default: return 0; - } -} - -CASADI_SYMBOL_EXPORT const char* gN_fun_name_out(int i){ - switch (i) { - case 0: return "o0"; - default: return 0; - } -} - -CASADI_SYMBOL_EXPORT const int* gN_fun_sparsity_in(int i) { - switch (i) { - case 0: return casadi_s0; - case 1: return casadi_s2; - case 2: return casadi_s0; - case 3: return casadi_s0; - default: return 0; - } -} - -CASADI_SYMBOL_EXPORT const int* gN_fun_sparsity_out(int i) { - switch (i) { - case 0: return casadi_s0; - default: return 0; - } -} - -CASADI_SYMBOL_EXPORT int gN_fun_work(int *sz_arg, int* sz_res, int *sz_iw, int *sz_w) { - if (sz_arg) *sz_arg = 4; - if (sz_res) *sz_res = 1; - if (sz_iw) *sz_iw = 0; - if (sz_w) *sz_w = 5; - return 0; -} - -/* Hi_fun:(i0[4],i1,i2[0],i3[5],i4[5])->(o0[4x4],o1,o2[4]) */ -static int casadi_f15(const casadi_real** arg, casadi_real** res, int* iw, casadi_real* w, void* mem) { - casadi_real a0=arg[4] ? arg[4][0] : 0; - if (res[0]!=0) res[0][0]=a0; - a0=0.; - if (res[0]!=0) res[0][1]=a0; - if (res[0]!=0) res[0][2]=a0; - if (res[0]!=0) res[0][3]=a0; - if (res[0]!=0) res[0][4]=a0; - casadi_real a1=arg[4] ? arg[4][1] : 0; - if (res[0]!=0) res[0][5]=a1; - if (res[0]!=0) res[0][6]=a0; - if (res[0]!=0) res[0][7]=a0; - if (res[0]!=0) res[0][8]=a0; - if (res[0]!=0) res[0][9]=a0; - a1=arg[4] ? arg[4][2] : 0; - if (res[0]!=0) res[0][10]=a1; - if (res[0]!=0) res[0][11]=a0; - if (res[0]!=0) res[0][12]=a0; - if (res[0]!=0) res[0][13]=a0; - if (res[0]!=0) res[0][14]=a0; - a1=arg[4] ? arg[4][3] : 0; - if (res[0]!=0) res[0][15]=a1; - a1=arg[4] ? arg[4][4] : 0; - if (res[1]!=0) res[1][0]=a1; - if (res[2]!=0) res[2][0]=a0; - if (res[2]!=0) res[2][1]=a0; - if (res[2]!=0) res[2][2]=a0; - if (res[2]!=0) res[2][3]=a0; - return 0; -} - -CASADI_SYMBOL_EXPORT int Hi_fun(const casadi_real** arg, casadi_real** res, int* iw, casadi_real* w, void* mem){ - return casadi_f15(arg, res, iw, w, mem); -} - -CASADI_SYMBOL_EXPORT void Hi_fun_incref(void) { -} - -CASADI_SYMBOL_EXPORT void Hi_fun_decref(void) { -} - -CASADI_SYMBOL_EXPORT int Hi_fun_n_in(void) { return 5;} - -CASADI_SYMBOL_EXPORT int Hi_fun_n_out(void) { return 3;} - -CASADI_SYMBOL_EXPORT const char* Hi_fun_name_in(int i){ - switch (i) { - case 0: return "i0"; - case 1: return "i1"; - case 2: return "i2"; - case 3: return "i3"; - case 4: return "i4"; - default: return 0; - } -} - -CASADI_SYMBOL_EXPORT const char* Hi_fun_name_out(int i){ - switch (i) { - case 0: return "o0"; - case 1: return "o1"; - case 2: return "o2"; - default: return 0; - } -} - -CASADI_SYMBOL_EXPORT const int* Hi_fun_sparsity_in(int i) { - switch (i) { - case 0: return casadi_s0; - case 1: return casadi_s1; - case 2: return casadi_s2; - case 3: return casadi_s4; - case 4: return casadi_s4; - default: return 0; - } -} - -CASADI_SYMBOL_EXPORT const int* Hi_fun_sparsity_out(int i) { - switch (i) { - case 0: return casadi_s3; - case 1: return casadi_s1; - case 2: return casadi_s0; - default: return 0; - } -} - -CASADI_SYMBOL_EXPORT int Hi_fun_work(int *sz_arg, int* sz_res, int *sz_iw, int *sz_w) { - if (sz_arg) *sz_arg = 5; - if (sz_res) *sz_res = 3; - if (sz_iw) *sz_iw = 0; - if (sz_w) *sz_w = 2; - return 0; -} - -/* HN_fun:(i0[4],i1[0],i2[4],i3[4])->(o0[4x4]) */ -static int casadi_f16(const casadi_real** arg, casadi_real** res, int* iw, casadi_real* w, void* mem) { - casadi_real a0=arg[3] ? arg[3][0] : 0; - if (res[0]!=0) res[0][0]=a0; - a0=0.; - if (res[0]!=0) res[0][1]=a0; - if (res[0]!=0) res[0][2]=a0; - if (res[0]!=0) res[0][3]=a0; - if (res[0]!=0) res[0][4]=a0; - casadi_real a1=arg[3] ? arg[3][1] : 0; - if (res[0]!=0) res[0][5]=a1; - if (res[0]!=0) res[0][6]=a0; - if (res[0]!=0) res[0][7]=a0; - if (res[0]!=0) res[0][8]=a0; - if (res[0]!=0) res[0][9]=a0; - a1=arg[3] ? arg[3][2] : 0; - if (res[0]!=0) res[0][10]=a1; - if (res[0]!=0) res[0][11]=a0; - if (res[0]!=0) res[0][12]=a0; - if (res[0]!=0) res[0][13]=a0; - if (res[0]!=0) res[0][14]=a0; - a0=arg[3] ? arg[3][3] : 0; - if (res[0]!=0) res[0][15]=a0; - return 0; -} - -CASADI_SYMBOL_EXPORT int HN_fun(const casadi_real** arg, casadi_real** res, int* iw, casadi_real* w, void* mem){ - return casadi_f16(arg, res, iw, w, mem); -} - -CASADI_SYMBOL_EXPORT void HN_fun_incref(void) { -} - -CASADI_SYMBOL_EXPORT void HN_fun_decref(void) { -} - -CASADI_SYMBOL_EXPORT int HN_fun_n_in(void) { return 4;} - -CASADI_SYMBOL_EXPORT int HN_fun_n_out(void) { return 1;} - -CASADI_SYMBOL_EXPORT const char* HN_fun_name_in(int i){ - switch (i) { - case 0: return "i0"; - case 1: return "i1"; - case 2: return "i2"; - case 3: return "i3"; - default: return 0; - } -} - -CASADI_SYMBOL_EXPORT const char* HN_fun_name_out(int i){ - switch (i) { - case 0: return "o0"; - default: return 0; - } -} - -CASADI_SYMBOL_EXPORT const int* HN_fun_sparsity_in(int i) { - switch (i) { - case 0: return casadi_s0; - case 1: return casadi_s2; - case 2: return casadi_s0; - case 3: return casadi_s0; - default: return 0; - } -} - -CASADI_SYMBOL_EXPORT const int* HN_fun_sparsity_out(int i) { - switch (i) { - case 0: return casadi_s3; - default: return 0; - } -} - -CASADI_SYMBOL_EXPORT int HN_fun_work(int *sz_arg, int* sz_res, int *sz_iw, int *sz_w) { - if (sz_arg) *sz_arg = 4; - if (sz_res) *sz_res = 1; - if (sz_iw) *sz_iw = 0; - if (sz_w) *sz_w = 2; - return 0; -} - -/* Ci_fun:(i0[4],i1,i2[0])->(o0[0x4],o1[0]) */ -static int casadi_f17(const casadi_real** arg, casadi_real** res, int* iw, casadi_real* w, void* mem) { - return 0; -} - -CASADI_SYMBOL_EXPORT int Ci_fun(const casadi_real** arg, casadi_real** res, int* iw, casadi_real* w, void* mem){ - return casadi_f17(arg, res, iw, w, mem); -} - -CASADI_SYMBOL_EXPORT void Ci_fun_incref(void) { -} - -CASADI_SYMBOL_EXPORT void Ci_fun_decref(void) { -} - -CASADI_SYMBOL_EXPORT int Ci_fun_n_in(void) { return 3;} - -CASADI_SYMBOL_EXPORT int Ci_fun_n_out(void) { return 2;} - -CASADI_SYMBOL_EXPORT const char* Ci_fun_name_in(int i){ - switch (i) { - case 0: return "i0"; - case 1: return "i1"; - case 2: return "i2"; - default: return 0; - } -} - -CASADI_SYMBOL_EXPORT const char* Ci_fun_name_out(int i){ - switch (i) { - case 0: return "o0"; - case 1: return "o1"; - default: return 0; - } -} - -CASADI_SYMBOL_EXPORT const int* Ci_fun_sparsity_in(int i) { - switch (i) { - case 0: return casadi_s0; - case 1: return casadi_s1; - case 2: return casadi_s2; - default: return 0; - } -} - -CASADI_SYMBOL_EXPORT const int* Ci_fun_sparsity_out(int i) { - switch (i) { - case 0: return casadi_s6; - case 1: return casadi_s2; - default: return 0; - } -} - -CASADI_SYMBOL_EXPORT int Ci_fun_work(int *sz_arg, int* sz_res, int *sz_iw, int *sz_w) { - if (sz_arg) *sz_arg = 3; - if (sz_res) *sz_res = 2; - if (sz_iw) *sz_iw = 0; - if (sz_w) *sz_w = 0; - return 0; -} - -/* CN_fun:(i0[4],i1[0])->(o0[0x4]) */ -static int casadi_f18(const casadi_real** arg, casadi_real** res, int* iw, casadi_real* w, void* mem) { - return 0; -} - -CASADI_SYMBOL_EXPORT int CN_fun(const casadi_real** arg, casadi_real** res, int* iw, casadi_real* w, void* mem){ - return casadi_f18(arg, res, iw, w, mem); -} - -CASADI_SYMBOL_EXPORT void CN_fun_incref(void) { -} - -CASADI_SYMBOL_EXPORT void CN_fun_decref(void) { -} - -CASADI_SYMBOL_EXPORT int CN_fun_n_in(void) { return 2;} - -CASADI_SYMBOL_EXPORT int CN_fun_n_out(void) { return 1;} - -CASADI_SYMBOL_EXPORT const char* CN_fun_name_in(int i){ - switch (i) { - case 0: return "i0"; - case 1: return "i1"; - default: return 0; - } -} - -CASADI_SYMBOL_EXPORT const char* CN_fun_name_out(int i){ - switch (i) { - case 0: return "o0"; - default: return 0; - } -} - -CASADI_SYMBOL_EXPORT const int* CN_fun_sparsity_in(int i) { - switch (i) { - case 0: return casadi_s0; - case 1: return casadi_s2; - default: return 0; - } -} - -CASADI_SYMBOL_EXPORT const int* CN_fun_sparsity_out(int i) { - switch (i) { - case 0: return casadi_s6; - default: return 0; - } -} - -CASADI_SYMBOL_EXPORT int CN_fun_work(int *sz_arg, int* sz_res, int *sz_iw, int *sz_w) { - if (sz_arg) *sz_arg = 2; - if (sz_res) *sz_res = 1; - if (sz_iw) *sz_iw = 0; - if (sz_w) *sz_w = 0; - return 0; -} - -/* adj_fun:(i0[4],i1,i2[0],i3[5],i4[5],i5[4],i6,i7,i8[0])->(o0[5],o1[5],o2[5]) */ -static int casadi_f19(const casadi_real** arg, casadi_real** res, int* iw, casadi_real* w, void* mem) { - casadi_real a0=5.0000000000000000e-01; - casadi_real a1=arg[0] ? arg[0][0] : 0; - casadi_real a2=arg[3] ? arg[3][0] : 0; - casadi_real a3=(a1-a2); - a3=(a0*a3); - casadi_real a4=arg[4] ? arg[4][0] : 0; - a3=(a3*a4); - a1=(a1-a2); - a4=(a4*a1); - a4=(a0*a4); - a3=(a3+a4); - if (res[0]!=0) res[0][0]=a3; - a3=arg[0] ? arg[0][1] : 0; - a4=arg[3] ? arg[3][1] : 0; - a1=(a3-a4); - a1=(a0*a1); - a2=arg[4] ? arg[4][1] : 0; - a1=(a1*a2); - a4=(a3-a4); - a2=(a2*a4); - a2=(a0*a2); - a1=(a1+a2); - if (res[0]!=0) res[0][1]=a1; - a1=arg[0] ? arg[0][2] : 0; - a2=arg[3] ? arg[3][2] : 0; - a4=(a1-a2); - a4=(a0*a4); - casadi_real a5=arg[4] ? arg[4][2] : 0; - a4=(a4*a5); - a1=(a1-a2); - a5=(a5*a1); - a5=(a0*a5); - a4=(a4+a5); - if (res[0]!=0) res[0][2]=a4; - a4=arg[0] ? arg[0][3] : 0; - a5=arg[3] ? arg[3][3] : 0; - a1=(a4-a5); - a1=(a0*a1); - a2=arg[4] ? arg[4][3] : 0; - a1=(a1*a2); - a5=(a4-a5); - a2=(a2*a5); - a2=(a0*a2); - a1=(a1+a2); - if (res[0]!=0) res[0][3]=a1; - a1=arg[1] ? arg[1][0] : 0; - a2=arg[3] ? arg[3][4] : 0; - a5=(a1-a2); - casadi_real a6=arg[4] ? arg[4][4] : 0; - casadi_real a7=(a0*a6); - a5=(a5*a7); - a2=(a1-a2); - a0=(a0*a2); - a0=(a0*a6); - a5=(a5+a0); - if (res[0]!=0) res[0][4]=a5; - a5=arg[5] ? arg[5][0] : 0; - if (res[1]!=0) res[1][0]=a5; - a0=5.0000000000000003e-02; - a6=2.5000000000000001e-02; - a2=-8.0000000000000016e-02; - a7=(a6*a4); - a7=(a3+a7); - casadi_real a8=cos(a7); - a8=(a2*a8); - casadi_real a9=sin(a7); - casadi_real a10=(a8*a9); - casadi_real a11=cos(a3); - a11=(a2*a11); - casadi_real a12=sin(a3); - casadi_real a13=(a11*a12); - casadi_real a14=sq(a4); - casadi_real a15=(a13*a14); - casadi_real a16=cos(a3); - casadi_real a17=(a1*a16); - a15=(a15+a17); - a17=1.0791000000000002e+01; - casadi_real a18=sin(a3); - a18=(a17*a18); - a15=(a15+a18); - a18=8.0000000000000004e-01; - casadi_real a19=1.1000000000000001e+00; - casadi_real a20=1.0000000000000001e-01; - casadi_real a21=cos(a3); - casadi_real a22=sq(a21); - a22=(a20*a22); - a22=(a19-a22); - casadi_real a23=(a18*a22); - a15=(a15/a23); - casadi_real a24=(a6*a15); - a24=(a4+a24); - casadi_real a25=sq(a24); - casadi_real a26=(a10*a25); - casadi_real a27=cos(a7); - casadi_real a28=(a1*a27); - a26=(a26+a28); - a28=sin(a7); - a28=(a17*a28); - a26=(a26+a28); - a28=cos(a7); - casadi_real a29=sq(a28); - a29=(a20*a29); - a29=(a19-a29); - casadi_real a30=(a18*a29); - a26=(a26/a30); - casadi_real a31=(a6*a26); - a31=(a4+a31); - casadi_real a32=(a0*a31); - a32=(a3+a32); - casadi_real a33=cos(a32); - casadi_real a34=8.3333333333333332e-03; - casadi_real a35=arg[5] ? arg[5][3] : 0; - casadi_real a36=(a34*a35); - casadi_real a37=cos(a32); - casadi_real a38=sq(a37); - a38=(a20*a38); - a38=(a19-a38); - casadi_real a39=(a18*a38); - casadi_real a40=(a36/a39); - casadi_real a41=(a17*a40); - a33=(a33*a41); - a41=sin(a32); - casadi_real a42=(a1*a40); - a41=(a41*a42); - a33=(a33-a41); - a41=cos(a32); - a42=cos(a32); - a42=(a2*a42); - casadi_real a43=(a6*a24); - a43=(a3+a43); - casadi_real a44=cos(a43); - a44=(a2*a44); - casadi_real a45=sin(a43); - casadi_real a46=(a44*a45); - casadi_real a47=sq(a31); - casadi_real a48=(a46*a47); - casadi_real a49=cos(a43); - casadi_real a50=(a1*a49); - a48=(a48+a50); - a50=sin(a43); - a50=(a17*a50); - a48=(a48+a50); - a50=cos(a43); - casadi_real a51=sq(a50); - a51=(a20*a51); - a19=(a19-a51); - a51=(a18*a19); - a48=(a48/a51); - casadi_real a52=(a0*a48); - a52=(a4+a52); - casadi_real a53=sq(a52); - casadi_real a54=(a53*a40); - casadi_real a55=(a42*a54); - a41=(a41*a55); - a33=(a33+a41); - a41=sin(a32); - a55=sin(a32); - a54=(a55*a54); - a54=(a2*a54); - a41=(a41*a54); - a33=(a33-a41); - a41=sin(a32); - a37=(a37+a37); - a42=(a42*a55); - a53=(a42*a53); - a55=cos(a32); - a54=(a1*a55); - a53=(a53+a54); - a54=sin(a32); - a54=(a17*a54); - a53=(a53+a54); - a53=(a53/a39); - a53=(a53/a39); - a53=(a53*a36); - a53=(a18*a53); - a39=sin(a32); - a39=(a2*a39); - a54=sq(a52); - casadi_real a56=(a39*a54); - casadi_real a57=9.8100000000000009e-01; - casadi_real a58=cos(a32); - a58=(a57*a58); - casadi_real a59=sin(a32); - casadi_real a60=(a58*a59); - a56=(a56+a60); - a56=(a56+a1); - a56=(a56/a38); - a56=(a56/a38); - a60=arg[5] ? arg[5][2] : 0; - casadi_real a61=(a34*a60); - a56=(a56*a61); - a53=(a53+a56); - a53=(a20*a53); - a37=(a37*a53); - a41=(a41*a37); - a33=(a33-a41); - a41=cos(a32); - a38=(a61/a38); - a58=(a58*a38); - a41=(a41*a58); - a33=(a33+a41); - a41=sin(a32); - a59=(a59*a38); - a59=(a57*a59); - a41=(a41*a59); - a33=(a33-a41); - a32=cos(a32); - a54=(a54*a38); - a54=(a2*a54); - a32=(a32*a54); - a33=(a33+a32); - a32=arg[5] ? arg[5][1] : 0; - a54=(a33+a32); - a41=cos(a43); - a59=2.; - a58=(a59*a36); - a37=(a52+a52); - a42=(a42*a40); - a37=(a37*a42); - a52=(a52+a52); - a39=(a39*a38); - a52=(a52*a39); - a37=(a37+a52); - a32=(a34*a32); - a37=(a37+a32); - a52=(a0*a37); - a58=(a58+a52); - a52=(a58/a51); - a39=(a17*a52); - a41=(a41*a39); - a39=sin(a43); - a42=(a1*a52); - a39=(a39*a42); - a41=(a41-a39); - a39=cos(a43); - a47=(a47*a52); - a44=(a44*a47); - a39=(a39*a44); - a41=(a41+a39); - a39=sin(a43); - a45=(a45*a47); - a45=(a2*a45); - a39=(a39*a45); - a41=(a41-a39); - a39=sin(a43); - a50=(a50+a50); - a48=(a48/a51); - a48=(a48*a58); - a48=(a18*a48); - a58=sin(a43); - a58=(a2*a58); - a51=sq(a31); - a45=(a58*a51); - a47=cos(a43); - a47=(a57*a47); - a44=sin(a43); - a42=(a47*a44); - a45=(a45+a42); - a45=(a45+a1); - a45=(a45/a19); - a45=(a45/a19); - a42=(a59*a61); - a34=(a34*a5); - a5=(a0*a34); - a42=(a42+a5); - a45=(a45*a42); - a48=(a48+a45); - a48=(a20*a48); - a50=(a50*a48); - a39=(a39*a50); - a41=(a41-a39); - a39=cos(a43); - a42=(a42/a19); - a47=(a47*a42); - a39=(a39*a47); - a41=(a41+a39); - a39=sin(a43); - a44=(a44*a42); - a44=(a57*a44); - a39=(a39*a44); - a41=(a41-a39); - a43=cos(a43); - a51=(a51*a42); - a51=(a2*a51); - a43=(a43*a51); - a41=(a41+a43); - a54=(a54+a41); - a43=cos(a3); - a51=(a59*a32); - a39=(a24+a24); - a44=(a59*a36); - a0=(a0*a33); - a33=(a31+a31); - a46=(a46*a52); - a33=(a33*a46); - a0=(a0+a33); - a33=(a59*a32); - a0=(a0+a33); - a31=(a31+a31); - a58=(a58*a42); - a31=(a31*a58); - a0=(a0+a31); - a31=(a6*a0); - a44=(a44+a31); - a31=(a44/a30); - a10=(a10*a31); - a39=(a39*a10); - a51=(a51+a39); - a41=(a6*a41); - a51=(a51+a41); - a41=(a24+a24); - a39=sin(a7); - a39=(a2*a39); - a10=(a59*a61); - a58=(a59*a34); - a33=(a6*a58); - a10=(a10+a33); - a33=(a10/a29); - a46=(a39*a33); - a41=(a41*a46); - a51=(a51+a41); - a41=(a6*a51); - a36=(a36+a41); - a41=(a36/a23); - a46=(a17*a41); - a43=(a43*a46); - a54=(a54+a43); - a43=sin(a3); - a46=(a1*a41); - a43=(a43*a46); - a54=(a54-a43); - a43=cos(a3); - a14=(a14*a41); - a11=(a11*a14); - a43=(a43*a11); - a54=(a54+a43); - a43=sin(a3); - a12=(a12*a14); - a12=(a2*a12); - a43=(a43*a12); - a54=(a54-a43); - a43=cos(a7); - a17=(a17*a31); - a43=(a43*a17); - a17=sin(a7); - a12=(a1*a31); - a17=(a17*a12); - a43=(a43-a17); - a17=cos(a7); - a25=(a25*a31); - a8=(a8*a25); - a17=(a17*a8); - a43=(a43+a17); - a17=sin(a7); - a9=(a9*a25); - a9=(a2*a9); - a17=(a17*a9); - a43=(a43-a17); - a17=sin(a7); - a28=(a28+a28); - a26=(a26/a30); - a26=(a26*a44); - a26=(a18*a26); - a24=sq(a24); - a39=(a39*a24); - a44=cos(a7); - a44=(a57*a44); - a30=sin(a7); - a9=(a44*a30); - a39=(a39+a9); - a39=(a39+a1); - a39=(a39/a29); - a39=(a39/a29); - a39=(a39*a10); - a26=(a26+a39); - a26=(a20*a26); - a28=(a28*a26); - a17=(a17*a28); - a43=(a43-a17); - a17=cos(a7); - a44=(a44*a33); - a17=(a17*a44); - a43=(a43+a17); - a17=sin(a7); - a30=(a30*a33); - a30=(a57*a30); - a17=(a17*a30); - a43=(a43-a17); - a7=cos(a7); - a24=(a24*a33); - a24=(a2*a24); - a7=(a7*a24); - a43=(a43+a7); - a54=(a54+a43); - a7=sin(a3); - a21=(a21+a21); - a15=(a15/a23); - a15=(a15*a36); - a18=(a18*a15); - a15=sin(a3); - a15=(a2*a15); - a36=sq(a4); - a23=(a15*a36); - a24=cos(a3); - a24=(a57*a24); - a17=sin(a3); - a30=(a24*a17); - a23=(a23+a30); - a23=(a23+a1); - a23=(a23/a22); - a23=(a23/a22); - a59=(a59*a34); - a1=(a6*a59); - a61=(a61+a1); - a23=(a23*a61); - a18=(a18+a23); - a20=(a20*a18); - a21=(a21*a20); - a7=(a7*a21); - a54=(a54-a7); - a7=cos(a3); - a61=(a61/a22); - a24=(a24*a61); - a7=(a7*a24); - a54=(a54+a7); - a7=sin(a3); - a17=(a17*a61); - a57=(a57*a17); - a7=(a7*a57); - a54=(a54-a7); - a3=cos(a3); - a36=(a36*a61); - a2=(a2*a36); - a3=(a3*a2); - a54=(a54+a3); - if (res[1]!=0) res[1][1]=a54; - a60=(a60+a34); - a60=(a60+a58); - a60=(a60+a34); - a60=(a60+a59); - if (res[1]!=0) res[1][2]=a60; - a35=(a35+a37); - a35=(a35+a32); - a35=(a35+a0); - a35=(a35+a51); - a51=(a4+a4); - a13=(a13*a41); - a51=(a51*a13); - a35=(a35+a51); - a6=(a6*a43); - a35=(a35+a6); - a4=(a4+a4); - a15=(a15*a61); - a4=(a4*a15); - a35=(a35+a4); - if (res[1]!=0) res[1][3]=a35; - a55=(a55*a40); - a55=(a55+a38); - a49=(a49*a52); - a55=(a55+a49); - a55=(a55+a42); - a27=(a27*a31); - a55=(a55+a27); - a55=(a55+a33); - a16=(a16*a41); - a55=(a55+a16); - a55=(a55+a61); - if (res[1]!=0) res[1][4]=a55; - a55=arg[6] ? arg[6][0] : 0; - if (res[2]!=0) res[2][0]=a55; - a55=0.; - if (res[2]!=0) res[2][1]=a55; - if (res[2]!=0) res[2][2]=a55; - if (res[2]!=0) res[2][3]=a55; - a55=arg[7] ? arg[7][0] : 0; - if (res[2]!=0) res[2][4]=a55; - return 0; -} - -CASADI_SYMBOL_EXPORT int adj_fun(const casadi_real** arg, casadi_real** res, int* iw, casadi_real* w, void* mem){ - return casadi_f19(arg, res, iw, w, mem); -} - -CASADI_SYMBOL_EXPORT void adj_fun_incref(void) { -} - -CASADI_SYMBOL_EXPORT void adj_fun_decref(void) { -} - -CASADI_SYMBOL_EXPORT int adj_fun_n_in(void) { return 9;} - -CASADI_SYMBOL_EXPORT int adj_fun_n_out(void) { return 3;} - -CASADI_SYMBOL_EXPORT const char* adj_fun_name_in(int i){ - switch (i) { - case 0: return "i0"; - case 1: return "i1"; - case 2: return "i2"; - case 3: return "i3"; - case 4: return "i4"; - case 5: return "i5"; - case 6: return "i6"; - case 7: return "i7"; - case 8: return "i8"; - default: return 0; - } -} - -CASADI_SYMBOL_EXPORT const char* adj_fun_name_out(int i){ - switch (i) { - case 0: return "o0"; - case 1: return "o1"; - case 2: return "o2"; - default: return 0; - } -} - -CASADI_SYMBOL_EXPORT const int* adj_fun_sparsity_in(int i) { - switch (i) { - case 0: return casadi_s0; - case 1: return casadi_s1; - case 2: return casadi_s2; - case 3: return casadi_s4; - case 4: return casadi_s4; - case 5: return casadi_s0; - case 6: return casadi_s1; - case 7: return casadi_s1; - case 8: return casadi_s2; - default: return 0; - } -} - -CASADI_SYMBOL_EXPORT const int* adj_fun_sparsity_out(int i) { - switch (i) { - case 0: return casadi_s4; - case 1: return casadi_s4; - case 2: return casadi_s4; - default: return 0; - } -} - -CASADI_SYMBOL_EXPORT int adj_fun_work(int *sz_arg, int* sz_res, int *sz_iw, int *sz_w) { - if (sz_arg) *sz_arg = 9; - if (sz_res) *sz_res = 3; - if (sz_iw) *sz_iw = 0; - if (sz_w) *sz_w = 62; - return 0; -} - -/* adjN_fun:(i0[4],i1[0],i2[4],i3[4],i4,i5[0])->(o0[4],o1[4]) */ -static int casadi_f20(const casadi_real** arg, casadi_real** res, int* iw, casadi_real* w, void* mem) { - casadi_real a0=5.0000000000000000e-01; - casadi_real a1=arg[0] ? arg[0][0] : 0; - casadi_real a2=arg[2] ? arg[2][0] : 0; - casadi_real a3=(a1-a2); - a3=(a0*a3); - casadi_real a4=arg[3] ? arg[3][0] : 0; - a3=(a3*a4); - a1=(a1-a2); - a4=(a4*a1); - a4=(a0*a4); - a3=(a3+a4); - if (res[0]!=0) res[0][0]=a3; - a3=arg[0] ? arg[0][1] : 0; - a4=arg[2] ? arg[2][1] : 0; - a1=(a3-a4); - a1=(a0*a1); - a2=arg[3] ? arg[3][1] : 0; - a1=(a1*a2); - a3=(a3-a4); - a2=(a2*a3); - a2=(a0*a2); - a1=(a1+a2); - if (res[0]!=0) res[0][1]=a1; - a1=arg[0] ? arg[0][2] : 0; - a2=arg[2] ? arg[2][2] : 0; - a3=(a1-a2); - a3=(a0*a3); - a4=arg[3] ? arg[3][2] : 0; - a3=(a3*a4); - a1=(a1-a2); - a4=(a4*a1); - a4=(a0*a4); - a3=(a3+a4); - if (res[0]!=0) res[0][2]=a3; - a3=arg[0] ? arg[0][3] : 0; - a4=arg[2] ? arg[2][3] : 0; - a1=(a3-a4); - a1=(a0*a1); - a2=arg[3] ? arg[3][3] : 0; - a1=(a1*a2); - a3=(a3-a4); - a2=(a2*a3); - a0=(a0*a2); - a1=(a1+a0); - if (res[0]!=0) res[0][3]=a1; - a1=arg[4] ? arg[4][0] : 0; - if (res[1]!=0) res[1][0]=a1; - a1=0.; - if (res[1]!=0) res[1][1]=a1; - if (res[1]!=0) res[1][2]=a1; - if (res[1]!=0) res[1][3]=a1; - return 0; -} - -CASADI_SYMBOL_EXPORT int adjN_fun(const casadi_real** arg, casadi_real** res, int* iw, casadi_real* w, void* mem){ - return casadi_f20(arg, res, iw, w, mem); -} - -CASADI_SYMBOL_EXPORT void adjN_fun_incref(void) { -} - -CASADI_SYMBOL_EXPORT void adjN_fun_decref(void) { -} - -CASADI_SYMBOL_EXPORT int adjN_fun_n_in(void) { return 6;} - -CASADI_SYMBOL_EXPORT int adjN_fun_n_out(void) { return 2;} - -CASADI_SYMBOL_EXPORT const char* adjN_fun_name_in(int i){ - switch (i) { - case 0: return "i0"; - case 1: return "i1"; - case 2: return "i2"; - case 3: return "i3"; - case 4: return "i4"; - case 5: return "i5"; - default: return 0; - } -} - -CASADI_SYMBOL_EXPORT const char* adjN_fun_name_out(int i){ - switch (i) { - case 0: return "o0"; - case 1: return "o1"; - default: return 0; - } -} - -CASADI_SYMBOL_EXPORT const int* adjN_fun_sparsity_in(int i) { - switch (i) { - case 0: return casadi_s0; - case 1: return casadi_s2; - case 2: return casadi_s0; - case 3: return casadi_s0; - case 4: return casadi_s1; - case 5: return casadi_s2; - default: return 0; - } -} - -CASADI_SYMBOL_EXPORT const int* adjN_fun_sparsity_out(int i) { - switch (i) { - case 0: return casadi_s0; - case 1: return casadi_s0; - default: return 0; - } -} - -CASADI_SYMBOL_EXPORT int adjN_fun_work(int *sz_arg, int* sz_res, int *sz_iw, int *sz_w) { - if (sz_arg) *sz_arg = 6; - if (sz_res) *sz_res = 2; - if (sz_iw) *sz_iw = 0; - if (sz_w) *sz_w = 5; - return 0; -} - -/* adj_dG_fun:(i0[4],i1,i2[0],i3[5],i4[5],i5[4])->(o0[5],o1[5]) */ -static int casadi_f21(const casadi_real** arg, casadi_real** res, int* iw, casadi_real* w, void* mem) { - casadi_real a0=5.0000000000000000e-01; - casadi_real a1=arg[0] ? arg[0][0] : 0; - casadi_real a2=arg[3] ? arg[3][0] : 0; - casadi_real a3=(a1-a2); - a3=(a0*a3); - casadi_real a4=arg[4] ? arg[4][0] : 0; - a3=(a3*a4); - a1=(a1-a2); - a4=(a4*a1); - a4=(a0*a4); - a3=(a3+a4); - if (res[0]!=0) res[0][0]=a3; - a3=arg[0] ? arg[0][1] : 0; - a4=arg[3] ? arg[3][1] : 0; - a1=(a3-a4); - a1=(a0*a1); - a2=arg[4] ? arg[4][1] : 0; - a1=(a1*a2); - a4=(a3-a4); - a2=(a2*a4); - a2=(a0*a2); - a1=(a1+a2); - if (res[0]!=0) res[0][1]=a1; - a1=arg[0] ? arg[0][2] : 0; - a2=arg[3] ? arg[3][2] : 0; - a4=(a1-a2); - a4=(a0*a4); - casadi_real a5=arg[4] ? arg[4][2] : 0; - a4=(a4*a5); - a1=(a1-a2); - a5=(a5*a1); - a5=(a0*a5); - a4=(a4+a5); - if (res[0]!=0) res[0][2]=a4; - a4=arg[0] ? arg[0][3] : 0; - a5=arg[3] ? arg[3][3] : 0; - a1=(a4-a5); - a1=(a0*a1); - a2=arg[4] ? arg[4][3] : 0; - a1=(a1*a2); - a5=(a4-a5); - a2=(a2*a5); - a2=(a0*a2); - a1=(a1+a2); - if (res[0]!=0) res[0][3]=a1; - a1=arg[1] ? arg[1][0] : 0; - a2=arg[3] ? arg[3][4] : 0; - a5=(a1-a2); - casadi_real a6=arg[4] ? arg[4][4] : 0; - casadi_real a7=(a0*a6); - a5=(a5*a7); - a2=(a1-a2); - a0=(a0*a2); - a0=(a0*a6); - a5=(a5+a0); - if (res[0]!=0) res[0][4]=a5; - a5=arg[5] ? arg[5][0] : 0; - if (res[1]!=0) res[1][0]=a5; - a0=5.0000000000000003e-02; - a6=2.5000000000000001e-02; - a2=-8.0000000000000016e-02; - a7=(a6*a4); - a7=(a3+a7); - casadi_real a8=cos(a7); - a8=(a2*a8); - casadi_real a9=sin(a7); - casadi_real a10=(a8*a9); - casadi_real a11=cos(a3); - a11=(a2*a11); - casadi_real a12=sin(a3); - casadi_real a13=(a11*a12); - casadi_real a14=sq(a4); - casadi_real a15=(a13*a14); - casadi_real a16=cos(a3); - casadi_real a17=(a1*a16); - a15=(a15+a17); - a17=1.0791000000000002e+01; - casadi_real a18=sin(a3); - a18=(a17*a18); - a15=(a15+a18); - a18=8.0000000000000004e-01; - casadi_real a19=1.1000000000000001e+00; - casadi_real a20=1.0000000000000001e-01; - casadi_real a21=cos(a3); - casadi_real a22=sq(a21); - a22=(a20*a22); - a22=(a19-a22); - casadi_real a23=(a18*a22); - a15=(a15/a23); - casadi_real a24=(a6*a15); - a24=(a4+a24); - casadi_real a25=sq(a24); - casadi_real a26=(a10*a25); - casadi_real a27=cos(a7); - casadi_real a28=(a1*a27); - a26=(a26+a28); - a28=sin(a7); - a28=(a17*a28); - a26=(a26+a28); - a28=cos(a7); - casadi_real a29=sq(a28); - a29=(a20*a29); - a29=(a19-a29); - casadi_real a30=(a18*a29); - a26=(a26/a30); - casadi_real a31=(a6*a26); - a31=(a4+a31); - casadi_real a32=(a0*a31); - a32=(a3+a32); - casadi_real a33=cos(a32); - casadi_real a34=8.3333333333333332e-03; - casadi_real a35=arg[5] ? arg[5][3] : 0; - casadi_real a36=(a34*a35); - casadi_real a37=cos(a32); - casadi_real a38=sq(a37); - a38=(a20*a38); - a38=(a19-a38); - casadi_real a39=(a18*a38); - casadi_real a40=(a36/a39); - casadi_real a41=(a17*a40); - a33=(a33*a41); - a41=sin(a32); - casadi_real a42=(a1*a40); - a41=(a41*a42); - a33=(a33-a41); - a41=cos(a32); - a42=cos(a32); - a42=(a2*a42); - casadi_real a43=(a6*a24); - a43=(a3+a43); - casadi_real a44=cos(a43); - a44=(a2*a44); - casadi_real a45=sin(a43); - casadi_real a46=(a44*a45); - casadi_real a47=sq(a31); - casadi_real a48=(a46*a47); - casadi_real a49=cos(a43); - casadi_real a50=(a1*a49); - a48=(a48+a50); - a50=sin(a43); - a50=(a17*a50); - a48=(a48+a50); - a50=cos(a43); - casadi_real a51=sq(a50); - a51=(a20*a51); - a19=(a19-a51); - a51=(a18*a19); - a48=(a48/a51); - casadi_real a52=(a0*a48); - a52=(a4+a52); - casadi_real a53=sq(a52); - casadi_real a54=(a53*a40); - casadi_real a55=(a42*a54); - a41=(a41*a55); - a33=(a33+a41); - a41=sin(a32); - a55=sin(a32); - a54=(a55*a54); - a54=(a2*a54); - a41=(a41*a54); - a33=(a33-a41); - a41=sin(a32); - a37=(a37+a37); - a42=(a42*a55); - a53=(a42*a53); - a55=cos(a32); - a54=(a1*a55); - a53=(a53+a54); - a54=sin(a32); - a54=(a17*a54); - a53=(a53+a54); - a53=(a53/a39); - a53=(a53/a39); - a53=(a53*a36); - a53=(a18*a53); - a39=sin(a32); - a39=(a2*a39); - a54=sq(a52); - casadi_real a56=(a39*a54); - casadi_real a57=9.8100000000000009e-01; - casadi_real a58=cos(a32); - a58=(a57*a58); - casadi_real a59=sin(a32); - casadi_real a60=(a58*a59); - a56=(a56+a60); - a56=(a56+a1); - a56=(a56/a38); - a56=(a56/a38); - a60=arg[5] ? arg[5][2] : 0; - casadi_real a61=(a34*a60); - a56=(a56*a61); - a53=(a53+a56); - a53=(a20*a53); - a37=(a37*a53); - a41=(a41*a37); - a33=(a33-a41); - a41=cos(a32); - a38=(a61/a38); - a58=(a58*a38); - a41=(a41*a58); - a33=(a33+a41); - a41=sin(a32); - a59=(a59*a38); - a59=(a57*a59); - a41=(a41*a59); - a33=(a33-a41); - a32=cos(a32); - a54=(a54*a38); - a54=(a2*a54); - a32=(a32*a54); - a33=(a33+a32); - a32=arg[5] ? arg[5][1] : 0; - a54=(a33+a32); - a41=cos(a43); - a59=2.; - a58=(a59*a36); - a37=(a52+a52); - a42=(a42*a40); - a37=(a37*a42); - a52=(a52+a52); - a39=(a39*a38); - a52=(a52*a39); - a37=(a37+a52); - a32=(a34*a32); - a37=(a37+a32); - a52=(a0*a37); - a58=(a58+a52); - a52=(a58/a51); - a39=(a17*a52); - a41=(a41*a39); - a39=sin(a43); - a42=(a1*a52); - a39=(a39*a42); - a41=(a41-a39); - a39=cos(a43); - a47=(a47*a52); - a44=(a44*a47); - a39=(a39*a44); - a41=(a41+a39); - a39=sin(a43); - a45=(a45*a47); - a45=(a2*a45); - a39=(a39*a45); - a41=(a41-a39); - a39=sin(a43); - a50=(a50+a50); - a48=(a48/a51); - a48=(a48*a58); - a48=(a18*a48); - a58=sin(a43); - a58=(a2*a58); - a51=sq(a31); - a45=(a58*a51); - a47=cos(a43); - a47=(a57*a47); - a44=sin(a43); - a42=(a47*a44); - a45=(a45+a42); - a45=(a45+a1); - a45=(a45/a19); - a45=(a45/a19); - a42=(a59*a61); - a34=(a34*a5); - a5=(a0*a34); - a42=(a42+a5); - a45=(a45*a42); - a48=(a48+a45); - a48=(a20*a48); - a50=(a50*a48); - a39=(a39*a50); - a41=(a41-a39); - a39=cos(a43); - a42=(a42/a19); - a47=(a47*a42); - a39=(a39*a47); - a41=(a41+a39); - a39=sin(a43); - a44=(a44*a42); - a44=(a57*a44); - a39=(a39*a44); - a41=(a41-a39); - a43=cos(a43); - a51=(a51*a42); - a51=(a2*a51); - a43=(a43*a51); - a41=(a41+a43); - a54=(a54+a41); - a43=cos(a3); - a51=(a59*a32); - a39=(a24+a24); - a44=(a59*a36); - a0=(a0*a33); - a33=(a31+a31); - a46=(a46*a52); - a33=(a33*a46); - a0=(a0+a33); - a33=(a59*a32); - a0=(a0+a33); - a31=(a31+a31); - a58=(a58*a42); - a31=(a31*a58); - a0=(a0+a31); - a31=(a6*a0); - a44=(a44+a31); - a31=(a44/a30); - a10=(a10*a31); - a39=(a39*a10); - a51=(a51+a39); - a41=(a6*a41); - a51=(a51+a41); - a41=(a24+a24); - a39=sin(a7); - a39=(a2*a39); - a10=(a59*a61); - a58=(a59*a34); - a33=(a6*a58); - a10=(a10+a33); - a33=(a10/a29); - a46=(a39*a33); - a41=(a41*a46); - a51=(a51+a41); - a41=(a6*a51); - a36=(a36+a41); - a41=(a36/a23); - a46=(a17*a41); - a43=(a43*a46); - a54=(a54+a43); - a43=sin(a3); - a46=(a1*a41); - a43=(a43*a46); - a54=(a54-a43); - a43=cos(a3); - a14=(a14*a41); - a11=(a11*a14); - a43=(a43*a11); - a54=(a54+a43); - a43=sin(a3); - a12=(a12*a14); - a12=(a2*a12); - a43=(a43*a12); - a54=(a54-a43); - a43=cos(a7); - a17=(a17*a31); - a43=(a43*a17); - a17=sin(a7); - a12=(a1*a31); - a17=(a17*a12); - a43=(a43-a17); - a17=cos(a7); - a25=(a25*a31); - a8=(a8*a25); - a17=(a17*a8); - a43=(a43+a17); - a17=sin(a7); - a9=(a9*a25); - a9=(a2*a9); - a17=(a17*a9); - a43=(a43-a17); - a17=sin(a7); - a28=(a28+a28); - a26=(a26/a30); - a26=(a26*a44); - a26=(a18*a26); - a24=sq(a24); - a39=(a39*a24); - a44=cos(a7); - a44=(a57*a44); - a30=sin(a7); - a9=(a44*a30); - a39=(a39+a9); - a39=(a39+a1); - a39=(a39/a29); - a39=(a39/a29); - a39=(a39*a10); - a26=(a26+a39); - a26=(a20*a26); - a28=(a28*a26); - a17=(a17*a28); - a43=(a43-a17); - a17=cos(a7); - a44=(a44*a33); - a17=(a17*a44); - a43=(a43+a17); - a17=sin(a7); - a30=(a30*a33); - a30=(a57*a30); - a17=(a17*a30); - a43=(a43-a17); - a7=cos(a7); - a24=(a24*a33); - a24=(a2*a24); - a7=(a7*a24); - a43=(a43+a7); - a54=(a54+a43); - a7=sin(a3); - a21=(a21+a21); - a15=(a15/a23); - a15=(a15*a36); - a18=(a18*a15); - a15=sin(a3); - a15=(a2*a15); - a36=sq(a4); - a23=(a15*a36); - a24=cos(a3); - a24=(a57*a24); - a17=sin(a3); - a30=(a24*a17); - a23=(a23+a30); - a23=(a23+a1); - a23=(a23/a22); - a23=(a23/a22); - a59=(a59*a34); - a1=(a6*a59); - a61=(a61+a1); - a23=(a23*a61); - a18=(a18+a23); - a20=(a20*a18); - a21=(a21*a20); - a7=(a7*a21); - a54=(a54-a7); - a7=cos(a3); - a61=(a61/a22); - a24=(a24*a61); - a7=(a7*a24); - a54=(a54+a7); - a7=sin(a3); - a17=(a17*a61); - a57=(a57*a17); - a7=(a7*a57); - a54=(a54-a7); - a3=cos(a3); - a36=(a36*a61); - a2=(a2*a36); - a3=(a3*a2); - a54=(a54+a3); - if (res[1]!=0) res[1][1]=a54; - a60=(a60+a34); - a60=(a60+a58); - a60=(a60+a34); - a60=(a60+a59); - if (res[1]!=0) res[1][2]=a60; - a35=(a35+a37); - a35=(a35+a32); - a35=(a35+a0); - a35=(a35+a51); - a51=(a4+a4); - a13=(a13*a41); - a51=(a51*a13); - a35=(a35+a51); - a6=(a6*a43); - a35=(a35+a6); - a4=(a4+a4); - a15=(a15*a61); - a4=(a4*a15); - a35=(a35+a4); - if (res[1]!=0) res[1][3]=a35; - a55=(a55*a40); - a55=(a55+a38); - a49=(a49*a52); - a55=(a55+a49); - a55=(a55+a42); - a27=(a27*a31); - a55=(a55+a27); - a55=(a55+a33); - a16=(a16*a41); - a55=(a55+a16); - a55=(a55+a61); - if (res[1]!=0) res[1][4]=a55; - return 0; -} - -CASADI_SYMBOL_EXPORT int adj_dG_fun(const casadi_real** arg, casadi_real** res, int* iw, casadi_real* w, void* mem){ - return casadi_f21(arg, res, iw, w, mem); -} - -CASADI_SYMBOL_EXPORT void adj_dG_fun_incref(void) { -} - -CASADI_SYMBOL_EXPORT void adj_dG_fun_decref(void) { -} - -CASADI_SYMBOL_EXPORT int adj_dG_fun_n_in(void) { return 6;} - -CASADI_SYMBOL_EXPORT int adj_dG_fun_n_out(void) { return 2;} - -CASADI_SYMBOL_EXPORT const char* adj_dG_fun_name_in(int i){ - switch (i) { - case 0: return "i0"; - case 1: return "i1"; - case 2: return "i2"; - case 3: return "i3"; - case 4: return "i4"; - case 5: return "i5"; - default: return 0; - } -} - -CASADI_SYMBOL_EXPORT const char* adj_dG_fun_name_out(int i){ - switch (i) { - case 0: return "o0"; - case 1: return "o1"; - default: return 0; - } -} - -CASADI_SYMBOL_EXPORT const int* adj_dG_fun_sparsity_in(int i) { - switch (i) { - case 0: return casadi_s0; - case 1: return casadi_s1; - case 2: return casadi_s2; - case 3: return casadi_s4; - case 4: return casadi_s4; - case 5: return casadi_s0; - default: return 0; - } -} - -CASADI_SYMBOL_EXPORT const int* adj_dG_fun_sparsity_out(int i) { - switch (i) { - case 0: return casadi_s4; - case 1: return casadi_s4; - default: return 0; - } -} - -CASADI_SYMBOL_EXPORT int adj_dG_fun_work(int *sz_arg, int* sz_res, int *sz_iw, int *sz_w) { - if (sz_arg) *sz_arg = 6; - if (sz_res) *sz_res = 2; - if (sz_iw) *sz_iw = 0; - if (sz_w) *sz_w = 62; - return 0; -} - - -#ifdef __cplusplus -} /* extern "C" */ -#endif +/* This file was automatically generated by CasADi. + The CasADi copyright holders make no ownership claim of its contents. */ +/* How to prefix internal symbols */ +#ifdef CASADI_CODEGEN_PREFIX + #define CASADI_NAMESPACE_CONCAT(NS, ID) _CASADI_NAMESPACE_CONCAT(NS, ID) + #define _CASADI_NAMESPACE_CONCAT(NS, ID) NS ## ID + #define CASADI_PREFIX(ID) CASADI_NAMESPACE_CONCAT(CODEGEN_PREFIX, ID) +#else + #define CASADI_PREFIX(ID) casadi_src_ ## ID +#endif + +#include + +#ifndef casadi_real +#define casadi_real double +#endif + +#ifndef casadi_int +#define casadi_int long long int +#endif + +/* Add prefix to internal symbols */ +#define casadi_f0 CASADI_PREFIX(f0) +#define casadi_f1 CASADI_PREFIX(f1) +#define casadi_f10 CASADI_PREFIX(f10) +#define casadi_f11 CASADI_PREFIX(f11) +#define casadi_f12 CASADI_PREFIX(f12) +#define casadi_f13 CASADI_PREFIX(f13) +#define casadi_f14 CASADI_PREFIX(f14) +#define casadi_f15 CASADI_PREFIX(f15) +#define casadi_f16 CASADI_PREFIX(f16) +#define casadi_f17 CASADI_PREFIX(f17) +#define casadi_f18 CASADI_PREFIX(f18) +#define casadi_f19 CASADI_PREFIX(f19) +#define casadi_f2 CASADI_PREFIX(f2) +#define casadi_f20 CASADI_PREFIX(f20) +#define casadi_f21 CASADI_PREFIX(f21) +#define casadi_f3 CASADI_PREFIX(f3) +#define casadi_f4 CASADI_PREFIX(f4) +#define casadi_f5 CASADI_PREFIX(f5) +#define casadi_f6 CASADI_PREFIX(f6) +#define casadi_f7 CASADI_PREFIX(f7) +#define casadi_f8 CASADI_PREFIX(f8) +#define casadi_f9 CASADI_PREFIX(f9) +#define casadi_s0 CASADI_PREFIX(s0) +#define casadi_s1 CASADI_PREFIX(s1) +#define casadi_s2 CASADI_PREFIX(s2) +#define casadi_s3 CASADI_PREFIX(s3) +#define casadi_s4 CASADI_PREFIX(s4) +#define casadi_s5 CASADI_PREFIX(s5) +#define casadi_s6 CASADI_PREFIX(s6) +#define casadi_sq CASADI_PREFIX(sq) + +/* Symbol visibility in DLLs */ +#ifndef CASADI_SYMBOL_EXPORT + #if defined(_WIN32) || defined(__WIN32__) || defined(__CYGWIN__) + #if defined(STATIC_LINKED) + #define CASADI_SYMBOL_EXPORT + #else + #define CASADI_SYMBOL_EXPORT __declspec(dllexport) + #endif + #elif defined(__GNUC__) && defined(GCC_HASCLASSVISIBILITY) + #define CASADI_SYMBOL_EXPORT __attribute__ ((visibility ("default"))) + #else + #define CASADI_SYMBOL_EXPORT + #endif +#endif + +casadi_real casadi_sq(casadi_real x) { return x*x;} + +static const casadi_int casadi_s0[8] = {4, 1, 0, 4, 0, 1, 2, 3}; +static const casadi_int casadi_s1[5] = {1, 1, 0, 1, 0}; +static const casadi_int casadi_s2[4] = {0, 1, 0, 0}; +static const casadi_int casadi_s3[23] = {4, 4, 0, 4, 8, 12, 16, 0, 1, 2, 3, 0, 1, 2, 3, 0, 1, 2, 3, 0, 1, 2, 3}; +static const casadi_int casadi_s4[9] = {5, 1, 0, 5, 0, 1, 2, 3, 4}; +static const casadi_int casadi_s5[3] = {0, 0, 0}; +static const casadi_int casadi_s6[7] = {0, 4, 0, 0, 0, 0, 0}; + +/* f_fun:(states[4],controls,params[0])->(xdot[4]) */ +static int casadi_f0(const casadi_real** arg, casadi_real** res, casadi_int* iw, casadi_real* w, int mem) { + casadi_real a0, a1, a2, a3, a4, a5, a6, a7; + a0=arg[0]? arg[0][2] : 0; + if (res[0]!=0) res[0][0]=a0; + a0=arg[0]? arg[0][3] : 0; + if (res[0]!=0) res[0][1]=a0; + a1=-8.0000000000000016e-02; + a2=arg[0]? arg[0][1] : 0; + a3=sin(a2); + a3=(a1*a3); + a4=casadi_sq(a0); + a3=(a3*a4); + a4=9.8100000000000009e-01; + a5=cos(a2); + a4=(a4*a5); + a5=sin(a2); + a4=(a4*a5); + a3=(a3+a4); + a4=arg[1]? arg[1][0] : 0; + a3=(a3+a4); + a5=1.1000000000000001e+00; + a6=1.0000000000000001e-01; + a7=cos(a2); + a7=casadi_sq(a7); + a6=(a6*a7); + a5=(a5-a6); + a3=(a3/a5); + if (res[0]!=0) res[0][2]=a3; + a3=cos(a2); + a1=(a1*a3); + a3=sin(a2); + a1=(a1*a3); + a0=casadi_sq(a0); + a1=(a1*a0); + a0=cos(a2); + a4=(a4*a0); + a1=(a1+a4); + a4=1.0791000000000002e+01; + a2=sin(a2); + a4=(a4*a2); + a1=(a1+a4); + a4=8.0000000000000004e-01; + a4=(a4*a5); + a1=(a1/a4); + if (res[0]!=0) res[0][3]=a1; + return 0; +} + +extern "C" CASADI_SYMBOL_EXPORT int f_fun(const casadi_real** arg, casadi_real** res, casadi_int* iw, casadi_real* w, int mem){ + return casadi_f0(arg, res, iw, w, mem); +} + +extern "C" CASADI_SYMBOL_EXPORT int f_fun_alloc_mem(void) { + return 0; +} + +extern "C" CASADI_SYMBOL_EXPORT int f_fun_init_mem(int mem) { + return 0; +} + +extern "C" CASADI_SYMBOL_EXPORT void f_fun_free_mem(int mem) { +} + +extern "C" CASADI_SYMBOL_EXPORT int f_fun_checkout(void) { + return 0; +} + +extern "C" CASADI_SYMBOL_EXPORT void f_fun_release(int mem) { +} + +extern "C" CASADI_SYMBOL_EXPORT void f_fun_incref(void) { +} + +extern "C" CASADI_SYMBOL_EXPORT void f_fun_decref(void) { +} + +extern "C" CASADI_SYMBOL_EXPORT casadi_int f_fun_n_in(void) { return 3;} + +extern "C" CASADI_SYMBOL_EXPORT casadi_int f_fun_n_out(void) { return 1;} + +extern "C" CASADI_SYMBOL_EXPORT casadi_real f_fun_default_in(casadi_int i){ + switch (i) { + default: return 0; + } +} + +extern "C" CASADI_SYMBOL_EXPORT const char* f_fun_name_in(casadi_int i){ + switch (i) { + case 0: return "states"; + case 1: return "controls"; + case 2: return "params"; + default: return 0; + } +} + +extern "C" CASADI_SYMBOL_EXPORT const char* f_fun_name_out(casadi_int i){ + switch (i) { + case 0: return "xdot"; + default: return 0; + } +} + +extern "C" CASADI_SYMBOL_EXPORT const casadi_int* f_fun_sparsity_in(casadi_int i) { + switch (i) { + case 0: return casadi_s0; + case 1: return casadi_s1; + case 2: return casadi_s2; + default: return 0; + } +} + +extern "C" CASADI_SYMBOL_EXPORT const casadi_int* f_fun_sparsity_out(casadi_int i) { + switch (i) { + case 0: return casadi_s0; + default: return 0; + } +} + +extern "C" CASADI_SYMBOL_EXPORT int f_fun_work(casadi_int *sz_arg, casadi_int* sz_res, casadi_int *sz_iw, casadi_int *sz_w) { + if (sz_arg) *sz_arg = 3; + if (sz_res) *sz_res = 1; + if (sz_iw) *sz_iw = 0; + if (sz_w) *sz_w = 0; + return 0; +} + +/* vdeFun:(i0[4],i1,i2[0],i3[4x4],i4[4])->(o0[4x4],o1[4]) */ +static int casadi_f1(const casadi_real** arg, casadi_real** res, casadi_int* iw, casadi_real* w, int mem) { + casadi_real a0, a1, a10, a11, a12, a13, a14, a15, a16, a17, a18, a19, a2, a20, a21, a22, a23, a24, a25, a26, a27, a28, a29, a3, a30, a31, a32, a33, a34, a35, a36, a37, a38, a39, a4, a5, a6, a7, a8, a9; + a0=arg[3]? arg[3][2] : 0; + if (res[0]!=0) res[0][0]=a0; + a0=arg[3]? arg[3][3] : 0; + if (res[0]!=0) res[0][1]=a0; + a1=arg[0]? arg[0][3] : 0; + a2=casadi_sq(a1); + a3=-8.0000000000000016e-02; + a4=arg[0]? arg[0][1] : 0; + a5=cos(a4); + a6=arg[3]? arg[3][1] : 0; + a7=(a5*a6); + a7=(a3*a7); + a7=(a2*a7); + a8=sin(a4); + a8=(a3*a8); + a9=(a1+a1); + a10=(a9*a0); + a10=(a8*a10); + a7=(a7+a10); + a10=9.8100000000000009e-01; + a11=cos(a4); + a11=(a10*a11); + a12=cos(a4); + a13=(a12*a6); + a13=(a11*a13); + a14=sin(a4); + a15=sin(a4); + a16=(a15*a6); + a16=(a10*a16); + a16=(a14*a16); + a13=(a13-a16); + a7=(a7+a13); + a13=1.1000000000000001e+00; + a16=1.0000000000000001e-01; + a17=cos(a4); + a18=casadi_sq(a17); + a18=(a16*a18); + a13=(a13-a18); + a7=(a7/a13); + a18=(a8*a2); + a19=(a11*a14); + a18=(a18+a19); + a19=arg[1]? arg[1][0] : 0; + a18=(a18+a19); + a18=(a18/a13); + a20=(a18/a13); + a21=(a17+a17); + a22=sin(a4); + a23=(a22*a6); + a23=(a21*a23); + a23=(a16*a23); + a24=(a20*a23); + a7=(a7-a24); + if (res[0]!=0) res[0][2]=a7; + a7=casadi_sq(a1); + a24=cos(a4); + a24=(a3*a24); + a25=cos(a4); + a26=(a25*a6); + a26=(a24*a26); + a27=sin(a4); + a28=sin(a4); + a29=(a28*a6); + a29=(a3*a29); + a29=(a27*a29); + a26=(a26-a29); + a26=(a7*a26); + a29=(a24*a27); + a30=(a1+a1); + a0=(a30*a0); + a0=(a29*a0); + a26=(a26+a0); + a0=sin(a4); + a31=(a0*a6); + a31=(a19*a31); + a26=(a26-a31); + a31=1.0791000000000002e+01; + a32=cos(a4); + a6=(a32*a6); + a6=(a31*a6); + a26=(a26+a6); + a6=8.0000000000000004e-01; + a33=(a6*a13); + a26=(a26/a33); + a34=(a29*a7); + a35=cos(a4); + a36=(a19*a35); + a34=(a34+a36); + a36=sin(a4); + a36=(a31*a36); + a34=(a34+a36); + a34=(a34/a33); + a36=(a34/a33); + a23=(a6*a23); + a23=(a36*a23); + a26=(a26-a23); + if (res[0]!=0) res[0][3]=a26; + a26=arg[3]? arg[3][6] : 0; + if (res[0]!=0) res[0][4]=a26; + a26=arg[3]? arg[3][7] : 0; + if (res[0]!=0) res[0][5]=a26; + a23=arg[3]? arg[3][5] : 0; + a37=(a5*a23); + a37=(a3*a37); + a37=(a2*a37); + a38=(a9*a26); + a38=(a8*a38); + a37=(a37+a38); + a38=(a12*a23); + a38=(a11*a38); + a39=(a15*a23); + a39=(a10*a39); + a39=(a14*a39); + a38=(a38-a39); + a37=(a37+a38); + a37=(a37/a13); + a38=(a22*a23); + a38=(a21*a38); + a38=(a16*a38); + a39=(a20*a38); + a37=(a37-a39); + if (res[0]!=0) res[0][6]=a37; + a37=(a25*a23); + a37=(a24*a37); + a39=(a28*a23); + a39=(a3*a39); + a39=(a27*a39); + a37=(a37-a39); + a37=(a7*a37); + a26=(a30*a26); + a26=(a29*a26); + a37=(a37+a26); + a26=(a0*a23); + a26=(a19*a26); + a37=(a37-a26); + a23=(a32*a23); + a23=(a31*a23); + a37=(a37+a23); + a37=(a37/a33); + a38=(a6*a38); + a38=(a36*a38); + a37=(a37-a38); + if (res[0]!=0) res[0][7]=a37; + a37=arg[3]? arg[3][10] : 0; + if (res[0]!=0) res[0][8]=a37; + a37=arg[3]? arg[3][11] : 0; + if (res[0]!=0) res[0][9]=a37; + a38=arg[3]? arg[3][9] : 0; + a23=(a5*a38); + a23=(a3*a23); + a23=(a2*a23); + a26=(a9*a37); + a26=(a8*a26); + a23=(a23+a26); + a26=(a12*a38); + a26=(a11*a26); + a39=(a15*a38); + a39=(a10*a39); + a39=(a14*a39); + a26=(a26-a39); + a23=(a23+a26); + a23=(a23/a13); + a26=(a22*a38); + a26=(a21*a26); + a26=(a16*a26); + a39=(a20*a26); + a23=(a23-a39); + if (res[0]!=0) res[0][10]=a23; + a23=(a25*a38); + a23=(a24*a23); + a39=(a28*a38); + a39=(a3*a39); + a39=(a27*a39); + a23=(a23-a39); + a23=(a7*a23); + a37=(a30*a37); + a37=(a29*a37); + a23=(a23+a37); + a37=(a0*a38); + a37=(a19*a37); + a23=(a23-a37); + a38=(a32*a38); + a38=(a31*a38); + a23=(a23+a38); + a23=(a23/a33); + a26=(a6*a26); + a26=(a36*a26); + a23=(a23-a26); + if (res[0]!=0) res[0][11]=a23; + a23=arg[3]? arg[3][14] : 0; + if (res[0]!=0) res[0][12]=a23; + a23=arg[3]? arg[3][15] : 0; + if (res[0]!=0) res[0][13]=a23; + a26=arg[3]? arg[3][13] : 0; + a5=(a5*a26); + a5=(a3*a5); + a5=(a2*a5); + a9=(a9*a23); + a9=(a8*a9); + a5=(a5+a9); + a12=(a12*a26); + a12=(a11*a12); + a15=(a15*a26); + a15=(a10*a15); + a15=(a14*a15); + a12=(a12-a15); + a5=(a5+a12); + a5=(a5/a13); + a22=(a22*a26); + a21=(a21*a22); + a21=(a16*a21); + a20=(a20*a21); + a5=(a5-a20); + if (res[0]!=0) res[0][14]=a5; + a25=(a25*a26); + a25=(a24*a25); + a28=(a28*a26); + a28=(a3*a28); + a28=(a27*a28); + a25=(a25-a28); + a25=(a7*a25); + a30=(a30*a23); + a30=(a29*a30); + a25=(a25+a30); + a0=(a0*a26); + a0=(a19*a0); + a25=(a25-a0); + a32=(a32*a26); + a32=(a31*a32); + a25=(a25+a32); + a25=(a25/a33); + a21=(a6*a21); + a36=(a36*a21); + a25=(a25-a36); + if (res[0]!=0) res[0][15]=a25; + a25=arg[4]? arg[4][2] : 0; + if (res[1]!=0) res[1][0]=a25; + a25=arg[4]? arg[4][3] : 0; + if (res[1]!=0) res[1][1]=a25; + a36=(1./a13); + a21=cos(a4); + a32=arg[4]? arg[4][1] : 0; + a21=(a21*a32); + a21=(a3*a21); + a2=(a2*a21); + a21=(a1+a1); + a21=(a21*a25); + a8=(a8*a21); + a2=(a2+a8); + a8=cos(a4); + a8=(a8*a32); + a11=(a11*a8); + a8=sin(a4); + a8=(a8*a32); + a10=(a10*a8); + a14=(a14*a10); + a11=(a11-a14); + a2=(a2+a11); + a2=(a2/a13); + a18=(a18/a13); + a17=(a17+a17); + a13=sin(a4); + a13=(a13*a32); + a17=(a17*a13); + a16=(a16*a17); + a18=(a18*a16); + a2=(a2-a18); + a36=(a36+a2); + if (res[1]!=0) res[1][2]=a36; + a35=(a35/a33); + a36=cos(a4); + a36=(a36*a32); + a24=(a24*a36); + a36=sin(a4); + a36=(a36*a32); + a3=(a3*a36); + a27=(a27*a3); + a24=(a24-a27); + a7=(a7*a24); + a1=(a1+a1); + a1=(a1*a25); + a29=(a29*a1); + a7=(a7+a29); + a29=sin(a4); + a29=(a29*a32); + a19=(a19*a29); + a7=(a7-a19); + a4=cos(a4); + a4=(a4*a32); + a31=(a31*a4); + a7=(a7+a31); + a7=(a7/a33); + a34=(a34/a33); + a6=(a6*a16); + a34=(a34*a6); + a7=(a7-a34); + a35=(a35+a7); + if (res[1]!=0) res[1][3]=a35; + return 0; +} + +extern "C" CASADI_SYMBOL_EXPORT int vdeFun(const casadi_real** arg, casadi_real** res, casadi_int* iw, casadi_real* w, int mem){ + return casadi_f1(arg, res, iw, w, mem); +} + +extern "C" CASADI_SYMBOL_EXPORT int vdeFun_alloc_mem(void) { + return 0; +} + +extern "C" CASADI_SYMBOL_EXPORT int vdeFun_init_mem(int mem) { + return 0; +} + +extern "C" CASADI_SYMBOL_EXPORT void vdeFun_free_mem(int mem) { +} + +extern "C" CASADI_SYMBOL_EXPORT int vdeFun_checkout(void) { + return 0; +} + +extern "C" CASADI_SYMBOL_EXPORT void vdeFun_release(int mem) { +} + +extern "C" CASADI_SYMBOL_EXPORT void vdeFun_incref(void) { +} + +extern "C" CASADI_SYMBOL_EXPORT void vdeFun_decref(void) { +} + +extern "C" CASADI_SYMBOL_EXPORT casadi_int vdeFun_n_in(void) { return 5;} + +extern "C" CASADI_SYMBOL_EXPORT casadi_int vdeFun_n_out(void) { return 2;} + +extern "C" CASADI_SYMBOL_EXPORT casadi_real vdeFun_default_in(casadi_int i){ + switch (i) { + default: return 0; + } +} + +extern "C" CASADI_SYMBOL_EXPORT const char* vdeFun_name_in(casadi_int i){ + switch (i) { + case 0: return "i0"; + case 1: return "i1"; + case 2: return "i2"; + case 3: return "i3"; + case 4: return "i4"; + default: return 0; + } +} + +extern "C" CASADI_SYMBOL_EXPORT const char* vdeFun_name_out(casadi_int i){ + switch (i) { + case 0: return "o0"; + case 1: return "o1"; + default: return 0; + } +} + +extern "C" CASADI_SYMBOL_EXPORT const casadi_int* vdeFun_sparsity_in(casadi_int i) { + switch (i) { + case 0: return casadi_s0; + case 1: return casadi_s1; + case 2: return casadi_s2; + case 3: return casadi_s3; + case 4: return casadi_s0; + default: return 0; + } +} + +extern "C" CASADI_SYMBOL_EXPORT const casadi_int* vdeFun_sparsity_out(casadi_int i) { + switch (i) { + case 0: return casadi_s3; + case 1: return casadi_s0; + default: return 0; + } +} + +extern "C" CASADI_SYMBOL_EXPORT int vdeFun_work(casadi_int *sz_arg, casadi_int* sz_res, casadi_int *sz_iw, casadi_int *sz_w) { + if (sz_arg) *sz_arg = 5; + if (sz_res) *sz_res = 2; + if (sz_iw) *sz_iw = 0; + if (sz_w) *sz_w = 0; + return 0; +} + +/* impl_f_fun:(i0[4],i1,i2[0],i3[4])->(o0[4]) */ +static int casadi_f2(const casadi_real** arg, casadi_real** res, casadi_int* iw, casadi_real* w, int mem) { + casadi_real a0, a1, a2, a3, a4, a5, a6, a7, a8; + a0=arg[3]? arg[3][0] : 0; + a1=arg[0]? arg[0][2] : 0; + a0=(a0-a1); + if (res[0]!=0) res[0][0]=a0; + a0=arg[3]? arg[3][1] : 0; + a1=arg[0]? arg[0][3] : 0; + a0=(a0-a1); + if (res[0]!=0) res[0][1]=a0; + a0=arg[3]? arg[3][2] : 0; + a2=-8.0000000000000016e-02; + a3=arg[0]? arg[0][1] : 0; + a4=sin(a3); + a4=(a2*a4); + a5=casadi_sq(a1); + a4=(a4*a5); + a5=9.8100000000000009e-01; + a6=cos(a3); + a5=(a5*a6); + a6=sin(a3); + a5=(a5*a6); + a4=(a4+a5); + a5=arg[1]? arg[1][0] : 0; + a4=(a4+a5); + a6=1.1000000000000001e+00; + a7=1.0000000000000001e-01; + a8=cos(a3); + a8=casadi_sq(a8); + a7=(a7*a8); + a6=(a6-a7); + a4=(a4/a6); + a0=(a0-a4); + if (res[0]!=0) res[0][2]=a0; + a0=arg[3]? arg[3][3] : 0; + a4=cos(a3); + a2=(a2*a4); + a4=sin(a3); + a2=(a2*a4); + a1=casadi_sq(a1); + a2=(a2*a1); + a1=cos(a3); + a5=(a5*a1); + a2=(a2+a5); + a5=1.0791000000000002e+01; + a3=sin(a3); + a5=(a5*a3); + a2=(a2+a5); + a5=8.0000000000000004e-01; + a5=(a5*a6); + a2=(a2/a5); + a0=(a0-a2); + if (res[0]!=0) res[0][3]=a0; + return 0; +} + +extern "C" CASADI_SYMBOL_EXPORT int impl_f_fun(const casadi_real** arg, casadi_real** res, casadi_int* iw, casadi_real* w, int mem){ + return casadi_f2(arg, res, iw, w, mem); +} + +extern "C" CASADI_SYMBOL_EXPORT int impl_f_fun_alloc_mem(void) { + return 0; +} + +extern "C" CASADI_SYMBOL_EXPORT int impl_f_fun_init_mem(int mem) { + return 0; +} + +extern "C" CASADI_SYMBOL_EXPORT void impl_f_fun_free_mem(int mem) { +} + +extern "C" CASADI_SYMBOL_EXPORT int impl_f_fun_checkout(void) { + return 0; +} + +extern "C" CASADI_SYMBOL_EXPORT void impl_f_fun_release(int mem) { +} + +extern "C" CASADI_SYMBOL_EXPORT void impl_f_fun_incref(void) { +} + +extern "C" CASADI_SYMBOL_EXPORT void impl_f_fun_decref(void) { +} + +extern "C" CASADI_SYMBOL_EXPORT casadi_int impl_f_fun_n_in(void) { return 4;} + +extern "C" CASADI_SYMBOL_EXPORT casadi_int impl_f_fun_n_out(void) { return 1;} + +extern "C" CASADI_SYMBOL_EXPORT casadi_real impl_f_fun_default_in(casadi_int i){ + switch (i) { + default: return 0; + } +} + +extern "C" CASADI_SYMBOL_EXPORT const char* impl_f_fun_name_in(casadi_int i){ + switch (i) { + case 0: return "i0"; + case 1: return "i1"; + case 2: return "i2"; + case 3: return "i3"; + default: return 0; + } +} + +extern "C" CASADI_SYMBOL_EXPORT const char* impl_f_fun_name_out(casadi_int i){ + switch (i) { + case 0: return "o0"; + default: return 0; + } +} + +extern "C" CASADI_SYMBOL_EXPORT const casadi_int* impl_f_fun_sparsity_in(casadi_int i) { + switch (i) { + case 0: return casadi_s0; + case 1: return casadi_s1; + case 2: return casadi_s2; + case 3: return casadi_s0; + default: return 0; + } +} + +extern "C" CASADI_SYMBOL_EXPORT const casadi_int* impl_f_fun_sparsity_out(casadi_int i) { + switch (i) { + case 0: return casadi_s0; + default: return 0; + } +} + +extern "C" CASADI_SYMBOL_EXPORT int impl_f_fun_work(casadi_int *sz_arg, casadi_int* sz_res, casadi_int *sz_iw, casadi_int *sz_w) { + if (sz_arg) *sz_arg = 4; + if (sz_res) *sz_res = 1; + if (sz_iw) *sz_iw = 0; + if (sz_w) *sz_w = 0; + return 0; +} + +/* impl_jac_x_fun:(i0[4],i1,i2[0],i3[4])->(o0[4x4]) */ +static int casadi_f3(const casadi_real** arg, casadi_real** res, casadi_int* iw, casadi_real* w, int mem) { + casadi_real a0, a1, a10, a11, a12, a13, a2, a3, a4, a5, a6, a7, a8, a9; + a0=0.; + if (res[0]!=0) res[0][0]=a0; + if (res[0]!=0) res[0][1]=a0; + if (res[0]!=0) res[0][2]=a0; + if (res[0]!=0) res[0][3]=a0; + if (res[0]!=0) res[0][4]=a0; + if (res[0]!=0) res[0][5]=a0; + a1=arg[0]? arg[0][3] : 0; + a2=casadi_sq(a1); + a3=-8.0000000000000016e-02; + a4=arg[0]? arg[0][1] : 0; + a5=cos(a4); + a5=(a3*a5); + a5=(a2*a5); + a6=9.8100000000000009e-01; + a7=cos(a4); + a7=(a6*a7); + a8=cos(a4); + a8=(a7*a8); + a9=sin(a4); + a10=sin(a4); + a6=(a6*a10); + a6=(a9*a6); + a8=(a8-a6); + a5=(a5+a8); + a8=1.1000000000000001e+00; + a6=1.0000000000000001e-01; + a10=cos(a4); + a11=casadi_sq(a10); + a11=(a6*a11); + a8=(a8-a11); + a5=(a5/a8); + a11=sin(a4); + a11=(a3*a11); + a2=(a11*a2); + a7=(a7*a9); + a2=(a2+a7); + a7=arg[1]? arg[1][0] : 0; + a2=(a2+a7); + a2=(a2/a8); + a2=(a2/a8); + a10=(a10+a10); + a9=sin(a4); + a10=(a10*a9); + a6=(a6*a10); + a2=(a2*a6); + a5=(a5-a2); + a5=(-a5); + if (res[0]!=0) res[0][6]=a5; + a5=casadi_sq(a1); + a2=cos(a4); + a2=(a3*a2); + a10=cos(a4); + a10=(a2*a10); + a9=sin(a4); + a12=sin(a4); + a3=(a3*a12); + a3=(a9*a3); + a10=(a10-a3); + a10=(a5*a10); + a3=sin(a4); + a3=(a7*a3); + a10=(a10-a3); + a3=1.0791000000000002e+01; + a12=cos(a4); + a12=(a3*a12); + a10=(a10+a12); + a12=8.0000000000000004e-01; + a13=(a12*a8); + a10=(a10/a13); + a2=(a2*a9); + a5=(a2*a5); + a9=cos(a4); + a7=(a7*a9); + a5=(a5+a7); + a4=sin(a4); + a3=(a3*a4); + a5=(a5+a3); + a5=(a5/a13); + a5=(a5/a13); + a12=(a12*a6); + a5=(a5*a12); + a10=(a10-a5); + a10=(-a10); + if (res[0]!=0) res[0][7]=a10; + a10=-1.; + if (res[0]!=0) res[0][8]=a10; + if (res[0]!=0) res[0][9]=a0; + if (res[0]!=0) res[0][10]=a0; + if (res[0]!=0) res[0][11]=a0; + if (res[0]!=0) res[0][12]=a0; + if (res[0]!=0) res[0][13]=a10; + a10=(a1+a1); + a11=(a11*a10); + a11=(a11/a8); + a11=(-a11); + if (res[0]!=0) res[0][14]=a11; + a1=(a1+a1); + a2=(a2*a1); + a2=(a2/a13); + a2=(-a2); + if (res[0]!=0) res[0][15]=a2; + return 0; +} + +extern "C" CASADI_SYMBOL_EXPORT int impl_jac_x_fun(const casadi_real** arg, casadi_real** res, casadi_int* iw, casadi_real* w, int mem){ + return casadi_f3(arg, res, iw, w, mem); +} + +extern "C" CASADI_SYMBOL_EXPORT int impl_jac_x_fun_alloc_mem(void) { + return 0; +} + +extern "C" CASADI_SYMBOL_EXPORT int impl_jac_x_fun_init_mem(int mem) { + return 0; +} + +extern "C" CASADI_SYMBOL_EXPORT void impl_jac_x_fun_free_mem(int mem) { +} + +extern "C" CASADI_SYMBOL_EXPORT int impl_jac_x_fun_checkout(void) { + return 0; +} + +extern "C" CASADI_SYMBOL_EXPORT void impl_jac_x_fun_release(int mem) { +} + +extern "C" CASADI_SYMBOL_EXPORT void impl_jac_x_fun_incref(void) { +} + +extern "C" CASADI_SYMBOL_EXPORT void impl_jac_x_fun_decref(void) { +} + +extern "C" CASADI_SYMBOL_EXPORT casadi_int impl_jac_x_fun_n_in(void) { return 4;} + +extern "C" CASADI_SYMBOL_EXPORT casadi_int impl_jac_x_fun_n_out(void) { return 1;} + +extern "C" CASADI_SYMBOL_EXPORT casadi_real impl_jac_x_fun_default_in(casadi_int i){ + switch (i) { + default: return 0; + } +} + +extern "C" CASADI_SYMBOL_EXPORT const char* impl_jac_x_fun_name_in(casadi_int i){ + switch (i) { + case 0: return "i0"; + case 1: return "i1"; + case 2: return "i2"; + case 3: return "i3"; + default: return 0; + } +} + +extern "C" CASADI_SYMBOL_EXPORT const char* impl_jac_x_fun_name_out(casadi_int i){ + switch (i) { + case 0: return "o0"; + default: return 0; + } +} + +extern "C" CASADI_SYMBOL_EXPORT const casadi_int* impl_jac_x_fun_sparsity_in(casadi_int i) { + switch (i) { + case 0: return casadi_s0; + case 1: return casadi_s1; + case 2: return casadi_s2; + case 3: return casadi_s0; + default: return 0; + } +} + +extern "C" CASADI_SYMBOL_EXPORT const casadi_int* impl_jac_x_fun_sparsity_out(casadi_int i) { + switch (i) { + case 0: return casadi_s3; + default: return 0; + } +} + +extern "C" CASADI_SYMBOL_EXPORT int impl_jac_x_fun_work(casadi_int *sz_arg, casadi_int* sz_res, casadi_int *sz_iw, casadi_int *sz_w) { + if (sz_arg) *sz_arg = 4; + if (sz_res) *sz_res = 1; + if (sz_iw) *sz_iw = 0; + if (sz_w) *sz_w = 0; + return 0; +} + +/* impl_jac_u_fun:(i0[4],i1,i2[0],i3[4])->(o0[4]) */ +static int casadi_f4(const casadi_real** arg, casadi_real** res, casadi_int* iw, casadi_real* w, int mem) { + casadi_real a0, a1, a2, a3; + a0=0.; + if (res[0]!=0) res[0][0]=a0; + if (res[0]!=0) res[0][1]=a0; + a0=1.1000000000000001e+00; + a1=1.0000000000000001e-01; + a2=arg[0]? arg[0][1] : 0; + a3=cos(a2); + a3=casadi_sq(a3); + a1=(a1*a3); + a0=(a0-a1); + a1=(1./a0); + a1=(-a1); + if (res[0]!=0) res[0][2]=a1; + a2=cos(a2); + a1=8.0000000000000004e-01; + a1=(a1*a0); + a2=(a2/a1); + a2=(-a2); + if (res[0]!=0) res[0][3]=a2; + return 0; +} + +extern "C" CASADI_SYMBOL_EXPORT int impl_jac_u_fun(const casadi_real** arg, casadi_real** res, casadi_int* iw, casadi_real* w, int mem){ + return casadi_f4(arg, res, iw, w, mem); +} + +extern "C" CASADI_SYMBOL_EXPORT int impl_jac_u_fun_alloc_mem(void) { + return 0; +} + +extern "C" CASADI_SYMBOL_EXPORT int impl_jac_u_fun_init_mem(int mem) { + return 0; +} + +extern "C" CASADI_SYMBOL_EXPORT void impl_jac_u_fun_free_mem(int mem) { +} + +extern "C" CASADI_SYMBOL_EXPORT int impl_jac_u_fun_checkout(void) { + return 0; +} + +extern "C" CASADI_SYMBOL_EXPORT void impl_jac_u_fun_release(int mem) { +} + +extern "C" CASADI_SYMBOL_EXPORT void impl_jac_u_fun_incref(void) { +} + +extern "C" CASADI_SYMBOL_EXPORT void impl_jac_u_fun_decref(void) { +} + +extern "C" CASADI_SYMBOL_EXPORT casadi_int impl_jac_u_fun_n_in(void) { return 4;} + +extern "C" CASADI_SYMBOL_EXPORT casadi_int impl_jac_u_fun_n_out(void) { return 1;} + +extern "C" CASADI_SYMBOL_EXPORT casadi_real impl_jac_u_fun_default_in(casadi_int i){ + switch (i) { + default: return 0; + } +} + +extern "C" CASADI_SYMBOL_EXPORT const char* impl_jac_u_fun_name_in(casadi_int i){ + switch (i) { + case 0: return "i0"; + case 1: return "i1"; + case 2: return "i2"; + case 3: return "i3"; + default: return 0; + } +} + +extern "C" CASADI_SYMBOL_EXPORT const char* impl_jac_u_fun_name_out(casadi_int i){ + switch (i) { + case 0: return "o0"; + default: return 0; + } +} + +extern "C" CASADI_SYMBOL_EXPORT const casadi_int* impl_jac_u_fun_sparsity_in(casadi_int i) { + switch (i) { + case 0: return casadi_s0; + case 1: return casadi_s1; + case 2: return casadi_s2; + case 3: return casadi_s0; + default: return 0; + } +} + +extern "C" CASADI_SYMBOL_EXPORT const casadi_int* impl_jac_u_fun_sparsity_out(casadi_int i) { + switch (i) { + case 0: return casadi_s0; + default: return 0; + } +} + +extern "C" CASADI_SYMBOL_EXPORT int impl_jac_u_fun_work(casadi_int *sz_arg, casadi_int* sz_res, casadi_int *sz_iw, casadi_int *sz_w) { + if (sz_arg) *sz_arg = 4; + if (sz_res) *sz_res = 1; + if (sz_iw) *sz_iw = 0; + if (sz_w) *sz_w = 0; + return 0; +} + +/* impl_jac_xdot_fun:(i0[4],i1,i2[0],i3[4])->(o0[4x4]) */ +static int casadi_f5(const casadi_real** arg, casadi_real** res, casadi_int* iw, casadi_real* w, int mem) { + casadi_real a0, a1; + a0=1.; + if (res[0]!=0) res[0][0]=a0; + a1=0.; + if (res[0]!=0) res[0][1]=a1; + if (res[0]!=0) res[0][2]=a1; + if (res[0]!=0) res[0][3]=a1; + if (res[0]!=0) res[0][4]=a1; + if (res[0]!=0) res[0][5]=a0; + if (res[0]!=0) res[0][6]=a1; + if (res[0]!=0) res[0][7]=a1; + if (res[0]!=0) res[0][8]=a1; + if (res[0]!=0) res[0][9]=a1; + if (res[0]!=0) res[0][10]=a0; + if (res[0]!=0) res[0][11]=a1; + if (res[0]!=0) res[0][12]=a1; + if (res[0]!=0) res[0][13]=a1; + if (res[0]!=0) res[0][14]=a1; + if (res[0]!=0) res[0][15]=a0; + return 0; +} + +extern "C" CASADI_SYMBOL_EXPORT int impl_jac_xdot_fun(const casadi_real** arg, casadi_real** res, casadi_int* iw, casadi_real* w, int mem){ + return casadi_f5(arg, res, iw, w, mem); +} + +extern "C" CASADI_SYMBOL_EXPORT int impl_jac_xdot_fun_alloc_mem(void) { + return 0; +} + +extern "C" CASADI_SYMBOL_EXPORT int impl_jac_xdot_fun_init_mem(int mem) { + return 0; +} + +extern "C" CASADI_SYMBOL_EXPORT void impl_jac_xdot_fun_free_mem(int mem) { +} + +extern "C" CASADI_SYMBOL_EXPORT int impl_jac_xdot_fun_checkout(void) { + return 0; +} + +extern "C" CASADI_SYMBOL_EXPORT void impl_jac_xdot_fun_release(int mem) { +} + +extern "C" CASADI_SYMBOL_EXPORT void impl_jac_xdot_fun_incref(void) { +} + +extern "C" CASADI_SYMBOL_EXPORT void impl_jac_xdot_fun_decref(void) { +} + +extern "C" CASADI_SYMBOL_EXPORT casadi_int impl_jac_xdot_fun_n_in(void) { return 4;} + +extern "C" CASADI_SYMBOL_EXPORT casadi_int impl_jac_xdot_fun_n_out(void) { return 1;} + +extern "C" CASADI_SYMBOL_EXPORT casadi_real impl_jac_xdot_fun_default_in(casadi_int i){ + switch (i) { + default: return 0; + } +} + +extern "C" CASADI_SYMBOL_EXPORT const char* impl_jac_xdot_fun_name_in(casadi_int i){ + switch (i) { + case 0: return "i0"; + case 1: return "i1"; + case 2: return "i2"; + case 3: return "i3"; + default: return 0; + } +} + +extern "C" CASADI_SYMBOL_EXPORT const char* impl_jac_xdot_fun_name_out(casadi_int i){ + switch (i) { + case 0: return "o0"; + default: return 0; + } +} + +extern "C" CASADI_SYMBOL_EXPORT const casadi_int* impl_jac_xdot_fun_sparsity_in(casadi_int i) { + switch (i) { + case 0: return casadi_s0; + case 1: return casadi_s1; + case 2: return casadi_s2; + case 3: return casadi_s0; + default: return 0; + } +} + +extern "C" CASADI_SYMBOL_EXPORT const casadi_int* impl_jac_xdot_fun_sparsity_out(casadi_int i) { + switch (i) { + case 0: return casadi_s3; + default: return 0; + } +} + +extern "C" CASADI_SYMBOL_EXPORT int impl_jac_xdot_fun_work(casadi_int *sz_arg, casadi_int* sz_res, casadi_int *sz_iw, casadi_int *sz_w) { + if (sz_arg) *sz_arg = 4; + if (sz_res) *sz_res = 1; + if (sz_iw) *sz_iw = 0; + if (sz_w) *sz_w = 0; + return 0; +} + +/* F:(i0[4],i1,i2[0])->(o0[4]) */ +static int casadi_f6(const casadi_real** arg, casadi_real** res, casadi_int* iw, casadi_real* w, int mem) { + casadi_real a0, a1, a10, a11, a12, a13, a14, a15, a16, a17, a18, a19, a2, a20, a21, a22, a23, a24, a25, a3, a4, a5, a6, a7, a8, a9; + a0=arg[0]? arg[0][0] : 0; + a1=8.3333333333333332e-03; + a2=arg[0]? arg[0][2] : 0; + a3=2.; + a4=2.5000000000000001e-02; + a5=-8.0000000000000016e-02; + a6=arg[0]? arg[0][1] : 0; + a7=sin(a6); + a7=(a5*a7); + a8=arg[0]? arg[0][3] : 0; + a9=casadi_sq(a8); + a7=(a7*a9); + a9=9.8100000000000009e-01; + a10=cos(a6); + a10=(a9*a10); + a11=sin(a6); + a10=(a10*a11); + a7=(a7+a10); + a10=arg[1]? arg[1][0] : 0; + a7=(a7+a10); + a11=1.1000000000000001e+00; + a12=1.0000000000000001e-01; + a13=cos(a6); + a13=casadi_sq(a13); + a13=(a12*a13); + a13=(a11-a13); + a7=(a7/a13); + a14=(a4*a7); + a14=(a2+a14); + a14=(a3*a14); + a14=(a2+a14); + a15=(a4*a8); + a15=(a6+a15); + a16=sin(a15); + a16=(a5*a16); + a17=cos(a6); + a17=(a5*a17); + a18=sin(a6); + a17=(a17*a18); + a18=casadi_sq(a8); + a17=(a17*a18); + a18=cos(a6); + a18=(a10*a18); + a17=(a17+a18); + a18=1.0791000000000002e+01; + a19=sin(a6); + a19=(a18*a19); + a17=(a17+a19); + a19=8.0000000000000004e-01; + a13=(a19*a13); + a17=(a17/a13); + a13=(a4*a17); + a13=(a8+a13); + a20=casadi_sq(a13); + a16=(a16*a20); + a20=cos(a15); + a20=(a9*a20); + a21=sin(a15); + a20=(a20*a21); + a16=(a16+a20); + a16=(a16+a10); + a20=cos(a15); + a20=casadi_sq(a20); + a20=(a12*a20); + a20=(a11-a20); + a16=(a16/a20); + a21=(a4*a16); + a21=(a2+a21); + a21=(a3*a21); + a14=(a14+a21); + a21=5.0000000000000003e-02; + a22=(a4*a13); + a22=(a6+a22); + a23=sin(a22); + a23=(a5*a23); + a24=cos(a15); + a24=(a5*a24); + a25=sin(a15); + a24=(a24*a25); + a25=casadi_sq(a13); + a24=(a24*a25); + a25=cos(a15); + a25=(a10*a25); + a24=(a24+a25); + a15=sin(a15); + a15=(a18*a15); + a24=(a24+a15); + a20=(a19*a20); + a24=(a24/a20); + a4=(a4*a24); + a4=(a8+a4); + a20=casadi_sq(a4); + a23=(a23*a20); + a20=cos(a22); + a20=(a9*a20); + a15=sin(a22); + a20=(a20*a15); + a23=(a23+a20); + a23=(a23+a10); + a20=cos(a22); + a20=casadi_sq(a20); + a20=(a12*a20); + a20=(a11-a20); + a23=(a23/a20); + a15=(a21*a23); + a15=(a2+a15); + a14=(a14+a15); + a14=(a1*a14); + a0=(a0+a14); + if (res[0]!=0) res[0][0]=a0; + a13=(a3*a13); + a13=(a8+a13); + a0=(a3*a4); + a13=(a13+a0); + a0=cos(a22); + a0=(a5*a0); + a14=sin(a22); + a0=(a0*a14); + a14=casadi_sq(a4); + a0=(a0*a14); + a14=cos(a22); + a14=(a10*a14); + a0=(a0+a14); + a22=sin(a22); + a22=(a18*a22); + a0=(a0+a22); + a20=(a19*a20); + a0=(a0/a20); + a20=(a21*a0); + a20=(a8+a20); + a13=(a13+a20); + a13=(a1*a13); + a13=(a6+a13); + if (res[0]!=0) res[0][1]=a13; + a16=(a3*a16); + a7=(a7+a16); + a23=(a3*a23); + a7=(a7+a23); + a21=(a21*a4); + a6=(a6+a21); + a21=sin(a6); + a21=(a5*a21); + a4=casadi_sq(a20); + a21=(a21*a4); + a4=cos(a6); + a9=(a9*a4); + a4=sin(a6); + a9=(a9*a4); + a21=(a21+a9); + a21=(a21+a10); + a9=cos(a6); + a9=casadi_sq(a9); + a12=(a12*a9); + a11=(a11-a12); + a21=(a21/a11); + a7=(a7+a21); + a7=(a1*a7); + a2=(a2+a7); + if (res[0]!=0) res[0][2]=a2; + a24=(a3*a24); + a17=(a17+a24); + a3=(a3*a0); + a17=(a17+a3); + a3=cos(a6); + a5=(a5*a3); + a3=sin(a6); + a5=(a5*a3); + a20=casadi_sq(a20); + a5=(a5*a20); + a20=cos(a6); + a10=(a10*a20); + a5=(a5+a10); + a6=sin(a6); + a18=(a18*a6); + a5=(a5+a18); + a19=(a19*a11); + a5=(a5/a19); + a17=(a17+a5); + a1=(a1*a17); + a8=(a8+a1); + if (res[0]!=0) res[0][3]=a8; + return 0; +} + +extern "C" CASADI_SYMBOL_EXPORT int F(const casadi_real** arg, casadi_real** res, casadi_int* iw, casadi_real* w, int mem){ + return casadi_f6(arg, res, iw, w, mem); +} + +extern "C" CASADI_SYMBOL_EXPORT int F_alloc_mem(void) { + return 0; +} + +extern "C" CASADI_SYMBOL_EXPORT int F_init_mem(int mem) { + return 0; +} + +extern "C" CASADI_SYMBOL_EXPORT void F_free_mem(int mem) { +} + +extern "C" CASADI_SYMBOL_EXPORT int F_checkout(void) { + return 0; +} + +extern "C" CASADI_SYMBOL_EXPORT void F_release(int mem) { +} + +extern "C" CASADI_SYMBOL_EXPORT void F_incref(void) { +} + +extern "C" CASADI_SYMBOL_EXPORT void F_decref(void) { +} + +extern "C" CASADI_SYMBOL_EXPORT casadi_int F_n_in(void) { return 3;} + +extern "C" CASADI_SYMBOL_EXPORT casadi_int F_n_out(void) { return 1;} + +extern "C" CASADI_SYMBOL_EXPORT casadi_real F_default_in(casadi_int i){ + switch (i) { + default: return 0; + } +} + +extern "C" CASADI_SYMBOL_EXPORT const char* F_name_in(casadi_int i){ + switch (i) { + case 0: return "i0"; + case 1: return "i1"; + case 2: return "i2"; + default: return 0; + } +} + +extern "C" CASADI_SYMBOL_EXPORT const char* F_name_out(casadi_int i){ + switch (i) { + case 0: return "o0"; + default: return 0; + } +} + +extern "C" CASADI_SYMBOL_EXPORT const casadi_int* F_sparsity_in(casadi_int i) { + switch (i) { + case 0: return casadi_s0; + case 1: return casadi_s1; + case 2: return casadi_s2; + default: return 0; + } +} + +extern "C" CASADI_SYMBOL_EXPORT const casadi_int* F_sparsity_out(casadi_int i) { + switch (i) { + case 0: return casadi_s0; + default: return 0; + } +} + +extern "C" CASADI_SYMBOL_EXPORT int F_work(casadi_int *sz_arg, casadi_int* sz_res, casadi_int *sz_iw, casadi_int *sz_w) { + if (sz_arg) *sz_arg = 3; + if (sz_res) *sz_res = 1; + if (sz_iw) *sz_iw = 0; + if (sz_w) *sz_w = 0; + return 0; +} + +/* D:(i0[4],i1,i2[0])->(o0[4x4],o1[4]) */ +static int casadi_f7(const casadi_real** arg, casadi_real** res, casadi_int* iw, casadi_real* w, int mem) { + casadi_real a0, a1, a10, a100, a101, a102, a103, a11, a12, a13, a14, a15, a16, a17, a18, a19, a2, a20, a21, a22, a23, a24, a25, a26, a27, a28, a29, a3, a30, a31, a32, a33, a34, a35, a36, a37, a38, a39, a4, a40, a41, a42, a43, a44, a45, a46, a47, a48, a49, a5, a50, a51, a52, a53, a54, a55, a56, a57, a58, a59, a6, a60, a61, a62, a63, a64, a65, a66, a67, a68, a69, a7, a70, a71, a72, a73, a74, a75, a76, a77, a78, a79, a8, a80, a81, a82, a83, a84, a85, a86, a87, a88, a89, a9, a90, a91, a92, a93, a94, a95, a96, a97, a98, a99; + a0=1.; + if (res[0]!=0) res[0][0]=a0; + a1=0.; + if (res[0]!=0) res[0][1]=a1; + if (res[0]!=0) res[0][2]=a1; + if (res[0]!=0) res[0][3]=a1; + a2=8.3333333333333332e-03; + a3=2.; + a4=2.5000000000000001e-02; + a5=arg[0]? arg[0][3] : 0; + a6=casadi_sq(a5); + a7=-8.0000000000000016e-02; + a8=arg[0]? arg[0][1] : 0; + a9=cos(a8); + a9=(a7*a9); + a9=(a6*a9); + a10=9.8100000000000009e-01; + a11=cos(a8); + a11=(a10*a11); + a12=cos(a8); + a12=(a11*a12); + a13=sin(a8); + a14=sin(a8); + a14=(a10*a14); + a14=(a13*a14); + a12=(a12-a14); + a9=(a9+a12); + a12=1.1000000000000001e+00; + a14=1.0000000000000001e-01; + a15=cos(a8); + a16=casadi_sq(a15); + a16=(a14*a16); + a16=(a12-a16); + a9=(a9/a16); + a17=sin(a8); + a17=(a7*a17); + a6=(a17*a6); + a11=(a11*a13); + a6=(a6+a11); + a11=arg[1]? arg[1][0] : 0; + a6=(a6+a11); + a6=(a6/a16); + a6=(a6/a16); + a15=(a15+a15); + a13=sin(a8); + a15=(a15*a13); + a15=(a14*a15); + a6=(a6*a15); + a9=(a9-a6); + a6=(a4*a9); + a6=(a3*a6); + a13=cos(a8); + a13=(a7*a13); + a18=sin(a8); + a19=(a13*a18); + a20=casadi_sq(a5); + a21=(a19*a20); + a22=cos(a8); + a23=(a11*a22); + a21=(a21+a23); + a23=1.0791000000000002e+01; + a24=sin(a8); + a24=(a23*a24); + a21=(a21+a24); + a24=8.0000000000000004e-01; + a25=(a24*a16); + a21=(a21/a25); + a26=(a4*a21); + a26=(a5+a26); + a27=casadi_sq(a26); + a28=(a4*a5); + a28=(a8+a28); + a29=cos(a28); + a30=(a7*a29); + a30=(a27*a30); + a31=sin(a28); + a31=(a7*a31); + a32=(a26+a26); + a33=cos(a8); + a13=(a13*a33); + a33=sin(a8); + a33=(a7*a33); + a18=(a18*a33); + a13=(a13-a18); + a20=(a20*a13); + a13=sin(a8); + a13=(a11*a13); + a20=(a20-a13); + a13=cos(a8); + a13=(a23*a13); + a20=(a20+a13); + a20=(a20/a25); + a21=(a21/a25); + a15=(a24*a15); + a21=(a21*a15); + a20=(a20-a21); + a21=(a4*a20); + a15=(a32*a21); + a15=(a31*a15); + a30=(a30+a15); + a15=cos(a28); + a15=(a10*a15); + a13=cos(a28); + a18=(a15*a13); + a33=sin(a28); + a34=sin(a28); + a35=(a10*a34); + a35=(a33*a35); + a18=(a18-a35); + a30=(a30+a18); + a18=cos(a28); + a35=casadi_sq(a18); + a35=(a14*a35); + a35=(a12-a35); + a30=(a30/a35); + a36=(a31*a27); + a37=(a15*a33); + a36=(a36+a37); + a36=(a36+a11); + a36=(a36/a35); + a36=(a36/a35); + a18=(a18+a18); + a37=sin(a28); + a38=(a18*a37); + a38=(a14*a38); + a39=(a36*a38); + a30=(a30-a39); + a39=(a4*a30); + a39=(a3*a39); + a6=(a6+a39); + a39=5.0000000000000003e-02; + a40=cos(a28); + a40=(a7*a40); + a41=sin(a28); + a42=(a40*a41); + a43=casadi_sq(a26); + a44=(a42*a43); + a45=cos(a28); + a46=(a11*a45); + a44=(a44+a46); + a46=sin(a28); + a46=(a23*a46); + a44=(a44+a46); + a46=(a24*a35); + a44=(a44/a46); + a47=(a4*a44); + a47=(a5+a47); + a48=casadi_sq(a47); + a49=(a4*a26); + a49=(a8+a49); + a50=cos(a49); + a51=(a4*a21); + a51=(a0+a51); + a52=(a50*a51); + a52=(a7*a52); + a52=(a48*a52); + a53=sin(a49); + a53=(a7*a53); + a54=(a47+a47); + a55=cos(a28); + a56=(a40*a55); + a57=sin(a28); + a58=(a7*a57); + a58=(a41*a58); + a56=(a56-a58); + a56=(a43*a56); + a58=(a26+a26); + a59=(a58*a21); + a59=(a42*a59); + a56=(a56+a59); + a59=sin(a28); + a60=(a11*a59); + a56=(a56-a60); + a28=cos(a28); + a60=(a23*a28); + a56=(a56+a60); + a56=(a56/a46); + a44=(a44/a46); + a38=(a24*a38); + a38=(a44*a38); + a56=(a56-a38); + a38=(a4*a56); + a60=(a54*a38); + a60=(a53*a60); + a52=(a52+a60); + a60=cos(a49); + a60=(a10*a60); + a61=cos(a49); + a62=(a61*a51); + a62=(a60*a62); + a63=sin(a49); + a64=sin(a49); + a65=(a64*a51); + a65=(a10*a65); + a65=(a63*a65); + a62=(a62-a65); + a52=(a52+a62); + a62=cos(a49); + a65=casadi_sq(a62); + a65=(a14*a65); + a65=(a12-a65); + a52=(a52/a65); + a66=(a53*a48); + a67=(a60*a63); + a66=(a66+a67); + a66=(a66+a11); + a66=(a66/a65); + a67=(a66/a65); + a68=(a62+a62); + a69=sin(a49); + a70=(a69*a51); + a70=(a68*a70); + a70=(a14*a70); + a71=(a67*a70); + a52=(a52-a71); + a71=(a39*a52); + a6=(a6+a71); + a6=(a2*a6); + if (res[0]!=0) res[0][4]=a6; + a21=(a3*a21); + a6=(a3*a38); + a21=(a21+a6); + a6=casadi_sq(a47); + a71=cos(a49); + a71=(a7*a71); + a72=cos(a49); + a73=(a72*a51); + a73=(a71*a73); + a74=sin(a49); + a75=sin(a49); + a76=(a75*a51); + a76=(a7*a76); + a76=(a74*a76); + a73=(a73-a76); + a73=(a6*a73); + a76=(a71*a74); + a77=(a47+a47); + a78=(a77*a38); + a78=(a76*a78); + a73=(a73+a78); + a78=sin(a49); + a79=(a78*a51); + a79=(a11*a79); + a73=(a73-a79); + a79=cos(a49); + a51=(a79*a51); + a51=(a23*a51); + a73=(a73+a51); + a51=(a24*a65); + a73=(a73/a51); + a80=(a76*a6); + a81=cos(a49); + a82=(a11*a81); + a80=(a80+a82); + a82=sin(a49); + a82=(a23*a82); + a80=(a80+a82); + a80=(a80/a51); + a82=(a80/a51); + a70=(a24*a70); + a70=(a82*a70); + a73=(a73-a70); + a70=(a39*a73); + a21=(a21+a70); + a21=(a2*a21); + a21=(a0+a21); + if (res[0]!=0) res[0][5]=a21; + a30=(a3*a30); + a9=(a9+a30); + a52=(a3*a52); + a9=(a9+a52); + a52=(a39*a80); + a52=(a5+a52); + a30=casadi_sq(a52); + a21=(a39*a47); + a8=(a8+a21); + a21=cos(a8); + a38=(a39*a38); + a38=(a0+a38); + a83=(a21*a38); + a83=(a7*a83); + a83=(a30*a83); + a84=sin(a8); + a84=(a7*a84); + a85=(a52+a52); + a86=(a85*a70); + a86=(a84*a86); + a83=(a83+a86); + a86=cos(a8); + a86=(a10*a86); + a87=cos(a8); + a88=(a87*a38); + a88=(a86*a88); + a89=sin(a8); + a90=sin(a8); + a91=(a90*a38); + a91=(a10*a91); + a91=(a89*a91); + a88=(a88-a91); + a83=(a83+a88); + a88=cos(a8); + a91=casadi_sq(a88); + a91=(a14*a91); + a12=(a12-a91); + a83=(a83/a12); + a91=(a84*a30); + a92=(a86*a89); + a91=(a91+a92); + a91=(a91+a11); + a91=(a91/a12); + a92=(a91/a12); + a93=(a88+a88); + a94=sin(a8); + a95=(a94*a38); + a95=(a93*a95); + a95=(a14*a95); + a96=(a92*a95); + a83=(a83-a96); + a9=(a9+a83); + a9=(a2*a9); + if (res[0]!=0) res[0][6]=a9; + a56=(a3*a56); + a20=(a20+a56); + a73=(a3*a73); + a20=(a20+a73); + a73=casadi_sq(a52); + a56=cos(a8); + a56=(a7*a56); + a9=cos(a8); + a83=(a9*a38); + a83=(a56*a83); + a96=sin(a8); + a97=sin(a8); + a98=(a97*a38); + a98=(a7*a98); + a98=(a96*a98); + a83=(a83-a98); + a83=(a73*a83); + a98=(a56*a96); + a99=(a52+a52); + a70=(a99*a70); + a70=(a98*a70); + a83=(a83+a70); + a70=sin(a8); + a100=(a70*a38); + a100=(a11*a100); + a83=(a83-a100); + a100=cos(a8); + a38=(a100*a38); + a38=(a23*a38); + a83=(a83+a38); + a38=(a24*a12); + a83=(a83/a38); + a101=(a98*a73); + a102=cos(a8); + a103=(a11*a102); + a101=(a101+a103); + a103=sin(a8); + a103=(a23*a103); + a101=(a101+a103); + a101=(a101/a38); + a103=(a101/a38); + a95=(a24*a95); + a95=(a103*a95); + a83=(a83-a95); + a20=(a20+a83); + a20=(a2*a20); + if (res[0]!=0) res[0][7]=a20; + if (res[0]!=0) res[0][8]=a39; + if (res[0]!=0) res[0][9]=a1; + if (res[0]!=0) res[0][10]=a0; + if (res[0]!=0) res[0][11]=a1; + a1=(a5+a5); + a17=(a17*a1); + a17=(a17/a16); + a1=(a4*a17); + a1=(a3*a1); + a29=(a4*a29); + a29=(a7*a29); + a27=(a27*a29); + a5=(a5+a5); + a19=(a19*a5); + a19=(a19/a25); + a5=(a4*a19); + a5=(a0+a5); + a32=(a32*a5); + a32=(a31*a32); + a27=(a27+a32); + a13=(a4*a13); + a15=(a15*a13); + a34=(a4*a34); + a34=(a10*a34); + a33=(a33*a34); + a15=(a15-a33); + a27=(a27+a15); + a27=(a27/a35); + a37=(a4*a37); + a18=(a18*a37); + a18=(a14*a18); + a36=(a36*a18); + a27=(a27-a36); + a36=(a4*a27); + a36=(a3*a36); + a1=(a1+a36); + a36=(a4*a5); + a50=(a50*a36); + a50=(a7*a50); + a50=(a48*a50); + a55=(a4*a55); + a40=(a40*a55); + a57=(a4*a57); + a57=(a7*a57); + a41=(a41*a57); + a40=(a40-a41); + a43=(a43*a40); + a58=(a58*a5); + a58=(a42*a58); + a43=(a43+a58); + a59=(a4*a59); + a59=(a11*a59); + a43=(a43-a59); + a28=(a4*a28); + a28=(a23*a28); + a43=(a43+a28); + a43=(a43/a46); + a18=(a24*a18); + a44=(a44*a18); + a43=(a43-a44); + a44=(a4*a43); + a44=(a0+a44); + a54=(a54*a44); + a54=(a53*a54); + a50=(a50+a54); + a61=(a61*a36); + a61=(a60*a61); + a64=(a64*a36); + a64=(a10*a64); + a64=(a63*a64); + a61=(a61-a64); + a50=(a50+a61); + a50=(a50/a65); + a69=(a69*a36); + a68=(a68*a69); + a68=(a14*a68); + a67=(a67*a68); + a50=(a50-a67); + a67=(a39*a50); + a1=(a1+a67); + a1=(a2*a1); + if (res[0]!=0) res[0][12]=a1; + a5=(a3*a5); + a5=(a0+a5); + a1=(a3*a44); + a5=(a5+a1); + a72=(a72*a36); + a72=(a71*a72); + a75=(a75*a36); + a75=(a7*a75); + a75=(a74*a75); + a72=(a72-a75); + a72=(a6*a72); + a77=(a77*a44); + a77=(a76*a77); + a72=(a72+a77); + a78=(a78*a36); + a78=(a11*a78); + a72=(a72-a78); + a79=(a79*a36); + a79=(a23*a79); + a72=(a72+a79); + a72=(a72/a51); + a68=(a24*a68); + a82=(a82*a68); + a72=(a72-a82); + a82=(a39*a72); + a82=(a0+a82); + a5=(a5+a82); + a5=(a2*a5); + if (res[0]!=0) res[0][13]=a5; + a27=(a3*a27); + a17=(a17+a27); + a50=(a3*a50); + a17=(a17+a50); + a44=(a39*a44); + a21=(a21*a44); + a21=(a7*a21); + a21=(a30*a21); + a85=(a85*a82); + a85=(a84*a85); + a21=(a21+a85); + a87=(a87*a44); + a87=(a86*a87); + a90=(a90*a44); + a90=(a10*a90); + a90=(a89*a90); + a87=(a87-a90); + a21=(a21+a87); + a21=(a21/a12); + a94=(a94*a44); + a93=(a93*a94); + a93=(a14*a93); + a92=(a92*a93); + a21=(a21-a92); + a17=(a17+a21); + a17=(a2*a17); + if (res[0]!=0) res[0][14]=a17; + a43=(a3*a43); + a19=(a19+a43); + a72=(a3*a72); + a19=(a19+a72); + a9=(a9*a44); + a9=(a56*a9); + a97=(a97*a44); + a97=(a7*a97); + a97=(a96*a97); + a9=(a9-a97); + a9=(a73*a9); + a99=(a99*a82); + a99=(a98*a99); + a9=(a9+a99); + a70=(a70*a44); + a70=(a11*a70); + a9=(a9-a70); + a100=(a100*a44); + a100=(a23*a100); + a9=(a9+a100); + a9=(a9/a38); + a93=(a24*a93); + a103=(a103*a93); + a9=(a9-a103); + a19=(a19+a9); + a19=(a2*a19); + a19=(a0+a19); + if (res[0]!=0) res[0][15]=a19; + a19=(a4/a16); + a19=(a3*a19); + a9=(a26+a26); + a22=(a22/a25); + a25=(a4*a22); + a9=(a9*a25); + a31=(a31*a9); + a31=(a31+a0); + a31=(a31/a35); + a35=(a4*a31); + a35=(a3*a35); + a19=(a19+a35); + a35=cos(a49); + a9=(a4*a25); + a35=(a35*a9); + a35=(a7*a35); + a48=(a48*a35); + a35=(a47+a47); + a26=(a26+a26); + a26=(a26*a25); + a42=(a42*a26); + a42=(a42+a45); + a42=(a42/a46); + a4=(a4*a42); + a35=(a35*a4); + a53=(a53*a35); + a48=(a48+a53); + a53=cos(a49); + a53=(a53*a9); + a60=(a60*a53); + a53=sin(a49); + a53=(a53*a9); + a53=(a10*a53); + a63=(a63*a53); + a60=(a60-a63); + a48=(a48+a60); + a48=(a48+a0); + a48=(a48/a65); + a66=(a66/a65); + a62=(a62+a62); + a65=sin(a49); + a65=(a65*a9); + a62=(a62*a65); + a62=(a14*a62); + a66=(a66*a62); + a48=(a48-a66); + a66=(a39*a48); + a19=(a19+a66); + a19=(a2*a19); + if (res[1]!=0) res[1][0]=a19; + a25=(a3*a25); + a19=(a3*a4); + a25=(a25+a19); + a19=cos(a49); + a19=(a19*a9); + a71=(a71*a19); + a19=sin(a49); + a19=(a19*a9); + a19=(a7*a19); + a74=(a74*a19); + a71=(a71-a74); + a6=(a6*a71); + a47=(a47+a47); + a47=(a47*a4); + a76=(a76*a47); + a6=(a6+a76); + a76=sin(a49); + a76=(a76*a9); + a76=(a11*a76); + a81=(a81-a76); + a6=(a6+a81); + a49=cos(a49); + a49=(a49*a9); + a49=(a23*a49); + a6=(a6+a49); + a6=(a6/a51); + a80=(a80/a51); + a62=(a24*a62); + a80=(a80*a62); + a6=(a6-a80); + a80=(a39*a6); + a25=(a25+a80); + a25=(a2*a25); + if (res[1]!=0) res[1][1]=a25; + a16=(1./a16); + a31=(a3*a31); + a16=(a16+a31); + a48=(a3*a48); + a16=(a16+a48); + a48=cos(a8); + a39=(a39*a4); + a48=(a48*a39); + a48=(a7*a48); + a30=(a30*a48); + a48=(a52+a52); + a48=(a48*a80); + a84=(a84*a48); + a30=(a30+a84); + a84=cos(a8); + a84=(a84*a39); + a86=(a86*a84); + a84=sin(a8); + a84=(a84*a39); + a10=(a10*a84); + a89=(a89*a10); + a86=(a86-a89); + a30=(a30+a86); + a30=(a30+a0); + a30=(a30/a12); + a91=(a91/a12); + a88=(a88+a88); + a12=sin(a8); + a12=(a12*a39); + a88=(a88*a12); + a14=(a14*a88); + a91=(a91*a14); + a30=(a30-a91); + a16=(a16+a30); + a16=(a2*a16); + if (res[1]!=0) res[1][2]=a16; + a42=(a3*a42); + a22=(a22+a42); + a3=(a3*a6); + a22=(a22+a3); + a3=cos(a8); + a3=(a3*a39); + a56=(a56*a3); + a3=sin(a8); + a3=(a3*a39); + a7=(a7*a3); + a96=(a96*a7); + a56=(a56-a96); + a73=(a73*a56); + a52=(a52+a52); + a52=(a52*a80); + a98=(a98*a52); + a73=(a73+a98); + a98=sin(a8); + a98=(a98*a39); + a11=(a11*a98); + a102=(a102-a11); + a73=(a73+a102); + a8=cos(a8); + a8=(a8*a39); + a23=(a23*a8); + a73=(a73+a23); + a73=(a73/a38); + a101=(a101/a38); + a24=(a24*a14); + a101=(a101*a24); + a73=(a73-a101); + a22=(a22+a73); + a2=(a2*a22); + if (res[1]!=0) res[1][3]=a2; + return 0; +} + +extern "C" CASADI_SYMBOL_EXPORT int D(const casadi_real** arg, casadi_real** res, casadi_int* iw, casadi_real* w, int mem){ + return casadi_f7(arg, res, iw, w, mem); +} + +extern "C" CASADI_SYMBOL_EXPORT int D_alloc_mem(void) { + return 0; +} + +extern "C" CASADI_SYMBOL_EXPORT int D_init_mem(int mem) { + return 0; +} + +extern "C" CASADI_SYMBOL_EXPORT void D_free_mem(int mem) { +} + +extern "C" CASADI_SYMBOL_EXPORT int D_checkout(void) { + return 0; +} + +extern "C" CASADI_SYMBOL_EXPORT void D_release(int mem) { +} + +extern "C" CASADI_SYMBOL_EXPORT void D_incref(void) { +} + +extern "C" CASADI_SYMBOL_EXPORT void D_decref(void) { +} + +extern "C" CASADI_SYMBOL_EXPORT casadi_int D_n_in(void) { return 3;} + +extern "C" CASADI_SYMBOL_EXPORT casadi_int D_n_out(void) { return 2;} + +extern "C" CASADI_SYMBOL_EXPORT casadi_real D_default_in(casadi_int i){ + switch (i) { + default: return 0; + } +} + +extern "C" CASADI_SYMBOL_EXPORT const char* D_name_in(casadi_int i){ + switch (i) { + case 0: return "i0"; + case 1: return "i1"; + case 2: return "i2"; + default: return 0; + } +} + +extern "C" CASADI_SYMBOL_EXPORT const char* D_name_out(casadi_int i){ + switch (i) { + case 0: return "o0"; + case 1: return "o1"; + default: return 0; + } +} + +extern "C" CASADI_SYMBOL_EXPORT const casadi_int* D_sparsity_in(casadi_int i) { + switch (i) { + case 0: return casadi_s0; + case 1: return casadi_s1; + case 2: return casadi_s2; + default: return 0; + } +} + +extern "C" CASADI_SYMBOL_EXPORT const casadi_int* D_sparsity_out(casadi_int i) { + switch (i) { + case 0: return casadi_s3; + case 1: return casadi_s0; + default: return 0; + } +} + +extern "C" CASADI_SYMBOL_EXPORT int D_work(casadi_int *sz_arg, casadi_int* sz_res, casadi_int *sz_iw, casadi_int *sz_w) { + if (sz_arg) *sz_arg = 3; + if (sz_res) *sz_res = 2; + if (sz_iw) *sz_iw = 0; + if (sz_w) *sz_w = 0; + return 0; +} + +/* h_fun:(states[4],controls,params[0])->(h[5]) */ +static int casadi_f8(const casadi_real** arg, casadi_real** res, casadi_int* iw, casadi_real* w, int mem) { + casadi_real a0; + a0=arg[0]? arg[0][0] : 0; + if (res[0]!=0) res[0][0]=a0; + a0=arg[0]? arg[0][1] : 0; + if (res[0]!=0) res[0][1]=a0; + a0=arg[0]? arg[0][2] : 0; + if (res[0]!=0) res[0][2]=a0; + a0=arg[0]? arg[0][3] : 0; + if (res[0]!=0) res[0][3]=a0; + a0=arg[1]? arg[1][0] : 0; + if (res[0]!=0) res[0][4]=a0; + return 0; +} + +extern "C" CASADI_SYMBOL_EXPORT int h_fun(const casadi_real** arg, casadi_real** res, casadi_int* iw, casadi_real* w, int mem){ + return casadi_f8(arg, res, iw, w, mem); +} + +extern "C" CASADI_SYMBOL_EXPORT int h_fun_alloc_mem(void) { + return 0; +} + +extern "C" CASADI_SYMBOL_EXPORT int h_fun_init_mem(int mem) { + return 0; +} + +extern "C" CASADI_SYMBOL_EXPORT void h_fun_free_mem(int mem) { +} + +extern "C" CASADI_SYMBOL_EXPORT int h_fun_checkout(void) { + return 0; +} + +extern "C" CASADI_SYMBOL_EXPORT void h_fun_release(int mem) { +} + +extern "C" CASADI_SYMBOL_EXPORT void h_fun_incref(void) { +} + +extern "C" CASADI_SYMBOL_EXPORT void h_fun_decref(void) { +} + +extern "C" CASADI_SYMBOL_EXPORT casadi_int h_fun_n_in(void) { return 3;} + +extern "C" CASADI_SYMBOL_EXPORT casadi_int h_fun_n_out(void) { return 1;} + +extern "C" CASADI_SYMBOL_EXPORT casadi_real h_fun_default_in(casadi_int i){ + switch (i) { + default: return 0; + } +} + +extern "C" CASADI_SYMBOL_EXPORT const char* h_fun_name_in(casadi_int i){ + switch (i) { + case 0: return "states"; + case 1: return "controls"; + case 2: return "params"; + default: return 0; + } +} + +extern "C" CASADI_SYMBOL_EXPORT const char* h_fun_name_out(casadi_int i){ + switch (i) { + case 0: return "h"; + default: return 0; + } +} + +extern "C" CASADI_SYMBOL_EXPORT const casadi_int* h_fun_sparsity_in(casadi_int i) { + switch (i) { + case 0: return casadi_s0; + case 1: return casadi_s1; + case 2: return casadi_s2; + default: return 0; + } +} + +extern "C" CASADI_SYMBOL_EXPORT const casadi_int* h_fun_sparsity_out(casadi_int i) { + switch (i) { + case 0: return casadi_s4; + default: return 0; + } +} + +extern "C" CASADI_SYMBOL_EXPORT int h_fun_work(casadi_int *sz_arg, casadi_int* sz_res, casadi_int *sz_iw, casadi_int *sz_w) { + if (sz_arg) *sz_arg = 3; + if (sz_res) *sz_res = 1; + if (sz_iw) *sz_iw = 0; + if (sz_w) *sz_w = 0; + return 0; +} + +/* path_con_fun:(states[4],controls,params[0])->(general_con[]) */ +static int casadi_f9(const casadi_real** arg, casadi_real** res, casadi_int* iw, casadi_real* w, int mem) { + return 0; +} + +extern "C" CASADI_SYMBOL_EXPORT int path_con_fun(const casadi_real** arg, casadi_real** res, casadi_int* iw, casadi_real* w, int mem){ + return casadi_f9(arg, res, iw, w, mem); +} + +extern "C" CASADI_SYMBOL_EXPORT int path_con_fun_alloc_mem(void) { + return 0; +} + +extern "C" CASADI_SYMBOL_EXPORT int path_con_fun_init_mem(int mem) { + return 0; +} + +extern "C" CASADI_SYMBOL_EXPORT void path_con_fun_free_mem(int mem) { +} + +extern "C" CASADI_SYMBOL_EXPORT int path_con_fun_checkout(void) { + return 0; +} + +extern "C" CASADI_SYMBOL_EXPORT void path_con_fun_release(int mem) { +} + +extern "C" CASADI_SYMBOL_EXPORT void path_con_fun_incref(void) { +} + +extern "C" CASADI_SYMBOL_EXPORT void path_con_fun_decref(void) { +} + +extern "C" CASADI_SYMBOL_EXPORT casadi_int path_con_fun_n_in(void) { return 3;} + +extern "C" CASADI_SYMBOL_EXPORT casadi_int path_con_fun_n_out(void) { return 1;} + +extern "C" CASADI_SYMBOL_EXPORT casadi_real path_con_fun_default_in(casadi_int i){ + switch (i) { + default: return 0; + } +} + +extern "C" CASADI_SYMBOL_EXPORT const char* path_con_fun_name_in(casadi_int i){ + switch (i) { + case 0: return "states"; + case 1: return "controls"; + case 2: return "params"; + default: return 0; + } +} + +extern "C" CASADI_SYMBOL_EXPORT const char* path_con_fun_name_out(casadi_int i){ + switch (i) { + case 0: return "general_con"; + default: return 0; + } +} + +extern "C" CASADI_SYMBOL_EXPORT const casadi_int* path_con_fun_sparsity_in(casadi_int i) { + switch (i) { + case 0: return casadi_s0; + case 1: return casadi_s1; + case 2: return casadi_s2; + default: return 0; + } +} + +extern "C" CASADI_SYMBOL_EXPORT const casadi_int* path_con_fun_sparsity_out(casadi_int i) { + switch (i) { + case 0: return casadi_s5; + default: return 0; + } +} + +extern "C" CASADI_SYMBOL_EXPORT int path_con_fun_work(casadi_int *sz_arg, casadi_int* sz_res, casadi_int *sz_iw, casadi_int *sz_w) { + if (sz_arg) *sz_arg = 3; + if (sz_res) *sz_res = 1; + if (sz_iw) *sz_iw = 0; + if (sz_w) *sz_w = 0; + return 0; +} + +/* path_con_N_fun:(states[4],params[0])->(general_con_N[]) */ +static int casadi_f10(const casadi_real** arg, casadi_real** res, casadi_int* iw, casadi_real* w, int mem) { + return 0; +} + +extern "C" CASADI_SYMBOL_EXPORT int path_con_N_fun(const casadi_real** arg, casadi_real** res, casadi_int* iw, casadi_real* w, int mem){ + return casadi_f10(arg, res, iw, w, mem); +} + +extern "C" CASADI_SYMBOL_EXPORT int path_con_N_fun_alloc_mem(void) { + return 0; +} + +extern "C" CASADI_SYMBOL_EXPORT int path_con_N_fun_init_mem(int mem) { + return 0; +} + +extern "C" CASADI_SYMBOL_EXPORT void path_con_N_fun_free_mem(int mem) { +} + +extern "C" CASADI_SYMBOL_EXPORT int path_con_N_fun_checkout(void) { + return 0; +} + +extern "C" CASADI_SYMBOL_EXPORT void path_con_N_fun_release(int mem) { +} + +extern "C" CASADI_SYMBOL_EXPORT void path_con_N_fun_incref(void) { +} + +extern "C" CASADI_SYMBOL_EXPORT void path_con_N_fun_decref(void) { +} + +extern "C" CASADI_SYMBOL_EXPORT casadi_int path_con_N_fun_n_in(void) { return 2;} + +extern "C" CASADI_SYMBOL_EXPORT casadi_int path_con_N_fun_n_out(void) { return 1;} + +extern "C" CASADI_SYMBOL_EXPORT casadi_real path_con_N_fun_default_in(casadi_int i){ + switch (i) { + default: return 0; + } +} + +extern "C" CASADI_SYMBOL_EXPORT const char* path_con_N_fun_name_in(casadi_int i){ + switch (i) { + case 0: return "states"; + case 1: return "params"; + default: return 0; + } +} + +extern "C" CASADI_SYMBOL_EXPORT const char* path_con_N_fun_name_out(casadi_int i){ + switch (i) { + case 0: return "general_con_N"; + default: return 0; + } +} + +extern "C" CASADI_SYMBOL_EXPORT const casadi_int* path_con_N_fun_sparsity_in(casadi_int i) { + switch (i) { + case 0: return casadi_s0; + case 1: return casadi_s2; + default: return 0; + } +} + +extern "C" CASADI_SYMBOL_EXPORT const casadi_int* path_con_N_fun_sparsity_out(casadi_int i) { + switch (i) { + case 0: return casadi_s5; + default: return 0; + } +} + +extern "C" CASADI_SYMBOL_EXPORT int path_con_N_fun_work(casadi_int *sz_arg, casadi_int* sz_res, casadi_int *sz_iw, casadi_int *sz_w) { + if (sz_arg) *sz_arg = 2; + if (sz_res) *sz_res = 1; + if (sz_iw) *sz_iw = 0; + if (sz_w) *sz_w = 0; + return 0; +} + +/* obji_fun:(i0[4],i1,i2[0],i3[5],i4[5])->(o0) */ +static int casadi_f11(const casadi_real** arg, casadi_real** res, casadi_int* iw, casadi_real* w, int mem) { + casadi_real a0, a1, a2, a3, a4, a5; + a0=5.0000000000000000e-01; + a1=arg[0]? arg[0][0] : 0; + a2=arg[3]? arg[3][0] : 0; + a3=(a1-a2); + a3=(a0*a3); + a4=arg[4]? arg[4][0] : 0; + a3=(a3*a4); + a1=(a1-a2); + a3=(a3*a1); + a1=arg[0]? arg[0][1] : 0; + a2=arg[3]? arg[3][1] : 0; + a4=(a1-a2); + a4=(a0*a4); + a5=arg[4]? arg[4][1] : 0; + a4=(a4*a5); + a1=(a1-a2); + a4=(a4*a1); + a3=(a3+a4); + a4=arg[0]? arg[0][2] : 0; + a1=arg[3]? arg[3][2] : 0; + a2=(a4-a1); + a2=(a0*a2); + a5=arg[4]? arg[4][2] : 0; + a2=(a2*a5); + a4=(a4-a1); + a2=(a2*a4); + a3=(a3+a2); + a2=arg[0]? arg[0][3] : 0; + a4=arg[3]? arg[3][3] : 0; + a1=(a2-a4); + a1=(a0*a1); + a5=arg[4]? arg[4][3] : 0; + a1=(a1*a5); + a2=(a2-a4); + a1=(a1*a2); + a3=(a3+a1); + a1=arg[1]? arg[1][0] : 0; + a2=arg[3]? arg[3][4] : 0; + a4=(a1-a2); + a0=(a0*a4); + a4=arg[4]? arg[4][4] : 0; + a0=(a0*a4); + a1=(a1-a2); + a0=(a0*a1); + a3=(a3+a0); + if (res[0]!=0) res[0][0]=a3; + return 0; +} + +extern "C" CASADI_SYMBOL_EXPORT int obji_fun(const casadi_real** arg, casadi_real** res, casadi_int* iw, casadi_real* w, int mem){ + return casadi_f11(arg, res, iw, w, mem); +} + +extern "C" CASADI_SYMBOL_EXPORT int obji_fun_alloc_mem(void) { + return 0; +} + +extern "C" CASADI_SYMBOL_EXPORT int obji_fun_init_mem(int mem) { + return 0; +} + +extern "C" CASADI_SYMBOL_EXPORT void obji_fun_free_mem(int mem) { +} + +extern "C" CASADI_SYMBOL_EXPORT int obji_fun_checkout(void) { + return 0; +} + +extern "C" CASADI_SYMBOL_EXPORT void obji_fun_release(int mem) { +} + +extern "C" CASADI_SYMBOL_EXPORT void obji_fun_incref(void) { +} + +extern "C" CASADI_SYMBOL_EXPORT void obji_fun_decref(void) { +} + +extern "C" CASADI_SYMBOL_EXPORT casadi_int obji_fun_n_in(void) { return 5;} + +extern "C" CASADI_SYMBOL_EXPORT casadi_int obji_fun_n_out(void) { return 1;} + +extern "C" CASADI_SYMBOL_EXPORT casadi_real obji_fun_default_in(casadi_int i){ + switch (i) { + default: return 0; + } +} + +extern "C" CASADI_SYMBOL_EXPORT const char* obji_fun_name_in(casadi_int i){ + switch (i) { + case 0: return "i0"; + case 1: return "i1"; + case 2: return "i2"; + case 3: return "i3"; + case 4: return "i4"; + default: return 0; + } +} + +extern "C" CASADI_SYMBOL_EXPORT const char* obji_fun_name_out(casadi_int i){ + switch (i) { + case 0: return "o0"; + default: return 0; + } +} + +extern "C" CASADI_SYMBOL_EXPORT const casadi_int* obji_fun_sparsity_in(casadi_int i) { + switch (i) { + case 0: return casadi_s0; + case 1: return casadi_s1; + case 2: return casadi_s2; + case 3: return casadi_s4; + case 4: return casadi_s4; + default: return 0; + } +} + +extern "C" CASADI_SYMBOL_EXPORT const casadi_int* obji_fun_sparsity_out(casadi_int i) { + switch (i) { + case 0: return casadi_s1; + default: return 0; + } +} + +extern "C" CASADI_SYMBOL_EXPORT int obji_fun_work(casadi_int *sz_arg, casadi_int* sz_res, casadi_int *sz_iw, casadi_int *sz_w) { + if (sz_arg) *sz_arg = 5; + if (sz_res) *sz_res = 1; + if (sz_iw) *sz_iw = 0; + if (sz_w) *sz_w = 0; + return 0; +} + +/* objN_fun:(i0[4],i1[0],i2[4],i3[4])->(o0) */ +static int casadi_f12(const casadi_real** arg, casadi_real** res, casadi_int* iw, casadi_real* w, int mem) { + casadi_real a0, a1, a2, a3, a4, a5; + a0=5.0000000000000000e-01; + a1=arg[0]? arg[0][0] : 0; + a2=arg[2]? arg[2][0] : 0; + a3=(a1-a2); + a3=(a0*a3); + a4=arg[3]? arg[3][0] : 0; + a3=(a3*a4); + a1=(a1-a2); + a3=(a3*a1); + a1=arg[0]? arg[0][1] : 0; + a2=arg[2]? arg[2][1] : 0; + a4=(a1-a2); + a4=(a0*a4); + a5=arg[3]? arg[3][1] : 0; + a4=(a4*a5); + a1=(a1-a2); + a4=(a4*a1); + a3=(a3+a4); + a4=arg[0]? arg[0][2] : 0; + a1=arg[2]? arg[2][2] : 0; + a2=(a4-a1); + a2=(a0*a2); + a5=arg[3]? arg[3][2] : 0; + a2=(a2*a5); + a4=(a4-a1); + a2=(a2*a4); + a3=(a3+a2); + a2=arg[0]? arg[0][3] : 0; + a4=arg[2]? arg[2][3] : 0; + a1=(a2-a4); + a0=(a0*a1); + a1=arg[3]? arg[3][3] : 0; + a0=(a0*a1); + a2=(a2-a4); + a0=(a0*a2); + a3=(a3+a0); + if (res[0]!=0) res[0][0]=a3; + return 0; +} + +extern "C" CASADI_SYMBOL_EXPORT int objN_fun(const casadi_real** arg, casadi_real** res, casadi_int* iw, casadi_real* w, int mem){ + return casadi_f12(arg, res, iw, w, mem); +} + +extern "C" CASADI_SYMBOL_EXPORT int objN_fun_alloc_mem(void) { + return 0; +} + +extern "C" CASADI_SYMBOL_EXPORT int objN_fun_init_mem(int mem) { + return 0; +} + +extern "C" CASADI_SYMBOL_EXPORT void objN_fun_free_mem(int mem) { +} + +extern "C" CASADI_SYMBOL_EXPORT int objN_fun_checkout(void) { + return 0; +} + +extern "C" CASADI_SYMBOL_EXPORT void objN_fun_release(int mem) { +} + +extern "C" CASADI_SYMBOL_EXPORT void objN_fun_incref(void) { +} + +extern "C" CASADI_SYMBOL_EXPORT void objN_fun_decref(void) { +} + +extern "C" CASADI_SYMBOL_EXPORT casadi_int objN_fun_n_in(void) { return 4;} + +extern "C" CASADI_SYMBOL_EXPORT casadi_int objN_fun_n_out(void) { return 1;} + +extern "C" CASADI_SYMBOL_EXPORT casadi_real objN_fun_default_in(casadi_int i){ + switch (i) { + default: return 0; + } +} + +extern "C" CASADI_SYMBOL_EXPORT const char* objN_fun_name_in(casadi_int i){ + switch (i) { + case 0: return "i0"; + case 1: return "i1"; + case 2: return "i2"; + case 3: return "i3"; + default: return 0; + } +} + +extern "C" CASADI_SYMBOL_EXPORT const char* objN_fun_name_out(casadi_int i){ + switch (i) { + case 0: return "o0"; + default: return 0; + } +} + +extern "C" CASADI_SYMBOL_EXPORT const casadi_int* objN_fun_sparsity_in(casadi_int i) { + switch (i) { + case 0: return casadi_s0; + case 1: return casadi_s2; + case 2: return casadi_s0; + case 3: return casadi_s0; + default: return 0; + } +} + +extern "C" CASADI_SYMBOL_EXPORT const casadi_int* objN_fun_sparsity_out(casadi_int i) { + switch (i) { + case 0: return casadi_s1; + default: return 0; + } +} + +extern "C" CASADI_SYMBOL_EXPORT int objN_fun_work(casadi_int *sz_arg, casadi_int* sz_res, casadi_int *sz_iw, casadi_int *sz_w) { + if (sz_arg) *sz_arg = 4; + if (sz_res) *sz_res = 1; + if (sz_iw) *sz_iw = 0; + if (sz_w) *sz_w = 0; + return 0; +} + +/* gi_fun:(i0[4],i1,i2[0],i3[5],i4[5])->(o0[4],o1) */ +static int casadi_f13(const casadi_real** arg, casadi_real** res, casadi_int* iw, casadi_real* w, int mem) { + casadi_real a0, a1, a2, a3, a4, a5; + a0=5.0000000000000000e-01; + a1=arg[0]? arg[0][0] : 0; + a2=arg[3]? arg[3][0] : 0; + a3=(a1-a2); + a3=(a0*a3); + a4=arg[4]? arg[4][0] : 0; + a3=(a3*a4); + a1=(a1-a2); + a4=(a4*a1); + a4=(a0*a4); + a3=(a3+a4); + if (res[0]!=0) res[0][0]=a3; + a3=arg[0]? arg[0][1] : 0; + a4=arg[3]? arg[3][1] : 0; + a1=(a3-a4); + a1=(a0*a1); + a2=arg[4]? arg[4][1] : 0; + a1=(a1*a2); + a3=(a3-a4); + a2=(a2*a3); + a2=(a0*a2); + a1=(a1+a2); + if (res[0]!=0) res[0][1]=a1; + a1=arg[0]? arg[0][2] : 0; + a2=arg[3]? arg[3][2] : 0; + a3=(a1-a2); + a3=(a0*a3); + a4=arg[4]? arg[4][2] : 0; + a3=(a3*a4); + a1=(a1-a2); + a4=(a4*a1); + a4=(a0*a4); + a3=(a3+a4); + if (res[0]!=0) res[0][2]=a3; + a3=arg[0]? arg[0][3] : 0; + a4=arg[3]? arg[3][3] : 0; + a1=(a3-a4); + a1=(a0*a1); + a2=arg[4]? arg[4][3] : 0; + a1=(a1*a2); + a3=(a3-a4); + a2=(a2*a3); + a2=(a0*a2); + a1=(a1+a2); + if (res[0]!=0) res[0][3]=a1; + a1=arg[1]? arg[1][0] : 0; + a2=arg[3]? arg[3][4] : 0; + a3=(a1-a2); + a4=arg[4]? arg[4][4] : 0; + a5=(a0*a4); + a3=(a3*a5); + a1=(a1-a2); + a0=(a0*a1); + a0=(a0*a4); + a3=(a3+a0); + if (res[1]!=0) res[1][0]=a3; + return 0; +} + +extern "C" CASADI_SYMBOL_EXPORT int gi_fun(const casadi_real** arg, casadi_real** res, casadi_int* iw, casadi_real* w, int mem){ + return casadi_f13(arg, res, iw, w, mem); +} + +extern "C" CASADI_SYMBOL_EXPORT int gi_fun_alloc_mem(void) { + return 0; +} + +extern "C" CASADI_SYMBOL_EXPORT int gi_fun_init_mem(int mem) { + return 0; +} + +extern "C" CASADI_SYMBOL_EXPORT void gi_fun_free_mem(int mem) { +} + +extern "C" CASADI_SYMBOL_EXPORT int gi_fun_checkout(void) { + return 0; +} + +extern "C" CASADI_SYMBOL_EXPORT void gi_fun_release(int mem) { +} + +extern "C" CASADI_SYMBOL_EXPORT void gi_fun_incref(void) { +} + +extern "C" CASADI_SYMBOL_EXPORT void gi_fun_decref(void) { +} + +extern "C" CASADI_SYMBOL_EXPORT casadi_int gi_fun_n_in(void) { return 5;} + +extern "C" CASADI_SYMBOL_EXPORT casadi_int gi_fun_n_out(void) { return 2;} + +extern "C" CASADI_SYMBOL_EXPORT casadi_real gi_fun_default_in(casadi_int i){ + switch (i) { + default: return 0; + } +} + +extern "C" CASADI_SYMBOL_EXPORT const char* gi_fun_name_in(casadi_int i){ + switch (i) { + case 0: return "i0"; + case 1: return "i1"; + case 2: return "i2"; + case 3: return "i3"; + case 4: return "i4"; + default: return 0; + } +} + +extern "C" CASADI_SYMBOL_EXPORT const char* gi_fun_name_out(casadi_int i){ + switch (i) { + case 0: return "o0"; + case 1: return "o1"; + default: return 0; + } +} + +extern "C" CASADI_SYMBOL_EXPORT const casadi_int* gi_fun_sparsity_in(casadi_int i) { + switch (i) { + case 0: return casadi_s0; + case 1: return casadi_s1; + case 2: return casadi_s2; + case 3: return casadi_s4; + case 4: return casadi_s4; + default: return 0; + } +} + +extern "C" CASADI_SYMBOL_EXPORT const casadi_int* gi_fun_sparsity_out(casadi_int i) { + switch (i) { + case 0: return casadi_s0; + case 1: return casadi_s1; + default: return 0; + } +} + +extern "C" CASADI_SYMBOL_EXPORT int gi_fun_work(casadi_int *sz_arg, casadi_int* sz_res, casadi_int *sz_iw, casadi_int *sz_w) { + if (sz_arg) *sz_arg = 5; + if (sz_res) *sz_res = 2; + if (sz_iw) *sz_iw = 0; + if (sz_w) *sz_w = 0; + return 0; +} + +/* gN_fun:(i0[4],i1[0],i2[4],i3[4])->(o0[4]) */ +static int casadi_f14(const casadi_real** arg, casadi_real** res, casadi_int* iw, casadi_real* w, int mem) { + casadi_real a0, a1, a2, a3, a4; + a0=5.0000000000000000e-01; + a1=arg[0]? arg[0][0] : 0; + a2=arg[2]? arg[2][0] : 0; + a3=(a1-a2); + a3=(a0*a3); + a4=arg[3]? arg[3][0] : 0; + a3=(a3*a4); + a1=(a1-a2); + a4=(a4*a1); + a4=(a0*a4); + a3=(a3+a4); + if (res[0]!=0) res[0][0]=a3; + a3=arg[0]? arg[0][1] : 0; + a4=arg[2]? arg[2][1] : 0; + a1=(a3-a4); + a1=(a0*a1); + a2=arg[3]? arg[3][1] : 0; + a1=(a1*a2); + a3=(a3-a4); + a2=(a2*a3); + a2=(a0*a2); + a1=(a1+a2); + if (res[0]!=0) res[0][1]=a1; + a1=arg[0]? arg[0][2] : 0; + a2=arg[2]? arg[2][2] : 0; + a3=(a1-a2); + a3=(a0*a3); + a4=arg[3]? arg[3][2] : 0; + a3=(a3*a4); + a1=(a1-a2); + a4=(a4*a1); + a4=(a0*a4); + a3=(a3+a4); + if (res[0]!=0) res[0][2]=a3; + a3=arg[0]? arg[0][3] : 0; + a4=arg[2]? arg[2][3] : 0; + a1=(a3-a4); + a1=(a0*a1); + a2=arg[3]? arg[3][3] : 0; + a1=(a1*a2); + a3=(a3-a4); + a2=(a2*a3); + a0=(a0*a2); + a1=(a1+a0); + if (res[0]!=0) res[0][3]=a1; + return 0; +} + +extern "C" CASADI_SYMBOL_EXPORT int gN_fun(const casadi_real** arg, casadi_real** res, casadi_int* iw, casadi_real* w, int mem){ + return casadi_f14(arg, res, iw, w, mem); +} + +extern "C" CASADI_SYMBOL_EXPORT int gN_fun_alloc_mem(void) { + return 0; +} + +extern "C" CASADI_SYMBOL_EXPORT int gN_fun_init_mem(int mem) { + return 0; +} + +extern "C" CASADI_SYMBOL_EXPORT void gN_fun_free_mem(int mem) { +} + +extern "C" CASADI_SYMBOL_EXPORT int gN_fun_checkout(void) { + return 0; +} + +extern "C" CASADI_SYMBOL_EXPORT void gN_fun_release(int mem) { +} + +extern "C" CASADI_SYMBOL_EXPORT void gN_fun_incref(void) { +} + +extern "C" CASADI_SYMBOL_EXPORT void gN_fun_decref(void) { +} + +extern "C" CASADI_SYMBOL_EXPORT casadi_int gN_fun_n_in(void) { return 4;} + +extern "C" CASADI_SYMBOL_EXPORT casadi_int gN_fun_n_out(void) { return 1;} + +extern "C" CASADI_SYMBOL_EXPORT casadi_real gN_fun_default_in(casadi_int i){ + switch (i) { + default: return 0; + } +} + +extern "C" CASADI_SYMBOL_EXPORT const char* gN_fun_name_in(casadi_int i){ + switch (i) { + case 0: return "i0"; + case 1: return "i1"; + case 2: return "i2"; + case 3: return "i3"; + default: return 0; + } +} + +extern "C" CASADI_SYMBOL_EXPORT const char* gN_fun_name_out(casadi_int i){ + switch (i) { + case 0: return "o0"; + default: return 0; + } +} + +extern "C" CASADI_SYMBOL_EXPORT const casadi_int* gN_fun_sparsity_in(casadi_int i) { + switch (i) { + case 0: return casadi_s0; + case 1: return casadi_s2; + case 2: return casadi_s0; + case 3: return casadi_s0; + default: return 0; + } +} + +extern "C" CASADI_SYMBOL_EXPORT const casadi_int* gN_fun_sparsity_out(casadi_int i) { + switch (i) { + case 0: return casadi_s0; + default: return 0; + } +} + +extern "C" CASADI_SYMBOL_EXPORT int gN_fun_work(casadi_int *sz_arg, casadi_int* sz_res, casadi_int *sz_iw, casadi_int *sz_w) { + if (sz_arg) *sz_arg = 4; + if (sz_res) *sz_res = 1; + if (sz_iw) *sz_iw = 0; + if (sz_w) *sz_w = 0; + return 0; +} + +/* Hi_fun:(i0[4],i1,i2[0],i3[5],i4[5])->(o0[4x4],o1,o2[4]) */ +static int casadi_f15(const casadi_real** arg, casadi_real** res, casadi_int* iw, casadi_real* w, int mem) { + casadi_real a0, a1; + a0=arg[4]? arg[4][0] : 0; + if (res[0]!=0) res[0][0]=a0; + a0=0.; + if (res[0]!=0) res[0][1]=a0; + if (res[0]!=0) res[0][2]=a0; + if (res[0]!=0) res[0][3]=a0; + if (res[0]!=0) res[0][4]=a0; + a1=arg[4]? arg[4][1] : 0; + if (res[0]!=0) res[0][5]=a1; + if (res[0]!=0) res[0][6]=a0; + if (res[0]!=0) res[0][7]=a0; + if (res[0]!=0) res[0][8]=a0; + if (res[0]!=0) res[0][9]=a0; + a1=arg[4]? arg[4][2] : 0; + if (res[0]!=0) res[0][10]=a1; + if (res[0]!=0) res[0][11]=a0; + if (res[0]!=0) res[0][12]=a0; + if (res[0]!=0) res[0][13]=a0; + if (res[0]!=0) res[0][14]=a0; + a1=arg[4]? arg[4][3] : 0; + if (res[0]!=0) res[0][15]=a1; + a1=arg[4]? arg[4][4] : 0; + if (res[1]!=0) res[1][0]=a1; + if (res[2]!=0) res[2][0]=a0; + if (res[2]!=0) res[2][1]=a0; + if (res[2]!=0) res[2][2]=a0; + if (res[2]!=0) res[2][3]=a0; + return 0; +} + +extern "C" CASADI_SYMBOL_EXPORT int Hi_fun(const casadi_real** arg, casadi_real** res, casadi_int* iw, casadi_real* w, int mem){ + return casadi_f15(arg, res, iw, w, mem); +} + +extern "C" CASADI_SYMBOL_EXPORT int Hi_fun_alloc_mem(void) { + return 0; +} + +extern "C" CASADI_SYMBOL_EXPORT int Hi_fun_init_mem(int mem) { + return 0; +} + +extern "C" CASADI_SYMBOL_EXPORT void Hi_fun_free_mem(int mem) { +} + +extern "C" CASADI_SYMBOL_EXPORT int Hi_fun_checkout(void) { + return 0; +} + +extern "C" CASADI_SYMBOL_EXPORT void Hi_fun_release(int mem) { +} + +extern "C" CASADI_SYMBOL_EXPORT void Hi_fun_incref(void) { +} + +extern "C" CASADI_SYMBOL_EXPORT void Hi_fun_decref(void) { +} + +extern "C" CASADI_SYMBOL_EXPORT casadi_int Hi_fun_n_in(void) { return 5;} + +extern "C" CASADI_SYMBOL_EXPORT casadi_int Hi_fun_n_out(void) { return 3;} + +extern "C" CASADI_SYMBOL_EXPORT casadi_real Hi_fun_default_in(casadi_int i){ + switch (i) { + default: return 0; + } +} + +extern "C" CASADI_SYMBOL_EXPORT const char* Hi_fun_name_in(casadi_int i){ + switch (i) { + case 0: return "i0"; + case 1: return "i1"; + case 2: return "i2"; + case 3: return "i3"; + case 4: return "i4"; + default: return 0; + } +} + +extern "C" CASADI_SYMBOL_EXPORT const char* Hi_fun_name_out(casadi_int i){ + switch (i) { + case 0: return "o0"; + case 1: return "o1"; + case 2: return "o2"; + default: return 0; + } +} + +extern "C" CASADI_SYMBOL_EXPORT const casadi_int* Hi_fun_sparsity_in(casadi_int i) { + switch (i) { + case 0: return casadi_s0; + case 1: return casadi_s1; + case 2: return casadi_s2; + case 3: return casadi_s4; + case 4: return casadi_s4; + default: return 0; + } +} + +extern "C" CASADI_SYMBOL_EXPORT const casadi_int* Hi_fun_sparsity_out(casadi_int i) { + switch (i) { + case 0: return casadi_s3; + case 1: return casadi_s1; + case 2: return casadi_s0; + default: return 0; + } +} + +extern "C" CASADI_SYMBOL_EXPORT int Hi_fun_work(casadi_int *sz_arg, casadi_int* sz_res, casadi_int *sz_iw, casadi_int *sz_w) { + if (sz_arg) *sz_arg = 5; + if (sz_res) *sz_res = 3; + if (sz_iw) *sz_iw = 0; + if (sz_w) *sz_w = 0; + return 0; +} + +/* HN_fun:(i0[4],i1[0],i2[4],i3[4])->(o0[4x4]) */ +static int casadi_f16(const casadi_real** arg, casadi_real** res, casadi_int* iw, casadi_real* w, int mem) { + casadi_real a0, a1; + a0=arg[3]? arg[3][0] : 0; + if (res[0]!=0) res[0][0]=a0; + a0=0.; + if (res[0]!=0) res[0][1]=a0; + if (res[0]!=0) res[0][2]=a0; + if (res[0]!=0) res[0][3]=a0; + if (res[0]!=0) res[0][4]=a0; + a1=arg[3]? arg[3][1] : 0; + if (res[0]!=0) res[0][5]=a1; + if (res[0]!=0) res[0][6]=a0; + if (res[0]!=0) res[0][7]=a0; + if (res[0]!=0) res[0][8]=a0; + if (res[0]!=0) res[0][9]=a0; + a1=arg[3]? arg[3][2] : 0; + if (res[0]!=0) res[0][10]=a1; + if (res[0]!=0) res[0][11]=a0; + if (res[0]!=0) res[0][12]=a0; + if (res[0]!=0) res[0][13]=a0; + if (res[0]!=0) res[0][14]=a0; + a0=arg[3]? arg[3][3] : 0; + if (res[0]!=0) res[0][15]=a0; + return 0; +} + +extern "C" CASADI_SYMBOL_EXPORT int HN_fun(const casadi_real** arg, casadi_real** res, casadi_int* iw, casadi_real* w, int mem){ + return casadi_f16(arg, res, iw, w, mem); +} + +extern "C" CASADI_SYMBOL_EXPORT int HN_fun_alloc_mem(void) { + return 0; +} + +extern "C" CASADI_SYMBOL_EXPORT int HN_fun_init_mem(int mem) { + return 0; +} + +extern "C" CASADI_SYMBOL_EXPORT void HN_fun_free_mem(int mem) { +} + +extern "C" CASADI_SYMBOL_EXPORT int HN_fun_checkout(void) { + return 0; +} + +extern "C" CASADI_SYMBOL_EXPORT void HN_fun_release(int mem) { +} + +extern "C" CASADI_SYMBOL_EXPORT void HN_fun_incref(void) { +} + +extern "C" CASADI_SYMBOL_EXPORT void HN_fun_decref(void) { +} + +extern "C" CASADI_SYMBOL_EXPORT casadi_int HN_fun_n_in(void) { return 4;} + +extern "C" CASADI_SYMBOL_EXPORT casadi_int HN_fun_n_out(void) { return 1;} + +extern "C" CASADI_SYMBOL_EXPORT casadi_real HN_fun_default_in(casadi_int i){ + switch (i) { + default: return 0; + } +} + +extern "C" CASADI_SYMBOL_EXPORT const char* HN_fun_name_in(casadi_int i){ + switch (i) { + case 0: return "i0"; + case 1: return "i1"; + case 2: return "i2"; + case 3: return "i3"; + default: return 0; + } +} + +extern "C" CASADI_SYMBOL_EXPORT const char* HN_fun_name_out(casadi_int i){ + switch (i) { + case 0: return "o0"; + default: return 0; + } +} + +extern "C" CASADI_SYMBOL_EXPORT const casadi_int* HN_fun_sparsity_in(casadi_int i) { + switch (i) { + case 0: return casadi_s0; + case 1: return casadi_s2; + case 2: return casadi_s0; + case 3: return casadi_s0; + default: return 0; + } +} + +extern "C" CASADI_SYMBOL_EXPORT const casadi_int* HN_fun_sparsity_out(casadi_int i) { + switch (i) { + case 0: return casadi_s3; + default: return 0; + } +} + +extern "C" CASADI_SYMBOL_EXPORT int HN_fun_work(casadi_int *sz_arg, casadi_int* sz_res, casadi_int *sz_iw, casadi_int *sz_w) { + if (sz_arg) *sz_arg = 4; + if (sz_res) *sz_res = 1; + if (sz_iw) *sz_iw = 0; + if (sz_w) *sz_w = 0; + return 0; +} + +/* Ci_fun:(i0[4],i1,i2[0])->(o0[0x4],o1[0]) */ +static int casadi_f17(const casadi_real** arg, casadi_real** res, casadi_int* iw, casadi_real* w, int mem) { + return 0; +} + +extern "C" CASADI_SYMBOL_EXPORT int Ci_fun(const casadi_real** arg, casadi_real** res, casadi_int* iw, casadi_real* w, int mem){ + return casadi_f17(arg, res, iw, w, mem); +} + +extern "C" CASADI_SYMBOL_EXPORT int Ci_fun_alloc_mem(void) { + return 0; +} + +extern "C" CASADI_SYMBOL_EXPORT int Ci_fun_init_mem(int mem) { + return 0; +} + +extern "C" CASADI_SYMBOL_EXPORT void Ci_fun_free_mem(int mem) { +} + +extern "C" CASADI_SYMBOL_EXPORT int Ci_fun_checkout(void) { + return 0; +} + +extern "C" CASADI_SYMBOL_EXPORT void Ci_fun_release(int mem) { +} + +extern "C" CASADI_SYMBOL_EXPORT void Ci_fun_incref(void) { +} + +extern "C" CASADI_SYMBOL_EXPORT void Ci_fun_decref(void) { +} + +extern "C" CASADI_SYMBOL_EXPORT casadi_int Ci_fun_n_in(void) { return 3;} + +extern "C" CASADI_SYMBOL_EXPORT casadi_int Ci_fun_n_out(void) { return 2;} + +extern "C" CASADI_SYMBOL_EXPORT casadi_real Ci_fun_default_in(casadi_int i){ + switch (i) { + default: return 0; + } +} + +extern "C" CASADI_SYMBOL_EXPORT const char* Ci_fun_name_in(casadi_int i){ + switch (i) { + case 0: return "i0"; + case 1: return "i1"; + case 2: return "i2"; + default: return 0; + } +} + +extern "C" CASADI_SYMBOL_EXPORT const char* Ci_fun_name_out(casadi_int i){ + switch (i) { + case 0: return "o0"; + case 1: return "o1"; + default: return 0; + } +} + +extern "C" CASADI_SYMBOL_EXPORT const casadi_int* Ci_fun_sparsity_in(casadi_int i) { + switch (i) { + case 0: return casadi_s0; + case 1: return casadi_s1; + case 2: return casadi_s2; + default: return 0; + } +} + +extern "C" CASADI_SYMBOL_EXPORT const casadi_int* Ci_fun_sparsity_out(casadi_int i) { + switch (i) { + case 0: return casadi_s6; + case 1: return casadi_s2; + default: return 0; + } +} + +extern "C" CASADI_SYMBOL_EXPORT int Ci_fun_work(casadi_int *sz_arg, casadi_int* sz_res, casadi_int *sz_iw, casadi_int *sz_w) { + if (sz_arg) *sz_arg = 3; + if (sz_res) *sz_res = 2; + if (sz_iw) *sz_iw = 0; + if (sz_w) *sz_w = 0; + return 0; +} + +/* CN_fun:(i0[4],i1[0])->(o0[0x4]) */ +static int casadi_f18(const casadi_real** arg, casadi_real** res, casadi_int* iw, casadi_real* w, int mem) { + return 0; +} + +extern "C" CASADI_SYMBOL_EXPORT int CN_fun(const casadi_real** arg, casadi_real** res, casadi_int* iw, casadi_real* w, int mem){ + return casadi_f18(arg, res, iw, w, mem); +} + +extern "C" CASADI_SYMBOL_EXPORT int CN_fun_alloc_mem(void) { + return 0; +} + +extern "C" CASADI_SYMBOL_EXPORT int CN_fun_init_mem(int mem) { + return 0; +} + +extern "C" CASADI_SYMBOL_EXPORT void CN_fun_free_mem(int mem) { +} + +extern "C" CASADI_SYMBOL_EXPORT int CN_fun_checkout(void) { + return 0; +} + +extern "C" CASADI_SYMBOL_EXPORT void CN_fun_release(int mem) { +} + +extern "C" CASADI_SYMBOL_EXPORT void CN_fun_incref(void) { +} + +extern "C" CASADI_SYMBOL_EXPORT void CN_fun_decref(void) { +} + +extern "C" CASADI_SYMBOL_EXPORT casadi_int CN_fun_n_in(void) { return 2;} + +extern "C" CASADI_SYMBOL_EXPORT casadi_int CN_fun_n_out(void) { return 1;} + +extern "C" CASADI_SYMBOL_EXPORT casadi_real CN_fun_default_in(casadi_int i){ + switch (i) { + default: return 0; + } +} + +extern "C" CASADI_SYMBOL_EXPORT const char* CN_fun_name_in(casadi_int i){ + switch (i) { + case 0: return "i0"; + case 1: return "i1"; + default: return 0; + } +} + +extern "C" CASADI_SYMBOL_EXPORT const char* CN_fun_name_out(casadi_int i){ + switch (i) { + case 0: return "o0"; + default: return 0; + } +} + +extern "C" CASADI_SYMBOL_EXPORT const casadi_int* CN_fun_sparsity_in(casadi_int i) { + switch (i) { + case 0: return casadi_s0; + case 1: return casadi_s2; + default: return 0; + } +} + +extern "C" CASADI_SYMBOL_EXPORT const casadi_int* CN_fun_sparsity_out(casadi_int i) { + switch (i) { + case 0: return casadi_s6; + default: return 0; + } +} + +extern "C" CASADI_SYMBOL_EXPORT int CN_fun_work(casadi_int *sz_arg, casadi_int* sz_res, casadi_int *sz_iw, casadi_int *sz_w) { + if (sz_arg) *sz_arg = 2; + if (sz_res) *sz_res = 1; + if (sz_iw) *sz_iw = 0; + if (sz_w) *sz_w = 0; + return 0; +} + +/* adj_fun:(i0[4],i1,i2[0],i3[5],i4[5],i5[4],i6,i7,i8[0])->(o0[5],o1[5],o2[5]) */ +static int casadi_f19(const casadi_real** arg, casadi_real** res, casadi_int* iw, casadi_real* w, int mem) { + casadi_real a0, a1, a10, a11, a12, a13, a14, a15, a16, a17, a18, a19, a2, a20, a21, a22, a23, a24, a25, a26, a27, a28, a29, a3, a30, a31, a32, a33, a34, a35, a36, a37, a38, a39, a4, a40, a41, a42, a43, a44, a45, a46, a47, a48, a49, a5, a50, a51, a52, a53, a54, a55, a56, a57, a58, a59, a6, a60, a61, a7, a8, a9; + a0=5.0000000000000000e-01; + a1=arg[0]? arg[0][0] : 0; + a2=arg[3]? arg[3][0] : 0; + a3=(a1-a2); + a3=(a0*a3); + a4=arg[4]? arg[4][0] : 0; + a3=(a3*a4); + a1=(a1-a2); + a4=(a4*a1); + a4=(a0*a4); + a3=(a3+a4); + if (res[0]!=0) res[0][0]=a3; + a3=arg[0]? arg[0][1] : 0; + a4=arg[3]? arg[3][1] : 0; + a1=(a3-a4); + a1=(a0*a1); + a2=arg[4]? arg[4][1] : 0; + a1=(a1*a2); + a4=(a3-a4); + a2=(a2*a4); + a2=(a0*a2); + a1=(a1+a2); + if (res[0]!=0) res[0][1]=a1; + a1=arg[0]? arg[0][2] : 0; + a2=arg[3]? arg[3][2] : 0; + a4=(a1-a2); + a4=(a0*a4); + a5=arg[4]? arg[4][2] : 0; + a4=(a4*a5); + a1=(a1-a2); + a5=(a5*a1); + a5=(a0*a5); + a4=(a4+a5); + if (res[0]!=0) res[0][2]=a4; + a4=arg[0]? arg[0][3] : 0; + a5=arg[3]? arg[3][3] : 0; + a1=(a4-a5); + a1=(a0*a1); + a2=arg[4]? arg[4][3] : 0; + a1=(a1*a2); + a5=(a4-a5); + a2=(a2*a5); + a2=(a0*a2); + a1=(a1+a2); + if (res[0]!=0) res[0][3]=a1; + a1=arg[1]? arg[1][0] : 0; + a2=arg[3]? arg[3][4] : 0; + a5=(a1-a2); + a6=arg[4]? arg[4][4] : 0; + a7=(a0*a6); + a5=(a5*a7); + a2=(a1-a2); + a0=(a0*a2); + a0=(a0*a6); + a5=(a5+a0); + if (res[0]!=0) res[0][4]=a5; + a5=arg[5]? arg[5][0] : 0; + if (res[1]!=0) res[1][0]=a5; + a0=5.0000000000000003e-02; + a6=2.5000000000000001e-02; + a2=-8.0000000000000016e-02; + a7=(a6*a4); + a7=(a3+a7); + a8=cos(a7); + a8=(a2*a8); + a9=sin(a7); + a10=(a8*a9); + a11=cos(a3); + a11=(a2*a11); + a12=sin(a3); + a13=(a11*a12); + a14=casadi_sq(a4); + a15=(a13*a14); + a16=cos(a3); + a17=(a1*a16); + a15=(a15+a17); + a17=1.0791000000000002e+01; + a18=sin(a3); + a18=(a17*a18); + a15=(a15+a18); + a18=8.0000000000000004e-01; + a19=1.1000000000000001e+00; + a20=1.0000000000000001e-01; + a21=cos(a3); + a22=casadi_sq(a21); + a22=(a20*a22); + a22=(a19-a22); + a23=(a18*a22); + a15=(a15/a23); + a24=(a6*a15); + a24=(a4+a24); + a25=casadi_sq(a24); + a26=(a10*a25); + a27=cos(a7); + a28=(a1*a27); + a26=(a26+a28); + a28=sin(a7); + a28=(a17*a28); + a26=(a26+a28); + a28=cos(a7); + a29=casadi_sq(a28); + a29=(a20*a29); + a29=(a19-a29); + a30=(a18*a29); + a26=(a26/a30); + a31=(a6*a26); + a31=(a4+a31); + a32=(a0*a31); + a32=(a3+a32); + a33=cos(a32); + a34=8.3333333333333332e-03; + a35=arg[5]? arg[5][3] : 0; + a36=(a34*a35); + a37=cos(a32); + a38=casadi_sq(a37); + a38=(a20*a38); + a38=(a19-a38); + a39=(a18*a38); + a40=(a36/a39); + a41=(a17*a40); + a33=(a33*a41); + a41=sin(a32); + a42=(a1*a40); + a41=(a41*a42); + a33=(a33-a41); + a41=cos(a32); + a42=cos(a32); + a42=(a2*a42); + a43=(a6*a24); + a43=(a3+a43); + a44=cos(a43); + a44=(a2*a44); + a45=sin(a43); + a46=(a44*a45); + a47=casadi_sq(a31); + a48=(a46*a47); + a49=cos(a43); + a50=(a1*a49); + a48=(a48+a50); + a50=sin(a43); + a50=(a17*a50); + a48=(a48+a50); + a50=cos(a43); + a51=casadi_sq(a50); + a51=(a20*a51); + a19=(a19-a51); + a51=(a18*a19); + a48=(a48/a51); + a52=(a0*a48); + a52=(a4+a52); + a53=casadi_sq(a52); + a54=(a53*a40); + a55=(a42*a54); + a41=(a41*a55); + a33=(a33+a41); + a41=sin(a32); + a55=sin(a32); + a54=(a55*a54); + a54=(a2*a54); + a41=(a41*a54); + a33=(a33-a41); + a41=sin(a32); + a37=(a37+a37); + a42=(a42*a55); + a53=(a42*a53); + a55=cos(a32); + a54=(a1*a55); + a53=(a53+a54); + a54=sin(a32); + a54=(a17*a54); + a53=(a53+a54); + a53=(a53/a39); + a53=(a53/a39); + a53=(a53*a36); + a53=(a18*a53); + a39=sin(a32); + a39=(a2*a39); + a54=casadi_sq(a52); + a56=(a39*a54); + a57=9.8100000000000009e-01; + a58=cos(a32); + a58=(a57*a58); + a59=sin(a32); + a60=(a58*a59); + a56=(a56+a60); + a56=(a56+a1); + a56=(a56/a38); + a56=(a56/a38); + a60=arg[5]? arg[5][2] : 0; + a61=(a34*a60); + a56=(a56*a61); + a53=(a53+a56); + a53=(a20*a53); + a37=(a37*a53); + a41=(a41*a37); + a33=(a33-a41); + a41=cos(a32); + a38=(a61/a38); + a58=(a58*a38); + a41=(a41*a58); + a33=(a33+a41); + a41=sin(a32); + a59=(a59*a38); + a59=(a57*a59); + a41=(a41*a59); + a33=(a33-a41); + a32=cos(a32); + a54=(a54*a38); + a54=(a2*a54); + a32=(a32*a54); + a33=(a33+a32); + a32=arg[5]? arg[5][1] : 0; + a54=(a33+a32); + a41=cos(a43); + a59=2.; + a58=(a59*a36); + a37=(a52+a52); + a42=(a42*a40); + a37=(a37*a42); + a52=(a52+a52); + a39=(a39*a38); + a52=(a52*a39); + a37=(a37+a52); + a32=(a34*a32); + a37=(a37+a32); + a52=(a0*a37); + a58=(a58+a52); + a52=(a58/a51); + a39=(a17*a52); + a41=(a41*a39); + a39=sin(a43); + a42=(a1*a52); + a39=(a39*a42); + a41=(a41-a39); + a39=cos(a43); + a47=(a47*a52); + a44=(a44*a47); + a39=(a39*a44); + a41=(a41+a39); + a39=sin(a43); + a45=(a45*a47); + a45=(a2*a45); + a39=(a39*a45); + a41=(a41-a39); + a39=sin(a43); + a50=(a50+a50); + a48=(a48/a51); + a48=(a48*a58); + a48=(a18*a48); + a58=sin(a43); + a58=(a2*a58); + a51=casadi_sq(a31); + a45=(a58*a51); + a47=cos(a43); + a47=(a57*a47); + a44=sin(a43); + a42=(a47*a44); + a45=(a45+a42); + a45=(a45+a1); + a45=(a45/a19); + a45=(a45/a19); + a42=(a59*a61); + a34=(a34*a5); + a5=(a0*a34); + a42=(a42+a5); + a45=(a45*a42); + a48=(a48+a45); + a48=(a20*a48); + a50=(a50*a48); + a39=(a39*a50); + a41=(a41-a39); + a39=cos(a43); + a42=(a42/a19); + a47=(a47*a42); + a39=(a39*a47); + a41=(a41+a39); + a39=sin(a43); + a44=(a44*a42); + a44=(a57*a44); + a39=(a39*a44); + a41=(a41-a39); + a43=cos(a43); + a51=(a51*a42); + a51=(a2*a51); + a43=(a43*a51); + a41=(a41+a43); + a54=(a54+a41); + a43=cos(a3); + a51=(a59*a32); + a39=(a24+a24); + a44=(a59*a36); + a0=(a0*a33); + a33=(a31+a31); + a46=(a46*a52); + a33=(a33*a46); + a0=(a0+a33); + a33=(a59*a32); + a0=(a0+a33); + a31=(a31+a31); + a58=(a58*a42); + a31=(a31*a58); + a0=(a0+a31); + a31=(a6*a0); + a44=(a44+a31); + a31=(a44/a30); + a10=(a10*a31); + a39=(a39*a10); + a51=(a51+a39); + a41=(a6*a41); + a51=(a51+a41); + a41=(a24+a24); + a39=sin(a7); + a39=(a2*a39); + a10=(a59*a61); + a58=(a59*a34); + a33=(a6*a58); + a10=(a10+a33); + a33=(a10/a29); + a46=(a39*a33); + a41=(a41*a46); + a51=(a51+a41); + a41=(a6*a51); + a36=(a36+a41); + a41=(a36/a23); + a46=(a17*a41); + a43=(a43*a46); + a54=(a54+a43); + a43=sin(a3); + a46=(a1*a41); + a43=(a43*a46); + a54=(a54-a43); + a43=cos(a3); + a14=(a14*a41); + a11=(a11*a14); + a43=(a43*a11); + a54=(a54+a43); + a43=sin(a3); + a12=(a12*a14); + a12=(a2*a12); + a43=(a43*a12); + a54=(a54-a43); + a43=cos(a7); + a17=(a17*a31); + a43=(a43*a17); + a17=sin(a7); + a12=(a1*a31); + a17=(a17*a12); + a43=(a43-a17); + a17=cos(a7); + a25=(a25*a31); + a8=(a8*a25); + a17=(a17*a8); + a43=(a43+a17); + a17=sin(a7); + a9=(a9*a25); + a9=(a2*a9); + a17=(a17*a9); + a43=(a43-a17); + a17=sin(a7); + a28=(a28+a28); + a26=(a26/a30); + a26=(a26*a44); + a26=(a18*a26); + a24=casadi_sq(a24); + a39=(a39*a24); + a44=cos(a7); + a44=(a57*a44); + a30=sin(a7); + a9=(a44*a30); + a39=(a39+a9); + a39=(a39+a1); + a39=(a39/a29); + a39=(a39/a29); + a39=(a39*a10); + a26=(a26+a39); + a26=(a20*a26); + a28=(a28*a26); + a17=(a17*a28); + a43=(a43-a17); + a17=cos(a7); + a44=(a44*a33); + a17=(a17*a44); + a43=(a43+a17); + a17=sin(a7); + a30=(a30*a33); + a30=(a57*a30); + a17=(a17*a30); + a43=(a43-a17); + a7=cos(a7); + a24=(a24*a33); + a24=(a2*a24); + a7=(a7*a24); + a43=(a43+a7); + a54=(a54+a43); + a7=sin(a3); + a21=(a21+a21); + a15=(a15/a23); + a15=(a15*a36); + a18=(a18*a15); + a15=sin(a3); + a15=(a2*a15); + a36=casadi_sq(a4); + a23=(a15*a36); + a24=cos(a3); + a24=(a57*a24); + a17=sin(a3); + a30=(a24*a17); + a23=(a23+a30); + a23=(a23+a1); + a23=(a23/a22); + a23=(a23/a22); + a59=(a59*a34); + a1=(a6*a59); + a61=(a61+a1); + a23=(a23*a61); + a18=(a18+a23); + a20=(a20*a18); + a21=(a21*a20); + a7=(a7*a21); + a54=(a54-a7); + a7=cos(a3); + a61=(a61/a22); + a24=(a24*a61); + a7=(a7*a24); + a54=(a54+a7); + a7=sin(a3); + a17=(a17*a61); + a57=(a57*a17); + a7=(a7*a57); + a54=(a54-a7); + a3=cos(a3); + a36=(a36*a61); + a2=(a2*a36); + a3=(a3*a2); + a54=(a54+a3); + if (res[1]!=0) res[1][1]=a54; + a60=(a60+a34); + a60=(a60+a58); + a60=(a60+a34); + a60=(a60+a59); + if (res[1]!=0) res[1][2]=a60; + a35=(a35+a37); + a35=(a35+a32); + a35=(a35+a0); + a35=(a35+a51); + a51=(a4+a4); + a13=(a13*a41); + a51=(a51*a13); + a35=(a35+a51); + a6=(a6*a43); + a35=(a35+a6); + a4=(a4+a4); + a15=(a15*a61); + a4=(a4*a15); + a35=(a35+a4); + if (res[1]!=0) res[1][3]=a35; + a55=(a55*a40); + a55=(a55+a38); + a49=(a49*a52); + a55=(a55+a49); + a55=(a55+a42); + a27=(a27*a31); + a55=(a55+a27); + a55=(a55+a33); + a16=(a16*a41); + a55=(a55+a16); + a55=(a55+a61); + if (res[1]!=0) res[1][4]=a55; + a55=arg[6]? arg[6][0] : 0; + if (res[2]!=0) res[2][0]=a55; + a55=0.; + if (res[2]!=0) res[2][1]=a55; + if (res[2]!=0) res[2][2]=a55; + if (res[2]!=0) res[2][3]=a55; + a55=arg[7]? arg[7][0] : 0; + if (res[2]!=0) res[2][4]=a55; + return 0; +} + +extern "C" CASADI_SYMBOL_EXPORT int adj_fun(const casadi_real** arg, casadi_real** res, casadi_int* iw, casadi_real* w, int mem){ + return casadi_f19(arg, res, iw, w, mem); +} + +extern "C" CASADI_SYMBOL_EXPORT int adj_fun_alloc_mem(void) { + return 0; +} + +extern "C" CASADI_SYMBOL_EXPORT int adj_fun_init_mem(int mem) { + return 0; +} + +extern "C" CASADI_SYMBOL_EXPORT void adj_fun_free_mem(int mem) { +} + +extern "C" CASADI_SYMBOL_EXPORT int adj_fun_checkout(void) { + return 0; +} + +extern "C" CASADI_SYMBOL_EXPORT void adj_fun_release(int mem) { +} + +extern "C" CASADI_SYMBOL_EXPORT void adj_fun_incref(void) { +} + +extern "C" CASADI_SYMBOL_EXPORT void adj_fun_decref(void) { +} + +extern "C" CASADI_SYMBOL_EXPORT casadi_int adj_fun_n_in(void) { return 9;} + +extern "C" CASADI_SYMBOL_EXPORT casadi_int adj_fun_n_out(void) { return 3;} + +extern "C" CASADI_SYMBOL_EXPORT casadi_real adj_fun_default_in(casadi_int i){ + switch (i) { + default: return 0; + } +} + +extern "C" CASADI_SYMBOL_EXPORT const char* adj_fun_name_in(casadi_int i){ + switch (i) { + case 0: return "i0"; + case 1: return "i1"; + case 2: return "i2"; + case 3: return "i3"; + case 4: return "i4"; + case 5: return "i5"; + case 6: return "i6"; + case 7: return "i7"; + case 8: return "i8"; + default: return 0; + } +} + +extern "C" CASADI_SYMBOL_EXPORT const char* adj_fun_name_out(casadi_int i){ + switch (i) { + case 0: return "o0"; + case 1: return "o1"; + case 2: return "o2"; + default: return 0; + } +} + +extern "C" CASADI_SYMBOL_EXPORT const casadi_int* adj_fun_sparsity_in(casadi_int i) { + switch (i) { + case 0: return casadi_s0; + case 1: return casadi_s1; + case 2: return casadi_s2; + case 3: return casadi_s4; + case 4: return casadi_s4; + case 5: return casadi_s0; + case 6: return casadi_s1; + case 7: return casadi_s1; + case 8: return casadi_s2; + default: return 0; + } +} + +extern "C" CASADI_SYMBOL_EXPORT const casadi_int* adj_fun_sparsity_out(casadi_int i) { + switch (i) { + case 0: return casadi_s4; + case 1: return casadi_s4; + case 2: return casadi_s4; + default: return 0; + } +} + +extern "C" CASADI_SYMBOL_EXPORT int adj_fun_work(casadi_int *sz_arg, casadi_int* sz_res, casadi_int *sz_iw, casadi_int *sz_w) { + if (sz_arg) *sz_arg = 9; + if (sz_res) *sz_res = 3; + if (sz_iw) *sz_iw = 0; + if (sz_w) *sz_w = 0; + return 0; +} + +/* adjN_fun:(i0[4],i1[0],i2[4],i3[4],i4,i5[0])->(o0[4],o1[4]) */ +static int casadi_f20(const casadi_real** arg, casadi_real** res, casadi_int* iw, casadi_real* w, int mem) { + casadi_real a0, a1, a2, a3, a4; + a0=5.0000000000000000e-01; + a1=arg[0]? arg[0][0] : 0; + a2=arg[2]? arg[2][0] : 0; + a3=(a1-a2); + a3=(a0*a3); + a4=arg[3]? arg[3][0] : 0; + a3=(a3*a4); + a1=(a1-a2); + a4=(a4*a1); + a4=(a0*a4); + a3=(a3+a4); + if (res[0]!=0) res[0][0]=a3; + a3=arg[0]? arg[0][1] : 0; + a4=arg[2]? arg[2][1] : 0; + a1=(a3-a4); + a1=(a0*a1); + a2=arg[3]? arg[3][1] : 0; + a1=(a1*a2); + a3=(a3-a4); + a2=(a2*a3); + a2=(a0*a2); + a1=(a1+a2); + if (res[0]!=0) res[0][1]=a1; + a1=arg[0]? arg[0][2] : 0; + a2=arg[2]? arg[2][2] : 0; + a3=(a1-a2); + a3=(a0*a3); + a4=arg[3]? arg[3][2] : 0; + a3=(a3*a4); + a1=(a1-a2); + a4=(a4*a1); + a4=(a0*a4); + a3=(a3+a4); + if (res[0]!=0) res[0][2]=a3; + a3=arg[0]? arg[0][3] : 0; + a4=arg[2]? arg[2][3] : 0; + a1=(a3-a4); + a1=(a0*a1); + a2=arg[3]? arg[3][3] : 0; + a1=(a1*a2); + a3=(a3-a4); + a2=(a2*a3); + a0=(a0*a2); + a1=(a1+a0); + if (res[0]!=0) res[0][3]=a1; + a1=arg[4]? arg[4][0] : 0; + if (res[1]!=0) res[1][0]=a1; + a1=0.; + if (res[1]!=0) res[1][1]=a1; + if (res[1]!=0) res[1][2]=a1; + if (res[1]!=0) res[1][3]=a1; + return 0; +} + +extern "C" CASADI_SYMBOL_EXPORT int adjN_fun(const casadi_real** arg, casadi_real** res, casadi_int* iw, casadi_real* w, int mem){ + return casadi_f20(arg, res, iw, w, mem); +} + +extern "C" CASADI_SYMBOL_EXPORT int adjN_fun_alloc_mem(void) { + return 0; +} + +extern "C" CASADI_SYMBOL_EXPORT int adjN_fun_init_mem(int mem) { + return 0; +} + +extern "C" CASADI_SYMBOL_EXPORT void adjN_fun_free_mem(int mem) { +} + +extern "C" CASADI_SYMBOL_EXPORT int adjN_fun_checkout(void) { + return 0; +} + +extern "C" CASADI_SYMBOL_EXPORT void adjN_fun_release(int mem) { +} + +extern "C" CASADI_SYMBOL_EXPORT void adjN_fun_incref(void) { +} + +extern "C" CASADI_SYMBOL_EXPORT void adjN_fun_decref(void) { +} + +extern "C" CASADI_SYMBOL_EXPORT casadi_int adjN_fun_n_in(void) { return 6;} + +extern "C" CASADI_SYMBOL_EXPORT casadi_int adjN_fun_n_out(void) { return 2;} + +extern "C" CASADI_SYMBOL_EXPORT casadi_real adjN_fun_default_in(casadi_int i){ + switch (i) { + default: return 0; + } +} + +extern "C" CASADI_SYMBOL_EXPORT const char* adjN_fun_name_in(casadi_int i){ + switch (i) { + case 0: return "i0"; + case 1: return "i1"; + case 2: return "i2"; + case 3: return "i3"; + case 4: return "i4"; + case 5: return "i5"; + default: return 0; + } +} + +extern "C" CASADI_SYMBOL_EXPORT const char* adjN_fun_name_out(casadi_int i){ + switch (i) { + case 0: return "o0"; + case 1: return "o1"; + default: return 0; + } +} + +extern "C" CASADI_SYMBOL_EXPORT const casadi_int* adjN_fun_sparsity_in(casadi_int i) { + switch (i) { + case 0: return casadi_s0; + case 1: return casadi_s2; + case 2: return casadi_s0; + case 3: return casadi_s0; + case 4: return casadi_s1; + case 5: return casadi_s2; + default: return 0; + } +} + +extern "C" CASADI_SYMBOL_EXPORT const casadi_int* adjN_fun_sparsity_out(casadi_int i) { + switch (i) { + case 0: return casadi_s0; + case 1: return casadi_s0; + default: return 0; + } +} + +extern "C" CASADI_SYMBOL_EXPORT int adjN_fun_work(casadi_int *sz_arg, casadi_int* sz_res, casadi_int *sz_iw, casadi_int *sz_w) { + if (sz_arg) *sz_arg = 6; + if (sz_res) *sz_res = 2; + if (sz_iw) *sz_iw = 0; + if (sz_w) *sz_w = 0; + return 0; +} + +/* adj_dG_fun:(i0[4],i1,i2[0],i3[5],i4[5],i5[4])->(o0[5],o1[5]) */ +static int casadi_f21(const casadi_real** arg, casadi_real** res, casadi_int* iw, casadi_real* w, int mem) { + casadi_real a0, a1, a10, a11, a12, a13, a14, a15, a16, a17, a18, a19, a2, a20, a21, a22, a23, a24, a25, a26, a27, a28, a29, a3, a30, a31, a32, a33, a34, a35, a36, a37, a38, a39, a4, a40, a41, a42, a43, a44, a45, a46, a47, a48, a49, a5, a50, a51, a52, a53, a54, a55, a56, a57, a58, a59, a6, a60, a61, a7, a8, a9; + a0=5.0000000000000000e-01; + a1=arg[0]? arg[0][0] : 0; + a2=arg[3]? arg[3][0] : 0; + a3=(a1-a2); + a3=(a0*a3); + a4=arg[4]? arg[4][0] : 0; + a3=(a3*a4); + a1=(a1-a2); + a4=(a4*a1); + a4=(a0*a4); + a3=(a3+a4); + if (res[0]!=0) res[0][0]=a3; + a3=arg[0]? arg[0][1] : 0; + a4=arg[3]? arg[3][1] : 0; + a1=(a3-a4); + a1=(a0*a1); + a2=arg[4]? arg[4][1] : 0; + a1=(a1*a2); + a4=(a3-a4); + a2=(a2*a4); + a2=(a0*a2); + a1=(a1+a2); + if (res[0]!=0) res[0][1]=a1; + a1=arg[0]? arg[0][2] : 0; + a2=arg[3]? arg[3][2] : 0; + a4=(a1-a2); + a4=(a0*a4); + a5=arg[4]? arg[4][2] : 0; + a4=(a4*a5); + a1=(a1-a2); + a5=(a5*a1); + a5=(a0*a5); + a4=(a4+a5); + if (res[0]!=0) res[0][2]=a4; + a4=arg[0]? arg[0][3] : 0; + a5=arg[3]? arg[3][3] : 0; + a1=(a4-a5); + a1=(a0*a1); + a2=arg[4]? arg[4][3] : 0; + a1=(a1*a2); + a5=(a4-a5); + a2=(a2*a5); + a2=(a0*a2); + a1=(a1+a2); + if (res[0]!=0) res[0][3]=a1; + a1=arg[1]? arg[1][0] : 0; + a2=arg[3]? arg[3][4] : 0; + a5=(a1-a2); + a6=arg[4]? arg[4][4] : 0; + a7=(a0*a6); + a5=(a5*a7); + a2=(a1-a2); + a0=(a0*a2); + a0=(a0*a6); + a5=(a5+a0); + if (res[0]!=0) res[0][4]=a5; + a5=arg[5]? arg[5][0] : 0; + if (res[1]!=0) res[1][0]=a5; + a0=5.0000000000000003e-02; + a6=2.5000000000000001e-02; + a2=-8.0000000000000016e-02; + a7=(a6*a4); + a7=(a3+a7); + a8=cos(a7); + a8=(a2*a8); + a9=sin(a7); + a10=(a8*a9); + a11=cos(a3); + a11=(a2*a11); + a12=sin(a3); + a13=(a11*a12); + a14=casadi_sq(a4); + a15=(a13*a14); + a16=cos(a3); + a17=(a1*a16); + a15=(a15+a17); + a17=1.0791000000000002e+01; + a18=sin(a3); + a18=(a17*a18); + a15=(a15+a18); + a18=8.0000000000000004e-01; + a19=1.1000000000000001e+00; + a20=1.0000000000000001e-01; + a21=cos(a3); + a22=casadi_sq(a21); + a22=(a20*a22); + a22=(a19-a22); + a23=(a18*a22); + a15=(a15/a23); + a24=(a6*a15); + a24=(a4+a24); + a25=casadi_sq(a24); + a26=(a10*a25); + a27=cos(a7); + a28=(a1*a27); + a26=(a26+a28); + a28=sin(a7); + a28=(a17*a28); + a26=(a26+a28); + a28=cos(a7); + a29=casadi_sq(a28); + a29=(a20*a29); + a29=(a19-a29); + a30=(a18*a29); + a26=(a26/a30); + a31=(a6*a26); + a31=(a4+a31); + a32=(a0*a31); + a32=(a3+a32); + a33=cos(a32); + a34=8.3333333333333332e-03; + a35=arg[5]? arg[5][3] : 0; + a36=(a34*a35); + a37=cos(a32); + a38=casadi_sq(a37); + a38=(a20*a38); + a38=(a19-a38); + a39=(a18*a38); + a40=(a36/a39); + a41=(a17*a40); + a33=(a33*a41); + a41=sin(a32); + a42=(a1*a40); + a41=(a41*a42); + a33=(a33-a41); + a41=cos(a32); + a42=cos(a32); + a42=(a2*a42); + a43=(a6*a24); + a43=(a3+a43); + a44=cos(a43); + a44=(a2*a44); + a45=sin(a43); + a46=(a44*a45); + a47=casadi_sq(a31); + a48=(a46*a47); + a49=cos(a43); + a50=(a1*a49); + a48=(a48+a50); + a50=sin(a43); + a50=(a17*a50); + a48=(a48+a50); + a50=cos(a43); + a51=casadi_sq(a50); + a51=(a20*a51); + a19=(a19-a51); + a51=(a18*a19); + a48=(a48/a51); + a52=(a0*a48); + a52=(a4+a52); + a53=casadi_sq(a52); + a54=(a53*a40); + a55=(a42*a54); + a41=(a41*a55); + a33=(a33+a41); + a41=sin(a32); + a55=sin(a32); + a54=(a55*a54); + a54=(a2*a54); + a41=(a41*a54); + a33=(a33-a41); + a41=sin(a32); + a37=(a37+a37); + a42=(a42*a55); + a53=(a42*a53); + a55=cos(a32); + a54=(a1*a55); + a53=(a53+a54); + a54=sin(a32); + a54=(a17*a54); + a53=(a53+a54); + a53=(a53/a39); + a53=(a53/a39); + a53=(a53*a36); + a53=(a18*a53); + a39=sin(a32); + a39=(a2*a39); + a54=casadi_sq(a52); + a56=(a39*a54); + a57=9.8100000000000009e-01; + a58=cos(a32); + a58=(a57*a58); + a59=sin(a32); + a60=(a58*a59); + a56=(a56+a60); + a56=(a56+a1); + a56=(a56/a38); + a56=(a56/a38); + a60=arg[5]? arg[5][2] : 0; + a61=(a34*a60); + a56=(a56*a61); + a53=(a53+a56); + a53=(a20*a53); + a37=(a37*a53); + a41=(a41*a37); + a33=(a33-a41); + a41=cos(a32); + a38=(a61/a38); + a58=(a58*a38); + a41=(a41*a58); + a33=(a33+a41); + a41=sin(a32); + a59=(a59*a38); + a59=(a57*a59); + a41=(a41*a59); + a33=(a33-a41); + a32=cos(a32); + a54=(a54*a38); + a54=(a2*a54); + a32=(a32*a54); + a33=(a33+a32); + a32=arg[5]? arg[5][1] : 0; + a54=(a33+a32); + a41=cos(a43); + a59=2.; + a58=(a59*a36); + a37=(a52+a52); + a42=(a42*a40); + a37=(a37*a42); + a52=(a52+a52); + a39=(a39*a38); + a52=(a52*a39); + a37=(a37+a52); + a32=(a34*a32); + a37=(a37+a32); + a52=(a0*a37); + a58=(a58+a52); + a52=(a58/a51); + a39=(a17*a52); + a41=(a41*a39); + a39=sin(a43); + a42=(a1*a52); + a39=(a39*a42); + a41=(a41-a39); + a39=cos(a43); + a47=(a47*a52); + a44=(a44*a47); + a39=(a39*a44); + a41=(a41+a39); + a39=sin(a43); + a45=(a45*a47); + a45=(a2*a45); + a39=(a39*a45); + a41=(a41-a39); + a39=sin(a43); + a50=(a50+a50); + a48=(a48/a51); + a48=(a48*a58); + a48=(a18*a48); + a58=sin(a43); + a58=(a2*a58); + a51=casadi_sq(a31); + a45=(a58*a51); + a47=cos(a43); + a47=(a57*a47); + a44=sin(a43); + a42=(a47*a44); + a45=(a45+a42); + a45=(a45+a1); + a45=(a45/a19); + a45=(a45/a19); + a42=(a59*a61); + a34=(a34*a5); + a5=(a0*a34); + a42=(a42+a5); + a45=(a45*a42); + a48=(a48+a45); + a48=(a20*a48); + a50=(a50*a48); + a39=(a39*a50); + a41=(a41-a39); + a39=cos(a43); + a42=(a42/a19); + a47=(a47*a42); + a39=(a39*a47); + a41=(a41+a39); + a39=sin(a43); + a44=(a44*a42); + a44=(a57*a44); + a39=(a39*a44); + a41=(a41-a39); + a43=cos(a43); + a51=(a51*a42); + a51=(a2*a51); + a43=(a43*a51); + a41=(a41+a43); + a54=(a54+a41); + a43=cos(a3); + a51=(a59*a32); + a39=(a24+a24); + a44=(a59*a36); + a0=(a0*a33); + a33=(a31+a31); + a46=(a46*a52); + a33=(a33*a46); + a0=(a0+a33); + a33=(a59*a32); + a0=(a0+a33); + a31=(a31+a31); + a58=(a58*a42); + a31=(a31*a58); + a0=(a0+a31); + a31=(a6*a0); + a44=(a44+a31); + a31=(a44/a30); + a10=(a10*a31); + a39=(a39*a10); + a51=(a51+a39); + a41=(a6*a41); + a51=(a51+a41); + a41=(a24+a24); + a39=sin(a7); + a39=(a2*a39); + a10=(a59*a61); + a58=(a59*a34); + a33=(a6*a58); + a10=(a10+a33); + a33=(a10/a29); + a46=(a39*a33); + a41=(a41*a46); + a51=(a51+a41); + a41=(a6*a51); + a36=(a36+a41); + a41=(a36/a23); + a46=(a17*a41); + a43=(a43*a46); + a54=(a54+a43); + a43=sin(a3); + a46=(a1*a41); + a43=(a43*a46); + a54=(a54-a43); + a43=cos(a3); + a14=(a14*a41); + a11=(a11*a14); + a43=(a43*a11); + a54=(a54+a43); + a43=sin(a3); + a12=(a12*a14); + a12=(a2*a12); + a43=(a43*a12); + a54=(a54-a43); + a43=cos(a7); + a17=(a17*a31); + a43=(a43*a17); + a17=sin(a7); + a12=(a1*a31); + a17=(a17*a12); + a43=(a43-a17); + a17=cos(a7); + a25=(a25*a31); + a8=(a8*a25); + a17=(a17*a8); + a43=(a43+a17); + a17=sin(a7); + a9=(a9*a25); + a9=(a2*a9); + a17=(a17*a9); + a43=(a43-a17); + a17=sin(a7); + a28=(a28+a28); + a26=(a26/a30); + a26=(a26*a44); + a26=(a18*a26); + a24=casadi_sq(a24); + a39=(a39*a24); + a44=cos(a7); + a44=(a57*a44); + a30=sin(a7); + a9=(a44*a30); + a39=(a39+a9); + a39=(a39+a1); + a39=(a39/a29); + a39=(a39/a29); + a39=(a39*a10); + a26=(a26+a39); + a26=(a20*a26); + a28=(a28*a26); + a17=(a17*a28); + a43=(a43-a17); + a17=cos(a7); + a44=(a44*a33); + a17=(a17*a44); + a43=(a43+a17); + a17=sin(a7); + a30=(a30*a33); + a30=(a57*a30); + a17=(a17*a30); + a43=(a43-a17); + a7=cos(a7); + a24=(a24*a33); + a24=(a2*a24); + a7=(a7*a24); + a43=(a43+a7); + a54=(a54+a43); + a7=sin(a3); + a21=(a21+a21); + a15=(a15/a23); + a15=(a15*a36); + a18=(a18*a15); + a15=sin(a3); + a15=(a2*a15); + a36=casadi_sq(a4); + a23=(a15*a36); + a24=cos(a3); + a24=(a57*a24); + a17=sin(a3); + a30=(a24*a17); + a23=(a23+a30); + a23=(a23+a1); + a23=(a23/a22); + a23=(a23/a22); + a59=(a59*a34); + a1=(a6*a59); + a61=(a61+a1); + a23=(a23*a61); + a18=(a18+a23); + a20=(a20*a18); + a21=(a21*a20); + a7=(a7*a21); + a54=(a54-a7); + a7=cos(a3); + a61=(a61/a22); + a24=(a24*a61); + a7=(a7*a24); + a54=(a54+a7); + a7=sin(a3); + a17=(a17*a61); + a57=(a57*a17); + a7=(a7*a57); + a54=(a54-a7); + a3=cos(a3); + a36=(a36*a61); + a2=(a2*a36); + a3=(a3*a2); + a54=(a54+a3); + if (res[1]!=0) res[1][1]=a54; + a60=(a60+a34); + a60=(a60+a58); + a60=(a60+a34); + a60=(a60+a59); + if (res[1]!=0) res[1][2]=a60; + a35=(a35+a37); + a35=(a35+a32); + a35=(a35+a0); + a35=(a35+a51); + a51=(a4+a4); + a13=(a13*a41); + a51=(a51*a13); + a35=(a35+a51); + a6=(a6*a43); + a35=(a35+a6); + a4=(a4+a4); + a15=(a15*a61); + a4=(a4*a15); + a35=(a35+a4); + if (res[1]!=0) res[1][3]=a35; + a55=(a55*a40); + a55=(a55+a38); + a49=(a49*a52); + a55=(a55+a49); + a55=(a55+a42); + a27=(a27*a31); + a55=(a55+a27); + a55=(a55+a33); + a16=(a16*a41); + a55=(a55+a16); + a55=(a55+a61); + if (res[1]!=0) res[1][4]=a55; + return 0; +} + +extern "C" CASADI_SYMBOL_EXPORT int adj_dG_fun(const casadi_real** arg, casadi_real** res, casadi_int* iw, casadi_real* w, int mem){ + return casadi_f21(arg, res, iw, w, mem); +} + +extern "C" CASADI_SYMBOL_EXPORT int adj_dG_fun_alloc_mem(void) { + return 0; +} + +extern "C" CASADI_SYMBOL_EXPORT int adj_dG_fun_init_mem(int mem) { + return 0; +} + +extern "C" CASADI_SYMBOL_EXPORT void adj_dG_fun_free_mem(int mem) { +} + +extern "C" CASADI_SYMBOL_EXPORT int adj_dG_fun_checkout(void) { + return 0; +} + +extern "C" CASADI_SYMBOL_EXPORT void adj_dG_fun_release(int mem) { +} + +extern "C" CASADI_SYMBOL_EXPORT void adj_dG_fun_incref(void) { +} + +extern "C" CASADI_SYMBOL_EXPORT void adj_dG_fun_decref(void) { +} + +extern "C" CASADI_SYMBOL_EXPORT casadi_int adj_dG_fun_n_in(void) { return 6;} + +extern "C" CASADI_SYMBOL_EXPORT casadi_int adj_dG_fun_n_out(void) { return 2;} + +extern "C" CASADI_SYMBOL_EXPORT casadi_real adj_dG_fun_default_in(casadi_int i){ + switch (i) { + default: return 0; + } +} + +extern "C" CASADI_SYMBOL_EXPORT const char* adj_dG_fun_name_in(casadi_int i){ + switch (i) { + case 0: return "i0"; + case 1: return "i1"; + case 2: return "i2"; + case 3: return "i3"; + case 4: return "i4"; + case 5: return "i5"; + default: return 0; + } +} + +extern "C" CASADI_SYMBOL_EXPORT const char* adj_dG_fun_name_out(casadi_int i){ + switch (i) { + case 0: return "o0"; + case 1: return "o1"; + default: return 0; + } +} + +extern "C" CASADI_SYMBOL_EXPORT const casadi_int* adj_dG_fun_sparsity_in(casadi_int i) { + switch (i) { + case 0: return casadi_s0; + case 1: return casadi_s1; + case 2: return casadi_s2; + case 3: return casadi_s4; + case 4: return casadi_s4; + case 5: return casadi_s0; + default: return 0; + } +} + +extern "C" CASADI_SYMBOL_EXPORT const casadi_int* adj_dG_fun_sparsity_out(casadi_int i) { + switch (i) { + case 0: return casadi_s4; + case 1: return casadi_s4; + default: return 0; + } +} + +extern "C" CASADI_SYMBOL_EXPORT int adj_dG_fun_work(casadi_int *sz_arg, casadi_int* sz_res, casadi_int *sz_iw, casadi_int *sz_w) { + if (sz_arg) *sz_arg = 6; + if (sz_res) *sz_res = 2; + if (sz_iw) *sz_iw = 0; + if (sz_w) *sz_w = 0; + return 0; +} + + diff --git a/model/casadi_src.h b/model/casadi_src.h index d38005e..970fa9c 100644 --- a/model/casadi_src.h +++ b/model/casadi_src.h @@ -1,233 +1,362 @@ -/* This file was automatically generated by CasADi. - The CasADi copyright holders make no ownership claim of its contents. */ -#ifdef __cplusplus -extern "C" { -#endif - -#ifndef casadi_real -#define casadi_real double -#endif - -int f_fun(const casadi_real** arg, casadi_real** res, int* iw, casadi_real* w, void* mem); -void f_fun_incref(void); -void f_fun_decref(void); -int f_fun_n_out(void); -int f_fun_n_in(void); -const char* f_fun_name_in(int i); -const char* f_fun_name_out(int i); -const int* f_fun_sparsity_in(int i); -const int* f_fun_sparsity_out(int i); -int f_fun_work(int *sz_arg, int* sz_res, int *sz_iw, int *sz_w); -int vdeFun(const casadi_real** arg, casadi_real** res, int* iw, casadi_real* w, void* mem); -void vdeFun_incref(void); -void vdeFun_decref(void); -int vdeFun_n_out(void); -int vdeFun_n_in(void); -const char* vdeFun_name_in(int i); -const char* vdeFun_name_out(int i); -const int* vdeFun_sparsity_in(int i); -const int* vdeFun_sparsity_out(int i); -int vdeFun_work(int *sz_arg, int* sz_res, int *sz_iw, int *sz_w); -int impl_f_fun(const casadi_real** arg, casadi_real** res, int* iw, casadi_real* w, void* mem); -void impl_f_fun_incref(void); -void impl_f_fun_decref(void); -int impl_f_fun_n_out(void); -int impl_f_fun_n_in(void); -const char* impl_f_fun_name_in(int i); -const char* impl_f_fun_name_out(int i); -const int* impl_f_fun_sparsity_in(int i); -const int* impl_f_fun_sparsity_out(int i); -int impl_f_fun_work(int *sz_arg, int* sz_res, int *sz_iw, int *sz_w); -int impl_jac_x_fun(const casadi_real** arg, casadi_real** res, int* iw, casadi_real* w, void* mem); -void impl_jac_x_fun_incref(void); -void impl_jac_x_fun_decref(void); -int impl_jac_x_fun_n_out(void); -int impl_jac_x_fun_n_in(void); -const char* impl_jac_x_fun_name_in(int i); -const char* impl_jac_x_fun_name_out(int i); -const int* impl_jac_x_fun_sparsity_in(int i); -const int* impl_jac_x_fun_sparsity_out(int i); -int impl_jac_x_fun_work(int *sz_arg, int* sz_res, int *sz_iw, int *sz_w); -int impl_jac_u_fun(const casadi_real** arg, casadi_real** res, int* iw, casadi_real* w, void* mem); -void impl_jac_u_fun_incref(void); -void impl_jac_u_fun_decref(void); -int impl_jac_u_fun_n_out(void); -int impl_jac_u_fun_n_in(void); -const char* impl_jac_u_fun_name_in(int i); -const char* impl_jac_u_fun_name_out(int i); -const int* impl_jac_u_fun_sparsity_in(int i); -const int* impl_jac_u_fun_sparsity_out(int i); -int impl_jac_u_fun_work(int *sz_arg, int* sz_res, int *sz_iw, int *sz_w); -int impl_jac_xdot_fun(const casadi_real** arg, casadi_real** res, int* iw, casadi_real* w, void* mem); -void impl_jac_xdot_fun_incref(void); -void impl_jac_xdot_fun_decref(void); -int impl_jac_xdot_fun_n_out(void); -int impl_jac_xdot_fun_n_in(void); -const char* impl_jac_xdot_fun_name_in(int i); -const char* impl_jac_xdot_fun_name_out(int i); -const int* impl_jac_xdot_fun_sparsity_in(int i); -const int* impl_jac_xdot_fun_sparsity_out(int i); -int impl_jac_xdot_fun_work(int *sz_arg, int* sz_res, int *sz_iw, int *sz_w); -int F(const casadi_real** arg, casadi_real** res, int* iw, casadi_real* w, void* mem); -void F_incref(void); -void F_decref(void); -int F_n_out(void); -int F_n_in(void); -const char* F_name_in(int i); -const char* F_name_out(int i); -const int* F_sparsity_in(int i); -const int* F_sparsity_out(int i); -int F_work(int *sz_arg, int* sz_res, int *sz_iw, int *sz_w); -int D(const casadi_real** arg, casadi_real** res, int* iw, casadi_real* w, void* mem); -void D_incref(void); -void D_decref(void); -int D_n_out(void); -int D_n_in(void); -const char* D_name_in(int i); -const char* D_name_out(int i); -const int* D_sparsity_in(int i); -const int* D_sparsity_out(int i); -int D_work(int *sz_arg, int* sz_res, int *sz_iw, int *sz_w); -int h_fun(const casadi_real** arg, casadi_real** res, int* iw, casadi_real* w, void* mem); -void h_fun_incref(void); -void h_fun_decref(void); -int h_fun_n_out(void); -int h_fun_n_in(void); -const char* h_fun_name_in(int i); -const char* h_fun_name_out(int i); -const int* h_fun_sparsity_in(int i); -const int* h_fun_sparsity_out(int i); -int h_fun_work(int *sz_arg, int* sz_res, int *sz_iw, int *sz_w); -int path_con_fun(const casadi_real** arg, casadi_real** res, int* iw, casadi_real* w, void* mem); -void path_con_fun_incref(void); -void path_con_fun_decref(void); -int path_con_fun_n_out(void); -int path_con_fun_n_in(void); -const char* path_con_fun_name_in(int i); -const char* path_con_fun_name_out(int i); -const int* path_con_fun_sparsity_in(int i); -const int* path_con_fun_sparsity_out(int i); -int path_con_fun_work(int *sz_arg, int* sz_res, int *sz_iw, int *sz_w); -int path_con_N_fun(const casadi_real** arg, casadi_real** res, int* iw, casadi_real* w, void* mem); -void path_con_N_fun_incref(void); -void path_con_N_fun_decref(void); -int path_con_N_fun_n_out(void); -int path_con_N_fun_n_in(void); -const char* path_con_N_fun_name_in(int i); -const char* path_con_N_fun_name_out(int i); -const int* path_con_N_fun_sparsity_in(int i); -const int* path_con_N_fun_sparsity_out(int i); -int path_con_N_fun_work(int *sz_arg, int* sz_res, int *sz_iw, int *sz_w); -int obji_fun(const casadi_real** arg, casadi_real** res, int* iw, casadi_real* w, void* mem); -void obji_fun_incref(void); -void obji_fun_decref(void); -int obji_fun_n_out(void); -int obji_fun_n_in(void); -const char* obji_fun_name_in(int i); -const char* obji_fun_name_out(int i); -const int* obji_fun_sparsity_in(int i); -const int* obji_fun_sparsity_out(int i); -int obji_fun_work(int *sz_arg, int* sz_res, int *sz_iw, int *sz_w); -int objN_fun(const casadi_real** arg, casadi_real** res, int* iw, casadi_real* w, void* mem); -void objN_fun_incref(void); -void objN_fun_decref(void); -int objN_fun_n_out(void); -int objN_fun_n_in(void); -const char* objN_fun_name_in(int i); -const char* objN_fun_name_out(int i); -const int* objN_fun_sparsity_in(int i); -const int* objN_fun_sparsity_out(int i); -int objN_fun_work(int *sz_arg, int* sz_res, int *sz_iw, int *sz_w); -int gi_fun(const casadi_real** arg, casadi_real** res, int* iw, casadi_real* w, void* mem); -void gi_fun_incref(void); -void gi_fun_decref(void); -int gi_fun_n_out(void); -int gi_fun_n_in(void); -const char* gi_fun_name_in(int i); -const char* gi_fun_name_out(int i); -const int* gi_fun_sparsity_in(int i); -const int* gi_fun_sparsity_out(int i); -int gi_fun_work(int *sz_arg, int* sz_res, int *sz_iw, int *sz_w); -int gN_fun(const casadi_real** arg, casadi_real** res, int* iw, casadi_real* w, void* mem); -void gN_fun_incref(void); -void gN_fun_decref(void); -int gN_fun_n_out(void); -int gN_fun_n_in(void); -const char* gN_fun_name_in(int i); -const char* gN_fun_name_out(int i); -const int* gN_fun_sparsity_in(int i); -const int* gN_fun_sparsity_out(int i); -int gN_fun_work(int *sz_arg, int* sz_res, int *sz_iw, int *sz_w); -int Hi_fun(const casadi_real** arg, casadi_real** res, int* iw, casadi_real* w, void* mem); -void Hi_fun_incref(void); -void Hi_fun_decref(void); -int Hi_fun_n_out(void); -int Hi_fun_n_in(void); -const char* Hi_fun_name_in(int i); -const char* Hi_fun_name_out(int i); -const int* Hi_fun_sparsity_in(int i); -const int* Hi_fun_sparsity_out(int i); -int Hi_fun_work(int *sz_arg, int* sz_res, int *sz_iw, int *sz_w); -int HN_fun(const casadi_real** arg, casadi_real** res, int* iw, casadi_real* w, void* mem); -void HN_fun_incref(void); -void HN_fun_decref(void); -int HN_fun_n_out(void); -int HN_fun_n_in(void); -const char* HN_fun_name_in(int i); -const char* HN_fun_name_out(int i); -const int* HN_fun_sparsity_in(int i); -const int* HN_fun_sparsity_out(int i); -int HN_fun_work(int *sz_arg, int* sz_res, int *sz_iw, int *sz_w); -int Ci_fun(const casadi_real** arg, casadi_real** res, int* iw, casadi_real* w, void* mem); -void Ci_fun_incref(void); -void Ci_fun_decref(void); -int Ci_fun_n_out(void); -int Ci_fun_n_in(void); -const char* Ci_fun_name_in(int i); -const char* Ci_fun_name_out(int i); -const int* Ci_fun_sparsity_in(int i); -const int* Ci_fun_sparsity_out(int i); -int Ci_fun_work(int *sz_arg, int* sz_res, int *sz_iw, int *sz_w); -int CN_fun(const casadi_real** arg, casadi_real** res, int* iw, casadi_real* w, void* mem); -void CN_fun_incref(void); -void CN_fun_decref(void); -int CN_fun_n_out(void); -int CN_fun_n_in(void); -const char* CN_fun_name_in(int i); -const char* CN_fun_name_out(int i); -const int* CN_fun_sparsity_in(int i); -const int* CN_fun_sparsity_out(int i); -int CN_fun_work(int *sz_arg, int* sz_res, int *sz_iw, int *sz_w); -int adj_fun(const casadi_real** arg, casadi_real** res, int* iw, casadi_real* w, void* mem); -void adj_fun_incref(void); -void adj_fun_decref(void); -int adj_fun_n_out(void); -int adj_fun_n_in(void); -const char* adj_fun_name_in(int i); -const char* adj_fun_name_out(int i); -const int* adj_fun_sparsity_in(int i); -const int* adj_fun_sparsity_out(int i); -int adj_fun_work(int *sz_arg, int* sz_res, int *sz_iw, int *sz_w); -int adjN_fun(const casadi_real** arg, casadi_real** res, int* iw, casadi_real* w, void* mem); -void adjN_fun_incref(void); -void adjN_fun_decref(void); -int adjN_fun_n_out(void); -int adjN_fun_n_in(void); -const char* adjN_fun_name_in(int i); -const char* adjN_fun_name_out(int i); -const int* adjN_fun_sparsity_in(int i); -const int* adjN_fun_sparsity_out(int i); -int adjN_fun_work(int *sz_arg, int* sz_res, int *sz_iw, int *sz_w); -int adj_dG_fun(const casadi_real** arg, casadi_real** res, int* iw, casadi_real* w, void* mem); -void adj_dG_fun_incref(void); -void adj_dG_fun_decref(void); -int adj_dG_fun_n_out(void); -int adj_dG_fun_n_in(void); -const char* adj_dG_fun_name_in(int i); -const char* adj_dG_fun_name_out(int i); -const int* adj_dG_fun_sparsity_in(int i); -const int* adj_dG_fun_sparsity_out(int i); -int adj_dG_fun_work(int *sz_arg, int* sz_res, int *sz_iw, int *sz_w); -#ifdef __cplusplus -} /* extern "C" */ -#endif +/* This file was automatically generated by CasADi. + The CasADi copyright holders make no ownership claim of its contents. */ +#ifndef casadi_real +#define casadi_real double +#endif + +#ifndef casadi_int +#define casadi_int long long int +#endif + +extern "C" int f_fun(const casadi_real** arg, casadi_real** res, casadi_int* iw, casadi_real* w, int mem); +extern "C" int f_fun_alloc_mem(void); +extern "C" int f_fun_init_mem(int mem); +extern "C" void f_fun_free_mem(int mem); +extern "C" int f_fun_checkout(void); +extern "C" void f_fun_release(int mem); +extern "C" void f_fun_incref(void); +extern "C" void f_fun_decref(void); +extern "C" casadi_int f_fun_n_out(void); +extern "C" casadi_int f_fun_n_in(void); +extern "C" casadi_real f_fun_default_in(casadi_int i); +extern "C" const char* f_fun_name_in(casadi_int i); +extern "C" const char* f_fun_name_out(casadi_int i); +extern "C" const casadi_int* f_fun_sparsity_in(casadi_int i); +extern "C" const casadi_int* f_fun_sparsity_out(casadi_int i); +extern "C" int f_fun_work(casadi_int *sz_arg, casadi_int* sz_res, casadi_int *sz_iw, casadi_int *sz_w); +extern "C" int vdeFun(const casadi_real** arg, casadi_real** res, casadi_int* iw, casadi_real* w, int mem); +extern "C" int vdeFun_alloc_mem(void); +extern "C" int vdeFun_init_mem(int mem); +extern "C" void vdeFun_free_mem(int mem); +extern "C" int vdeFun_checkout(void); +extern "C" void vdeFun_release(int mem); +extern "C" void vdeFun_incref(void); +extern "C" void vdeFun_decref(void); +extern "C" casadi_int vdeFun_n_out(void); +extern "C" casadi_int vdeFun_n_in(void); +extern "C" casadi_real vdeFun_default_in(casadi_int i); +extern "C" const char* vdeFun_name_in(casadi_int i); +extern "C" const char* vdeFun_name_out(casadi_int i); +extern "C" const casadi_int* vdeFun_sparsity_in(casadi_int i); +extern "C" const casadi_int* vdeFun_sparsity_out(casadi_int i); +extern "C" int vdeFun_work(casadi_int *sz_arg, casadi_int* sz_res, casadi_int *sz_iw, casadi_int *sz_w); +extern "C" int impl_f_fun(const casadi_real** arg, casadi_real** res, casadi_int* iw, casadi_real* w, int mem); +extern "C" int impl_f_fun_alloc_mem(void); +extern "C" int impl_f_fun_init_mem(int mem); +extern "C" void impl_f_fun_free_mem(int mem); +extern "C" int impl_f_fun_checkout(void); +extern "C" void impl_f_fun_release(int mem); +extern "C" void impl_f_fun_incref(void); +extern "C" void impl_f_fun_decref(void); +extern "C" casadi_int impl_f_fun_n_out(void); +extern "C" casadi_int impl_f_fun_n_in(void); +extern "C" casadi_real impl_f_fun_default_in(casadi_int i); +extern "C" const char* impl_f_fun_name_in(casadi_int i); +extern "C" const char* impl_f_fun_name_out(casadi_int i); +extern "C" const casadi_int* impl_f_fun_sparsity_in(casadi_int i); +extern "C" const casadi_int* impl_f_fun_sparsity_out(casadi_int i); +extern "C" int impl_f_fun_work(casadi_int *sz_arg, casadi_int* sz_res, casadi_int *sz_iw, casadi_int *sz_w); +extern "C" int impl_jac_x_fun(const casadi_real** arg, casadi_real** res, casadi_int* iw, casadi_real* w, int mem); +extern "C" int impl_jac_x_fun_alloc_mem(void); +extern "C" int impl_jac_x_fun_init_mem(int mem); +extern "C" void impl_jac_x_fun_free_mem(int mem); +extern "C" int impl_jac_x_fun_checkout(void); +extern "C" void impl_jac_x_fun_release(int mem); +extern "C" void impl_jac_x_fun_incref(void); +extern "C" void impl_jac_x_fun_decref(void); +extern "C" casadi_int impl_jac_x_fun_n_out(void); +extern "C" casadi_int impl_jac_x_fun_n_in(void); +extern "C" casadi_real impl_jac_x_fun_default_in(casadi_int i); +extern "C" const char* impl_jac_x_fun_name_in(casadi_int i); +extern "C" const char* impl_jac_x_fun_name_out(casadi_int i); +extern "C" const casadi_int* impl_jac_x_fun_sparsity_in(casadi_int i); +extern "C" const casadi_int* impl_jac_x_fun_sparsity_out(casadi_int i); +extern "C" int impl_jac_x_fun_work(casadi_int *sz_arg, casadi_int* sz_res, casadi_int *sz_iw, casadi_int *sz_w); +extern "C" int impl_jac_u_fun(const casadi_real** arg, casadi_real** res, casadi_int* iw, casadi_real* w, int mem); +extern "C" int impl_jac_u_fun_alloc_mem(void); +extern "C" int impl_jac_u_fun_init_mem(int mem); +extern "C" void impl_jac_u_fun_free_mem(int mem); +extern "C" int impl_jac_u_fun_checkout(void); +extern "C" void impl_jac_u_fun_release(int mem); +extern "C" void impl_jac_u_fun_incref(void); +extern "C" void impl_jac_u_fun_decref(void); +extern "C" casadi_int impl_jac_u_fun_n_out(void); +extern "C" casadi_int impl_jac_u_fun_n_in(void); +extern "C" casadi_real impl_jac_u_fun_default_in(casadi_int i); +extern "C" const char* impl_jac_u_fun_name_in(casadi_int i); +extern "C" const char* impl_jac_u_fun_name_out(casadi_int i); +extern "C" const casadi_int* impl_jac_u_fun_sparsity_in(casadi_int i); +extern "C" const casadi_int* impl_jac_u_fun_sparsity_out(casadi_int i); +extern "C" int impl_jac_u_fun_work(casadi_int *sz_arg, casadi_int* sz_res, casadi_int *sz_iw, casadi_int *sz_w); +extern "C" int impl_jac_xdot_fun(const casadi_real** arg, casadi_real** res, casadi_int* iw, casadi_real* w, int mem); +extern "C" int impl_jac_xdot_fun_alloc_mem(void); +extern "C" int impl_jac_xdot_fun_init_mem(int mem); +extern "C" void impl_jac_xdot_fun_free_mem(int mem); +extern "C" int impl_jac_xdot_fun_checkout(void); +extern "C" void impl_jac_xdot_fun_release(int mem); +extern "C" void impl_jac_xdot_fun_incref(void); +extern "C" void impl_jac_xdot_fun_decref(void); +extern "C" casadi_int impl_jac_xdot_fun_n_out(void); +extern "C" casadi_int impl_jac_xdot_fun_n_in(void); +extern "C" casadi_real impl_jac_xdot_fun_default_in(casadi_int i); +extern "C" const char* impl_jac_xdot_fun_name_in(casadi_int i); +extern "C" const char* impl_jac_xdot_fun_name_out(casadi_int i); +extern "C" const casadi_int* impl_jac_xdot_fun_sparsity_in(casadi_int i); +extern "C" const casadi_int* impl_jac_xdot_fun_sparsity_out(casadi_int i); +extern "C" int impl_jac_xdot_fun_work(casadi_int *sz_arg, casadi_int* sz_res, casadi_int *sz_iw, casadi_int *sz_w); +extern "C" int F(const casadi_real** arg, casadi_real** res, casadi_int* iw, casadi_real* w, int mem); +extern "C" int F_alloc_mem(void); +extern "C" int F_init_mem(int mem); +extern "C" void F_free_mem(int mem); +extern "C" int F_checkout(void); +extern "C" void F_release(int mem); +extern "C" void F_incref(void); +extern "C" void F_decref(void); +extern "C" casadi_int F_n_out(void); +extern "C" casadi_int F_n_in(void); +extern "C" casadi_real F_default_in(casadi_int i); +extern "C" const char* F_name_in(casadi_int i); +extern "C" const char* F_name_out(casadi_int i); +extern "C" const casadi_int* F_sparsity_in(casadi_int i); +extern "C" const casadi_int* F_sparsity_out(casadi_int i); +extern "C" int F_work(casadi_int *sz_arg, casadi_int* sz_res, casadi_int *sz_iw, casadi_int *sz_w); +extern "C" int D(const casadi_real** arg, casadi_real** res, casadi_int* iw, casadi_real* w, int mem); +extern "C" int D_alloc_mem(void); +extern "C" int D_init_mem(int mem); +extern "C" void D_free_mem(int mem); +extern "C" int D_checkout(void); +extern "C" void D_release(int mem); +extern "C" void D_incref(void); +extern "C" void D_decref(void); +extern "C" casadi_int D_n_out(void); +extern "C" casadi_int D_n_in(void); +extern "C" casadi_real D_default_in(casadi_int i); +extern "C" const char* D_name_in(casadi_int i); +extern "C" const char* D_name_out(casadi_int i); +extern "C" const casadi_int* D_sparsity_in(casadi_int i); +extern "C" const casadi_int* D_sparsity_out(casadi_int i); +extern "C" int D_work(casadi_int *sz_arg, casadi_int* sz_res, casadi_int *sz_iw, casadi_int *sz_w); +extern "C" int h_fun(const casadi_real** arg, casadi_real** res, casadi_int* iw, casadi_real* w, int mem); +extern "C" int h_fun_alloc_mem(void); +extern "C" int h_fun_init_mem(int mem); +extern "C" void h_fun_free_mem(int mem); +extern "C" int h_fun_checkout(void); +extern "C" void h_fun_release(int mem); +extern "C" void h_fun_incref(void); +extern "C" void h_fun_decref(void); +extern "C" casadi_int h_fun_n_out(void); +extern "C" casadi_int h_fun_n_in(void); +extern "C" casadi_real h_fun_default_in(casadi_int i); +extern "C" const char* h_fun_name_in(casadi_int i); +extern "C" const char* h_fun_name_out(casadi_int i); +extern "C" const casadi_int* h_fun_sparsity_in(casadi_int i); +extern "C" const casadi_int* h_fun_sparsity_out(casadi_int i); +extern "C" int h_fun_work(casadi_int *sz_arg, casadi_int* sz_res, casadi_int *sz_iw, casadi_int *sz_w); +extern "C" int path_con_fun(const casadi_real** arg, casadi_real** res, casadi_int* iw, casadi_real* w, int mem); +extern "C" int path_con_fun_alloc_mem(void); +extern "C" int path_con_fun_init_mem(int mem); +extern "C" void path_con_fun_free_mem(int mem); +extern "C" int path_con_fun_checkout(void); +extern "C" void path_con_fun_release(int mem); +extern "C" void path_con_fun_incref(void); +extern "C" void path_con_fun_decref(void); +extern "C" casadi_int path_con_fun_n_out(void); +extern "C" casadi_int path_con_fun_n_in(void); +extern "C" casadi_real path_con_fun_default_in(casadi_int i); +extern "C" const char* path_con_fun_name_in(casadi_int i); +extern "C" const char* path_con_fun_name_out(casadi_int i); +extern "C" const casadi_int* path_con_fun_sparsity_in(casadi_int i); +extern "C" const casadi_int* path_con_fun_sparsity_out(casadi_int i); +extern "C" int path_con_fun_work(casadi_int *sz_arg, casadi_int* sz_res, casadi_int *sz_iw, casadi_int *sz_w); +extern "C" int path_con_N_fun(const casadi_real** arg, casadi_real** res, casadi_int* iw, casadi_real* w, int mem); +extern "C" int path_con_N_fun_alloc_mem(void); +extern "C" int path_con_N_fun_init_mem(int mem); +extern "C" void path_con_N_fun_free_mem(int mem); +extern "C" int path_con_N_fun_checkout(void); +extern "C" void path_con_N_fun_release(int mem); +extern "C" void path_con_N_fun_incref(void); +extern "C" void path_con_N_fun_decref(void); +extern "C" casadi_int path_con_N_fun_n_out(void); +extern "C" casadi_int path_con_N_fun_n_in(void); +extern "C" casadi_real path_con_N_fun_default_in(casadi_int i); +extern "C" const char* path_con_N_fun_name_in(casadi_int i); +extern "C" const char* path_con_N_fun_name_out(casadi_int i); +extern "C" const casadi_int* path_con_N_fun_sparsity_in(casadi_int i); +extern "C" const casadi_int* path_con_N_fun_sparsity_out(casadi_int i); +extern "C" int path_con_N_fun_work(casadi_int *sz_arg, casadi_int* sz_res, casadi_int *sz_iw, casadi_int *sz_w); +extern "C" int obji_fun(const casadi_real** arg, casadi_real** res, casadi_int* iw, casadi_real* w, int mem); +extern "C" int obji_fun_alloc_mem(void); +extern "C" int obji_fun_init_mem(int mem); +extern "C" void obji_fun_free_mem(int mem); +extern "C" int obji_fun_checkout(void); +extern "C" void obji_fun_release(int mem); +extern "C" void obji_fun_incref(void); +extern "C" void obji_fun_decref(void); +extern "C" casadi_int obji_fun_n_out(void); +extern "C" casadi_int obji_fun_n_in(void); +extern "C" casadi_real obji_fun_default_in(casadi_int i); +extern "C" const char* obji_fun_name_in(casadi_int i); +extern "C" const char* obji_fun_name_out(casadi_int i); +extern "C" const casadi_int* obji_fun_sparsity_in(casadi_int i); +extern "C" const casadi_int* obji_fun_sparsity_out(casadi_int i); +extern "C" int obji_fun_work(casadi_int *sz_arg, casadi_int* sz_res, casadi_int *sz_iw, casadi_int *sz_w); +extern "C" int objN_fun(const casadi_real** arg, casadi_real** res, casadi_int* iw, casadi_real* w, int mem); +extern "C" int objN_fun_alloc_mem(void); +extern "C" int objN_fun_init_mem(int mem); +extern "C" void objN_fun_free_mem(int mem); +extern "C" int objN_fun_checkout(void); +extern "C" void objN_fun_release(int mem); +extern "C" void objN_fun_incref(void); +extern "C" void objN_fun_decref(void); +extern "C" casadi_int objN_fun_n_out(void); +extern "C" casadi_int objN_fun_n_in(void); +extern "C" casadi_real objN_fun_default_in(casadi_int i); +extern "C" const char* objN_fun_name_in(casadi_int i); +extern "C" const char* objN_fun_name_out(casadi_int i); +extern "C" const casadi_int* objN_fun_sparsity_in(casadi_int i); +extern "C" const casadi_int* objN_fun_sparsity_out(casadi_int i); +extern "C" int objN_fun_work(casadi_int *sz_arg, casadi_int* sz_res, casadi_int *sz_iw, casadi_int *sz_w); +extern "C" int gi_fun(const casadi_real** arg, casadi_real** res, casadi_int* iw, casadi_real* w, int mem); +extern "C" int gi_fun_alloc_mem(void); +extern "C" int gi_fun_init_mem(int mem); +extern "C" void gi_fun_free_mem(int mem); +extern "C" int gi_fun_checkout(void); +extern "C" void gi_fun_release(int mem); +extern "C" void gi_fun_incref(void); +extern "C" void gi_fun_decref(void); +extern "C" casadi_int gi_fun_n_out(void); +extern "C" casadi_int gi_fun_n_in(void); +extern "C" casadi_real gi_fun_default_in(casadi_int i); +extern "C" const char* gi_fun_name_in(casadi_int i); +extern "C" const char* gi_fun_name_out(casadi_int i); +extern "C" const casadi_int* gi_fun_sparsity_in(casadi_int i); +extern "C" const casadi_int* gi_fun_sparsity_out(casadi_int i); +extern "C" int gi_fun_work(casadi_int *sz_arg, casadi_int* sz_res, casadi_int *sz_iw, casadi_int *sz_w); +extern "C" int gN_fun(const casadi_real** arg, casadi_real** res, casadi_int* iw, casadi_real* w, int mem); +extern "C" int gN_fun_alloc_mem(void); +extern "C" int gN_fun_init_mem(int mem); +extern "C" void gN_fun_free_mem(int mem); +extern "C" int gN_fun_checkout(void); +extern "C" void gN_fun_release(int mem); +extern "C" void gN_fun_incref(void); +extern "C" void gN_fun_decref(void); +extern "C" casadi_int gN_fun_n_out(void); +extern "C" casadi_int gN_fun_n_in(void); +extern "C" casadi_real gN_fun_default_in(casadi_int i); +extern "C" const char* gN_fun_name_in(casadi_int i); +extern "C" const char* gN_fun_name_out(casadi_int i); +extern "C" const casadi_int* gN_fun_sparsity_in(casadi_int i); +extern "C" const casadi_int* gN_fun_sparsity_out(casadi_int i); +extern "C" int gN_fun_work(casadi_int *sz_arg, casadi_int* sz_res, casadi_int *sz_iw, casadi_int *sz_w); +extern "C" int Hi_fun(const casadi_real** arg, casadi_real** res, casadi_int* iw, casadi_real* w, int mem); +extern "C" int Hi_fun_alloc_mem(void); +extern "C" int Hi_fun_init_mem(int mem); +extern "C" void Hi_fun_free_mem(int mem); +extern "C" int Hi_fun_checkout(void); +extern "C" void Hi_fun_release(int mem); +extern "C" void Hi_fun_incref(void); +extern "C" void Hi_fun_decref(void); +extern "C" casadi_int Hi_fun_n_out(void); +extern "C" casadi_int Hi_fun_n_in(void); +extern "C" casadi_real Hi_fun_default_in(casadi_int i); +extern "C" const char* Hi_fun_name_in(casadi_int i); +extern "C" const char* Hi_fun_name_out(casadi_int i); +extern "C" const casadi_int* Hi_fun_sparsity_in(casadi_int i); +extern "C" const casadi_int* Hi_fun_sparsity_out(casadi_int i); +extern "C" int Hi_fun_work(casadi_int *sz_arg, casadi_int* sz_res, casadi_int *sz_iw, casadi_int *sz_w); +extern "C" int HN_fun(const casadi_real** arg, casadi_real** res, casadi_int* iw, casadi_real* w, int mem); +extern "C" int HN_fun_alloc_mem(void); +extern "C" int HN_fun_init_mem(int mem); +extern "C" void HN_fun_free_mem(int mem); +extern "C" int HN_fun_checkout(void); +extern "C" void HN_fun_release(int mem); +extern "C" void HN_fun_incref(void); +extern "C" void HN_fun_decref(void); +extern "C" casadi_int HN_fun_n_out(void); +extern "C" casadi_int HN_fun_n_in(void); +extern "C" casadi_real HN_fun_default_in(casadi_int i); +extern "C" const char* HN_fun_name_in(casadi_int i); +extern "C" const char* HN_fun_name_out(casadi_int i); +extern "C" const casadi_int* HN_fun_sparsity_in(casadi_int i); +extern "C" const casadi_int* HN_fun_sparsity_out(casadi_int i); +extern "C" int HN_fun_work(casadi_int *sz_arg, casadi_int* sz_res, casadi_int *sz_iw, casadi_int *sz_w); +extern "C" int Ci_fun(const casadi_real** arg, casadi_real** res, casadi_int* iw, casadi_real* w, int mem); +extern "C" int Ci_fun_alloc_mem(void); +extern "C" int Ci_fun_init_mem(int mem); +extern "C" void Ci_fun_free_mem(int mem); +extern "C" int Ci_fun_checkout(void); +extern "C" void Ci_fun_release(int mem); +extern "C" void Ci_fun_incref(void); +extern "C" void Ci_fun_decref(void); +extern "C" casadi_int Ci_fun_n_out(void); +extern "C" casadi_int Ci_fun_n_in(void); +extern "C" casadi_real Ci_fun_default_in(casadi_int i); +extern "C" const char* Ci_fun_name_in(casadi_int i); +extern "C" const char* Ci_fun_name_out(casadi_int i); +extern "C" const casadi_int* Ci_fun_sparsity_in(casadi_int i); +extern "C" const casadi_int* Ci_fun_sparsity_out(casadi_int i); +extern "C" int Ci_fun_work(casadi_int *sz_arg, casadi_int* sz_res, casadi_int *sz_iw, casadi_int *sz_w); +extern "C" int CN_fun(const casadi_real** arg, casadi_real** res, casadi_int* iw, casadi_real* w, int mem); +extern "C" int CN_fun_alloc_mem(void); +extern "C" int CN_fun_init_mem(int mem); +extern "C" void CN_fun_free_mem(int mem); +extern "C" int CN_fun_checkout(void); +extern "C" void CN_fun_release(int mem); +extern "C" void CN_fun_incref(void); +extern "C" void CN_fun_decref(void); +extern "C" casadi_int CN_fun_n_out(void); +extern "C" casadi_int CN_fun_n_in(void); +extern "C" casadi_real CN_fun_default_in(casadi_int i); +extern "C" const char* CN_fun_name_in(casadi_int i); +extern "C" const char* CN_fun_name_out(casadi_int i); +extern "C" const casadi_int* CN_fun_sparsity_in(casadi_int i); +extern "C" const casadi_int* CN_fun_sparsity_out(casadi_int i); +extern "C" int CN_fun_work(casadi_int *sz_arg, casadi_int* sz_res, casadi_int *sz_iw, casadi_int *sz_w); +extern "C" int adj_fun(const casadi_real** arg, casadi_real** res, casadi_int* iw, casadi_real* w, int mem); +extern "C" int adj_fun_alloc_mem(void); +extern "C" int adj_fun_init_mem(int mem); +extern "C" void adj_fun_free_mem(int mem); +extern "C" int adj_fun_checkout(void); +extern "C" void adj_fun_release(int mem); +extern "C" void adj_fun_incref(void); +extern "C" void adj_fun_decref(void); +extern "C" casadi_int adj_fun_n_out(void); +extern "C" casadi_int adj_fun_n_in(void); +extern "C" casadi_real adj_fun_default_in(casadi_int i); +extern "C" const char* adj_fun_name_in(casadi_int i); +extern "C" const char* adj_fun_name_out(casadi_int i); +extern "C" const casadi_int* adj_fun_sparsity_in(casadi_int i); +extern "C" const casadi_int* adj_fun_sparsity_out(casadi_int i); +extern "C" int adj_fun_work(casadi_int *sz_arg, casadi_int* sz_res, casadi_int *sz_iw, casadi_int *sz_w); +extern "C" int adjN_fun(const casadi_real** arg, casadi_real** res, casadi_int* iw, casadi_real* w, int mem); +extern "C" int adjN_fun_alloc_mem(void); +extern "C" int adjN_fun_init_mem(int mem); +extern "C" void adjN_fun_free_mem(int mem); +extern "C" int adjN_fun_checkout(void); +extern "C" void adjN_fun_release(int mem); +extern "C" void adjN_fun_incref(void); +extern "C" void adjN_fun_decref(void); +extern "C" casadi_int adjN_fun_n_out(void); +extern "C" casadi_int adjN_fun_n_in(void); +extern "C" casadi_real adjN_fun_default_in(casadi_int i); +extern "C" const char* adjN_fun_name_in(casadi_int i); +extern "C" const char* adjN_fun_name_out(casadi_int i); +extern "C" const casadi_int* adjN_fun_sparsity_in(casadi_int i); +extern "C" const casadi_int* adjN_fun_sparsity_out(casadi_int i); +extern "C" int adjN_fun_work(casadi_int *sz_arg, casadi_int* sz_res, casadi_int *sz_iw, casadi_int *sz_w); +extern "C" int adj_dG_fun(const casadi_real** arg, casadi_real** res, casadi_int* iw, casadi_real* w, int mem); +extern "C" int adj_dG_fun_alloc_mem(void); +extern "C" int adj_dG_fun_init_mem(int mem); +extern "C" void adj_dG_fun_free_mem(int mem); +extern "C" int adj_dG_fun_checkout(void); +extern "C" void adj_dG_fun_release(int mem); +extern "C" void adj_dG_fun_incref(void); +extern "C" void adj_dG_fun_decref(void); +extern "C" casadi_int adj_dG_fun_n_out(void); +extern "C" casadi_int adj_dG_fun_n_in(void); +extern "C" casadi_real adj_dG_fun_default_in(casadi_int i); +extern "C" const char* adj_dG_fun_name_in(casadi_int i); +extern "C" const char* adj_dG_fun_name_out(casadi_int i); +extern "C" const casadi_int* adj_dG_fun_sparsity_in(casadi_int i); +extern "C" const casadi_int* adj_dG_fun_sparsity_out(casadi_int i); +extern "C" int adj_dG_fun_work(casadi_int *sz_arg, casadi_int* sz_res, casadi_int *sz_iw, casadi_int *sz_w); diff --git a/src/casadi_wrapper.cpp b/src/casadi_wrapper.cpp index f13b452..fd2baec 100644 --- a/src/casadi_wrapper.cpp +++ b/src/casadi_wrapper.cpp @@ -9,8 +9,8 @@ void f_Fun(double **in, double **out){ double *xn = out[0]; - void *casadi_mem = NULL; - int *casadi_iw = NULL; + int casadi_mem = 0; + long long int *casadi_iw = NULL; double *casadi_w = NULL; const double *casadi_arg[3]; @@ -35,8 +35,8 @@ void vde_Fun(double **in, double **out){ double *jac_x = out[0]; double *jac_u = out[1]; - void *casadi_mem = NULL; - int *casadi_iw = NULL; + int casadi_mem = 0; + long long int *casadi_iw = NULL; double *casadi_w = NULL; const double *casadi_arg[5]; @@ -62,8 +62,8 @@ void impl_f_Fun(double **in, double **out){ double *res = out[0]; - void *casadi_mem = NULL; - int *casadi_iw = NULL; + int casadi_mem = 0; + long long int *casadi_iw = NULL; double *casadi_w = NULL; const double *casadi_arg[4]; @@ -87,8 +87,8 @@ void impl_jac_x_Fun(double **in, double **out){ double *jac_x = out[0]; - void *casadi_mem = NULL; - int *casadi_iw = NULL; + int casadi_mem = 0; + long long int *casadi_iw = NULL; double *casadi_w = NULL; const double *casadi_arg[4]; @@ -112,8 +112,8 @@ void impl_jac_u_Fun(double **in, double **out){ double *jac_u = out[0]; - void *casadi_mem = NULL; - int *casadi_iw = NULL; + int casadi_mem = 0; + long long int *casadi_iw = NULL; double *casadi_w = NULL; const double *casadi_arg[4]; @@ -137,8 +137,8 @@ void impl_jac_xdot_Fun(double **in, double **out){ double *jac_xdot = out[0]; - void *casadi_mem = NULL; - int *casadi_iw = NULL; + int casadi_mem = 0; + long long int *casadi_iw = NULL; double *casadi_w = NULL; const double *casadi_arg[4]; @@ -162,8 +162,8 @@ void F_Fun(double **in, double **out) { double *x_out = out[0]; - void *casadi_mem = NULL; - int *casadi_iw = NULL; + int casadi_mem = 0; + long long int *casadi_iw = NULL; double *casadi_w = NULL; const double *casadi_arg[3]; @@ -187,8 +187,8 @@ void D_Fun(double **in, double **out) { double *A = out[0]; double *B = out[1]; - void *casadi_mem = NULL; - int *casadi_iw = NULL; + int casadi_mem = 0; + long long int *casadi_iw = NULL; double *casadi_w = NULL; const double *casadi_arg[3]; @@ -215,8 +215,8 @@ void Hi_Fun(double **in, double **out) { double *Hu = out[1]; double *Hxu = out[2]; - void *casadi_mem = NULL; - int *casadi_iw = NULL; + int casadi_mem = 0; + long long int *casadi_iw = NULL; double *casadi_w = NULL; const double *casadi_arg[5]; @@ -243,8 +243,8 @@ void HN_Fun(double **in, double **out) { double *HN = out[0]; - void *casadi_mem = NULL; - int *casadi_iw = NULL; + int casadi_mem = 0; + long long int *casadi_iw = NULL; double *casadi_w = NULL; const double *casadi_arg[4]; @@ -271,8 +271,8 @@ void gi_Fun(double **in, double **out) { double *gx = out[0]; double *gu = out[1]; - void *casadi_mem = NULL; - int *casadi_iw = NULL; + int casadi_mem = 0; + long long int *casadi_iw = NULL; double *casadi_w = NULL; const double *casadi_arg[5]; @@ -298,8 +298,8 @@ void path_con_Fun(double **in, double **out) { double *ci = out[0]; - void *casadi_mem = NULL; - int *casadi_iw = NULL; + int casadi_mem = 0; + long long int *casadi_iw = NULL; double *casadi_w = NULL; const double *casadi_arg[3]; @@ -322,8 +322,8 @@ void Ci_Fun(double **in, double **out) { double *Cx = out[0]; double *Cu = out[1]; - void *casadi_mem = NULL; - int *casadi_iw = NULL; + int casadi_mem = 0; + long long int *casadi_iw = NULL; double *casadi_w = NULL; const double *casadi_arg[3]; @@ -348,8 +348,8 @@ void gN_Fun(double **in, double **out) { double *gxN = out[0]; - void *casadi_mem = NULL; - int *casadi_iw = NULL; + int casadi_mem = 0; + long long int *casadi_iw = NULL; double *casadi_w = NULL; const double *casadi_arg[4]; @@ -372,8 +372,8 @@ void path_con_N_Fun(double **in, double **out) { double *cN = out[0]; - void *casadi_mem = NULL; - int *casadi_iw = NULL; + int casadi_mem = 0; + long long int *casadi_iw = NULL; double *casadi_w = NULL; const double *casadi_arg[2]; @@ -394,8 +394,8 @@ void CN_Fun(double **in, double **out) { double *CxN = out[0]; - void *casadi_mem = NULL; - int *casadi_iw = NULL; + int casadi_mem = 0; + long long int *casadi_iw = NULL; double *casadi_w = NULL; const double *casadi_arg[2]; @@ -423,8 +423,8 @@ void adj_Fun(double **in, double **out) { double *adj_dG = out[1]; double *adj_dB = out[2]; - void *casadi_mem = NULL; - int *casadi_iw = NULL; + int casadi_mem = 0; + long long int *casadi_iw = NULL; double *casadi_w = NULL; const double *casadi_arg[7]; @@ -456,8 +456,8 @@ void adjN_Fun(double **in, double **out) { double *dobj = out[0]; double *adj_dB = out[1]; - void *casadi_mem = NULL; - int *casadi_iw = NULL; + int casadi_mem = 0; + long long int *casadi_iw = NULL; double *casadi_w = NULL; const double *casadi_arg[5]; @@ -484,8 +484,8 @@ void obji_Fun(double **in, double **out){ double *obj = out[0]; - void *casadi_mem = NULL; - int *casadi_iw = NULL; + int casadi_mem = 0; + long long int *casadi_iw = NULL; double *casadi_w = NULL; const double *casadi_arg[5]; @@ -510,8 +510,8 @@ void objN_Fun(double **in, double **out){ double *objN = out[0]; - void *casadi_mem = NULL; - int *casadi_iw = NULL; + int casadi_mem = 0; + long long int *casadi_iw = NULL; double *casadi_w = NULL; const double *casadi_arg[4]; diff --git a/src/qp_problem.cpp b/src/qp_problem.cpp index b633ebd..45e4acc 100644 --- a/src/qp_problem.cpp +++ b/src/qp_problem.cpp @@ -15,7 +15,6 @@ qp_in& qp_in::init(model_size& size) int nyN = size.nyN; int np = size.np; int nbx = size.nbx; - int nbu = size.nbu; int nbg = size.nbg; int nbgN = size.nbgN; int N = size.N; @@ -27,8 +26,8 @@ qp_in& qp_in::init(model_size& size) p = MatrixXd::Zero(np,N+1); W = MatrixXd::Zero(ny,N); WN = VectorXd::Zero(nyN); - lbu = VectorXd::Zero(nbu); - ubu = VectorXd::Zero(nbu); + lbu = VectorXd::Zero(nu); + ubu = VectorXd::Zero(nu); lbx = VectorXd::Zero(nbx); ubx = VectorXd::Zero(nbx); lbg = VectorXd::Zero(nbg); @@ -44,7 +43,6 @@ qp_data& qp_data::init(model_size& size) int nx=size.nx; int nu=size.nu; int nbx = size.nbx; - int nbu = size.nbu; int nbg = size.nbg; int nbgN = size.nbgN; int N = size.N; @@ -62,8 +60,8 @@ qp_data& qp_data::init(model_size& size) gx = MatrixXd::Zero(nx,N+1); gu = MatrixXd::Zero(nu,N); a = MatrixXd::Zero(nx,N); - lb_u = VectorXd::Zero(N*nbu); - ub_u = VectorXd::Zero(N*nbu); + lb_u = VectorXd::Zero(N*nu); + ub_u = VectorXd::Zero(N*nu); lb_x = VectorXd::Zero(N*nbx); ub_x = VectorXd::Zero(N*nbx); lb_g = VectorXd::Zero(nbg*N+nbgN); @@ -113,12 +111,10 @@ qp_problem& qp_problem::generateQP(model_size& size) int ny = size.ny; int np = size.np; int nbx = size.nbx; - int nbu = size.nbu; int nbg = size.nbg; int nbgN = size.nbgN; int N = size.N; int* nbx_idx = size.nbx_idx; - int* nbu_idx = size.nbu_idx; int i, j; @@ -135,10 +131,10 @@ qp_problem& qp_problem::generateQP(model_size& size) casadi_in[3] = in.y.data()+i*ny; casadi_in[4] = in.W.data()+i*ny; // control bounds - for (j=0; j