Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

add renaming of nn to ml #12

Open
wants to merge 22 commits into
base: main
Choose a base branch
from
Open
Show file tree
Hide file tree
Changes from all commits
Commits
Show all changes
22 commits
Select commit Hold shift + click to select a range
18764dd
add initial algebraics to casadi_ml.py
SteffenEserAC Sep 20, 2024
43884f4
adjust naming in examples
SteffenEserAC Sep 20, 2024
8b07e54
format with ruff
SteffenEserAC Sep 20, 2024
7c42439
Update agentlib_mpc/optimization_backends/casadi_/casadi_ml.py
EserSteffen Oct 23, 2024
815ab37
Update agentlib_mpc/optimization_backends/casadi_/casadi_ml.py
EserSteffen Oct 23, 2024
e0f9122
uncache result df, as it is mutated during results writing
SteffenEserAC Oct 23, 2024
9479ba6
Merge remote-tracking branch 'origin/11-include-some-updates-from-git…
SteffenEserAC Oct 23, 2024
71b8036
fix space from github
SteffenEserAC Oct 23, 2024
d6b7131
adjust error message
SteffenEserAC Oct 30, 2024
c036dfc
merge main
SteffenEserAC Oct 31, 2024
4970054
dashboard now updates traces synchronously among all plots
SteffenEserAC Nov 7, 2024
d6ff61c
add validation for couplings to have a vlaue for the initial guess
SteffenEserAC Nov 14, 2024
668bf74
make algebraics and outputs inputs for the integrator in mpc
SteffenEserAC Nov 14, 2024
fed6167
remove outputs from initials in discretization and some renaming
SteffenEserAC Nov 14, 2024
557af75
allow algebraics again
SteffenEserAC Nov 14, 2024
a43e975
allow algebraics again
SteffenEserAC Nov 14, 2024
dfa819b
remove superfluous control from ml mpc
SteffenEserAC Nov 14, 2024
7af3bc9
Merge remote-tracking branch 'origin/11-include-some-updates-from-git…
SteffenEserAC Nov 14, 2024
222ce0d
add version number and fix bug
SteffenEserAC Nov 14, 2024
1c3bd51
fix time usage in mpc lags
SteffenEserAC Nov 14, 2024
d247814
add admm dasboard
SteffenEserAC Nov 14, 2024
9031329
Revert "allow algebraics again"
SteffenEserAC Nov 15, 2024
File filter

Filter by extension

Filter by extension


Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
6 changes: 6 additions & 0 deletions CHANGELOG.md
Original file line number Diff line number Diff line change
@@ -1,5 +1,11 @@
# Changelog

## 0.6.3
- Dashboard now synchronously updates traces of all plots when changing one plot
- Fix some smaller issues with lag structure in data driven mpc
- Add ADMM dashboard


## 0.6.2
- Add moving horizon estimator. Use it as ``"agentlib_mpc.mhe"``

Expand Down
2 changes: 1 addition & 1 deletion agentlib_mpc/__init__.py
Original file line number Diff line number Diff line change
Expand Up @@ -4,4 +4,4 @@
from .modules import MODULE_TYPES
from .models import MODEL_TYPES

__version__ = "0.6.2"
__version__ = "0.6.3"
26 changes: 26 additions & 0 deletions agentlib_mpc/data_structures/casadi_utils.py
Original file line number Diff line number Diff line change
Expand Up @@ -56,6 +56,8 @@ class Solvers(str, Enum):
gurobi = "gurobi"
bonmin = "bonmin"
fatrop = "fatrop"
proxqp = "proxqp"
osqp = "osqp"


