diff --git a/include/quadruped-reactive-walking/InvKin.hpp b/include/quadruped-reactive-walking/InvKin.hpp index 8678a7cbac0c06c1a3ed944fee2972cc032a0fae..2c50b7c4ae9e2f7bfff06b99dac6827c335a5d15 100644 --- a/include/quadruped-reactive-walking/InvKin.hpp +++ b/include/quadruped-reactive-walking/InvKin.hpp @@ -149,7 +149,7 @@ class InvKin { double Kp_base_position = 100.0; double Kd_base_position = 2.0 * std::sqrt(Kp_base_position); - double Kp_flyingfeet = 1000.0; + double Kp_flyingfeet = 100.0; double Kd_flyingfeet = 2.0 * std::sqrt(Kp_flyingfeet); public: diff --git a/include/quadruped-reactive-walking/QPWBC.hpp b/include/quadruped-reactive-walking/QPWBC.hpp index dd2e9ca646b1d29e790dc81ee6f079f95ecd8e73..13ed37e6767c18da49b74cffab82e467a45dc1d5 100644 --- a/include/quadruped-reactive-walking/QPWBC.hpp +++ b/include/quadruped-reactive-walking/QPWBC.hpp @@ -87,7 +87,7 @@ class QPWBC { void update_PQ(); int call_solver(); int retrieve_result(const Eigen::MatrixXd &f_cmd); - int run(const Eigen::MatrixXd &M, const Eigen::MatrixXd &Jc, const Eigen::MatrixXd &f_cmd, const Eigen::MatrixXd &RNEA); + int run(const Eigen::MatrixXd &M, const Eigen::MatrixXd &Jc, const Eigen::MatrixXd &f_cmd, const Eigen::MatrixXd &RNEA, const Eigen::MatrixXd &k_contact); // Getters Eigen::MatrixXd get_f_res(); diff --git a/python/gepadd.cpp b/python/gepadd.cpp index da855671c3980982884236a1515a10d9d0e4e652..e712b2529f1071e7737e62d24209ffcaa6cb644a 100644 --- a/python/gepadd.cpp +++ b/python/gepadd.cpp @@ -103,7 +103,7 @@ struct QPWBCPythonVisitor : public bp::def_visitor<QPWBCPythonVisitor<QPWBC> > { .def("get_H", &QPWBC::get_H, "Get H weight matrix.\n") // Run QPWBC from Python - .def("run", &QPWBC::run, bp::args("M", "Jc", "f_cmd", "RNEA"), "Run QPWBC from Python.\n"); + .def("run", &QPWBC::run, bp::args("M", "Jc", "f_cmd", "RNEA", "k_contacts"), "Run QPWBC from Python.\n"); } static void expose() { diff --git a/scripts/QP_WBC.py b/scripts/QP_WBC.py index 0d5518a687bec6fe5fbe6feea7cc1864eac62fc3..a683a56c65060eff148d1a8aa1e67fe2245213b1 100644 --- a/scripts/QP_WBC.py +++ b/scripts/QP_WBC.py @@ -26,6 +26,8 @@ class controller(): self.error = False # Set to True when an error happens in the controller + self.k_since_contact = np.zeros((1, 4)) + # Arrays to store results (for solo12) self.qdes = np.zeros((19, )) self.vdes = np.zeros((18, 1)) @@ -45,8 +47,8 @@ class controller(): self.log_f_cmd = np.zeros((12, N_SIMULATION)) self.log_f_out = np.zeros((12, N_SIMULATION)) self.log_x = np.zeros((12, N_SIMULATION)) - self.log_q = np.zeros((6, N_SIMULATION)) - self.log_dq = np.zeros((6, N_SIMULATION)) + self.log_q = np.zeros((18, N_SIMULATION)) + self.log_dq = np.zeros((18, N_SIMULATION)) self.log_x_ref_invkin = np.zeros((6, N_SIMULATION)) self.log_x_invkin = np.zeros((6, N_SIMULATION)) self.log_dx_ref_invkin = np.zeros((6, N_SIMULATION)) @@ -74,7 +76,11 @@ class controller(): planner (object): Object that contains the pos, vel and acc references for feet """ - #self.tic = time() + # Update nb of iterations since contact + self.k_since_contact += contacts # Increment feet in stance phase + self.k_since_contact *= contacts # Reset feet in swing phase + + # self.tic = time() # Compute Inverse Kinematics ddq_cmd = np.array([self.invKin.refreshAndCompute(q.copy(), dq.copy(), x_cmd, contacts, planner)]).T @@ -113,7 +119,7 @@ class controller(): RNEA = pin.rnea(self.invKin.rmodel, self.invKin.rdata, q, dq, ddq_cmd)[:6] # Solve the QP problem with C++ bindings - self.box_qp.run(self.M, self.Jc, f_cmd.reshape((-1, 1)), RNEA.reshape((-1, 1))) + self.box_qp.run(self.M, self.Jc, f_cmd.reshape((-1, 1)), RNEA.reshape((-1, 1)), self.k_since_contact) # Add deltas found by the QP problem to reference quantities deltaddq = self.box_qp.get_ddq_res() @@ -147,7 +153,7 @@ class controller(): self.log_x_cmd[:, self.k_log] = x_cmd[:] # Input of the WBC block (reference pos/ori/linvel/angvel) self.log_f_cmd[:, self.k_log] = f_cmd[:] # Input of the WBC block (contact forces) - self.log_f_out[:, self.k_log] = f_cmd[:] + np.array(self.x[6:]) # Input of the WBC block (contact forces) + self.log_f_out[:, self.k_log] = f_with_delta[:, 0] # Input of the WBC block (contact forces) self.log_x[0:3, self.k_log] = self.qint[0:3] # Output of the WBC block (pos) self.log_x[3:6, self.k_log] = quaternionToRPY(self.qint[3:7]).ravel() # Output of the WBC block (ori) oMb = pin.SE3(pin.Quaternion(np.array([self.qint[3:7]]).transpose()), np.zeros((3, 1))) @@ -155,7 +161,10 @@ class controller(): self.log_x[9:12, self.k_log] = oMb.rotation @ self.vint[3:6, 0] # Output of the WBC block (ang vel) self.log_q[0:3, self.k_log] = q[0:3, 0] # Input of the WBC block (current pos) self.log_q[3:6, self.k_log] = quaternionToRPY(q[3:7, 0]).ravel() # Input of the WBC block (current ori) - self.log_dq[:, self.k_log] = dq[0:6, 0] # Input of the WBC block (current linvel/angvel) + self.log_dq[:6, self.k_log] = dq[0:6, 0] # Input of the WBC block (current linvel/angvel) + + self.log_q[6:, self.k_log] = q[7:, 0].copy() + self.log_dq[6:, self.k_log] = dq[6:, 0].copy() self.log_x_ref_invkin[:, self.k_log] = self.invKin.x_ref[:, 0] # Position task reference # Position task state (reconstruct with pin.forwardKinematics) @@ -324,6 +333,7 @@ class controller(): else: plt.subplot(3, 4, index12[i], sharex=ax0) plt.plot(t_range, self.log_qdes[i, :], color='r', linewidth=3) + plt.plot(t_range, self.log_q[6+i, :], color='b', linewidth=3) plt.legend(["Qdes"], prop={'size': 8}) plt.show(block=True) diff --git a/src/QPWBC.cpp b/src/QPWBC.cpp index 38d42e409c50593f41b052d5cbff8b555f95630c..643161dc44c09a2c56da62fe3462ed492a3cdfbd 100644 --- a/src/QPWBC.cpp +++ b/src/QPWBC.cpp @@ -11,7 +11,7 @@ QPWBC::QPWBC() { int a[9] = {0, 1, 2, 3, 0, 1, 2, 3, 4}; int b[9] = {0, 0, 1, 1, 2, 2, 2, 2, 2}; double c[9] = {1.0, -1.0, 1.0, -1.0, -mu, -mu, -mu, -mu, -1}; - for (int i = 0; i < 8; i++) { + for (int i = 0; i <= 8; i++) { SC(a[i], b[i]) = -c[i]; } @@ -228,6 +228,10 @@ int QPWBC::call_solver() { data->l = v_NK_low; // dense array for lower bound (size m) data->u = v_NK_up; // dense array for upper bound (size m) + /*std::cout << data->l << std::endl; + std::cout << data->A << std::endl; + std::cout << data->u << std::endl;*/ + // Tuning parameters of the OSQP solver // settings->rho = 0.1f; // settings->sigma = 1e-6f; @@ -256,6 +260,10 @@ int QPWBC::call_solver() { // Update Q matrix of the OSQP solver osqp_update_lin_cost(workspce, &Q[0]); + // Update upper bound of the OSQP solver + osqp_update_upper_bound(workspce, &v_NK_up[0]); + osqp_update_lower_bound(workspce, &v_NK_low[0]); + } // Run the solver to solve the QP problem @@ -299,7 +307,8 @@ Eigen::MatrixXd QPWBC::get_H() { return Hxd; } -int QPWBC::run(const Eigen::MatrixXd &M, const Eigen::MatrixXd &Jc, const Eigen::MatrixXd &f_cmd, const Eigen::MatrixXd &RNEA) { +int QPWBC::run(const Eigen::MatrixXd &M, const Eigen::MatrixXd &Jc, const Eigen::MatrixXd &f_cmd, const Eigen::MatrixXd &RNEA, + const Eigen::MatrixXd &k_contact) { /* Run one iteration of the whole WBC QP problem by calling all the necessary functions (data retrieval, update of constraint matrices, update of the solver, running the solver, retrieving result) @@ -309,12 +318,14 @@ int QPWBC::run(const Eigen::MatrixXd &M, const Eigen::MatrixXd &Jc, const Eigen: - Jc (Eigen::MatrixXd): Jacobian of contact points - f_cmd (Eigen::MatrixXd): reference contact forces coming from the MPC - RNEA (Eigen::MatrixXd): joint torques according to the current state of the system and the desired joint accelerations + - k_contact (Eigen::MatrixXd): nb of iterations since contact has been enabled for each foot */ // Create the constraint and weight matrices used by the QP solver // Minimize x^T.P.x + 2 x^T.Q with constraints M.X == N and L.X <= K if (not initialized) { create_matrices(); + // std::cout << G << std::endl; } // Compute the different matrices involved in the box QP @@ -323,6 +334,32 @@ int QPWBC::run(const Eigen::MatrixXd &M, const Eigen::MatrixXd &Jc, const Eigen: // Update P and Q matrices of the cost function xT P x + 2 xT g update_PQ(); + const double Nz_max = 20.0; + Eigen::Matrix<double, 20, 1> Gf = G * f_cmd; + + for (int i = 0; i < G.rows(); i++) { + v_NK_low[i] = - Gf(i, 0); + v_NK_up[i] = - Gf(i, 0) + Nz_max; + } + + const double k_max = 15.0; + for (int i = 0; i < 4; i++) { + if (k_contact(0, i) < k_max) { + v_NK_up[5*i+4] -= Nz_max * (1.0 - k_contact(0, i) / k_max); + } + /*else if (k_contact(0, i) == (k_max+10)) + { + //char t_char[1] = {'M'}; + //cc_print( (data->A)->m, (data->A)->n, (data->A)->nzmax, (data->A)->i, (data->A)->p, (data->A)->x, t_char); + std::cout << " ### " << k_contact(0, i) << std::endl; + + for (int i = 0; i < data->m; i++) { + std::cout << data->l[i] << " | " << data->u[i] << " | " << f_cmd(i, 0) << std::endl; + } + }*/ + + } + // Create an initial guess and call the solver to solve the QP problem call_solver();