acados_solver_ros2
main
Acados-based NMPC controllers for ROS2 control
|
Functions | |
template<typename Derived > | |
bool | set_cost_field (AcadosSolver &solver, unsigned int stage, const std::string &field, Eigen::EigenBase< Derived > &value) |
Generic setter for the cost. More... | |
bool | set_cost_Vx (AcadosSolver &solver, unsigned int stage, Eigen::MatrixXd &Vx) |
Set the Vx matrix used for 'LINEAR_LS' cost. More... | |
bool | set_cost_Vu (AcadosSolver &solver, unsigned int stage, Eigen::MatrixXd &Vu) |
Set the Vu matrix used for 'LINEAR_LS' cost. More... | |
bool | set_cost_Vz (AcadosSolver &solver, unsigned int stage, Eigen::MatrixXd &Vz) |
Set the Vz matrix used for 'LINEAR_LS' cost. More... | |
bool | set_cost_W (AcadosSolver &solver, unsigned int stage, Eigen::MatrixXd &W) |
Set the W cost matrix used for 'LINEAR_LS' cost. More... | |
bool | set_cost_y_ref (AcadosSolver &solver, unsigned int stage, Eigen::VectorXd &y_ref) |
Set the y_ref vector for a given stage. More... | |
template<typename Derived > | |
bool | set_constraint_field (AcadosSolver &solver, unsigned int stage, const std::string &field, Eigen::EigenBase< Derived > &value) |
Generic setter for the constraints. More... | |
bool | set_const_C (AcadosSolver &solver, unsigned int stage, Eigen::MatrixXd &C) |
Set the C matrix used by polytopic constraints. More... | |
bool | set_const_D (AcadosSolver &solver, unsigned int stage, Eigen::MatrixXd &D) |
Set the D matrix used by polytopic constraints. More... | |
bool | set_const_g_min (AcadosSolver &solver, unsigned int stage, Eigen::VectorXd &g_min) |
Set the lower bound g_min used by polytopic constraints. More... | |
bool | set_const_g_max (AcadosSolver &solver, unsigned int stage, Eigen::VectorXd &g_max) |
Set the upper bound g_max used by polytopic constraints. More... | |
bool | set_const_h_min (AcadosSolver &solver, unsigned int stage, Eigen::VectorXd &h_min) |
Set the lower bound h_min used by non-linear constraints. More... | |
bool | set_const_h_max (AcadosSolver &solver, unsigned int stage, Eigen::VectorXd &h_max) |
Set the upper bound h_max used by non-linear constraints. More... | |
template<typename T > | |
void | unsafe_get_stats_field (AcadosSolver &solver, const std::string &field, T &value) |
Read a given field from the solver stats (solve must be called before...) More... | |
double | get_stats_cost_value (AcadosSolver &solver) |
Retrieve the current cost value. More... | |
int | get_stats_sqp_iter (AcadosSolver &solver) |
Retrieve the SQP iteration at the last solve() call. More... | |
double | get_stats_cpu_time (AcadosSolver &solver) |
Retrieve the CPU time needed for the last solve() call. More... | |
bool acados::utils::set_cost_field | ( | AcadosSolver & | solver, |
unsigned int | stage, | ||
const std::string & | field, | ||
Eigen::EigenBase< Derived > & | value | ||
) |
Generic setter for the cost.
ocp_nlp_cost_model_set
in acados/interfaces/acados_c/ocp_nlp_interface.c (https://github.com/acados) solver | Acados solver C++ wrapper handle |
stage | Stage in [0;N] |
field | Name of the field |
value | Matrix or vector containing the data (not modified) |
bool acados::utils::set_cost_Vx | ( | AcadosSolver & | solver, |
unsigned int | stage, | ||
Eigen::MatrixXd & | Vx | ||
) |
Set the Vx matrix used for 'LINEAR_LS' cost.
solver | Acados solver C++ wrapper handle |
stage | Stage in [0;N]. |
Vx | Matrix Vx |
bool acados::utils::set_cost_Vu | ( | AcadosSolver & | solver, |
unsigned int | stage, | ||
Eigen::MatrixXd & | Vu | ||
) |
Set the Vu matrix used for 'LINEAR_LS' cost.
solver | Acados solver C++ wrapper handle |
stage | Stage in [0;N]. |
Vu | Matrix Vu |
bool acados::utils::set_cost_Vz | ( | AcadosSolver & | solver, |
unsigned int | stage, | ||
Eigen::MatrixXd & | Vz | ||
) |
Set the Vz matrix used for 'LINEAR_LS' cost.
solver | Acados solver C++ wrapper handle |
stage | Stage in [0;N]. |
Vz | Matrix Vz |
bool acados::utils::set_cost_W | ( | AcadosSolver & | solver, |
unsigned int | stage, | ||
Eigen::MatrixXd & | W | ||
) |
Set the W cost matrix used for 'LINEAR_LS' cost.
solver | Acados solver C++ wrapper handle |
stage | Stage in [0;N]. |
W | Matrix W |
bool acados::utils::set_cost_y_ref | ( | AcadosSolver & | solver, |
unsigned int | stage, | ||
Eigen::VectorXd & | y_ref | ||
) |
Set the y_ref vector for a given stage.
solver | Acados solver C++ wrapper handle |
stage | Stage in [0;N]. |
y_ref | Reference vector |
bool acados::utils::set_constraint_field | ( | AcadosSolver & | solver, |
unsigned int | stage, | ||
const std::string & | field, | ||
Eigen::EigenBase< Derived > & | value | ||
) |
Generic setter for the constraints.
ocp_nlp_constraints_model_set
in acados/interfaces/acados_c/ocp_nlp_interface.c (https://github.com/acados) solver | Acados solver C++ wrapper handle |
stage | Stage in [0;N] |
field | Name of the field |
value | Matrix or vector containing the data (not modified, ) |
bool acados::utils::set_const_C | ( | AcadosSolver & | solver, |
unsigned int | stage, | ||
Eigen::MatrixXd & | C | ||
) |
Set the C matrix used by polytopic constraints.
solver | Acados solver C++ wrapper handle |
stage | Stage in [0;N]. |
C | Matrix C |
bool acados::utils::set_const_D | ( | AcadosSolver & | solver, |
unsigned int | stage, | ||
Eigen::MatrixXd & | D | ||
) |
Set the D matrix used by polytopic constraints.
solver | Acados solver C++ wrapper handle |
stage | Stage in [0;N]. |
D | Matrix D |
bool acados::utils::set_const_g_min | ( | AcadosSolver & | solver, |
unsigned int | stage, | ||
Eigen::VectorXd & | g_min | ||
) |
Set the lower bound g_min used by polytopic constraints.
solver | Acados solver C++ wrapper handle |
stage | Stage in [0;N]. |
g_min | Lower bounds on polytopic constraints. |
bool acados::utils::set_const_g_max | ( | AcadosSolver & | solver, |
unsigned int | stage, | ||
Eigen::VectorXd & | g_max | ||
) |
Set the upper bound g_max used by polytopic constraints.
solver | Acados solver C++ wrapper handle |
stage | Stage in [0;N]. |
g_max | Upper bounds on polytopic constraints. |
bool acados::utils::set_const_h_min | ( | AcadosSolver & | solver, |
unsigned int | stage, | ||
Eigen::VectorXd & | h_min | ||
) |
Set the lower bound h_min used by non-linear constraints.
solver | Acados solver C++ wrapper handle |
stage | Stage in [0;N]. |
h_min | Lower bounds on non-linear constraints. |
bool acados::utils::set_const_h_max | ( | AcadosSolver & | solver, |
unsigned int | stage, | ||
Eigen::VectorXd & | h_max | ||
) |
Set the upper bound h_max used by non-linear constraints.
solver | Acados solver C++ wrapper handle |
stage | Stage in [0;N]. |
h_max | Upper bounds on non-linear constraints. |
void acados::utils::unsafe_get_stats_field | ( | AcadosSolver & | solver, |
const std::string & | field, | ||
T & | value | ||
) |
Read a given field from the solver stats (solve must be called before...)
solver | Acados solver C++ wrapper handle |
field | Name of the field to retrieve (e.g., "time_tot", "cost_value", etc.) |
double acados::utils::get_stats_cost_value | ( | AcadosSolver & | solver | ) |
Retrieve the current cost value.
See acados::utils::get_stats_field
for implementation details.
solver | Acados solver C++ wrapper handle |
int acados::utils::get_stats_sqp_iter | ( | AcadosSolver & | solver | ) |
Retrieve the SQP iteration at the last solve() call.
See acados::utils::get_stats_field
for implementation details.
solver | Acados solver C++ wrapper handle |
double acados::utils::get_stats_cpu_time | ( | AcadosSolver & | solver | ) |
Retrieve the CPU time needed for the last solve() call.
See acados::utils::get_stats_field
for implementation details.
solver | Acados solver C++ wrapper handle |