OpTaS
1.0.7
An optimization-based task specification library for trajectory optimization and model predictive control.
|
This is a base class for CasADi solver interfaces. More...
Public Member Functions | |
def | setup (self, str solver_name, Dict solver_options={}) |
Setup the optimization solver. More... | |
Dict | stats (self) |
Statistics relating to the previous call to solve. More... | |
bool | did_solve (self) |
True when the solver succeeded, False otherwise. More... | |
int | number_of_iterations (self) |
Number of iterations it took the solver to converge. More... | |
Public Member Functions inherited from optas.solver.Solver | |
def | __init__ (self, Optimization optimization, bool error_on_fail=False) |
Constructor for the base Solver class. More... | |
type | opt_type (self) |
Optimization type. More... | |
def | setup (self, *args, **kwargs) |
Setup solver, note this method must return self. More... | |
None | reset_initial_seed (self, Dict[str, ArrayType] x0) |
Reset initial seed for the optimization problem. More... | |
None | reset_parameters (self, Dict[str, ArrayType] p) |
Reset the parameters for the optimization problem. More... | |
Dict | solve (self) |
Solve the optimization problem. More... | |
Tuple | violated_constraints (self, Dict[str, ArrayType] x, Dict[str, ArrayType] p) |
Indicate the violated constraints. More... | |
CasADiArrayType | evaluate_cost (self, Dict[str, ArrayType] x, Dict[str, ArrayType] p) |
Evaluates the cost function for given decision variables x and parameters p. More... | |
List | evaluate_cost_terms (self, Dict[str, ArrayType] x, Dict[str, ArrayType] p) |
Evaluates each cost term for given decision variables and parameters. More... | |
Static Public Attributes | |
dictionary | mi_solvers = {"bonmin", "knitro"} |
Possible mixed-integer solvers. More... | |
dictionary | nlp_solvers = {"ipopt", "knitro", "snopt", "worhp", "scpgen", "sqpmethod"} |
Possible NLP solvers. More... | |
dictionary | qp_solvers = {"cplex", "gurobi", "ooqp", "qpoases", "sqic", "nlp"} |
Possible QP solvers. More... | |
Private Member Functions | |
CasADiArrayType | _solve (self) |
Solve the optimization problem using the CasADi interface. More... | |
Private Attributes | |
_lbg | |
Lower bound on constraints. More... | |
_ubg | |
Upper bound on constraints. More... | |
_solver | |
Instance of the CasADi solver. More... | |
_solution | |
_stats | |
Additional Inherited Members | |
Static Public Member Functions inherited from optas.solver.Solver | |
interp1d | interpolate (cs.DM traj, float T, **interp_args) |
Interpolate a trajectory. More... | |
Public Attributes inherited from optas.solver.Solver | |
opt | |
Instance of the optimization problem. More... | |
x0 | |
Initial guess for the optimization problem (set using reset_initial_seed). More... | |
p | |
Parameter vector. More... | |
This is a base class for CasADi solver interfaces.
|
private |
Solve the optimization problem using the CasADi interface.
@return Solution to the problem.
Reimplemented from optas.solver.Solver.
bool optas.solver.CasADiSolver.did_solve | ( | self | ) |
True when the solver succeeded, False otherwise.
@return Boolean indicating success of solver.
Reimplemented from optas.solver.Solver.
int optas.solver.CasADiSolver.number_of_iterations | ( | self | ) |
Number of iterations it took the solver to converge.
@return Number of iterations.
Reimplemented from optas.solver.Solver.
def optas.solver.CasADiSolver.setup | ( | self, | |
str | solver_name, | ||
Dict | solver_options = {} |
||
) |
Setup the optimization solver.
@param solver_name The name of the solver to be used. @param solver_options Solver options passed to the solver. For details, see - https://casadi.sourceforge.net/v3.0.0/api/html/d9/d37/group__qpsol.html, and - https://casadi.sourceforge.net/v2.0.0/api/html/d6/d07/classcasadi_1_1NlpSolver.html @return An instance of the CasADiSovler class.
Dict optas.solver.CasADiSolver.stats | ( | self | ) |
Statistics relating to the previous call to solve.
@return Dictionary containing the statistics.
Reimplemented from optas.solver.Solver.
|
private |
Lower bound on constraints.
|
private |
|
private |
Instance of the CasADi solver.
|
private |
|
private |
Upper bound on constraints.
|
static |
Possible mixed-integer solvers.
|
static |
Possible NLP solvers.
|
static |
Possible QP solvers.