class Integrators(str, Enum):
Expand Down Expand Up @@ -141,6 +143,10 @@ def create_solver(
return self._create_sqpmethod_solver(nlp=nlp, options=options)
if solver_name == Solvers.qpoases:
return self._create_qpoases_solver(nlp=nlp, options=options)
if solver_name == Solvers.proxqp:
return self._create_proxqp_solver(nlp=nlp, options=options)
if solver_name == Solvers.osqp:
return self._create_osqp_solver(nlp=nlp, options=options)
if solver_name == Solvers.gurobi:
return self._create_gurobi_solver(
nlp=nlp, options=options, discrete=discrete
Expand Down Expand Up @@ -235,6 +241,26 @@ def _create_qpoases_solver(self, nlp: dict, options: dict):
opts = {**default_opts, **options}
return ca.qpsol("mpc", "qpoases", nlp, opts)

def _create_proxqp_solver(self, nlp: dict, options: dict):
default_opts = {
"verbose": False,
"print_time": False,
"record_time": True,
"proxqp": {"max_iter": 200, "eps_abs": 1e-4, "backend": "sparse"},
}
opts = {**default_opts, **options}
return ca.qpsol("mpc", "proxqp", nlp, opts)

def _create_osqp_solver(self, nlp: dict, options: dict):
default_opts = {
"verbose": False,
"print_time": False,
"record_time": True,
"osqp": {"max_iter": 200, "eps_abs": 1e-4, "verbose": False},
}
opts = {**default_opts, **options}
return ca.qpsol("mpc", "osqp", nlp, opts)

def _create_gurobi_solver(
self, nlp: dict, options: dict, discrete: DiscreteVars = None
):
Expand Down
11 changes: 3 additions & 8 deletions agentlib_mpc/models/casadi_ml_model.py
Original file line number Diff line number Diff line change
Expand Up @@ -183,11 +183,6 @@ def __init__(self, **kwargs):
# construct a stage function for optimization and simulation
self.sim_step = self._make_unified_predict_function()

def specify_ann_constructed_features(self):
"""to be implemented by user
todo example"""
pass

def setup_system(self):
return 0

Expand Down Expand Up @@ -380,9 +375,9 @@ def register_ml_models(
for output in self.config.outputs + self.config.states:
for serialized_output_names, ml_model in ml_model_sources_dict.items():
if output.name in serialized_output_names:
output_to_ml_model[output.name] = (
CasadiPredictor.from_serialized_model(ml_model)
)
output_to_ml_model[
output.name
] = CasadiPredictor.from_serialized_model(ml_model)
ml_model_dict[output.name] = ml_model
casadi_ml_model_dict: Dict[str, CasadiPredictor] = output_to_ml_model
return ml_model_dict, casadi_ml_model_dict
Expand Down
2 changes: 1 addition & 1 deletion agentlib_mpc/models/casadi_model.py
Original file line number Diff line number Diff line change
Expand Up @@ -223,7 +223,7 @@ def __attrs_post_init__(self):
@property
def alg(self) -> CasadiTypes:
raise AttributeError(
"Casadi States should not have .alg assignments. If you wish to provide "
"Casadi Inputs should not have .alg assignments. If you wish to provide "
"algebraic relationships to states, add them in the constraints."
)
return -1
Expand Down
15 changes: 14 additions & 1 deletion agentlib_mpc/modules/dmpc/admm/admm_coordinated.py
Original file line number Diff line number Diff line change
Expand Up @@ -2,8 +2,9 @@
with a coordinator."""

from collections import namedtuple
from typing import Dict, Optional
from typing import Dict, Optional, List
import pandas as pd
import pydantic

from agentlib_mpc.data_structures.mpc_datamodels import MPCVariable
from .admm import ADMM, ADMMConfig
Expand All @@ -22,6 +23,18 @@ class CoordinatedADMMConfig(MiniEmployeeConfig, ADMMConfig):
"shared_variable_fields"
) + ADMMConfig.default("shared_variable_fields")

@pydantic.field_validator("couplings", "exchange")
def couplings_should_have_values(cls, value: List[AgentVariable]):
"""Asserts that couplings and exchange have values, as they are needed for
initial guess."""
for var in value:
if var.value is None:
raise ValueError(
"Couplings and Exchange Variables should have a value, as it is "
"required for the initial guess."
)
return value


class CoordinatedADMM(MiniEmployee, ADMM):
"""
Expand Down
6 changes: 3 additions & 3 deletions agentlib_mpc/modules/mpc.py
Original file line number Diff line number Diff line change
Expand Up @@ -279,9 +279,9 @@ def _init_optimization(self):

def re_init_optimization(self, parameter: AgentVariable):
"""Re-initializes the optimization backend with new parameters."""
self.optimization_backend.discretization_options[parameter.name] = (
parameter.value
)
self.optimization_backend.discretization_options[
parameter.name
] = parameter.value
self._init_optimization()

@property
Expand Down
4 changes: 2 additions & 2 deletions agentlib_mpc/modules/mpc_full.py
Original file line number Diff line number Diff line change
Expand Up @@ -62,7 +62,7 @@ def _init_optimization(self):
history[v] = {}
# store scalar values as initial if they exist
if isinstance(var.value, (float, int)):
timestamp = var.timestamp or self.env.now
timestamp = var.timestamp or self.env.time
value = var.value
elif var.value is None:
self.logger.info(
Expand Down Expand Up @@ -93,7 +93,7 @@ def _remove_old_values_from_history(self):

# iterate over all saved values and delete them, if they are too old
for timestamp in list(var_history):
if timestamp < (self.env.now - lag_in_seconds):
if timestamp < (self.env.time - lag_in_seconds):
var_history.pop(timestamp)

def _callback_hist_vars(self, variable: AgentVariable, name: str):
Expand Down
12 changes: 10 additions & 2 deletions agentlib_mpc/optimization_backends/__init__.py
Original file line number Diff line number Diff line change
Expand Up @@ -41,12 +41,20 @@ def __call__(self, *args, **kwargs):
import_path="agentlib_mpc.optimization_backends.casadi_.minlp_cia",
class_name="CasADiCIABackend",
),
"casadi_ml": BackendImport(
import_path="agentlib_mpc.optimization_backends.casadi_.casadi_ml",
class_name="CasADiBBBackend",
),
"casadi_admm_ml": BackendImport(
import_path="agentlib_mpc.optimization_backends.casadi_.casadi_admm_ml",
class_name="CasADiADMMBackend_NN",
),
"casadi_nn": BackendImport(
import_path="agentlib_mpc.optimization_backends.casadi_.casadi_nn",
import_path="agentlib_mpc.optimization_backends.casadi_.casadi_ml",
class_name="CasADiBBBackend",
),
"casadi_admm_nn": BackendImport(
import_path="agentlib_mpc.optimization_backends.casadi_.casadi_admm_nn",
import_path="agentlib_mpc.optimization_backends.casadi_.casadi_admm_ml",
class_name="CasADiADMMBackend_NN",
),
"casadi_mhe": BackendImport(
Expand Down
13 changes: 10 additions & 3 deletions agentlib_mpc/optimization_backends/casadi_/admm.py
Original file line number Diff line number Diff line change
Expand Up @@ -257,7 +257,7 @@ def _discretize(self, sys: CasadiADMMSystem):
# integral and multiple shooting constraint
fk = opt_integrator(
x0=xk,
p=ca.vertcat(uk, v_localk, dk, const_par),
p=ca.vertcat(uk, v_localk, dk, const_par, zk, yk),
)
xk_end = fk["xf"]
self.k += 1
Expand Down Expand Up @@ -289,10 +289,17 @@ def _create_ode(
sys.local_couplings.full_symbolic,
sys.non_controlled_inputs.full_symbolic,
sys.model_parameters.full_symbolic,
sys.algebraics.full_symbolic,
sys.outputs.full_symbolic,
)
integrator_ode = {"x": x, "p": p, "ode": ode}
opt_integrator = ca.integrator("system", integrator, integrator_ode, opts)

if integrator == Integrators.euler:
xk_end = x + ode * opts["tf"]
opt_integrator = ca.Function(
"system", [x, p], [xk_end], ["x0", "p"], ["xf"]
)
else: # rk, cvodes
opt_integrator = ca.integrator("system", integrator, integrator_ode, opts)
return opt_integrator


Expand Down
5 changes: 4 additions & 1 deletion agentlib_mpc/optimization_backends/casadi_/basic.py
Original file line number Diff line number Diff line change
Expand Up @@ -430,7 +430,7 @@ def _discretize(self, sys: BaseSystem):
)
fk = opt_integrator(
x0=xk,
p=ca.vertcat(uk, dk, const_par),
p=ca.vertcat(uk, dk, const_par, zk, yk),
)
xk_end = fk["xf"]
# calculate model constraint
Expand All @@ -449,10 +449,13 @@ def _create_ode(self, sys: BaseSystem, opts: dict, integrator: Integrators):
ode = sys.ode
# create inputs
x = sys.states.full_symbolic
# the order of elements here is important when calling the integrator!
p = ca.vertcat(
sys.controls.full_symbolic,
sys.non_controlled_inputs.full_symbolic,
sys.model_parameters.full_symbolic,
sys.algebraics.full_symbolic,
sys.outputs.full_symbolic,
)
integrator_ode = {"x": x, "p": p, "ode": ode}

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -12,10 +12,10 @@
)
from agentlib_mpc.data_structures.ml_model_datatypes import name_with_lag
from agentlib_mpc.models.casadi_ml_model import CasadiMLModel
from agentlib_mpc.optimization_backends.casadi_.casadi_nn import (
CasadiNNSystem,
from agentlib_mpc.optimization_backends.casadi_.casadi_ml import (
CasadiMLSystem,
CasADiBBBackend,
MultipleShooting_NN,
MultipleShooting_ML,
)
from agentlib_mpc.optimization_backends.casadi_.core.VariableGroup import (
OptimizationVariable,
Expand All @@ -31,7 +31,7 @@
logger = logging.getLogger(__name__)


class CasadiADMMNNSystem(CasadiADMMSystem, CasadiNNSystem):
class CasadiADMMNNSystem(CasadiADMMSystem, CasadiMLSystem):
"""
In this class, the lags are determined by the trainer alone and the lags are
saved in the serialized MLModel so that it doesn't have to be defined in the
Expand Down Expand Up @@ -236,7 +236,7 @@ def sim_step_quantities(
}


class MultipleShootingADMMNN(ADMMMultipleShooting, MultipleShooting_NN):
class MultipleShootingADMMNN(ADMMMultipleShooting, MultipleShooting_ML):
max_lag: int

def _discretize(self, sys: CasadiADMMNNSystem):
Expand Down Expand Up @@ -331,9 +331,6 @@ def _discretize(self, sys: CasadiADMMNNSystem):
self.pred_time += ts
mx_dict[self.pred_time] = {sys.states.name: self.add_opt_var(sys.states)}

# control of last time step
mx_dict[0 - ts][sys.controls.name] = self.add_opt_par(sys.last_control)

all_quantities = sys.all_system_quantities()
# add constraints and create the objective function for all stages
for time in prediction_grid:
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -28,7 +28,7 @@
from agentlib_mpc.optimization_backends.casadi_.full import FullSystem


class CasadiNNSystem(FullSystem):
class CasadiMLSystem(FullSystem):
# multiple possibilities of using the MLModel
# stage function for neural networks
model: CasadiMLModel
Expand Down Expand Up @@ -73,14 +73,14 @@ def initialize(self, model: CasadiMLModel, var_ref: FullVariableReference):
ref_list=var_ref.parameters,
)
self.initial_state = OptimizationParameter.declare(
denotation="initial_state", # append the 0 as a convention to get initial guess
denotation="initial_state",
variables=model.get_states(var_ref.states),
ref_list=var_ref.states,
use_in_stage_function=False,
assert_complete=True,
)
EserSteffen marked this conversation as resolved.
Show resolved Hide resolved
self.last_control = OptimizationParameter.declare(
denotation="initial_control", # append the 0 as a convention to get initial guess
denotation="initial_control",
variables=model.get_inputs(var_ref.controls),
ref_list=var_ref.controls,
use_in_stage_function=False,
Expand Down Expand Up @@ -115,10 +115,10 @@ def all_system_quantities(self) -> dict[str, OptimizationQuantity]:
return {var.name: var for var in self.quantities}


class MultipleShooting_NN(MultipleShooting):
class MultipleShooting_ML(MultipleShooting):
max_lag: int

def _discretize(self, sys: CasadiNNSystem):
def _discretize(self, sys: CasadiMLSystem):
n = self.options.prediction_horizon
ts = self.options.time_step
const_par = self.add_opt_par(sys.model_parameters)
Expand Down Expand Up @@ -147,6 +147,11 @@ def _discretize(self, sys: CasadiNNSystem):
sys.states, lb=x_past, ub=x_past, guess=x_past
)
mx_dict[time][sys.initial_state.name] = x_past
y_past = self.add_opt_par(sys.initial_output)
mx_dict[time][sys.outputs.name] = self.add_opt_var(
sys.outputs, lb=y_past, ub=y_past, guess=y_past
)
mx_dict[time][sys.initial_output.name] = y_past

# add past inputs
for time in pre_grid_inputs:
Expand Down Expand Up @@ -179,9 +184,6 @@ def _discretize(self, sys: CasadiNNSystem):
self.pred_time += ts
mx_dict[self.pred_time] = {sys.states.name: self.add_opt_var(sys.states)}

# control of last time step
mx_dict[0 - ts][sys.controls.name] = self.add_opt_par(sys.last_control)

all_quantities = sys.all_system_quantities()
# add constraints and create the objective function for all stages
for time in prediction_grid:
Expand Down Expand Up @@ -231,13 +233,13 @@ def _discretize(self, sys: CasadiNNSystem):
)
self.objective_function += stage_result["cost_function"] * ts

def initialize(self, system: CasadiNNSystem, solver_factory: SolverFactory):
def initialize(self, system: CasadiMLSystem, solver_factory: SolverFactory):
"""Initializes the trajectory optimization problem, creating all symbolic
variables of the OCP, the mapping function and the numerical solver."""
self._construct_stage_function(system)
super().initialize(system=system, solver_factory=solver_factory)

def _construct_stage_function(self, system: CasadiNNSystem):
def _construct_stage_function(self, system: CasadiMLSystem):
"""
Combine information from the model and the var_ref to create CasADi
functions which describe the system dynamics and constraints at each
Expand Down Expand Up @@ -343,7 +345,7 @@ def _construct_stage_function(self, system: CasadiNNSystem):
output_denotations,
)

def _create_lag_structure_for_denotations(self, system: CasadiNNSystem):
def _create_lag_structure_for_denotations(self, system: CasadiMLSystem):
all_system_quantities = self.all_system_quantities(system)
all_input_variables = {}
lagged_inputs: dict[int, dict[str, ca.MX]] = {}
Expand Down Expand Up @@ -381,9 +383,9 @@ class CasADiBBBackend(CasADiBaseBackend):
Class doing optimization with a MLModel.
"""

system_type = CasadiNNSystem
discretization_types = {DiscretizationMethod.multiple_shooting: MultipleShooting_NN}
system: CasadiNNSystem
system_type = CasadiMLSystem
discretization_types = {DiscretizationMethod.multiple_shooting: MultipleShooting_ML}
system: CasadiMLSystem
# a dictionary of collections of the variable lags
lag_collection: Dict[str, collections.deque] = {}
max_lag: int
Expand Down
Original file line number Diff line number Diff line change
@@ -1,10 +1,9 @@
import logging
import platform
from pathlib import Path
from typing import Callable, Type, Optional
from typing import Type, Optional

import casadi as ca
import pandas as pd
import pydantic
from agentlib.core.errors import ConfigurationError

Expand Down
Loading