|
acados_solver_ros2 main
Acados-based NMPC controllers for ROS2 control
|
Abstract C++ wrapper of generated Acados solver C-code. More...
#include <acados_solver.hpp>
Classes | |
| class | Dimensions |
| Container for the (fixed) dimensions of the imported Acados OCP. More... | |
Public Member Functions | |
| AcadosSolver () | |
| Constructor of the AcadosSolver object. | |
| virtual | ~AcadosSolver () |
| Destructor of the AcadosSolver object. | |
| int | init (unsigned int N, double Ts) |
| Initialize the solver and set the (constant) sampling intervals. | |
| int | reset () |
| Resets the Acados solver, including the internal QP solver and the RTI phase cache. | |
| int | solve () |
| Solve the non-linear optimization problem given the provided initial state, constraints, etc. | |
| int | solve_rti (RtiStage rti_phase) |
| Solve the non-linear (RTI) optimization problem given the provided initial state, constraints, etc. | |
| int | simulate (double dt, ValueVector &x0, ValueVector &u0, ValueVector &p, ValueVector &x_next, ValueVector &z) |
| Simulate the next state given the current state, control inputs and runtime parameters. | |
| int | simulate (double dt, ValueMap const &x0_map, ValueMap const &u0_map, ValueMap const &p_map, ValueMap &x_next_map, ValueMap &z_map) |
| Simulate the next state given the current state, control inputs and runtime parameters. | |
| int | simulate (ValueMap const &x0_map, ValueMap const &u0_map, ValueMap const &p_map, ValueMap &x_next_map, ValueMap &z_map) |
| Simulate the next state given the current state, control inputs and runtime parameters. | |
| int | set_initial_state_values (ValueVector &x_0) |
| Set the initial state values (i.e., add constraints on initial state) | |
| int | set_initial_state_values (ValueMap const &x_0_map) |
| Set the initial state values (i.e., add constraints on initial state) from a map of key/ValueVector pairs. | |
| int | set_state_bounds (unsigned int stage, IndexVector &idxbx, ValueVector &lbx, ValueVector &ubx) |
| Set (differential) state bounds at a given stage. | |
| int | set_state_bounds (IndexVector &idxbx, ValueVector &lbx, ValueVector &ubx) |
| Set (differential) state bounds for all stages. | |
| int | set_control_bounds (unsigned int stage, IndexVector &idxbu, ValueVector &lbu, ValueVector &ubu) |
| Set control bounds at a given stage. | |
| int | set_control_bounds (IndexVector &idxbu, ValueVector &lbu, ValueVector &ubu) |
| Set control bounds for all stages. | |
| int | set_runtime_parameters (unsigned int stage, ValueVector &p_i) |
| Set the runtime parameters for one stage from ordered value vector. | |
| int | set_runtime_parameters (unsigned int stage, ValueMap const &p_i_map) |
| Set the runtime parameters for one stage from a key/values map. | |
| int | set_runtime_parameters (ValueVector &p_i) |
| Set the runtime parameters for all stages at once from ordered value vector. | |
| int | set_runtime_parameters (ValueMap const &p_i_map) |
| Set the runtime parameters for all stages at once from a key/values map. | |
| int | initialize_state_values (unsigned int stage, ValueVector &x_i) |
| Initialize the (differential) state values for a stage from an ordered value vector. | |
| int | initialize_state_values (unsigned int stage, ValueMap const &x_i_map) |
| Initialize the (differential) state values for a stage from a key/values map. | |
| int | initialize_state_values (ValueVector &x_i) |
| Initialize the (differential) state values for ALL stages at once from an ordered value vector. | |
| int | initialize_state_values (ValueMap const &x_i_map) |
| Initialize the (differential) state values for ALL stages at once from a key/values map. | |
| int | initialize_control_values (unsigned int stage, ValueVector &u_i) |
| Initialize the control variable values for one stage from an ordered value vector. | |
| int | initialize_control_values (unsigned int stage, ValueMap const &u_i_map) |
| Initialize the control variable values for one stage from a key/values map. | |
| int | initialize_control_values (ValueVector &u_i) |
| Initialize the control variable values for ALL stages at once from an ordered value vector. | |
| int | initialize_control_values (ValueMap const &u_i_map) |
| Initialize the control variable values for ALL stages at once from a key/values map. | |
| ValueVector | get_state_values (unsigned int stage) |
| Retrieve the differential state variables at a given stage. | |
| ValueMap | get_state_values_as_map (unsigned int stage) |
| Retrieve the differential state variables at a given stage and package them as a ValueMap. | |
| ValueVector | get_algebraic_state_values (unsigned int stage) |
| Retrieve the algebraic state variables at a given stage. | |
| ValueMap | get_algebraic_state_values_as_map (unsigned int stage) |
| Retrieve the algebraic state variables at a given stage and package them as a ValueMap. | |
| ValueVector | get_control_values (unsigned int stage) |
| Retrieve the control variables at a given stage. | |
| ValueMap | get_control_values_as_map (unsigned int stage) |
| Retrieve the control variables at a given stage and package them as a ValueMap. | |
| ValueVector | get_parameter_values (unsigned int stage) |
| Retrieve the parameters at a given stage. | |
| ValueMap | get_parameter_values_as_map (unsigned int stage) |
| Retrieve the parameters at a given stage and package them as a ValueMap. | |
| const IndexMap & | x_index_map () const |
Returns a constant reference to the Key/IndexVector map of differential state variables internally stored in AcadosSolver::_x_index_map. | |
| const IndexMap & | z_index_map () const |
Returns a constant reference to the Key/IndexVector map of algebraic state variables internally stored in AcadosSolver::_z_index_map. | |
| const IndexMap & | p_index_map () const |
Returns a constant reference to the Key/IndexVector map of runtime parameters internally stored in AcadosSolver::_p_index_map. | |
| const IndexMap & | u_index_map () const |
Returns a constant reference to the Key/IndexVector map of control variables internally stored in AcadosSolver::_u_index_map. | |
| const Dimensions & | dims () const |
Returns the (fixed) dimensions of the OCP problem stored in AcadosSolver::_dims. | |
| unsigned int | nx () const |
| Returns the dimensions of the differential state vector. | |
| unsigned int | nz () const |
| Returns the dimensions of the algebraic state vector. | |
| unsigned int | np () const |
| Returns the number of runtime parameters. | |
| unsigned int | nu () const |
| Returns the number of control variables. | |
| unsigned int | N () const |
| Returns the number of shooting nodes. | |
| double | Ts () const |
| Returns the (constant) sampling interval Ts (in seconds). | |
| std::vector< double > | sampling_intervals () const |
| Returns the vector of sampling interval (in seconds). | |
| virtual ocp_nlp_in * | get_nlp_in () const =0 |
Legacy C-function to retrieve the C-interface ocp_nlp_in property of the solver. | |
| virtual ocp_nlp_out * | get_nlp_out () const =0 |
Legacy C-function to retrieve the C-interface ocp_nlp_out property of the solver. | |
| virtual ocp_nlp_out * | get_sens_out () const =0 |
Legacy C-function to retrieve the C-interface ocp_nlp_out property of the solver. | |
| virtual ocp_nlp_solver * | get_nlp_solver () const =0 |
Legacy C-function to retrieve the C-interface ocp_nlp_solver property of the solver. | |
| virtual ocp_nlp_config * | get_nlp_config () const =0 |
Legacy C-function to retrieve the C-interface ocp_nlp_config property of the solver. | |
| virtual void * | get_nlp_opts () const =0 |
Legacy C-function to retrieve the C-interface get_nlp_opts property of the solver. | |
| virtual ocp_nlp_dims * | get_nlp_dims () const =0 |
Legacy C-function to retrieve the C-interface ocp_nlp_dims property of the solver that contains the dimensions of the problem. | |
| virtual ocp_nlp_plan_t * | get_nlp_plan () const =0 |
Legacy C-function to retrieve the C-interface ocp_nlp_plan property of the solver. | |
| virtual unsigned int | get_nlp_np () const =0 |
| Legacy C-function to retrieve the number of runtime parameters from the Acados capsule. | |
Static Public Member Functions | |
| static bool | is_map_size_consistent (IndexMap const &index_map, unsigned int expected_total_indexes) |
| Check if the total number of indexes contained in the provided index map is equal to an expected number. | |
| static bool | is_map_size_consistent (ValueMap const &values_map, unsigned int expected_total_indexes) |
| Check if the total number of values contained in the provided value map is equal to an expected number. | |
| static bool | is_values_map_complete (IndexMap const &index_map, ValueMap const &values_map) |
| Check if for each key-index pair contained in the index map there is a value provided by the value map. | |
| static void | fill_vector_from_map (IndexMap const &index_map, ValueMap const &values_map, unsigned int vector_size, ValueVector &values) |
| Fill (and resize if necessary) a vector with the values contained in the value map. | |
| static ValueVector | value_vector_from_map (IndexMap const &index_map, ValueMap const &values_map, unsigned int vector_size) |
| Returns a vector containing the values provided through the value map. | |
| static ValueMap | create_map_from_values (IndexMap const &index_map, ValueVector const &values) |
| Returns a vector ValueMap object containing the values of the value vector. | |
| static void | fill_map_from_values (IndexMap const &index_map, ValueVector const &values, ValueMap &value_map) |
| Fill a ValueMap object with the values of the value vector. | |
Protected Member Functions | |
| virtual int | create_index_maps ()=0 |
| Reinitialize the maps used to set or retrieve value using string variable names. | |
| int | free_memory () |
| Free all the allocated memory. | |
| virtual int | internal_create_capsule ()=0 |
| Create the Acados solver's capsule used by the Acados C-interface. | |
| virtual int | internal_create_with_discretization (int n_time_steps, double *new_time_steps)=0 |
| Initialize Acados solver and (optionally) redefine the shooting nodes. | |
| virtual int | internal_reset (int reset_qp_solver_mem=1)=0 |
| Reset the solver memory and (opt.) the internal QP solver. | |
| virtual int | internal_free ()=0 |
| Free the memory allocated for the solver. | |
| virtual int | internal_free_capsule ()=0 |
| Free the memory allocated for the capsule. | |
| virtual int | internal_update_qp_solver_cond_N (int qp_solver_cond_N)=0 |
Update the QP solver qp_solver_cond_N setting. | |
| virtual int | internal_update_params (unsigned int stage, double *value, int np)=0 |
| Internal update of the solver runtime parameters. | |
| virtual int | internal_update_params_sparse (unsigned int stage, int *idx, double *p, int n_update)=0 |
A sparse implementation of internal_update_params_sparse(). | |
| virtual int | internal_solve ()=0 |
| Solve the non-linear optimization`. | |
| virtual int | internal_simulate (double dt, double *x0, double *u0, double *p, double *x_next, double *z_next)=0 |
| Simulate the next state given the current state, control inputs and runtime parameters. | |
| virtual void | internal_print_stats () const =0 |
| Print the solver stats (e.g., number of SQP iters, number of QP iters, etc.) to the console. | |
Protected Attributes | |
| Dimensions | _dims |
| Fixed dimensions of the imported Acados OCP. | |
| IndexMap | _x_index_map |
| Unordered map used to set or retrieve the values of diff. state variables by name. | |
| IndexMap | _z_index_map |
| Unordered map used to set or retrieve the values of algebraic state variables by name. | |
| IndexMap | _p_index_map |
| Unordered map used to set the values of runtime parameters by name. | |
| IndexMap | _u_index_map |
| Unordered map used to set or retrieve the values of control variables by name. | |
Abstract C++ wrapper of generated Acados solver C-code.
| acados::AcadosSolver::AcadosSolver | ( | ) |
Constructor of the AcadosSolver object.
Does nothing for now.
AcadosSolver::_dims object.
|
virtual |
Destructor of the AcadosSolver object.
free_memory() function must called by the destructor of any class inheriting from AcadosSolver. Otherwise, the allocated memory won't be fully released. | int acados::AcadosSolver::init | ( | unsigned int | N, |
| double | Ts | ||
| ) |
| int acados::AcadosSolver::reset | ( | ) |
Resets the Acados solver, including the internal QP solver and the RTI phase cache.
| int acados::AcadosSolver::solve | ( | ) |
Solve the non-linear optimization problem given the provided initial state, constraints, etc.
The method returns the internal Acados status.
| int acados::AcadosSolver::solve_rti | ( | RtiStage | rti_phase | ) |
Solve the non-linear (RTI) optimization problem given the provided initial state, constraints, etc.
The method returns the internal Acados status.
| rti_phase | The RTI phase to be solved, i.e., either RtiStage::PREPARATION or RtiStage::FEEDBACK. |
| int acados::AcadosSolver::simulate | ( | double | dt, |
| ValueVector & | x0, | ||
| ValueVector & | u0, | ||
| ValueVector & | p, | ||
| ValueVector & | x_next, | ||
| ValueVector & | z | ||
| ) |
Simulate the next state given the current state, control inputs and runtime parameters.
The method returns the internal Acados status.
| int acados::AcadosSolver::simulate | ( | double | dt, |
| ValueMap const & | x0_map, | ||
| ValueMap const & | u0_map, | ||
| ValueMap const & | p_map, | ||
| ValueMap & | x_next_map, | ||
| ValueMap & | z_map | ||
| ) |
Simulate the next state given the current state, control inputs and runtime parameters.
See the other simulate() method for details.
| int acados::AcadosSolver::simulate | ( | ValueMap const & | x0_map, |
| ValueMap const & | u0_map, | ||
| ValueMap const & | p_map, | ||
| ValueMap & | x_next_map, | ||
| ValueMap & | z_map | ||
| ) |
Simulate the next state given the current state, control inputs and runtime parameters.
See the other simulate() method for details.
| int acados::AcadosSolver::set_initial_state_values | ( | ValueVector & | x_0 | ) |
Set the initial state values (i.e., add constraints on initial state)
| x_0 | State values at initial stage. |
| int acados::AcadosSolver::set_initial_state_values | ( | ValueMap const & | x_0_map | ) |
Set the initial state values (i.e., add constraints on initial state) from a map of key/ValueVector pairs.
| x_0_map | ValueMap of the initial state values. |
| int acados::AcadosSolver::set_state_bounds | ( | unsigned int | stage, |
| IndexVector & | idxbx, | ||
| ValueVector & | lbx, | ||
| ValueVector & | ubx | ||
| ) |
Set (differential) state bounds at a given stage.
| stage | Stage in [0;N]. |
| idxbx | Indexes of the bounded state variables. |
| lbx | Vector of lower bounds. |
| ubx | Vector of uower bounds. |
| int acados::AcadosSolver::set_state_bounds | ( | IndexVector & | idxbx, |
| ValueVector & | lbx, | ||
| ValueVector & | ubx | ||
| ) |
Set (differential) state bounds for all stages.
The bounds are therefore equal at each stage.
| idxbx | Indexes of the bounded state variables. |
| lbx | Vector of lower bounds. |
| ubx | Vector of uower bounds. |
| int acados::AcadosSolver::set_control_bounds | ( | unsigned int | stage, |
| IndexVector & | idxbu, | ||
| ValueVector & | lbu, | ||
| ValueVector & | ubu | ||
| ) |
Set control bounds at a given stage.
| stage | Stage in [0;N]. |
| idxbu | Indexes of the bounded control variables. |
| lbu | Vector of lower bounds. |
| ubu | Vector of uower bounds. |
| int acados::AcadosSolver::set_control_bounds | ( | IndexVector & | idxbu, |
| ValueVector & | lbu, | ||
| ValueVector & | ubu | ||
| ) |
Set control bounds for all stages.
The bounds are therefore equal at each stage.
| idxbu | Indexes of the bounded control variables. |
| lbu | Vector of lower bounds. |
| ubu | Vector of uower bounds. |
| int acados::AcadosSolver::set_runtime_parameters | ( | unsigned int | stage, |
| ValueVector & | p_i | ||
| ) |
Set the runtime parameters for one stage from ordered value vector.
| stage | Stage in [0;N]. |
| p_i | Vector containing the (ordered) runtime parameters. |
| int acados::AcadosSolver::set_runtime_parameters | ( | unsigned int | stage, |
| ValueMap const & | p_i_map | ||
| ) |
Set the runtime parameters for one stage from a key/values map.
set_runtime_parameters(ValueMap const &) alternative.| stage | Stage in [0;N]. |
| p_i_map | Key to ValueVector map containing the runtime parameters. |
| int acados::AcadosSolver::set_runtime_parameters | ( | ValueVector & | p_i | ) |
Set the runtime parameters for all stages at once from ordered value vector.
The runtime parameters for ALL stages are equal.
| p_i | Vector containing the (ordered) runtime parameters. |
| int acados::AcadosSolver::set_runtime_parameters | ( | ValueMap const & | p_i_map | ) |
Set the runtime parameters for all stages at once from a key/values map.
The runtime parameters for ALL stages are equal. Once the ordered vector of parameters is extracted, it is the set_runtime_parameters(unsigned int, ValueVector &) function that is used.
| p_i_map | Key to ValueVector map containing the runtime parameters. |
| int acados::AcadosSolver::initialize_state_values | ( | unsigned int | stage, |
| ValueVector & | x_i | ||
| ) |
Initialize the (differential) state values for a stage from an ordered value vector.
AcadoSolver::solve() call! Also, initializing the state values for stage zero is not equivalent to set the initial state (see AcadoSolver::set_initial_state_values()).| stage | Stage in [0;N]. |
| x_i | Vector containing the (ordered) state values. |
| int acados::AcadosSolver::initialize_state_values | ( | unsigned int | stage, |
| ValueMap const & | x_i_map | ||
| ) |
Initialize the (differential) state values for a stage from a key/values map.
set_runtime_parameters(ValueMap const &) alternative.| stage | Stage in [0;N]. |
| x_i_map | Key to ValueVector map containing the initial state values. |
| int acados::AcadosSolver::initialize_state_values | ( | ValueVector & | x_i | ) |
Initialize the (differential) state values for ALL stages at once from an ordered value vector.
| x_i | Vector containing the (ordered) state values. |
| int acados::AcadosSolver::initialize_state_values | ( | ValueMap const & | x_i_map | ) |
Initialize the (differential) state values for ALL stages at once from a key/values map.
| x_i_map | Key to ValueVector map containing the initial state values. |
| int acados::AcadosSolver::initialize_control_values | ( | unsigned int | stage, |
| ValueVector & | u_i | ||
| ) |
Initialize the control variable values for one stage from an ordered value vector.
| stage | Stage in [0;N]. |
| u_i | Vector containing the (ordered) control variables values. |
| int acados::AcadosSolver::initialize_control_values | ( | unsigned int | stage, |
| ValueMap const & | u_i_map | ||
| ) |
Initialize the control variable values for one stage from a key/values map.
| stage | Stage in [0;N]. |
| u_i_map | Key to ValueVector map containing the control variables values. |
| int acados::AcadosSolver::initialize_control_values | ( | ValueVector & | u_i | ) |
Initialize the control variable values for ALL stages at once from an ordered value vector.
| u_i | Vector containing the (ordered) control variables values. |
| int acados::AcadosSolver::initialize_control_values | ( | ValueMap const & | u_i_map | ) |
Initialize the control variable values for ALL stages at once from a key/values map.
| u_i_map | Key to ValueVector map containing the control variables values. |
| ValueVector acados::AcadosSolver::get_state_values | ( | unsigned int | stage | ) |
Retrieve the differential state variables at a given stage.
| stage | Stage in [0;N]. |
| ValueMap acados::AcadosSolver::get_state_values_as_map | ( | unsigned int | stage | ) |
Retrieve the differential state variables at a given stage and package them as a ValueMap.
| stage | Stage in [0;N]. |
| ValueVector acados::AcadosSolver::get_algebraic_state_values | ( | unsigned int | stage | ) |
Retrieve the algebraic state variables at a given stage.
| stage | Stage in [0;N]. |
| ValueMap acados::AcadosSolver::get_algebraic_state_values_as_map | ( | unsigned int | stage | ) |
Retrieve the algebraic state variables at a given stage and package them as a ValueMap.
| stage | Stage in [0;N]. |
| ValueVector acados::AcadosSolver::get_control_values | ( | unsigned int | stage | ) |
Retrieve the control variables at a given stage.
| stage | Stage in [0;N]. |
| ValueMap acados::AcadosSolver::get_control_values_as_map | ( | unsigned int | stage | ) |
Retrieve the control variables at a given stage and package them as a ValueMap.
| stage | Stage in [0;N]. |
| ValueVector acados::AcadosSolver::get_parameter_values | ( | unsigned int | stage | ) |
Retrieve the parameters at a given stage.
| stage | Stage in [0;N]. |
| ValueMap acados::AcadosSolver::get_parameter_values_as_map | ( | unsigned int | stage | ) |
Retrieve the parameters at a given stage and package them as a ValueMap.
| stage | Stage in [0;N]. |
| const IndexMap & acados::AcadosSolver::x_index_map | ( | ) | const |
Returns a constant reference to the Key/IndexVector map of differential state variables internally stored in AcadosSolver::_x_index_map.
| const IndexMap & acados::AcadosSolver::z_index_map | ( | ) | const |
Returns a constant reference to the Key/IndexVector map of algebraic state variables internally stored in AcadosSolver::_z_index_map.
| const IndexMap & acados::AcadosSolver::p_index_map | ( | ) | const |
Returns a constant reference to the Key/IndexVector map of runtime parameters internally stored in AcadosSolver::_p_index_map.
| const IndexMap & acados::AcadosSolver::u_index_map | ( | ) | const |
Returns a constant reference to the Key/IndexVector map of control variables internally stored in AcadosSolver::_u_index_map.
|
static |
Check if the total number of indexes contained in the provided index map is equal to an expected number.
| index_map | The Key/IndexVector map to be tested for size consistency. |
| expected_total_indexes | The expected number of indexes. |
|
static |
Check if the total number of values contained in the provided value map is equal to an expected number.
| values_map | The Key/ValueVector map to be tested for size consistency. |
| expected_total_indexes | The expected number of values. |
|
static |
Check if for each key-index pair contained in the index map there is a value provided by the value map.
It is considered complete even if there are too many values (e.g., unused keys in values_map).
| index_map | The Key/IndexVector map to be tested for size consistency. |
| values_map | The Key/ValueVector map to be tested for size consistency. |
|
static |
Fill (and resize if necessary) a vector with the values contained in the value map.
The index map is used to arrange the values within the vector.
| std::invalid_argument |
vector_size argument. The vector_size argument could (should?) be optional since it can be retrieved from the number of indexes contained in index_map.| [in] | index_map | Mapping between keys and indexes. |
| [in] | values_map | Mapping between keys and values to write in the value vector. |
| [in] | vector_size | The expected size of the resulting value vector. |
| [out] | values | The output container where the values will be written. |
|
static |
Returns a vector containing the values provided through the value map.
| [in] | index_map | Mapping between keys and indexes. |
| [in] | values_map | Mapping between keys and values to write in the value vector. |
| [out] | vector_size | The expected size of the resulting value vector. |
|
static |
Returns a vector ValueMap object containing the values of the value vector.
values must have been encoded as described by the index_map argument.| [in] | index_map | Mapping between keys and indexes. |
| [in] | values | Vector of (ordered) values. |
|
static |
Fill a ValueMap object with the values of the value vector.
index_map and values are consistent, i.e., that the number of indexes in index_map is equal to the size of values. | [in] | index_map | Mapping between keys and indexes. |
| [in] | values | Vector of (ordered) values. |
| [out] | value_map | The ValueMap object to be filled with the values. |
| const Dimensions & acados::AcadosSolver::dims | ( | ) | const |
Returns the (fixed) dimensions of the OCP problem stored in AcadosSolver::_dims.
| unsigned int acados::AcadosSolver::nx | ( | ) | const |
| unsigned int acados::AcadosSolver::nz | ( | ) | const |
| unsigned int acados::AcadosSolver::np | ( | ) | const |
| unsigned int acados::AcadosSolver::nu | ( | ) | const |
| unsigned int acados::AcadosSolver::N | ( | ) | const |
Returns the number of shooting nodes.
| double acados::AcadosSolver::Ts | ( | ) | const |
Returns the (constant) sampling interval Ts (in seconds).
If the sampling intervals are of variable duration (see sampling_intervals()), the function returns -1.
| std::vector< double > acados::AcadosSolver::sampling_intervals | ( | ) | const |
Returns the vector of sampling interval (in seconds).
|
protectedpure virtual |
Reinitialize the maps used to set or retrieve value using string variable names.
|
protected |
Free all the allocated memory.
Triggers calls to internal_free(), internal_free_capsule(), etc.
|
protectedpure virtual |
Create the Acados solver's capsule used by the Acados C-interface.
Wrapper of the <acados_model_name>_acados_create_capsule() C function. Note that the storage of the capsule itself is handled by the inherited class.
|
protectedpure virtual |
Initialize Acados solver and (optionally) redefine the shooting nodes.
This is a wrapper of the <acados_model_name>_acados_create_with_discretization(...) C function. For constant sampling intervals, provide new_time_steps = nullptr as argument.
| n_time_steps | number of shooting nodes. |
| new_time_steps | C-array of sampling intervals (in seconds). |
|
protectedpure virtual |
Reset the solver memory and (opt.) the internal QP solver.
This is a wrapper of the <acados_model_name>_acados_reset(...) C function.
| reset_qp_solver_mem | Reset if =1. |
|
protectedpure virtual |
Free the memory allocated for the solver.
This is a wrapper of the <acados_model_name>_acados_free(...) C function. Call internal_free() before internal_free_capsule().
|
protectedpure virtual |
Free the memory allocated for the capsule.
This is a wrapper of the <acados_model_name>_acados_free_capsule(...) C function.
|
protectedpure virtual |
Update the QP solver qp_solver_cond_N setting.
This is a wrapper of the <acados_model_name>_acados_update_qp_solver_cond_N(...) C function.
| qp_solver_cond_N | New horizon after partial condensing. |
|
protectedpure virtual |
Internal update of the solver runtime parameters.
This is a wrapper of the <acados_model_name>_acados_update_params(...) C function.
| stage | Stage in [0;N]. |
| value | Parameter values (C-array). |
| np | Number of parameters. |
|
protectedpure virtual |
A sparse implementation of internal_update_params_sparse().
This is a wrapper of the <acados_model_name>_acados_update_params_sparse(...) C function.
| stage | Stage in [0;N]. |
| idx | Parameter indexes (C-array). |
| p | Parameter values (C-array). |
| n_update | Number of parameters to update. |
|
protectedpure virtual |
Solve the non-linear optimization`.
This is a wrapper of the <acados_model_name>_acados_solve(...) C function.
|
protectedpure virtual |
Simulate the next state given the current state, control inputs and runtime parameters.
This is a wrapper of the <acados_model_name>_acados_solve(...) C function. The method returns the internal Acados status.
|
protectedpure virtual |
Print the solver stats (e.g., number of SQP iters, number of QP iters, etc.) to the console.
This is a wrapper of the <acados_model_name>_acados_print_stats(...) C function.
|
pure virtual |
Legacy C-function to retrieve the C-interface ocp_nlp_in property of the solver.
This is a wrapper of the auto-generated <acados_model_name>_acados_get_nlp_in(...) C function.
ocp_nlp_in object.
|
pure virtual |
Legacy C-function to retrieve the C-interface ocp_nlp_out property of the solver.
This is a wrapper of the auto-generated <acados_model_name>_acados_get_nlp_out(...) C function.
ocp_nlp_out object.
|
pure virtual |
Legacy C-function to retrieve the C-interface ocp_nlp_out property of the solver.
This is a wrapper of the auto-generated <acados_model_name>_acados_get_sens_out(...) C function. The function is used to retrieve the sensibility matrices.
ocp_nlp_out object.
|
pure virtual |
Legacy C-function to retrieve the C-interface ocp_nlp_solver property of the solver.
This is a wrapper of the auto-generated <acados_model_name>_acados_get_nlp_solver(...) C function.
ocp_nlp_solver object.
|
pure virtual |
Legacy C-function to retrieve the C-interface ocp_nlp_config property of the solver.
This is a wrapper of the auto-generated <acados_model_name>_acados_get_nlp_config(...) C function.
ocp_nlp_config object.
|
pure virtual |
Legacy C-function to retrieve the C-interface get_nlp_opts property of the solver.
This is a wrapper of the auto-generated <acados_model_name>_acados_get_nlp_opts(...) C function.
nlp_opts object.
|
pure virtual |
Legacy C-function to retrieve the C-interface ocp_nlp_dims property of the solver that contains the dimensions of the problem.
This is a wrapper of the auto-generated <acados_model_name>_acados_get_nlp_dims(...) C function.
ocp_nlp_dims object.
|
pure virtual |
Legacy C-function to retrieve the C-interface ocp_nlp_plan property of the solver.
This is a wrapper of the auto-generated <acados_model_name>_acados_get_nlp_plan(...) C function.
ocp_nlp_plan object.
|
pure virtual |
Legacy C-function to retrieve the number of runtime parameters from the Acados capsule.
This function returns the field capsule->nlp_np where capsule is the internal pointer to the acados solver data.
|
protected |
Fixed dimensions of the imported Acados OCP.
|
protected |
Unordered map used to set or retrieve the values of diff. state variables by name.
|
protected |
Unordered map used to set or retrieve the values of algebraic state variables by name.
|
protected |
Unordered map used to set the values of runtime parameters by name.
|
protected |
Unordered map used to set or retrieve the values of control variables by name.