1 #include "gmock/gmock.h" 2 #include "gtest/gtest.h" 4 #include <casadi/casadi.hpp> 20 cout <<
"program started" << endl;
27 SX u = SX::sym(
"u", nu);
33 SX dt = 10.0 / (nj * nu);
38 vector<SX> s_k, v_k, m_k;
41 SX s = s_0, v = v_0, m = m_0;
42 for (
int k = 0; k < nu; ++k) {
43 for (
int j = 0; j < nj; ++j) {
45 v += dt / m * (u(k) - alpha * v * v);
46 m += -dt * beta * u(k) * u(k);
52 SX s_all = vertcat(s_k), v_all = vertcat(v_k), m_all = vertcat(m_k);
58 SX g = vertcat(s, v, v_all);
61 SXDict nlp = {{
"x", u}, {
"f", f}, {
"g", g}};
64 Function solver = nlpsol(
"solver",
"ipopt", nlp);
67 vector<double> gmin = {10, 0};
68 vector<double> gmax = {10, 0};
69 gmin.resize(2 + nu, -numeric_limits<double>::infinity());
70 gmax.resize(2 + nu, 1.1);
74 {
"lbx", -10}, {
"ubx", 10}, {
"x0", 0.4}, {
"lbg", gmin}, {
"ubg", gmax}};
75 DMDict res = solver(arg);
78 double cost(res.at(
"f"));
79 cout <<
"optimal cost: " << cost << endl;
82 vector<double> uopt(res.at(
"x"));
83 cout <<
"optimal control: " << uopt << endl;
86 Function xfcn(
"xfcn", {u}, {s_all, v_all, m_all});
87 vector<double> sopt, vopt, mopt;
88 xfcn({uopt}, {&sopt, &vopt, &mopt});
89 cout <<
"position: " << sopt << endl;
90 cout <<
"velocity: " << vopt << endl;
91 cout <<
"mass: " << mopt << endl;
93 bool b_save_matlab_file(
false);
94 if (b_save_matlab_file) {
97 string filename =
"rocket_ipopt_results.m";
98 file.open(filename.c_str());
99 file <<
"% Results file from " __FILE__ << endl;
100 file <<
"% Generated " __DATE__
" at " __TIME__ << endl;
102 file <<
"cost = " << cost <<
";" << endl;
103 file <<
"u = " << uopt <<
";" << endl;
106 file <<
"t = linspace(0,10.0," << nu <<
");" << endl;
107 file <<
"s = " << sopt <<
";" << endl;
108 file <<
"v = " << vopt <<
";" << endl;
109 file <<
"m = " << mopt <<
";" << endl;
113 file <<
"% Plot the results" << endl;
114 file <<
"figure(1);" << endl;
115 file <<
"clf;" << endl << endl;
117 file <<
"subplot(2,2,1);" << endl;
118 file <<
"plot(t,s);" << endl;
119 file <<
"grid on;" << endl;
120 file <<
"xlabel('time [s]');" << endl;
121 file <<
"ylabel('position [m]');" << endl << endl;
123 file <<
"subplot(2,2,2);" << endl;
124 file <<
"plot(t,v);" << endl;
125 file <<
"grid on;" << endl;
126 file <<
"xlabel('time [s]');" << endl;
127 file <<
"ylabel('velocity [m/s]');" << endl << endl;
129 file <<
"subplot(2,2,3);" << endl;
130 file <<
"plot(t,m);" << endl;
131 file <<
"grid on;" << endl;
132 file <<
"xlabel('time [s]');" << endl;
133 file <<
"ylabel('mass [kg]');" << endl << endl;
135 file <<
"subplot(2,2,4);" << endl;
136 file <<
"plot(t,u);" << endl;
137 file <<
"grid on;" << endl;
138 file <<
"xlabel('time [s]');" << endl;
139 file <<
"ylabel('Thrust [kg m/s^2]');" << endl << endl;
142 cout <<
"Results saved to \"" << filename <<
"\"" << endl;
154 MX x = MX::sym(
"x", 2);
157 MX
f = x(0) * x(0) + x(1) * x(1);
160 MX g = x(0) + x(1) - 10;
163 Function solver = nlpsol(
"solver",
"ipopt", {{
"x", x}, {
"f", f}, {
"g", g}});
166 solver.generate_dependencies(
"nlp.c");
172 solver = nlpsol(
"solver",
"ipopt",
"nlp.c");
175 int flag = system(
"gcc -fPIC -shared -O3 nlp.c -o nlp.so");
176 casadi_assert(flag == 0,
"Compilation failed");
179 solver = nlpsol(
"solver",
"ipopt",
"nlp.so");
183 std::map<std::string, DM> arg, res;
184 arg[
"lbx"] = -DM::inf();
185 arg[
"ubx"] = DM::inf();
187 arg[
"ubg"] = DM::inf();
194 cout <<
"-----" << endl;
195 cout <<
"objective at solution = " << res.at(
"f") << endl;
196 cout <<
"primal solution = " << res.at(
"x") << endl;
197 cout <<
"dual solution (x) = " << res.at(
"lam_x") << endl;
198 cout <<
"dual solution (g) = " << res.at(
"lam_g") << endl;
202 MX
f(
const MX& x,
const MX& u) {
return vertcat(x(1), u - x(1)); }
214 auto opti = casadi::Opti();
218 auto X = opti.variable(2, N + 1);
219 auto pos =
X(0, all);
220 auto speed =
X(1, all);
221 auto U = opti.variable(1, N);
222 auto T = opti.variable();
229 for (
int k = 0; k < N; ++k) {
230 auto k1 =
f(
X(all, k), U(all, k));
231 auto k2 =
f(
X(all, k) + dt / 2 * k1, U(all, k));
232 auto k3 =
f(
X(all, k) + dt / 2 * k2, U(all, k));
233 auto k4 =
f(
X(all, k) + dt * k3, U(all, k));
234 auto x_next =
X(all, k) + dt / 6 * (k1 + 2 * k2 + 2 * k3 + k4);
235 opti.subject_to(
X(all, k + 1) == x_next);
239 opti.subject_to(speed <= 1 - sin(2 * pi * pos) / 2);
240 opti.subject_to(0 <= U <= 1);
243 opti.subject_to(pos(1) == 0);
244 opti.subject_to(speed(1) == 0);
245 opti.subject_to(pos(N) == 1);
248 opti.subject_to(T >= 0);
251 opti.set_initial(speed, 1);
252 opti.set_initial(T, 1);
255 opti.solver(
"ipopt");
256 auto sol = opti.solve();
258 bool b_matlab_file(
false);
262 string filename =
"race_car_results.m";
263 file.open(filename.c_str());
264 file <<
"% Results file from " __FILE__ << endl;
265 file <<
"% Generated " __DATE__
" at " __TIME__ << endl;
269 file <<
"t = linspace(0," << sol.value(T) <<
"," << N <<
"+1);" << endl;
270 file <<
"speed = " << std::vector<double>(sol.value(speed)) <<
";" << endl;
271 file <<
"pos = " << std::vector<double>(sol.value(pos)) <<
";" << endl;
272 file <<
"U = " << std::vector<double>(sol.value(U)) <<
";" << endl;
274 file <<
"figure;" << endl;
275 file <<
"hold on;" << endl;
276 file <<
"plot(t,speed);" << endl;
277 file <<
"plot(t,pos);" << endl;
278 file <<
"plot(t,1-sin(2*pi*pos)/2,'r--');" << endl;
279 file <<
"stairs(t(1:end-1),U,'k');" << endl;
280 file <<
"xlabel('Time [s]');" << endl;
281 file <<
"legend('speed','pos','speed " 282 "limit','throttle','Location','northwest');" 286 jacobian(opti.g(), opti.x()).sparsity().spy_matlab(
"race_car_jac_g.m");
288 file <<
"figure" << std::endl;
289 file <<
"race_car_jac_g;" << std::endl;
290 file <<
"xlabel('decision variables');" << std::endl;
291 file <<
"ylabel('constraints');" << std::endl;
292 file <<
"print('jac_sp','-dpng');" << std::endl;
297 MX
simple_dyn(
const MX& x,
const MX& u,
const MX& P,
int i) {
303 return vertcat (vertcat(x(3), x(4), x(5)),
304 vertcat(u(0)/M, u(1)/M -g), ((P(1) - x(1))*u(0) - (P(0) - x(0)) * u(1))/I );
306 return vertcat (vertcat(x(3), x(4), x(5)),
307 vertcat(u(0)/M, u(1)/M -g), ((P(3) - x(1))*u(0) - (P(2) - x(0)) * u(1))/I );
319 ret << x(3), x(4), x(5),
320 u(0)/M, u(1)/M -g, ((P(1) - x(1))*u(0) - (P(0) - x(0)) * u(1))/I ;
322 ret << x(3), x(4), x(5),
323 u(0)/M, u(1)/M -g, ((P(3) - x(1))*u(0) - (P(2) - x(0)) * u(1))/I ;
367 auto opti = casadi::Opti();
371 auto X = opti.variable(6, N+1);
372 auto P = opti.variable(4);
373 auto F = opti.variable(2, N);
374 auto cost = opti.variable();
377 X0<< 0.0, 0.2, 0.2, 0.5, -0.1, 0.1;
381 Xf<< 0.5, 0.23, -M_PI/4., 0.8, 0.8, 0.1;
383 cost = (
X(0,N) - Xf(0)) * (
X(0,N) - Xf(0))
384 + (
X(1,N) - Xf(1)) * (
X(1,N) - Xf(1))
385 + (
X(2,N) - Xf(2)) * (
X(2,N) - Xf(2))
386 + (
X(3,N) - Xf(3)) * (
X(3,N) - Xf(3))
387 + (
X(4,N) - Xf(4)) * (
X(4,N) - Xf(4))
388 + (
X(5,N) - Xf(5)) * (
X(5,N) - Xf(5));
397 for (
int k = 0; k < N; ++k) {
399 auto X_next =
X(all, k) + dt * dX;
400 opti.subject_to(
X(all, k + 1) == X_next);
403 opti.subject_to(-mu * F(1,k) <= F(0, k) <= mu* F(1,k));
404 opti.subject_to(0<=F(1,k) <= 300.);
406 opti.subject_to (-0.15 <= P(0) <= 0.15);
407 opti.subject_to (-0.15 <= P(2) <= 0.15);
408 opti.subject_to (P(1) == 0.);
409 opti.subject_to (P(3) == 0.);
412 opti.subject_to(F(1, N_fc) == 0.);
414 for(
int i(0); i<6; ++i){
415 opti.subject_to(
X(i, 1) == X0(i));
418 opti.solver(
"ipopt");
419 auto sol = opti.solve();
428 for(
int k(0); k<N; ++k){
429 std::vector<double> x_std_vec = std::vector<double>(sol.value(
X(all, k)));
430 std::vector<double> x_next_std_vec = std::vector<double>(sol.value(
X(all, k+1)));
431 std::vector<double>
f = std::vector<double>(sol.value(F(all, k)));
432 std::vector<double> p = std::vector<double>(sol.value(P(all)));
446 for(
int i(0); i<6; ++i){
447 x_current[i] = x_std_vec[i];
448 x_next[i] = x_next_std_vec[i];
452 EXPECT_TRUE(
almostEqual(x_next, x_next_eigen, .0001));
458 bool b_matlab_file(
true);
461 string filename =
"jump_result.m";
462 file.open(filename.c_str());
463 file <<
"% Results file from " __FILE__ << endl;
464 file <<
"% Generated " __DATE__
" at " __TIME__ << endl;
468 file <<
"xb= " << std::vector<double>(sol.value(
X(0, all) ) ) <<
";" << endl;
469 file <<
"zb= " << std::vector<double>(sol.value(
X(1, all))) <<
";" << endl;
470 file <<
"theta= " << std::vector<double>(sol.value(
X(2, all))) <<
";" << endl;
471 file <<
"dot_xb= " << std::vector<double>(sol.value(
X(3, all) ) ) <<
";" << endl;
472 file <<
"dot_zb= " << std::vector<double>(sol.value(
X(4, all))) <<
";" << endl;
473 file <<
"dot_theta= " << std::vector<double>(sol.value(
X(5, all))) <<
";" << endl;
475 file <<
"Fx = " << std::vector<double>(sol.value(F(0, all) ) ) <<
";" << endl;
476 file <<
"Fz = " << std::vector<double>(sol.value(F(1, all) ) )<<
";" << endl;
478 file <<
"P = " << std::vector<double>(sol.value(P(all) ) ) <<
";" << endl;
MX simple_dyn(const MX &x, const MX &u, const MX &P, int i)
Data structure containing parameters for quadruped robot.
Utility function to build a Mini Cheetah Quadruped object.
TEST(casadi, rocket_ipopt)
void pretty_print(DMat< T > const &mm, std::ostream &os, std::string const &title, std::string const &prefix="", bool vecmode=false, bool nonl=false)
bool almostEqual(const Eigen::MatrixBase< T > &a, const Eigen::MatrixBase< T > &b, T2 tol)
typename Eigen::Matrix< T, Eigen::Dynamic, 1 > DVec
Rigid Body Dynamics Simulator with Collisions.
Implementation of Rigid Body Floating Base model data structure.
DVec< double > simple_dyn_vec(const DVec< double > &x, const DVec< double > &u, const DVec< double > &P, int i)
MX f(const MX &x, const MX &u)