![]() |
OpTaS
1.0.7
An optimization-based task specification library for trajectory optimization and model predictive control.
|
Base optimization class. More...

Public Member Functions | |
| def | __init__ (self, SXContainer decision_variables, SXContainer parameters, SXContainer cost_terms) |
| Initializer for the Optimization class. More... | |
| None | set_models (self, List[Model] models) |
| Specify the models in the optimization problem. More... | |
| None | specify_quadratic_cost (self) |
| Specify the terms P and q of a quadratic cost function. More... | |
| None | specify_linear_constraints (self, lin_ineq_constraints, lin_eq_constraints) |
| Setup the constraints k(x, p) = M(p).x + c(p) >= 0, and a(x, p) = A(p).x + b(p) == 0. More... | |
| None | specify_nonlinear_constraints (self, SXContainer ineq_constraints, SXContainer eq_constraints) |
| Setup the constraints g(x, p) >= 0, and h(x, p) == 0. More... | |
| None | specify_v (self, List[cs.Function] ineq=[], List[cs.Function] eq=[]) |
| Specify the vertical constraints vector v. More... | |
| def | has_discrete_variables (self) |
Public Attributes | |
| models | |
| A list of the task and robot models (set during build method in the OptimizationBuilder class) More... | |
| decision_variables | |
| SXContainer containing decision variables. More... | |
| parameters | |
| SXContainer containing parameters. More... | |
| cost_terms | |
| SXContainer containing cost terms. More... | |
| lin_eq_constraints | |
| SXContainer containing linear equality constraints. More... | |
| lin_ineq_constraints | |
| SXContainer containing linear inequality constraints. More... | |
| eq_constraints | |
| SXContainer containing equality constraints. More... | |
| ineq_constraints | |
| SXContainer containing inequality constraints. More... | |
| P | |
| CasADi function that evaluates the P term in the cost function (note, this only applies to problems with a quadratic cost function). More... | |
| q | |
| CasADi function that evaluates the q term in the cost function (note, this only applies to problems with a quadratic cost function). More... | |
| k | |
| CasADi function that evaluates the linear equality constraints. More... | |
| nk | |
| Number of linear inequality constraints. More... | |
| lbk | |
| Lower bound for the linear inequality constraints (i.e. More... | |
| ubk | |
| Upper bound for the linear inequality constraints (i.e. More... | |
| M | |
| CasADi function that evaluates the M term in the linear inequality constraints. More... | |
| c | |
| CasADi function that evaluates the c term in the linear inequality constraints. More... | |
| a | |
| CasADi function that evaluates the linear equality constraints. More... | |
| na | |
| Number of linear equality constraints. More... | |
| lba | |
| Lower bound for the linear equality constraints (i.e. More... | |
| uba | |
| Upper bound for the linear equality constraints (i.e. More... | |
| A | |
| CasADi function that evaluates the A term in the linear equality constraints. More... | |
| b | |
| CasADi function that evaluates the b term in the linear equality constraints. More... | |
| g | |
| CasADi function that evaluates the inequality constraints. More... | |
| ng | |
| Number of inequality constraints. More... | |
| lbg | |
| Lower bound for the inequality constraints (i.e. More... | |
| ubg | |
| Upper bound for the inequality constraints (i.e. More... | |
| h | |
| CasADi function that evaluates the equality constraints. More... | |
| nh | |
| Number of equality constraints. More... | |
| lbh | |
| Lower bound for the equality constraints (i.e. More... | |
| ubh | |
| Upper bound for the equality constraints (i.e. More... | |
| v | |
| CasADi function that evaluates the constraints as a verticle column (set when specify_v is called), see vertcon. More... | |
| nv | |
| Number of vectorized constraints (see vertcon). More... | |
| lbv | |
| Lower bound for the verticle constraints v (i.e. More... | |
| ubv | |
| Upper bound for the verticle constraints v (i.e. More... | |
| dv | |
| CasADi function that evaluates the Jacobian of the constraints v (set when specify_v is called). More... | |
| ddv | |
| CasADi function that evaluates the Hessian of the constraints v (set when specify_v is called). More... | |
| x | |
| Vectorized decision variables. More... | |
| p | |
| Vectorized parameters. More... | |
| f | |
| CasADi function that evaluates the objective function. More... | |
| df | |
| Jacobian of the objective function. More... | |
| ddf | |
| Hessian of the objective function. More... | |
| nx | |
| Number of decision variables. More... | |
| np | |
| Number of parameters. More... | |
| ddg | |
| ddh | |
Static Public Attributes | |
| float | inf = 1.0e10 |
| big number rather than np.inf More... | |
Base optimization class.
| def optas.optimization.Optimization.__init__ | ( | self, | |
| SXContainer | decision_variables, | ||
| SXContainer | parameters, | ||
| SXContainer | cost_terms | ||
| ) |
Initializer for the Optimization class.
@param decision_variables SXContainer containing decision variables. @param parameters SXContainer containing parameters. @param cost_terms SXContainer containing cost terms. @return Instance of the Optimization class.
Reimplemented in optas.optimization.NonlinearCostUnconstrained, and optas.optimization.QuadraticCostUnconstrained.
| def optas.optimization.Optimization.has_discrete_variables | ( | self | ) |
| None optas.optimization.Optimization.set_models | ( | self, | |
| List[Model] | models | ||
| ) |
Specify the models in the optimization problem.
@param models A list of models (i.e. instance of a sub-class of Model).
| None optas.optimization.Optimization.specify_linear_constraints | ( | self, | |
| lin_ineq_constraints, | |||
| lin_eq_constraints | |||
| ) |
Setup the constraints k(x, p) = M(p).x + c(p) >= 0, and a(x, p) = A(p).x + b(p) == 0.
@param lin_ineq_constraints SXContainer containing the linear inequality constraints. @param lin_eq_constraints SXContainer containing the linear equality constraints.
| None optas.optimization.Optimization.specify_nonlinear_constraints | ( | self, | |
| SXContainer | ineq_constraints, | ||
| SXContainer | eq_constraints | ||
| ) |
Setup the constraints g(x, p) >= 0, and h(x, p) == 0.
@param ineq_constraints SXContainer containing the inequality constraints. @param eq_constraints SXContainer containing the equality constraints.
| None optas.optimization.Optimization.specify_quadratic_cost | ( | self | ) |
Specify the terms P and q of a quadratic cost function.
| None optas.optimization.Optimization.specify_v | ( | self, | |
| List[cs.Function] | ineq = [], |
||
| List[cs.Function] | eq = [] |
||
| ) |
Specify the vertical constraints vector v.
This is only called for optimization problems that have constraints.
@param ineq List of CasADi functions that evalaute the (non)linear inequality constraints. @param ineq List of CasADi functions that evalaute the (non)linear equality constraints.
| optas.optimization.Optimization.a |
CasADi function that evaluates the linear equality constraints.
| optas.optimization.Optimization.A |
CasADi function that evaluates the A term in the linear equality constraints.
| optas.optimization.Optimization.b |
CasADi function that evaluates the b term in the linear equality constraints.
| optas.optimization.Optimization.c |
CasADi function that evaluates the c term in the linear inequality constraints.
| optas.optimization.Optimization.cost_terms |
SXContainer containing cost terms.
| optas.optimization.Optimization.ddf |
Hessian of the objective function.
| optas.optimization.Optimization.ddg |
| optas.optimization.Optimization.ddh |
| optas.optimization.Optimization.ddv |
CasADi function that evaluates the Hessian of the constraints v (set when specify_v is called).
| optas.optimization.Optimization.decision_variables |
SXContainer containing decision variables.
| optas.optimization.Optimization.df |
Jacobian of the objective function.
| optas.optimization.Optimization.dv |
CasADi function that evaluates the Jacobian of the constraints v (set when specify_v is called).
| optas.optimization.Optimization.eq_constraints |
SXContainer containing equality constraints.
| optas.optimization.Optimization.f |
CasADi function that evaluates the objective function.
| optas.optimization.Optimization.g |
CasADi function that evaluates the inequality constraints.
| optas.optimization.Optimization.h |
CasADi function that evaluates the equality constraints.
| optas.optimization.Optimization.ineq_constraints |
SXContainer containing inequality constraints.
|
static |
big number rather than np.inf
| optas.optimization.Optimization.k |
CasADi function that evaluates the linear equality constraints.
| optas.optimization.Optimization.lba |
Lower bound for the linear equality constraints (i.e.
zeros).
| optas.optimization.Optimization.lbg |
Lower bound for the inequality constraints (i.e.
zeros).
| optas.optimization.Optimization.lbh |
Lower bound for the equality constraints (i.e.
zeros).
| optas.optimization.Optimization.lbk |
Lower bound for the linear inequality constraints (i.e.
zeros).
| optas.optimization.Optimization.lbv |
Lower bound for the verticle constraints v (i.e.
zeros).
| optas.optimization.Optimization.lin_eq_constraints |
SXContainer containing linear equality constraints.
| optas.optimization.Optimization.lin_ineq_constraints |
SXContainer containing linear inequality constraints.
| optas.optimization.Optimization.M |
CasADi function that evaluates the M term in the linear inequality constraints.
| optas.optimization.Optimization.models |
A list of the task and robot models (set during build method in the OptimizationBuilder class)
| optas.optimization.Optimization.na |
Number of linear equality constraints.
| optas.optimization.Optimization.ng |
Number of inequality constraints.
| optas.optimization.Optimization.nh |
Number of equality constraints.
| optas.optimization.Optimization.nk |
Number of linear inequality constraints.
| optas.optimization.Optimization.np |
Number of parameters.
| optas.optimization.Optimization.nv |
Number of vectorized constraints (see vertcon).
| optas.optimization.Optimization.nx |
Number of decision variables.
| optas.optimization.Optimization.P |
CasADi function that evaluates the P term in the cost function (note, this only applies to problems with a quadratic cost function).
| optas.optimization.Optimization.p |
Vectorized parameters.
| optas.optimization.Optimization.parameters |
SXContainer containing parameters.
| optas.optimization.Optimization.q |
CasADi function that evaluates the q term in the cost function (note, this only applies to problems with a quadratic cost function).
| optas.optimization.Optimization.uba |
Upper bound for the linear equality constraints (i.e.
zeros).
| optas.optimization.Optimization.ubg |
Upper bound for the inequality constraints (i.e.
inf).
| optas.optimization.Optimization.ubh |
Upper bound for the equality constraints (i.e.
zeros).
| optas.optimization.Optimization.ubk |
Upper bound for the linear inequality constraints (i.e.
inf).
| optas.optimization.Optimization.ubv |
Upper bound for the verticle constraints v (i.e.
inf).
| optas.optimization.Optimization.v |
CasADi function that evaluates the constraints as a verticle column (set when specify_v is called), see vertcon.
| optas.optimization.Optimization.x |
Vectorized decision variables.