OpTaS  1.0.7
An optimization-based task specification library for trajectory optimization and model predictive control.
Public Member Functions | Static Public Member Functions | Public Attributes | Private Member Functions | Private Attributes | List of all members
optas.solver.Solver Class Reference

Solver base class. More...

Inheritance diagram for optas.solver.Solver:
Inheritance graph
[legend]
Collaboration diagram for optas.solver.Solver:
Collaboration graph
[legend]

Public Member Functions

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...
 
def stats (self)
 Return stats from solver. More...
 
Tuple violated_constraints (self, Dict[str, ArrayType] x, Dict[str, ArrayType] p)
 Indicate the violated constraints. More...
 
bool did_solve (self)
 Returns true when the solver solved the previous problem, false otherwise. More...
 
int number_of_iterations (self)
 Returns the number of iterations required to solve the problem. 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 Member Functions

interp1d interpolate (cs.DM traj, float T, **interp_args)
 Interpolate a trajectory. More...
 

Public Attributes

 opt
 Instance of the optimization problem. More...
 
 x0
 Initial guess for the optimization problem (set using reset_initial_seed). More...
 
 p
 Parameter vector. More...
 

Private Member Functions

CasADiArrayType _solve (self)
 Solve the optimization problem and return the optimal decision variables as an array. More...
 

Private Attributes

 _p_dict
 Parameter dictionary. More...
 
 _error_on_fail
 When True, after solve() is called, if the solver did not converge then a RuntimeError is thrown. More...
 
 _solution
 Solution container. More...
 

Detailed Description

Solver base class.

Base solver interface class

Constructor & Destructor Documentation

◆ __init__()

def optas.solver.Solver.__init__ (   self,
Optimization  optimization,
bool   error_on_fail = False 
)

Constructor for the base Solver class.

   @param optimization The optimization problem created by calling the build method of the OptimizationBuilder class.
   @param error_on_fail When True, after solve() is called, if the solver did not converge then a RuntimeError is thrown. Default is False.
   @return An instance of the Solver class.

Member Function Documentation

◆ _solve()

CasADiArrayType optas.solver.Solver._solve (   self)
private

Solve the optimization problem and return the optimal decision variables as an array.

This is an abstract method.

   @return The solution from the solver.

Reimplemented in optas.solver.ScipyMinimizeSolver, optas.solver.CVXOPTSolver, optas.solver.OSQPSolver, and optas.solver.CasADiSolver.

◆ did_solve()

bool optas.solver.Solver.did_solve (   self)

Returns true when the solver solved the previous problem, false otherwise.

This is an abstract method.

   @return Result of whether the solver succeeded or not.

Reimplemented in optas.solver.ScipyMinimizeSolver, optas.solver.CVXOPTSolver, optas.solver.OSQPSolver, and optas.solver.CasADiSolver.

◆ evaluate_cost()

CasADiArrayType optas.solver.Solver.evaluate_cost (   self,
Dict[str, ArrayType]  x,
Dict[str, ArrayType]   p 
)

Evaluates the cost function for given decision variables x and parameters p.

   @param x The values for the decision variables.
   @param p The values for the parameters.
   @return The cost that results from x and p.

◆ evaluate_cost_terms()

List optas.solver.Solver.evaluate_cost_terms (   self,
Dict[str, ArrayType]  x,
Dict[str, ArrayType]   p 
)

Evaluates each cost term for given decision variables and parameters.

   @param x The values for the decision variables.
   @param p The values for the parameters.
   @return List corresponding to each cost term evalauted at x, p.

◆ interpolate()

interp1d optas.solver.Solver.interpolate ( cs.DM  traj,
float  T,
**  interp_args 
)
static

Interpolate a trajectory.

   @param traj The trajectory to be interpolated where the columns correspond to the states over time.
   @param T The time duration of the trajectory.
   @return An interpolated function.

◆ number_of_iterations()

int optas.solver.Solver.number_of_iterations (   self)

Returns the number of iterations required to solve the problem.

This is an abstract method.

   @return Number of iterations.

Reimplemented in optas.solver.ScipyMinimizeSolver, optas.solver.CVXOPTSolver, optas.solver.OSQPSolver, and optas.solver.CasADiSolver.

◆ opt_type()

type optas.solver.Solver.opt_type (   self)

Optimization type.

   @return The type of the optimization problem.

◆ reset_initial_seed()

None optas.solver.Solver.reset_initial_seed (   self,
Dict[str, ArrayType]  x0 
)

Reset initial seed for the optimization problem.

   @param x0 The initial seed.

◆ reset_parameters()

None optas.solver.Solver.reset_parameters (   self,
Dict[str, ArrayType]  p 
)

Reset the parameters for the optimization problem.

   @param p Specifies the parameters.

Reimplemented in optas.solver.ScipyMinimizeSolver, optas.solver.CVXOPTSolver, and optas.solver.OSQPSolver.

◆ setup()

def optas.solver.Solver.setup (   self,
args,
**  kwargs 
)

Setup solver, note this method must return self.

This is an abstract method.

◆ solve()

Dict optas.solver.Solver.solve (   self)

Solve the optimization problem.

   @return A dictionary containing the solution.

◆ stats()

def optas.solver.Solver.stats (   self)

Return stats from solver.

The return type is specifc to the solver used. This is an abstract method.

   @return The statistics returned by the solver. This is specified to the solver used.

Reimplemented in optas.solver.ScipyMinimizeSolver, optas.solver.CVXOPTSolver, optas.solver.OSQPSolver, and optas.solver.CasADiSolver.

◆ violated_constraints()

Tuple optas.solver.Solver.violated_constraints (   self,
Dict[str, ArrayType]  x,
Dict[str, ArrayType]   p 
)

Indicate the violated constraints.

   @param x The values for the decision variables.
   @param p The values for the parameters.
   @return Several lists that contain information regarding which constraints are violated.

Member Data Documentation

◆ _error_on_fail

optas.solver.Solver._error_on_fail
private

When True, after solve() is called, if the solver did not converge then a RuntimeError is thrown.

◆ _p_dict

optas.solver.Solver._p_dict
private

Parameter dictionary.

◆ _solution

optas.solver.Solver._solution
private

Solution container.

◆ opt

optas.solver.Solver.opt

Instance of the optimization problem.

◆ p

optas.solver.Solver.p

Parameter vector.

◆ x0

optas.solver.Solver.x0

Initial guess for the optimization problem (set using reset_initial_seed).


The documentation for this class was generated from the following file: