Quad-SDK
Loading...
Searching...
No Matches
quad_nlp.h
1// Copyright (C) 2005, 2007 International Business Machines and others.
2// All Rights Reserved.
3// This code is published under the Eclipse Public License.
4//
5// Authors: Carl Laird, Andreas Waechter IBM 2005-08-09
6
7#ifndef __quadNLP_HPP__
8#define __quadNLP_HPP__
9
10#include <quad_msgs/RobotPlanDiagnostics.h>
11#include <sys/resource.h>
12
13#include <Eigen/Dense>
14#include <Eigen/Sparse>
15#include <IpIpoptData.hpp>
16#include <grid_map_core/grid_map_core.hpp>
17#include <numeric>
18#include <unordered_map>
19#include <vector>
20
21#include "IpTNLP.hpp"
22#include "nmpc_controller/gen/eval_g_a1.h"
23#include "nmpc_controller/gen/eval_g_leg_complex.h"
24#include "nmpc_controller/gen/eval_g_leg_complex_to_simple.h"
25#include "nmpc_controller/gen/eval_g_leg_simple.h"
26#include "nmpc_controller/gen/eval_g_leg_simple_to_complex.h"
27#include "nmpc_controller/gen/eval_g_spirit.h"
28#include "nmpc_controller/gen/eval_hess_g_a1.h"
29#include "nmpc_controller/gen/eval_hess_g_leg_complex.h"
30#include "nmpc_controller/gen/eval_hess_g_leg_complex_to_simple.h"
31#include "nmpc_controller/gen/eval_hess_g_leg_simple.h"
32#include "nmpc_controller/gen/eval_hess_g_leg_simple_to_complex.h"
33#include "nmpc_controller/gen/eval_hess_g_spirit.h"
34#include "nmpc_controller/gen/eval_jac_g_a1.h"
35#include "nmpc_controller/gen/eval_jac_g_leg_complex.h"
36#include "nmpc_controller/gen/eval_jac_g_leg_complex_to_simple.h"
37#include "nmpc_controller/gen/eval_jac_g_leg_simple.h"
38#include "nmpc_controller/gen/eval_jac_g_leg_simple_to_complex.h"
39#include "nmpc_controller/gen/eval_jac_g_spirit.h"
40#include "quad_utils/function_timer.h"
41#include "quad_utils/quad_kd.h"
42
43using namespace Ipopt;
44
45enum SystemID {
46 SPIRIT,
47 A1,
48 SIMPLE_TO_SIMPLE,
49 SIMPLE_TO_COMPLEX,
50 COMPLEX_TO_COMPLEX,
51 COMPLEX_TO_SIMPLE
52};
53
54enum FunctionID { FUNC, JAC, HESS };
55
56// Struct for storing parameter information
57struct NLPConfig {
58 int x_dim_complex = 0;
59 int u_dim_complex = 0;
60 int g_dim_complex = 0;
61 int x_dim_cost_complex = 0;
62 int u_dim_cost_complex = 0;
63 int x_dim_simple = 0;
64 int u_dim_simple = 0;
65 int g_dim_simple = 0;
66 int x_dim_cost_simple = 0;
67 int u_dim_cost_simple = 0;
68 int x_dim_null = 0;
69 int u_dim_null = 0;
70
71 Eigen::VectorXd Q_complex;
72 Eigen::VectorXd R_complex;
73 Eigen::VectorXd x_min_complex;
74 Eigen::VectorXd x_max_complex;
75 Eigen::VectorXd x_min_complex_soft;
76 Eigen::VectorXd x_max_complex_soft;
77 Eigen::VectorXd u_min_complex;
78 Eigen::VectorXd u_max_complex;
79 Eigen::VectorXd g_min_complex;
80 Eigen::VectorXd g_max_complex;
81};
82
83// Struct for storing diagnostic information
85 double compute_time, cost;
86 int iterations, horizon_length;
87 Eigen::VectorXi complexity_schedule;
88 Eigen::VectorXd element_times;
89
90 void loadDiagnosticsMsg(quad_msgs::RobotPlanDiagnostics &msg) {
91 msg.compute_time = compute_time;
92 msg.cost = cost;
93 msg.iterations = iterations;
94 msg.horizon_length = horizon_length;
95
96 msg.complexity_schedule.resize(complexity_schedule.size());
97 msg.element_times.resize(element_times.size());
98 for (int i = 0; i < complexity_schedule.size(); i++) {
99 msg.complexity_schedule.at(i) = complexity_schedule[i];
100 msg.element_times.at(i) = element_times[i];
101 }
102 }
103};
104
105class quadNLP : public TNLP {
106 public:
109
112
115
116 // QuadKD object for kinematics calculations
117 std::shared_ptr<quad_utils::QuadKD> quadKD_;
118
119 // Horizon length, state dimension, input dimension, and constraints dimension
120 int N_, g_relaxed_;
121
122 // Number of states in different components
123 const int n_body_ = 12, n_foot_ = 24, n_joints_ = 24, n_tail_ = 4,
124 m_body_ = 12, m_foot_ = 24, m_tail_ = 2;
125
127 Eigen::VectorXi n_vec_, n_slack_vec_, m_vec_, g_vec_, g_slack_vec_,
128 n_cost_vec_, m_cost_vec_;
129
132
134 const bool always_constrain_feet_ = false;
135
137 const bool use_terrain_constraint_ = false;
138
140 const bool remember_complex_elements_ = true;
141
142 const grid_map::InterpolationMethods interp_type_ =
143 grid_map::InterpolationMethods::INTER_LINEAR;
144
146 std::vector<std::vector<std::string>> constr_names_;
147
149 int n_vars_, n_vars_primal_, n_vars_slack_, n_constraints_;
150
152 int n_null_, m_null_;
153
155 Eigen::VectorXd x_null_nom_;
156
159 static const int num_sys_id_ = 6;
160
163 static const int num_func_id_ = 3;
164
165 // Scale factor for Q and R
166 double Q_temporal_factor_, R_temporal_factor_;
167
168 // Feet location from feet to body COM in world frame
169 Eigen::MatrixXd foot_pos_body_;
170
171 // Foot locations in world frame
172 Eigen::MatrixXd foot_pos_world_;
173
174 // Foot velocities in world frame
175 Eigen::MatrixXd foot_vel_world_;
176
177 // Step length
178 double dt_;
179
180 // Friction coefficient
181 double mu_;
182
184 const double mass_ = 13.3;
185
187 const double foot_mass_ = 0.01;
188
190 const double grav_ = 9.81;
191
193 const int num_feet_ = 4;
194
196 grid_map::GridMap terrain_;
197
198 Eigen::VectorXd g_min_complex_soft_, g_max_complex_soft_;
199
200 // Ground height structure for the height bounds
201 Eigen::MatrixXd ground_height_;
202
203 // Initial guess
204 Eigen::VectorXd w0_, z_L0_, z_U0_, lambda0_, g0_;
205
207 double mu0_;
208
211
212 // State reference for computing cost
213 Eigen::MatrixXd x_reference_;
214
215 // Current state
216 Eigen::VectorXd x_current_;
217
218 // Feet contact sequence
219 Eigen::MatrixXi contact_sequence_;
220
221 // Nonzero entrance number in the constraint jacobian matrix
222 int nnz_jac_g_;
223
224 std::vector<int> first_step_idx_jac_g_;
225
226 // Nonzero entrance row and column in the constraint jacobian matrix
227 Eigen::VectorXi iRow_jac_g_, jCol_jac_g_;
228
229 // Nonzero entrance number in the pure hessian matrix (exclude the side
230 // jacobian part)
231 int nnz_h_, nnz_compact_h_;
232
233 // Vector of nnz in each block of the NLP Hessian
234 Eigen::VectorXi nnz_step_jac_g_, nnz_step_hess_;
235
236 std::vector<int> first_step_idx_hess_g_;
237
238 // Nonzero entrance row and column in the pure hessian matrix (exclude the
239 // side jacobian part)
240 Eigen::VectorXi iRow_h_, jCol_h_, iRow_compact_h_, jCol_compact_h_;
241
242 // Penalty on panic variables and constraints
243 double panic_weights_, constraint_panic_weights_;
244
245 // Time duration to the next plan index
246 double first_element_duration_;
247
250
253
255 Eigen::VectorXi fe_idxs_, u_idxs_, x_idxs_, slack_state_var_idxs_,
256 slack_constraint_var_idxs_, primal_constraint_idxs_,
257 slack_var_constraint_idxs_, dynamic_jac_var_idxs_,
258 relaxed_dynamic_jac_var_idxs_, panic_jac_var_idxs_,
259 dynamic_hess_var_idxs_, cost_idxs_, relaxed_constraint_idxs_;
260
263 constraint_panic_weights_vec_;
264
266 Eigen::VectorXi sys_id_schedule_;
267
269 Eigen::MatrixXi nnz_mat_, nrow_mat_, ncol_mat_, first_step_idx_mat_,
270 relaxed_nnz_mat_;
271
273 std::vector<std::vector<Eigen::VectorXi>> iRow_mat_, jCol_mat_;
274 std::vector<std::vector<Eigen::VectorXi>> iRow_mat_relaxed_,
275 jCol_mat_relaxed_, relaxed_idx_in_full_sparse_;
276
278 std::vector<casadi_int> nnz_jac_g_vec_, nnz_h_vec_;
279
280 // Maps for casadi functions
281 std::vector<std::vector<decltype(eval_g_spirit) *>> eval_vec_;
282 std::vector<std::vector<decltype(eval_g_spirit_work) *>> eval_work_vec_;
283 std::vector<std::vector<decltype(eval_g_spirit_incref) *>> eval_incref_vec_;
284 std::vector<std::vector<decltype(eval_g_spirit_decref) *>> eval_decref_vec_;
285 std::vector<std::vector<decltype(eval_g_spirit_checkout) *>>
286 eval_checkout_vec_;
287 std::vector<std::vector<decltype(eval_g_spirit_release) *>> eval_release_vec_;
288 std::vector<std::vector<decltype(eval_g_spirit_sparsity_out) *>>
289 eval_sparsity_vec_;
290
292 quadNLP(SystemID default_system, int N, double dt, double mu,
293 double panic_weights, double constraint_panic_weights,
294 double Q_temporal_factor, double R_temporal_factor,
295 const Eigen::VectorXi &fixed_complexity_schedule,
296 const NLPConfig &config);
297
302 quadNLP(const quadNLP &nlp);
303
305 virtual ~quadNLP();
306
310 virtual bool get_nlp_info(Index &n, Index &m, Index &nnz_jac_g,
311 Index &nnz_h_lag, IndexStyleEnum &index_style);
312
314 bool get_bounds_info_single_complex_fe(int i, Eigen::VectorXd &x_lb,
315 Eigen::VectorXd &x_ub,
316 Eigen::VectorXd &u_lb,
317 Eigen::VectorXd &u_ub,
318 Eigen::VectorXd &g_l,
319 Eigen::VectorXd &g_u);
320
322 virtual bool get_bounds_info(Index n, Number *x_l, Number *x_u, Index m,
323 Number *g_l, Number *g_u);
324
326 virtual bool get_starting_point(Index n, bool init_x, Number *x, bool init_z,
327 Number *z_L, Number *z_U, Index m,
328 bool init_lambda, Number *lambda);
329
331 virtual bool eval_f(Index n, const Number *x, bool new_x, Number &obj_value);
332
334 virtual bool eval_grad_f(Index n, const Number *x, bool new_x,
335 Number *grad_f);
336
338 Eigen::VectorXd eval_g_single_complex_fe(int i, const Eigen::VectorXd &x0,
339 const Eigen::VectorXd &u,
340 const Eigen::VectorXd &x1);
341
343 virtual bool eval_g(Index n, const Number *x, bool new_x, Index m, Number *g);
344
349 virtual bool eval_jac_g(Index n, const Number *x, bool new_x, Index m,
350 Index nele_jac, Index *iRow, Index *jCol,
351 Number *values);
352
353 virtual void compute_nnz_jac_g();
354
359 virtual bool eval_h(Index n, const Number *x, bool new_x, Number obj_factor,
360 Index m, const Number *lambda, bool new_lambda,
361 Index nele_hess, Index *iRow, Index *jCol,
362 Number *values);
363
364 virtual void compute_nnz_h();
365
368 virtual void finalize_solution(SolverReturn status, Index n, const Number *x,
369 const Number *z_L, const Number *z_U, Index m,
370 const Number *g, const Number *lambda,
371 Number obj_value, const IpoptData *ip_data,
372 IpoptCalculatedQuantities *ip_cq);
373
374 virtual void update_initial_guess(const quadNLP &nlp_prev, int shift_idx);
375
376 virtual void update_solver(
377 const Eigen::VectorXd &initial_state, const Eigen::MatrixXd &ref_traj,
378 const Eigen::MatrixXd &foot_positions,
379 const std::vector<std::vector<bool>> &contact_schedule,
380 const Eigen::VectorXi &adaptive_complexity_schedule,
381 const Eigen::VectorXd &ground_height,
382 const double &first_element_duration_, int plan_index_diff,
383 const bool &init);
384
385 void update_structure();
386
387 void get_lifted_trajectory(Eigen::MatrixXd &state_traj_lifted,
388 Eigen::MatrixXd &control_traj_lifted);
389
390 void get_heuristic_trajectory(Eigen::MatrixXd &state_traj_heuristic,
391 Eigen::MatrixXd &control_traj_heuristic);
392
393 // Get the idx-th state variable from decision variable
394 template <typename T>
395 inline Eigen::Block<T> get_primal_state_var(T &decision_var,
396 const int &idx) const {
397 return decision_var.block(x_idxs_[idx], 0, n_vec_[idx], 1);
398 }
399
400 // Get the idx-th body state variable from decision variable
401 template <typename T>
402 inline Eigen::Block<T> get_primal_body_state_var(T &decision_var,
403 const int &idx) const {
404 return decision_var.block(x_idxs_[idx], 0, n_body_, 1);
405 }
406
407 // Get the idx-th foot state variable from decision variable
408 template <typename T>
409 inline Eigen::Block<T> get_primal_foot_state_var(T &decision_var,
410 const int &idx) const {
411 return decision_var.block(x_idxs_[idx] + n_body_, 0, n_foot_, 1);
412 }
413
414 // Get the idx-th joint state variable from decision variable
415 template <typename T>
416 inline Eigen::Block<T> get_primal_joint_state_var(T &decision_var,
417 const int &idx) const {
418 return decision_var.block(x_idxs_[idx] + n_body_ + n_foot_, 0, n_joints_,
419 1);
420 }
421
422 // Get the idx-th control variable from decision variable
423 template <typename T>
424 inline Eigen::Block<T> get_primal_control_var(T &decision_var,
425 const int &idx) const {
426 return decision_var.block(u_idxs_[idx], 0, m_vec_[idx], 1);
427 }
428
429 // Get the idx-th body control variable from decision variable
430 template <typename T>
431 inline Eigen::Block<T> get_primal_body_control_var(T &decision_var,
432 const int &idx) const {
433 return decision_var.block(u_idxs_[idx], 0, m_body_, 1);
434 }
435
436 // Get the idx-th foot control variable from decision variable
437 template <typename T>
438 inline Eigen::Block<T> get_primal_foot_control_var(T &decision_var,
439 const int &idx) const {
440 return decision_var.block(u_idxs_[idx] + m_body_, 0, m_foot_, 1);
441 }
442
443 // Get the idx-th panic variable (for (idx+1)-th state variable) from decision
444 // variable
445 template <typename T>
446 inline Eigen::Block<T> get_slack_state_var(T &decision_var,
447 const int &idx) const {
448 return decision_var.block(slack_state_var_idxs_[idx], 0,
449 2 * n_slack_vec_[idx], 1);
450 }
451
452 // Get the idx-th panic variable (for (idx+1)-th constraint) from decision
453 // variable
454 template <typename T>
455 inline Eigen::Block<T> get_slack_constraint_var(T &decision_var,
456 const int &idx) const {
457 return decision_var.block(slack_constraint_var_idxs_[idx], 0,
458 2 * g_slack_vec_[idx], 1);
459 }
460
461 // Get the idx-th constraint from constraint values
462 template <typename T>
463 inline Eigen::Block<T> get_primal_constraint_vals(T &constraint_vals,
464 const int &idx) const {
465 return constraint_vals.block(primal_constraint_idxs_[idx], 0, g_vec_[idx],
466 1);
467 }
468
469 // Get the idx-th relaxed constraints from constraint values
470 template <typename T>
471 inline Eigen::Block<T> get_relaxed_primal_constraint_vals(
472 T &constraint_vals, const int &idx) const {
473 return constraint_vals.block(relaxed_constraint_idxs_[idx], 0,
474 2 * g_slack_vec_[idx], 1);
475 }
476
477 // Get the idx-th panic constraint (for (idx+1)-th state variable) from
478 // constraint variable
479 template <typename T>
480 inline Eigen::Block<T> get_slack_constraint_vals(T &constraint_vals,
481 const int &idx) const {
482 return constraint_vals.block(slack_var_constraint_idxs_[idx], 0,
483 2 * n_slack_vec_[idx], 1);
484 }
485
486 // Get the idx-th dynamic constraint related decision variable (idx and
487 // idx+1-th state and idx-th control)
488 template <typename T>
489 inline Eigen::Block<T> get_dynamic_var(T &decision_var,
490 const int &idx) const {
491 return decision_var.block(fe_idxs_[idx], 0,
492 n_vec_[idx] + m_vec_[idx] + n_vec_[idx + 1], 1);
493 }
494
495 // Get the idx-th dynamic constraint related jacobian nonzero entry
496 template <typename T>
497 inline Eigen::Block<T> get_dynamic_jac_var(T &jacobian_var,
498 const int &idx) const {
499 return jacobian_var.block(dynamic_jac_var_idxs_[idx], 0,
500 nnz_mat_(sys_id_schedule_[idx], JAC), 1);
501 }
502
503 // Get the idx-th dynamic constraint related jacobian nonzero entry
504 template <typename T>
505 inline Eigen::Block<T> get_relaxed_dynamic_jac_var(T &jacobian_var,
506 const int &idx) const {
507 return jacobian_var.block(
508 relaxed_dynamic_jac_var_idxs_[idx], 0,
509 2 * (relaxed_nnz_mat_(sys_id_schedule_[idx], JAC) + g_slack_vec_[idx]),
510 1);
511 }
512
513 // Get the idx-th panic constraint jacobian (for (idx+1)-th state variable)
514 // nonzero entry
515 template <typename T>
516 inline Eigen::Block<T> get_slack_jac_var(T &jacobian_var,
517 const int &idx) const {
518 return jacobian_var.block(panic_jac_var_idxs_[idx], 0,
519 4 * n_slack_vec_[idx], 1);
520 }
521
522 // Get the idx-th dynamic constraint related hessian nonzero entry
523 template <typename T>
524 inline Eigen::Block<T> get_dynamic_hess_var(T &hessian_var,
525 const int &idx) const {
526 return hessian_var.block(dynamic_hess_var_idxs_[idx], 0,
527 nnz_mat_(sys_id_schedule_[idx], HESS), 1);
528 }
529
530 // Get the idx-th state cost hessian nonzero entry
531 template <typename T>
532 inline Eigen::Block<T> get_state_cost_hess_var(T &hessian_var,
533 const int &idx) const {
534 return hessian_var.block(cost_idxs_[idx], 0, n_cost_vec_[idx], 1);
535 }
536
537 // Get the idx-th control cost hessian nonzero entry
538 template <typename T>
539 inline Eigen::Block<T> get_control_cost_hess_var(T &hessian_var,
540 const int &idx) const {
541 return hessian_var.block(cost_idxs_[idx] + n_cost_vec_[idx], 0,
542 m_cost_vec_[idx], 1);
543 }
544
552 inline int get_primal_constraint_idx(int idx) const {
553 return primal_constraint_idxs_[idx];
554 }
555
563 inline int get_slack_var_constraint_idx(int idx) const {
564 return slack_var_constraint_idxs_[idx];
565 }
566
574 inline int get_relaxed_constraint_idx(int idx) const {
575 return relaxed_constraint_idxs_[idx];
576 }
577
585 inline int get_primal_idx(int idx) const { return fe_idxs_[idx]; }
586
594 inline int get_primal_state_idx(int idx) const { return x_idxs_[idx]; }
595
603 inline int get_primal_control_idx(int idx) const { return u_idxs_[idx]; }
604
612 inline int get_slack_state_idx(int idx) const {
613 return slack_state_var_idxs_[idx];
614 }
615
623 inline int get_slack_constraint_var_idx(int idx) const {
624 return slack_constraint_var_idxs_[idx];
625 }
626
630 void loadCasadiFuncs();
631
635 void loadConstraintNames();
636
638
639 private:
651
652 quadNLP &operator=(const quadNLP &);
654};
655
656#endif
Definition quad_nlp.h:105
virtual ~quadNLP()
Definition quad_nlp.cpp:142
int get_primal_state_idx(int idx) const
Return the first index of the decision variable vector corresponding to the given finite element's st...
Definition quad_nlp.h:594
virtual bool eval_grad_f(Index n, const Number *x, bool new_x, Number *grad_f)
Definition quad_nlp.cpp:452
const double mass_
Mass of the platform (set to zero to ignore nominal ff)
Definition quad_nlp.h:184
virtual bool get_starting_point(Index n, bool init_x, Number *x, bool init_z, Number *z_L, Number *z_U, Index m, bool init_lambda, Number *lambda)
Definition quad_nlp.cpp:373
const bool use_terrain_constraint_
Boolean for whether to include the terrain in the foot height constraint.
Definition quad_nlp.h:137
double mu0_
Friction coefficient.
Definition quad_nlp.h:207
static const int num_sys_id_
Definition quad_nlp.h:159
virtual bool eval_h(Index n, const Number *x, bool new_x, Number obj_factor, Index m, const Number *lambda, bool new_lambda, Index nele_hess, Index *iRow, Index *jCol, Number *values)
Definition quad_nlp.cpp:950
virtual bool eval_f(Index n, const Number *x, bool new_x, Number &obj_value)
Definition quad_nlp.cpp:397
SystemID default_system_
Default system used for NLP (if not mixed complexity)
Definition quad_nlp.h:114
virtual bool eval_g(Index n, const Number *x, bool new_x, Index m, Number *g)
Definition quad_nlp.cpp:585
int n_vars_
Number of variables , primal variables, slack variables, and constraints.
Definition quad_nlp.h:149
std::vector< casadi_int > nnz_jac_g_vec_
Vector of nonzero entries for constraint Jacobian and Hessian.
Definition quad_nlp.h:278
Eigen::MatrixXi nnz_mat_
Matrix of function info.
Definition quad_nlp.h:269
const int num_feet_
Number of feet.
Definition quad_nlp.h:193
const bool apply_slack_to_complex_constr_
Boolean for whether to apply panic variables for complex constraints.
Definition quad_nlp.h:131
int get_slack_var_constraint_idx(int idx) const
Return the first index of the slack constraint vector corresponding to the given finite element.
Definition quad_nlp.h:563
Eigen::VectorXd eval_g_single_complex_fe(int i, const Eigen::VectorXd &x0, const Eigen::VectorXd &u, const Eigen::VectorXd &x1)
Definition quad_nlp.cpp:512
void loadCasadiFuncs()
Load the casadi function pointers into map member vars.
Definition quad_nlp_utils.cpp:10
int get_slack_constraint_var_idx(int idx) const
Return the first index of the decision variable vector corresponding to the slack variable for the gi...
Definition quad_nlp.h:623
int get_primal_idx(int idx) const
Return the first index of the decision variable vector corresponding to the given finite element.
Definition quad_nlp.h:585
Eigen::VectorXi adaptive_complexity_schedule_
Vector of ids for adaptive model complexity schedule.
Definition quad_nlp.h:249
std::vector< std::vector< Eigen::VectorXi > > iRow_mat_
Matrix of function sparsity data.
Definition quad_nlp.h:273
virtual bool eval_jac_g(Index n, const Number *x, bool new_x, Index m, Index nele_jac, Index *iRow, Index *jCol, Number *values)
Definition quad_nlp.cpp:673
Eigen::VectorXi fe_idxs_
Vector of indices for relevant quantities.
Definition quad_nlp.h:255
int n_null_
Number of state and control variables added in complex model.
Definition quad_nlp.h:152
bool get_bounds_info_single_complex_fe(int i, Eigen::VectorXd &x_lb, Eigen::VectorXd &x_ub, Eigen::VectorXd &u_lb, Eigen::VectorXd &u_ub, Eigen::VectorXd &g_l, Eigen::VectorXd &g_u)
Definition quad_nlp.cpp:165
NLPDiagnostics diagnostics_
Diagnostics struct for gathering metadata.
Definition quad_nlp.h:108
Eigen::VectorXd x_null_nom_
Nominal null state variables.
Definition quad_nlp.h:155
int get_primal_constraint_idx(int idx) const
Return the first index of the constraint vector corresponding to the given finite element.
Definition quad_nlp.h:552
grid_map::GridMap terrain_
Terrain map.
Definition quad_nlp.h:196
Eigen::VectorXi n_vec_
Vectors of state and constraint dimension for each finite element.
Definition quad_nlp.h:127
const double foot_mass_
Mass of the feet (as modeled in casadi)
Definition quad_nlp.h:187
bool warm_start_
Whether warm start.
Definition quad_nlp.h:210
virtual void finalize_solution(SolverReturn status, Index n, const Number *x, const Number *z_L, const Number *z_U, Index m, const Number *g, const Number *lambda, Number obj_value, const IpoptData *ip_data, IpoptCalculatedQuantities *ip_cq)
Definition quad_nlp.cpp:1142
Eigen::ArrayXi relaxed_primal_constraint_idxs_in_element_
Indices of relaxed constraints.
Definition quad_nlp.h:262
const double grav_
Gravity constant.
Definition quad_nlp.h:190
NLPConfig config_
Config struct for storing meta parameters.
Definition quad_nlp.h:111
int get_slack_state_idx(int idx) const
Return the first index of the decision variable vector corresponding to the slack variable for the gi...
Definition quad_nlp.h:612
Eigen::VectorXi sys_id_schedule_
Vector of system ids.
Definition quad_nlp.h:266
const bool always_constrain_feet_
Boolean for whether to allow modifications of foot trajectory.
Definition quad_nlp.h:134
std::vector< std::vector< std::string > > constr_names_
Map for constraint names.
Definition quad_nlp.h:146
int get_primal_control_idx(int idx) const
Return the first index of the decision variable vector corresponding to the given finite element's co...
Definition quad_nlp.h:603
void loadConstraintNames()
Load the constraint names for debugging.
Definition quad_nlp_utils.cpp:277
int get_relaxed_constraint_idx(int idx) const
Return the first index of the slack constraint vector corresponding to the given finite element.
Definition quad_nlp.h:574
const bool remember_complex_elements_
Boolean for whether to include the terrain in the foot height constraint.
Definition quad_nlp.h:140
virtual bool get_nlp_info(Index &n, Index &m, Index &nnz_jac_g, Index &nnz_h_lag, IndexStyleEnum &index_style)
Definition quad_nlp.cpp:145
virtual bool get_bounds_info(Index n, Number *x_l, Number *x_u, Index m, Number *g_l, Number *g_u)
Definition quad_nlp.cpp:221
Eigen::VectorXi fixed_complexity_schedule_
Vector of ids for fixed model complexity schedule.
Definition quad_nlp.h:252
static const int num_func_id_
Definition quad_nlp.h:163
Definition quad_nlp.h:57
Definition quad_nlp.h:84