From 999a9c14a97dbbfc6f41b75b55859c9039cc4a0c Mon Sep 17 00:00:00 2001 From: Jonathan Frey Date: Fri, 5 Jul 2024 19:44:03 +0200 Subject: [PATCH 01/14] Python cleanup (#1146) - deprecate `get_default_simulink_opts`, use `get_simulink_default_opts` instead - return `x0` if set --- .../ocp/nonuniform_discretization_example.py | 7 ++--- .../pendulum_on_cart/ocp/simulink_example.py | 4 +-- .../pendulum_on_cart/minimal_example_zoro.py | 4 +-- .../acados_template/acados_ocp_constraints.py | 27 +++++++++++++------ .../acados_template/acados_template/utils.py | 8 +++--- 5 files changed, 28 insertions(+), 22 deletions(-) diff --git a/examples/acados_python/pendulum_on_cart/ocp/nonuniform_discretization_example.py b/examples/acados_python/pendulum_on_cart/ocp/nonuniform_discretization_example.py index 575acd2c0f..19b3677989 100644 --- a/examples/acados_python/pendulum_on_cart/ocp/nonuniform_discretization_example.py +++ b/examples/acados_python/pendulum_on_cart/ocp/nonuniform_discretization_example.py @@ -32,7 +32,7 @@ import sys, json, os sys.path.insert(0, '../common') -from acados_template import AcadosOcp, AcadosOcpSolver, acados_dae_model_json_dump, get_acados_path +from acados_template import AcadosOcp, AcadosOcpSolver, acados_dae_model_json_dump, get_acados_path, get_simulink_default_opts from pendulum_model import export_pendulum_ode_model import numpy as np import scipy.linalg @@ -141,10 +141,7 @@ def main(discretization='shooting_nodes'): ocp.solver_options.initialize_t_slacks = 1 # Set additional options for Simulink interface: - acados_path = get_acados_path() - json_path = os.path.join(acados_path, 'interfaces/acados_template/acados_template') - with open(json_path + '/simulink_default_opts.json', 'r') as f: - simulink_opts = json.load(f) + simulink_opts = get_simulink_default_opts() ocp_solver = AcadosOcpSolver(ocp, json_file = 'acados_ocp.json', simulink_opts = simulink_opts, verbose=False) # ocp_solver = AcadosOcpSolver(ocp, json_file = 'acados_ocp.json') diff --git a/examples/acados_python/pendulum_on_cart/ocp/simulink_example.py b/examples/acados_python/pendulum_on_cart/ocp/simulink_example.py index d4aa5784a3..276a4fdde9 100644 --- a/examples/acados_python/pendulum_on_cart/ocp/simulink_example.py +++ b/examples/acados_python/pendulum_on_cart/ocp/simulink_example.py @@ -31,7 +31,7 @@ import sys sys.path.insert(0, '../common') -from acados_template import AcadosOcp, AcadosOcpSolver, get_default_simulink_opts +from acados_template import AcadosOcp, AcadosOcpSolver, get_simulink_default_opts from pendulum_model import export_pendulum_ode_model import numpy as np # from utils import plot_pendulum @@ -84,7 +84,7 @@ def main(): ocp.solver_options.tf = Tf # to generate Simulink wrapper for solver - simulink_opts = get_default_simulink_opts() # modify those options, if you like. + simulink_opts = get_simulink_default_opts() # modify those options, if you like. # create solver ocp_solver = AcadosOcpSolver(ocp, json_file = 'acados_ocp.json', simulink_opts=simulink_opts) diff --git a/examples/acados_python/zoRO_example/pendulum_on_cart/minimal_example_zoro.py b/examples/acados_python/zoRO_example/pendulum_on_cart/minimal_example_zoro.py index fcdfead1d5..e5a7572bf6 100644 --- a/examples/acados_python/zoRO_example/pendulum_on_cart/minimal_example_zoro.py +++ b/examples/acados_python/zoRO_example/pendulum_on_cart/minimal_example_zoro.py @@ -31,7 +31,7 @@ import numpy as np import scipy.linalg -from acados_template import AcadosOcp, AcadosOcpSolver, ZoroDescription, get_default_simulink_opts +from acados_template import AcadosOcp, AcadosOcpSolver, ZoroDescription, get_simulink_default_opts # same as in normal pendulum model local_path = os.path.dirname(os.path.abspath(__file__)) @@ -136,7 +136,7 @@ def main(): ocp.zoro_description = zoro_description # to export Simulink block - simulink_opts = get_default_simulink_opts() + simulink_opts = get_simulink_default_opts() simulink_opts['inputs']['lbx'] = 0 simulink_opts['inputs']['ubx'] = 0 simulink_opts['inputs']['lbx_e'] = 0 diff --git a/interfaces/acados_template/acados_template/acados_ocp_constraints.py b/interfaces/acados_template/acados_template/acados_ocp_constraints.py index e54b00f9f2..09e7d02a62 100644 --- a/interfaces/acados_template/acados_template/acados_ocp_constraints.py +++ b/interfaces/acados_template/acados_template/acados_ocp_constraints.py @@ -743,17 +743,28 @@ def Jsphi_e(self): @property def x0(self): - """:math:`x_0 \\in \mathbb{R}^{n_x}` - initial state -- - Translated internally to :py:attr:`idxbx_0`, :py:attr:`lbx_0`, :py:attr:`ubx_0`, :py:attr:`idxbxe_0` """ - print("x0 is converted to lbx_0, ubx_0, idxbx_0") - print("idxbx_0: ", self.__idxbx_0) - print("lbx_0: ", self.__lbx_0) - print("ubx_0: ", self.__ubx_0) - print("idxbxe_0: ", self.__idxbxe_0) - return None + """ + :math:`x_0 \\in \mathbb{R}^{n_x}` - initial state -- + Translated internally to :py:attr:`idxbx_0`, :py:attr:`lbx_0`, :py:attr:`ubx_0`, :py:attr:`idxbxe_0` + """ + if self.has_x0: + return self.lbx_0 + else: + print("x0 is not set. You can set it or specify lbx_0, ubx_0, idxbx_0, idxbxe_0 to implement general bounds on x0.") + print("") + print("idxbx_0: ", self.__idxbx_0) + print("lbx_0: ", self.__lbx_0) + print("ubx_0: ", self.__ubx_0) + print("idxbxe_0: ", self.__idxbxe_0) + return None @property def has_x0(self): + """ + Internal variable to check if x0 is set. + Cannot be set from outside. + :bool: True if x0 is set, False otherwise. + """ return self.__has_x0 # SETTERS diff --git a/interfaces/acados_template/acados_template/utils.py b/interfaces/acados_template/acados_template/utils.py index cb6bc40a5b..da8d7d139a 100644 --- a/interfaces/acados_template/acados_template/utils.py +++ b/interfaces/acados_template/acados_template/utils.py @@ -335,11 +335,9 @@ def format_class_dict(d): return out def get_default_simulink_opts() -> dict: - python_interface_path = get_python_interface_path() - abs_path = os.path.join(python_interface_path, 'simulink_default_opts.json') - with open(abs_path, 'r') as f: - simulink_opts = json.load(f) - return simulink_opts + print("get_default_simulink_opts is deprecated, use get_simulink_default_opts instead." + + " This function will be removed in a future release.") + return get_simulink_default_opts() def J_to_idx(J): From b1ee24f448ef548258138d9aa8c9aa848c0b9c48 Mon Sep 17 00:00:00 2001 From: Jonathan Frey Date: Mon, 8 Jul 2024 09:33:39 +0200 Subject: [PATCH 02/14] Getters for partial condensing matrices Q, R, S (#1145) --- acados/ocp_qp/ocp_qp_xcond_solver.c | 33 +++++++++- .../ocp/nonuniform_discretization_example.py | 36 ++++++++++- interfaces/acados_c/ocp_nlp_interface.c | 61 ++++++++++++++----- .../acados_template/acados_ocp_solver.py | 10 ++- 4 files changed, 118 insertions(+), 22 deletions(-) diff --git a/acados/ocp_qp/ocp_qp_xcond_solver.c b/acados/ocp_qp/ocp_qp_xcond_solver.c index 95fbee0865..1a127e1308 100644 --- a/acados/ocp_qp/ocp_qp_xcond_solver.c +++ b/acados/ocp_qp/ocp_qp_xcond_solver.c @@ -143,10 +143,37 @@ void ocp_qp_xcond_solver_dims_set_(void *config_, ocp_qp_xcond_solver_dims *dims void ocp_qp_xcond_solver_dims_get_(void *config_, ocp_qp_xcond_solver_dims *dims, int stage, const char *field, int* value) { - // get from orig_dims - ocp_qp_dims_get(config_, dims->orig_dims, stage, field, value); + // extract module name + char module[MAX_STR_LEN]; + char *ptr_module = NULL; + int module_length; + char *char_ = strchr(field, '_'); + if (char_!=NULL) + { + module_length = char_-field; + for (int ii=0; iixcond; + void *xcond_qp_dims; + xcond->dims_get(xcond, dims->xcond_dims, "xcond_dims", &xcond_qp_dims); + ocp_qp_dims_get(config_, xcond_qp_dims, stage, &field[6], value); + return; + } + else + { + // get from orig_dims + ocp_qp_dims_get(config_, dims->orig_dims, stage, field, value); + + return; + } } diff --git a/examples/acados_python/pendulum_on_cart/ocp/nonuniform_discretization_example.py b/examples/acados_python/pendulum_on_cart/ocp/nonuniform_discretization_example.py index 19b3677989..99237e1e51 100644 --- a/examples/acados_python/pendulum_on_cart/ocp/nonuniform_discretization_example.py +++ b/examples/acados_python/pendulum_on_cart/ocp/nonuniform_discretization_example.py @@ -38,6 +38,10 @@ import scipy.linalg from utils import plot_pendulum +import matplotlib.pyplot as plt + +import casadi as ca + TOL = 1e-7 def main(discretization='shooting_nodes'): @@ -144,9 +148,6 @@ def main(discretization='shooting_nodes'): simulink_opts = get_simulink_default_opts() ocp_solver = AcadosOcpSolver(ocp, json_file = 'acados_ocp.json', simulink_opts = simulink_opts, verbose=False) - # ocp_solver = AcadosOcpSolver(ocp, json_file = 'acados_ocp.json') - - simX = np.zeros((N+1, nx)) simU = np.zeros((N, nu)) @@ -175,6 +176,35 @@ def main(discretization='shooting_nodes'): simU[i,:] = ocp_solver.get(i, "u") simX[N,:] = ocp_solver.get(N, "x") + # get condensed Hessian + pcond_H = [] + pcond_Q = [] + pcond_R = [] + pcond_S = [] + for i in range(ocp.solver_options.qp_solver_cond_N+1): + pcond_Q.append(ocp_solver.get_from_qp_in(i, "pcond_Q")) + pcond_R.append(ocp_solver.get_from_qp_in(i, "pcond_R")) + pcond_S.append(ocp_solver.get_from_qp_in(i, "pcond_S")) + + pcond_RSQ = ca.blockcat(pcond_Q[-1], pcond_S[-1].T, pcond_S[-1], pcond_R[-1]).full() + # copy lower triangular part to upper triangular part + pcond_RSQ = np.tril(pcond_RSQ) + np.tril(pcond_RSQ, -1).T + pcond_H.append(pcond_RSQ) + + # pcond_H = ocp_solver.get_from_qp_in(ocp.solver_options.qp_solver_cond_N, "pcond_H") + # print("pcond_H", pcond_H) + # pcond_H_mat = scipy.linalg.block_diag(*pcond_H) + # plt.spy(pcond_H_mat) + # plt.show() + + # check dimensions of partially condensed matrices + assert pcond_Q[0].shape == (0, 0) + for i in range(1, ocp.solver_options.qp_solver_cond_N+1): + assert pcond_Q[i].shape == (nx, nx) + for i in range(ocp.solver_options.qp_solver_cond_N+1): + block_size = ocp.solver_options.qp_solver_cond_block_size[i] + assert pcond_R[i].shape == (nu*block_size, nu*block_size) + print("inequality multipliers at stage 1") print(ocp_solver.get(1, "lam")) # inequality multipliers at stage 1 print("slack values at stage 1") diff --git a/interfaces/acados_c/ocp_nlp_interface.c b/interfaces/acados_c/ocp_nlp_interface.c index 5b5b3f92d0..0a043f631a 100644 --- a/interfaces/acados_c/ocp_nlp_interface.c +++ b/interfaces/acados_c/ocp_nlp_interface.c @@ -612,7 +612,7 @@ int ocp_nlp_dims_get_from_attr(ocp_nlp_config *config, ocp_nlp_dims *dims, ocp_n int dims_value = -1; // ocp_nlp_dims - if (!strcmp(field, "x")) + if (!strcmp(field, "x") || !strcmp(field, "nx")) { return dims->nx[stage]; } @@ -620,15 +620,15 @@ int ocp_nlp_dims_get_from_attr(ocp_nlp_config *config, ocp_nlp_dims *dims, ocp_n { return dims->nx[stage+1]; } - else if (!strcmp(field, "u")) + else if (!strcmp(field, "u") || !strcmp(field, "nu")) { return dims->nu[stage]; } - else if (!strcmp(field, "z")) + else if (!strcmp(field, "z") || !strcmp(field, "nz")) { return dims->nz[stage]; } - else if (!strcmp(field, "p")) + else if (!strcmp(field, "p") || !strcmp(field, "np")) { return dims->np[stage]; } @@ -662,32 +662,32 @@ int ocp_nlp_dims_get_from_attr(ocp_nlp_config *config, ocp_nlp_dims *dims, ocp_n return dims_value; } // ocp_nlp_constraints_dims - else if (!strcmp(field, "lbx") || !strcmp(field, "ubx")) + else if (!strcmp(field, "lbx") || !strcmp(field, "ubx") || !strcmp(field, "nbx")) { config->constraints[stage]->dims_get(config->constraints[stage], dims->constraints[stage], "nbx", &dims_value); return dims_value; } - else if (!strcmp(field, "lbu") || !strcmp(field, "ubu")) + else if (!strcmp(field, "lbu") || !strcmp(field, "ubu") || !strcmp(field, "nbu")) { config->constraints[stage]->dims_get(config->constraints[stage], dims->constraints[stage], "nbu", &dims_value); return dims_value; } - else if (!strcmp(field, "lg") || !strcmp(field, "ug")) + else if (!strcmp(field, "lg") || !strcmp(field, "ug") || !strcmp(field, "ng")) { config->constraints[stage]->dims_get(config->constraints[stage], dims->constraints[stage], "ng", &dims_value); return dims_value; } - else if (!strcmp(field, "lh") || !strcmp(field, "uh")) + else if (!strcmp(field, "lh") || !strcmp(field, "uh") || !strcmp(field, "nh")) { config->constraints[stage]->dims_get(config->constraints[stage], dims->constraints[stage], "nh", &dims_value); return dims_value; } // ocp_nlp_cost_dims - else if (!strcmp(field, "y_ref") || !strcmp(field, "yref")) + else if (!strcmp(field, "y_ref") || !strcmp(field, "yref") || !strcmp(field, "ny")) { config->cost[stage]->dims_get(config->cost[stage], dims->cost[stage], "ny", &dims_value); @@ -707,31 +707,31 @@ void ocp_nlp_constraint_dims_get_from_attr(ocp_nlp_config *config, ocp_nlp_dims // vectors first dims_out[1] = 0; // ocp_nlp_constraints_dims - if (!strcmp(field, "lbx") || !strcmp(field, "ubx")) + if (!strcmp(field, "lbx") || !strcmp(field, "ubx") || !strcmp(field, "nbx")) { config->constraints[stage]->dims_get(config->constraints[stage], dims->constraints[stage], "nbx", &dims_out[0]); return; } - else if (!strcmp(field, "uphi")) + else if (!strcmp(field, "uphi") || !strcmp(field, "nphi")) { config->constraints[stage]->dims_get(config->constraints[stage], dims->constraints[stage], "nphi", &dims_out[0]); return; } - else if (!strcmp(field, "lbu") || !strcmp(field, "ubu")) + else if (!strcmp(field, "lbu") || !strcmp(field, "ubu") || !strcmp(field, "nbu")) { config->constraints[stage]->dims_get(config->constraints[stage], dims->constraints[stage], "nbu", &dims_out[0]); return; } - else if (!strcmp(field, "lg") || !strcmp(field, "ug")) + else if (!strcmp(field, "lg") || !strcmp(field, "ug") || !strcmp(field, "ng")) { config->constraints[stage]->dims_get(config->constraints[stage], dims->constraints[stage], "ng", &dims_out[0]); return; } - else if (!strcmp(field, "lh") || !strcmp(field, "uh")) + else if (!strcmp(field, "lh") || !strcmp(field, "uh") || !strcmp(field, "nh")) { config->constraints[stage]->dims_get(config->constraints[stage], dims->constraints[stage], "nh", &dims_out[0]); @@ -855,6 +855,21 @@ void ocp_nlp_qp_dims_get_from_attr(ocp_nlp_config *config, ocp_nlp_dims *dims, o config->qp_solver->dims_get(config->qp_solver, dims->qp_solver, stage, "nbu", &dims_out[0]); dims_out[1] = 1; } + else if (!strcmp(field, "pcond_R")) + { + config->qp_solver->dims_get(config->qp_solver, dims->qp_solver, stage, "pcond_nu", &dims_out[0]); + config->qp_solver->dims_get(config->qp_solver, dims->qp_solver, stage, "pcond_nu", &dims_out[1]); + } + else if (!strcmp(field, "pcond_Q")) + { + config->qp_solver->dims_get(config->qp_solver, dims->qp_solver, stage, "pcond_nx", &dims_out[0]); + config->qp_solver->dims_get(config->qp_solver, dims->qp_solver, stage, "pcond_nx", &dims_out[1]); + } + else if (!strcmp(field, "pcond_S")) + { + config->qp_solver->dims_get(config->qp_solver, dims->qp_solver, stage, "pcond_nu", &dims_out[0]); + config->qp_solver->dims_get(config->qp_solver, dims->qp_solver, stage, "pcond_nx", &dims_out[1]); + } else { printf("\nerror: ocp_nlp_qp_dims_get_from_attr: field %s not available\n", field); @@ -1265,6 +1280,24 @@ void ocp_nlp_get_at_stage(ocp_nlp_config *config, ocp_nlp_dims *dims, ocp_nlp_so } xcond_solver_config->solver_get(xcond_solver_config, nlp_mem->qp_in, nlp_mem->qp_out, nlp_opts->qp_solver_opts, nlp_mem->qp_solver_mem, field, stage, value, size1, size2); } + else if (!strcmp(field, "pcond_Q")) + { + ocp_qp_in *pcond_qp_in; + ocp_nlp_get(config, solver, "qp_xcond_in", &pcond_qp_in); + d_ocp_qp_get_Q(stage, pcond_qp_in, value); + } + else if (!strcmp(field, "pcond_R")) + { + ocp_qp_in *pcond_qp_in; + ocp_nlp_get(config, solver, "qp_xcond_in", &pcond_qp_in); + d_ocp_qp_get_R(stage, pcond_qp_in, value); + } + else if (!strcmp(field, "pcond_S")) + { + ocp_qp_in *pcond_qp_in; + ocp_nlp_get(config, solver, "qp_xcond_in", &pcond_qp_in); + d_ocp_qp_get_S(stage, pcond_qp_in, value); + } else { printf("\nerror: ocp_nlp_get_at_stage: field %s not available\n", field); diff --git a/interfaces/acados_template/acados_template/acados_ocp_solver.py b/interfaces/acados_template/acados_template/acados_ocp_solver.py index 39f5a5551d..32248c5ada 100644 --- a/interfaces/acados_template/acados_template/acados_ocp_solver.py +++ b/interfaces/acados_template/acados_template/acados_ocp_solver.py @@ -263,6 +263,7 @@ def __init__(self, acados_ocp: Union[AcadosOcp, AcadosMultiphaseOcp], json_file= self.__qp_cost_fields = ['Q', 'R', 'S', 'q', 'r'] self.__qp_constraint_fields = ['C', 'D', 'lg', 'ug', 'lbx', 'ubx', 'lbu', 'ubu'] self.__qp_pc_hpipm_fields = ['P', 'K', 'Lr', 'p'] + self.__qp_pc_fields = ['pcond_Q', 'pcond_R', 'pcond_S'] # set arg and res types self.__acados_lib.ocp_nlp_dims_get_from_attr.argtypes = [c_void_p, c_void_p, c_void_p, c_int, c_char_p] @@ -1374,7 +1375,10 @@ def get_from_qp_in(self, stage_: int, field_: str): :param stage: integer corresponding to shooting node :param field: string in ['A', 'B', 'b', 'Q', 'R', 'S', 'q', 'r', 'C', 'D', 'lg', 'ug', 'lbx', 'ubx', 'lbu', 'ubu'] - Note: additional supported fields are ['P', 'K', 'Lr'], which can be extracted form QP solver PARTIAL_CONDENSING_HPIPM. + Note: + - additional supported fields are ['P', 'K', 'Lr'], which can be extracted form QP solver PARTIAL_CONDENSING_HPIPM. + - for PARTIAL_CONDENSING_* QP solvers, the following additional fields are available: + ['pcond_Q', 'pcond_R', 'pcond_S'] """ # idx* should be added too.. if not isinstance(stage_, int): @@ -1383,13 +1387,15 @@ def get_from_qp_in(self, stage_: int, field_: str): raise Exception("stage should be <= self.N") if field_ in self.__qp_dynamics_fields and stage_ >= self.N: raise ValueError(f"dynamics field {field_} not available at terminal stage") - if field_ not in self.__qp_dynamics_fields + self.__qp_cost_fields + self.__qp_constraint_fields + self.__qp_pc_hpipm_fields: + if field_ not in self.__qp_dynamics_fields + self.__qp_cost_fields + self.__qp_constraint_fields + self.__qp_pc_hpipm_fields + self.__qp_pc_fields: raise Exception(f"field {field_} not supported.") if field_ in self.__qp_pc_hpipm_fields: if self.acados_ocp.solver_options.qp_solver != "PARTIAL_CONDENSING_HPIPM" or self.acados_ocp.solver_options.qp_solver_cond_N != self.acados_ocp.dims.N: raise Exception(f"field {field_} only works for PARTIAL_CONDENSING_HPIPM QP solver with qp_solver_cond_N == N.") if field_ in ["P", "K", "p"] and stage_ == 0 and self.acados_ocp.dims.nbxe_0 > 0: raise Exception(f"getting field {field_} at stage 0 only works without x0 elimination (see nbxe_0).") + if field_ in self.__qp_pc_fields and not self.acados_ocp.solver_options.qp_solver.startswith("PARTIAL_CONDENSING"): + raise Exception(f"field {field_} only works for PARTIAL_CONDENSING QP solvers.") field = field_.encode('utf-8') stage = c_int(stage_) From 5d4898899ad68e75fb07a2484890e94b816abfcd Mon Sep 17 00:00:00 2001 From: Jonathan Frey Date: Mon, 8 Jul 2024 09:49:49 +0200 Subject: [PATCH 03/14] Add timers: `time_preparation`, `time_feedback` (#1147) --- acados/ocp_nlp/ocp_nlp_ddp.c | 10 ++++++++ acados/ocp_nlp/ocp_nlp_sqp.c | 10 ++++++++ acados/ocp_nlp/ocp_nlp_sqp_rti.c | 23 +++++++++++++++---- acados/ocp_nlp/ocp_nlp_sqp_rti.h | 2 ++ .../acados_template/acados_ocp_solver.py | 13 +++++++---- 5 files changed, 48 insertions(+), 10 deletions(-) diff --git a/acados/ocp_nlp/ocp_nlp_ddp.c b/acados/ocp_nlp/ocp_nlp_ddp.c index 3e0fa22f0a..af79e0ef35 100644 --- a/acados/ocp_nlp/ocp_nlp_ddp.c +++ b/acados/ocp_nlp/ocp_nlp_ddp.c @@ -1265,6 +1265,16 @@ void ocp_nlp_ddp_get(void *config_, void *dims_, void *mem_, const char *field, double *value = return_value_; *value = mem->time_sim_ad; } + else if (!strcmp("time_preparation", field)) + { + double *value = return_value_; + *value = 0.0; + } + else if (!strcmp("time_feedback", field)) + { + double *value = return_value_; + *value = mem->time_tot; + } else if (!strcmp("stat", field)) { double **value = return_value_; diff --git a/acados/ocp_nlp/ocp_nlp_sqp.c b/acados/ocp_nlp/ocp_nlp_sqp.c index 343dce2854..093e23637e 100644 --- a/acados/ocp_nlp/ocp_nlp_sqp.c +++ b/acados/ocp_nlp/ocp_nlp_sqp.c @@ -1131,6 +1131,16 @@ void ocp_nlp_sqp_get(void *config_, void *dims_, void *mem_, const char *field, double *value = return_value_; *value = mem->time_sim_ad; } + else if (!strcmp("time_preparation", field)) + { + double *value = return_value_; + *value = 0.0; + } + else if (!strcmp("time_feedback", field)) + { + double *value = return_value_; + *value = mem->time_tot; + } else if (!strcmp("stat", field)) { double **value = return_value_; diff --git a/acados/ocp_nlp/ocp_nlp_sqp_rti.c b/acados/ocp_nlp/ocp_nlp_sqp_rti.c index fafaf15fe4..190ff6bfb7 100644 --- a/acados/ocp_nlp/ocp_nlp_sqp_rti.c +++ b/acados/ocp_nlp/ocp_nlp_sqp_rti.c @@ -1219,14 +1219,17 @@ int ocp_nlp_sqp_rti(void *config_, void *dims_, void *nlp_in_, void *nlp_out_, if (rti_phase == FEEDBACK) { ocp_nlp_sqp_rti_feedback_step(config, dims, nlp_in, nlp_out, opts, mem, work); + mem->time_feedback = acados_toc(&timer); } else if (rti_phase == PREPARATION && opts->as_rti_level == STANDARD_RTI) { ocp_nlp_sqp_rti_preparation_step(config, dims, nlp_in, nlp_out, opts, mem, work); + mem->time_preparation = acados_toc(&timer); } else if (rti_phase == PREPARATION) { ocp_nlp_sqp_rti_preparation_advanced_step(config, dims, nlp_in, nlp_out, opts, mem, work); + mem->time_preparation = acados_toc(&timer); } else if (rti_phase == PREPARATION_AND_FEEDBACK && opts->as_rti_level != STANDARD_RTI) { @@ -1237,7 +1240,12 @@ int ocp_nlp_sqp_rti(void *config_, void *dims_, void *nlp_in_, void *nlp_out_, { // rti_phase == PREPARATION_AND_FEEDBACK ocp_nlp_sqp_rti_preparation_step(config, dims, nlp_in, nlp_out, opts, mem, work); + mem->time_preparation = acados_toc(&timer); + + acados_timer timer_feedback; + acados_tic(&timer_feedback); ocp_nlp_sqp_rti_feedback_step(config, dims, nlp_in, nlp_out, opts, mem, work); + mem->time_feedback = acados_toc(&timer_feedback); } mem->time_tot = acados_toc(&timer); @@ -1318,9 +1326,6 @@ void ocp_nlp_sqp_rti_eval_param_sens(void *config_, void *dims_, void *opts_, void ocp_nlp_sqp_rti_eval_lagr_grad_p(void *config_, void *dims_, void *nlp_in_, void *opts_, void *mem_, void *work_, const char *field, void *grad_p) { - acados_timer timer0; - acados_tic(&timer0); - ocp_nlp_dims *dims = dims_; ocp_nlp_config *config = config_; ocp_nlp_sqp_rti_opts *opts = opts_; @@ -1334,8 +1339,6 @@ void ocp_nlp_sqp_rti_eval_lagr_grad_p(void *config_, void *dims_, void *nlp_in_, ocp_nlp_common_eval_lagr_grad_p(config, dims, nlp_in, opts->nlp_opts, nlp_mem, nlp_work, field, grad_p); - mem->time_solution_sensitivities = acados_toc(&timer0); - return; } @@ -1405,6 +1408,16 @@ void ocp_nlp_sqp_rti_get(void *config_, void *dims_, void *mem_, *ptr += tmp; } } + else if (!strcmp("time_preparation", field)) + { + double *value = return_value_; + *value = mem->time_preparation; + } + else if (!strcmp("time_feedback", field)) + { + double *value = return_value_; + *value = mem->time_feedback; + } else if (!strcmp("time_solution_sensitivities", field)) { double *value = return_value_; diff --git a/acados/ocp_nlp/ocp_nlp_sqp_rti.h b/acados/ocp_nlp/ocp_nlp_sqp_rti.h index 956e2492f3..8a4ffa439a 100644 --- a/acados/ocp_nlp/ocp_nlp_sqp_rti.h +++ b/acados/ocp_nlp/ocp_nlp_sqp_rti.h @@ -124,6 +124,8 @@ typedef struct double time_reg; double time_tot; double time_glob; + double time_preparation; + double time_feedback; double time_solution_sensitivities; // statistics diff --git a/interfaces/acados_template/acados_template/acados_ocp_solver.py b/interfaces/acados_template/acados_template/acados_ocp_solver.py index 32248c5ada..160cbc5fa1 100644 --- a/interfaces/acados_template/acados_template/acados_ocp_solver.py +++ b/interfaces/acados_template/acados_template/acados_ocp_solver.py @@ -510,7 +510,6 @@ def eval_and_get_optimal_value_gradient(self, with_respect_to: str = "initial_st - for field `params_global`, the gradient of the Lagrange function w.r.t. the global parameters is computed in acados. :param with_respect_to: string in ["initial_state", "params_global"] - """ if with_respect_to == "initial_state": @@ -571,7 +570,7 @@ def eval_solution_sensitivity(self, stages: Union[int, List[int]], with_respect_ .. note:: Timing of the sensitivities computation consists of time_solution_sens_lin, time_solution_sens_solve. .. note:: Solution sensitivities with respect to parameters are currently implemented assuming the parameter vector p is global within the OCP, i.e. p=p_i with i=0, ..., N. .. note:: Solution sensitivities with respect to parameters are currently implemented only for parametric discrete dynamics and parametric external costs (in particular, parametric constraints are not covered). - """ + """ if not (self.acados_ocp.solver_options.qp_solver == 'FULL_CONDENSING_HPIPM' or self.acados_ocp.solver_options.qp_solver == 'PARTIAL_CONDENSING_HPIPM'): @@ -966,6 +965,8 @@ def get_stats(self, field_: str) -> Union[int, float, np.ndarray]: - time_solution_sens_lin: CPU time for linearization in eval_param_sens - time_solution_sens_solve: CPU time for solving in eval_solution_sensitivity - time_reg: CPU time regularization + - time_preparation: CPU time for last preparation phase, relevant for (AS-)RTI, zero otherwise + - time_feedback: CPU time for last feedback phase, relevant for (AS-)RTI, otherwise returns total compuation time. - sqp_iter: number of SQP iterations - nlp_iter: number of NLP solver iterations (DDP or SQP) - qp_stat: status of QP solver @@ -992,7 +993,9 @@ def get_stats(self, field_: str) -> Union[int, float, np.ndarray]: 'time_qp_xcond', 'time_glob', 'time_solution_sensitivities', - 'time_reg' + 'time_reg', + 'time_preparation', + 'time_feedback', ] fields = double_fields + [ 'sqp_iter', @@ -1087,7 +1090,7 @@ def get_stats(self, field_: str) -> Union[int, float, np.ndarray]: + f'\n Possible values are {fields}.') - def get_cost(self): + def get_cost(self) -> float: """ Returns the cost value of the current solution. """ @@ -1217,7 +1220,7 @@ def set(self, stage_: int, field_: str, value_: np.ndarray): return - def cost_set(self, stage_: int, field_: str, value_, api='warn'): + def cost_set(self, stage_: int, field_: str, value_, api='warn') -> None: """ Set numerical data in the cost module of the solver. From ea10cdb7b1c470300e01362528a410e19283e724 Mon Sep 17 00:00:00 2001 From: Josip Kir Hromatko <36133788+josipkh@users.noreply.github.com> Date: Mon, 8 Jul 2024 17:05:32 +0200 Subject: [PATCH 04/14] Documentation update (#1141) This PR addresses some of the points listed in #1140 (and others) and updates the documentation in several places. --------- Co-authored-by: Jonathan Frey Co-authored-by: sandmaennchen --- README.md | 10 +-- docs/citing/index.md | 2 +- docs/developer_guide/index.md | 2 +- docs/matlab_octave_interface/index.md | 12 ++- .../problem_formulation_ocp_mex.pdf | Bin 130734 -> 134912 bytes .../problem_formulation_ocp_mex.tex | 71 ++++++++++++------ examples/acados_matlab_octave/README.md | 39 ---------- .../acados_template/acados_ocp_cost.py | 4 +- .../acados_template/acados_ocp_solver.py | 12 +++ .../matlab_templates/make_sfun.in.m | 2 +- 10 files changed, 76 insertions(+), 78 deletions(-) delete mode 100644 examples/acados_matlab_octave/README.md diff --git a/README.md b/README.md index a90520b97f..7fd24df52c 100644 --- a/README.md +++ b/README.md @@ -10,19 +10,19 @@ Fast and embedded solvers for nonlinear optimal control. ## General - `acados` implements 1. fast SQP-type solvers for Nonlinear Programming (NLP) formulations with an Optimal Control Problem (OCP) structure - 2. efficient integration methods, also called *integrators* to solve initial value problems with dynamic systems given as an ODE or index-1 DAE. + 2. efficient integration methods, also called *integrators*, to solve initial value problems with dynamic systems given as an ODE or index-1 DAE. These integrators can efficiently compute first and second-order sensitivities of the results. ## Documentation - Documentation can be found on [docs.acados.org](https://docs.acados.org/) -- An overview on the interfaces can be found at [docs.acados.org/interfaces](https://docs.acados.org/interfaces) +- An overview of the interfaces can be found at [docs.acados.org/interfaces](https://docs.acados.org/interfaces) ## Forum -- Forum: If you have any `acados`-related question, feel free to post on our forum [discourse.acados.org](https://discourse.acados.org/). +- If you have any `acados`-related questions, feel free to post on our forum at [discourse.acados.org](https://discourse.acados.org/) ## Citing -- Citing acados: references can be found [docs.acados.org/citing](https://docs.acados.org/citing). +- References can be found at [docs.acados.org/citing](https://docs.acados.org/citing) ## Installation -Instructions can be found on +- Instructions can be found at [docs.acados.org/installation](https://docs.acados.org/installation) diff --git a/docs/citing/index.md b/docs/citing/index.md index 500241a40f..c37f08791d 100644 --- a/docs/citing/index.md +++ b/docs/citing/index.md @@ -13,7 +13,7 @@ If you are using `acados` in your scientific work, please cite the original jour We highly appreciate if you share your `acados` success stories with the world, and mention them on the [List of projects that feature `acados`](../list_of_projects/index.md). Please submit a PR, make a forum post, or contact the developers if you want to showcase your project there! -## Publications on advanced `acados` features: +## Publications on advanced `acados` features If you are using some of the following advanced features of `acados`, please additionally cite the corresponding publications. ### Fast integrators with sensitivity propagation for use in CasADi diff --git a/docs/developer_guide/index.md b/docs/developer_guide/index.md index 98a08c305d..354a2fe623 100644 --- a/docs/developer_guide/index.md +++ b/docs/developer_guide/index.md @@ -6,7 +6,7 @@ Contributions are handled via pull requests on Github - Fork the project - Push your changes to your fork - Open a pull request https://github.com/acados/acados -- Describe what you changed and why. +- Describe what you changed and why - Rather make minimal changes - Rather more commits than less diff --git a/docs/matlab_octave_interface/index.md b/docs/matlab_octave_interface/index.md index 3363192b53..1ac731666e 100644 --- a/docs/matlab_octave_interface/index.md +++ b/docs/matlab_octave_interface/index.md @@ -11,8 +11,14 @@ Detailed instructions for a manual installation can be found in the last section The problem formulation is stated in [this PDF](https://github.com/acados/acados/tree/master/docs/problem_formulation/problem_formulation_ocp_mex.pdf). + +## Export environment variables +In order to run the examples, some environment variables need to be exported. +Instead of running the scripts below, you can modify an `rc` file, like `.bashrc` when launching MATLAB from bash, +[`.matlab7rc.sh`](https://discourse.acados.org/t/matlab-mex-more-elegant-way-to-setup-env-sh/62/4) or `startup.m` to always have those environment variables defined when starting `Matlab`. + ### Linux / macOS -To run the examples, navigate into the folder of the example you want to run and execute the following command: +Navigate into the folder of the example you want to run and execute the following command: ``` source env.sh # Which can be found in the folder of one of the examples ``` @@ -39,8 +45,6 @@ In addition to a `MEX` wrapper it contains all the `C` code that is needed for e These templates can be found in [`/interfaces/acados_template/acados_template/c_templates_tera`](https://github.com/acados/acados/tree/master/interfaces/acados_template/acados_template/c_templates_tera). ## Options documentation -A table and explanation of various options of the native `MEX` interface can be found in [this spreadsheet](https://docs.google.com/spreadsheets/d/1rVRycLnCyaWJLwnV47u30Vokp7vRu68og3OhlDbSjDU/edit?usp=sharing) (thanks to [@EnricaSo](https://github.com/EnricaSo)). - For the template based part of the `Matlab` interface, we refer to [the docstring based documentation of the Python interface](../python_interface/index.md). ## Simulink @@ -81,7 +85,7 @@ To use the mask command just copy-paste it in the "icon drawing commands" field, To create external function for your problem, we suggest to use `CasADi` from the folder `/external`. Depending on the environment you want to use to generate `CasADi` functions from, proceed with the corresponding paragraph (Matlab, Octave). -Any CasADi version between 3.4.0 and 3.6.3 should work. +Any CasADi version between 3.4.0 and 3.6.5 should work. If you don't have CasADi yet, you can install it as described below. ### **Matlab** diff --git a/docs/problem_formulation/problem_formulation_ocp_mex.pdf b/docs/problem_formulation/problem_formulation_ocp_mex.pdf index 6e721c8ea850acde2e6facd5f31654e07c651cc6..94ee678c3547d087b6d0fda0be8e43d2fe216387 100644 GIT binary patch delta 63566 zcmZshLv$q!u&ra;wr$()I33%zb7I@J+3DEo*v5%%oA1AO@CI+aS~aLqtyQCMSM93* zf)31wNu&m4ODQs>0bJ=Ty5e`B_FQO9scbCwiyV9;60G2B4M!|FNLKLpCQ|B{U`o=Z z7Vj!3~ zJL~)LVOo~$<`#TEyWe?pb@0;<44p-=n=4@(-lR88j-HtW0G>yOM?Hy483Z1n6iy?s zDM1z&mU{FI^bMGa&OJs<`0X)5J<#y2L#Asiv@%=?`rj9UlW$LUs(^rQdm%sVDT^4# z#W%&Tqy2AZAMP&|d1e2T-lV%K9w}C2FmtpicrE1T>xw4TgQ;z1BBG05hUpJAb3pH} zqam}u?@k)X0JPr3CxCDdxrLg|5W#8jKWkX)3+LlD*Ml9jQSzb~OmW!wAf#lQ`7aUm~ zRuLT>hAU)M9Vh9IX5@b~Yayzm42;i(neH%6EzPeD0DCvzg-5g@NQx9A_`R&TxQ;hy z*34b2I1IAz0k|&g(77@*p=P)|uIbm#w&}vPoM)!b3I+C4yB>ukV-r#PCZ_1edzYk4O>eWH7??-vRd@`PFA08>W){*K>KqNM1V|Kbwx-0gaS_7CXm z@Ft~{$2Mo~rOI_%l4vyZtTN-NR+%xSty<^- zqx%gLVuf^KO+o;wCuygp%{WZrS|OQ34v42DRq6mT?H`@_gQo(OTNg~sSRIveLY`}H z0PvflgcfS^C0>&*;-SSDyH<=DXpye#>m190y#uh5!k*JEL<{))A%%HG%ZV@QX3NA6JT|_za4F)CC%ZPlbS4)K! z*H~3>_S4h3o3pf8JabW93WQiVfRF{HT>KLxS~*u#PA&x(IV`MrFp|!a8}JwO@*)PB zEc6y#SK6qJ0`ybkM*pf6m@aXAx88Y<{Z%)Ir;M-Ny0{HPoMD9F4?O-K#$!XMB63< zTKYo`wQMOwnpdL^C!>fuXhpxGvp!i-g)X!BPtf$B7?p$}dQ*bi9F{r>*<(Rpf$Ihy z3_@*5xGu|#fcBvowd!xOS`}G*;s~Ldj*5-ZEKx5fz4^4~pjM1E6lSu|E{E4Vgr^QU z&FE}`dduwLN*arx?z(qTKr`E13>fNLAST>*YvyeE!}!ta`((}V=ic4Lk=ysHGQhO# zYxzv?l_k#j!Kv%FfF`y3Ud`LSPqG+=Hm1RF`~pY$UaR=cKzPfUS-lbevH{y=?Ht?T zi+;gIhH;vH!ZuKG$wmH}Dl`Pu!OZ}5h{gDidr1;_Y3zAc6h+)Na zYQ}Lq7f#v-9Wl5UFVW)Gro@a(yNqMOFof6%f~f%6&{_Gjb12xP;Z+cUM!lf`S$lkX zo|oEQ@FYO1KQjazV9^1lz@~!A6A~jm{s-@qLJUk>l)7RMGlYrzij9UXKM+;a+5`uZ zfq&S)%#d!>6awcHQ@as{T4KU9;A{5t-oa;Cajz&O4+eo&L2jon5jaRmQETtx`RnK? z%nUC{(z5j>(LK!t@j&|T%z%7jOB3_CPj%*Kc_x`L)R~d!+Gaq*d<^q<0mkGmx(Qp zaDXryr2L-;U_k$Tonrx(fPkF4+|O}o1#V-5rY(XO0~q7IouQKQV=6UG_=^GSXtppz zY@{w66D4;inTzG0rW@?Q-l{H-+L7JJ-}8{c8gV=i_%sD7>?XMwDAhLAaYAhq$aGrM zRt5Ang=*2`c)>7)B3yb$YwdzKE&B~m<0 zF^RXrp#e^@&7n;SqJ%wBF&Z|AY9tdsN%VX>)G4Xp%u6FtY@M^jkg;7P)3}2Ow#3sG zD9&&@QfjV#Wjtsbx>yE>SlqmHm~zj0RvRu}2NQC2p8TG7N<_sY9$?+mSJ^-#*v(s+ z6w%`dkTvhXBD7PGmaMz*QFJRtjHBlv-U%2EmrAL`&cfG_-pk0b0}dg|=5)v?sYNWm z%+5HTCd(Z`Q@$c4QGvzNO$-C2x^G;@G}tJFPQ3Y9RnVA(3uLQ<(D|KQnku6G0>QZ& zY)!5RC$(|gq$T}SA<=`-IlK)pG{nsA|B?y<_O{Du_q*c}A#U0vanzCd_S8Dih1R)L z=oqEJ%yp^#z&&ddHPt_I{lv$~>{7J3L@diMf!_o}Wc?+fB~Ql9Vs` z!v3_(-7m2($x{VB6dMhU{u4Fi-);8MQ-2<-yjBoldH-tw6awIF>(8@|7i<8G-xfLi zeOTXoxbqsA)Z>5G(MwmYK%x>wEs<{yBOrMQ?uV+MqZGvYU^j8vV%~~Gyc=diUMBa0Vx2UH%%p>>^i`nVDM)TASeID%;sV1>I>D|M}0w6s)5@5 zx~9IRdR^zbDojF6nNHgwpG`q%OQo{KxQ`b41ufM0}6jk{Hptx~7=-mxdZQrIZBc%j{Opl@+XqsErpiaXIN1?7T9z zH6cF2kA?XHRlmN+!lZQxJ5s#t{xpcmxZN`3F-%J%L9Xb#bb zOfDB6ib5tDOONKN2)DWj1kW$q4wnWiM}9T@VpNIAt*r6d@4MBwJGeES3)BHw-Z@Gh zM=vFPxifS=jdyH=3N4&*ANOG13?R}N88Fx`smH z(@vmbo45%Qf3fxE<8aP6XnL@fO~j6CrO>LGeI7TCt-RGDG`W5dp&J}(^wI(*#v4{0 z8@>blpMaRS#;@e$)2KyYyC$V^xYH|IeV@_NuCG^DFy!V-r`rvB2|SiEux*ZjvTf9c?bH4}6% zsNY^IV8K!Pt{(F8h)+Pky~6>Byt`5b$0A8c(BUL-_@zaW)`U2}c~bM$qDuEh>P%tS z*|Jq7C}3;upFEZsE+Zw#=*}veoGd5n@-*J^^aaBa1>qnhM_@?qC>%D1?1^nQV?k-i zs~+KLRYTpKXNhBw|9HI^vu4>)Ex)>J27FQdT3|$3(@~57noXi9z^DVncnF0z*hD{5 z*}@{{N@$B$N}&r{Ibq{I`9@`IR&Q*QTHt=$SVa`i(FX(IjD^-sf z35oa_G4>hix6?_9g5^91e*hOlZz<04% z{U?hL>B=Pn680d8!Nw4MAXrA`Yyry?uukxpii|EpqsshB#{hD&rZ1uazE=Sy?Yl8R z+aDNYUHPZdYR;*YBiHc;4Z~c74UIze6Gilnh^aVl$0&1^E8IGm3Nc*NAe3sO#JZp~ zDx}V*cul*QsYDhaB(3zzI$NTkypICLWgDppR95f^p8}scJp-Kni>YhNeAxc8wd3s< zjGZ$k#Fte(1R5Br&2g*8LgpQA)|ikC3mMH;{Lk zeK+Ps!_c=kGiOBqWzw%T_V&C3@2od;X*NMF=Y9mDxFQ9hP`cbPYZ{bAzjUnS-hGi% zn9{~~gob5?}6 zjUTS7YgR+o))QEg0GZpHeO$L6O&V^ef5GdEKtk9+x?8U~^aq>#s7B|k#k}PRDekTj z6b*K3bA1b-?{GsMx=#a3ASqG;6VC<&u^pSyKT4Inhl^ZFnq#>4G}Ud2<@e0_x^e-b z0y=o+Trthk>B6H_=P!3FPzH<8pA=gPA|n$!O{9~Ko4FNwnDh_odmvg4p1Re^nAW}e zklcdXwoeA0S^zD4OJhrM6c9i0SHWb*m5y96Y>fcF@+-+{p=`q`a_PsA8;MquBv1t^ z$@kPuT$BY>2gkF{8%gzSU{uc4-!dt>Jr!sVOAuygLk%P{VMBj%X#f-uh+9ujJe5c$ z#1QsjH0FXQi%rO5I<%KZzugfIPc#-pLN7c2zF8nw$9}`@`-~QWGFCgYIQD+M7tq=+ z%76jBoK+fSH3B8%SjLs5$Aw8i2PK&I^Wo@(|e!-$TQ3U-_g4&1- zq<4+Nq$%kk9E-=uU+@4ir+4UpSIt!5H6xI2XTdX8Bu9ToqcY2ma*ak%c+_}n29Q#T zgl|$>CNj?-w9*9k@(G5Q_Cqe9DDc2}SWHh1XAc7QeoS&AX|d_L1Uv58Z#f zZ|MZ|1q~KkVVOR<4UECdpu2_29^q6+?6cjoAZ=h^W=YfXmEj>g2>E=PJ@pJi)#GqZ zM~SiS31;mJ(7QyC_;7nJPxiYgqa1#X$%hsui}74N*^suEtic-<#Gx?p>7z05n?nQi z&g2I(=Ab=pQ(Hq4oIkONy4VGBV+_z1)gRw!s1~AVhZ2Q;=3_UwrK`Yvw42*+xcM*W z%3w*&E~^=6M-y^-@c;bYlHv2v!hG9jT}L0;lJa8Ng;-q*q;k`x^L_38_T0VD>8%jd zn&3t(WM_>fYM8J3HOwDlP*$(o4>AVe)uTJg{FuQ~4PmP8Cy99~IN(t4V{y-@doHSn zj5--B=Gn|}7RB-us9(j3&ehKRiVvUd6hik+K)@ay_N?!Tl~Jn z?7*#n;y#FR<(@~aE+_QyR9{2^X>pSKSalCDuQ1=`dQA_KZjF7_f1zjAo9!>D zb!IV?|799NL|o2NKgINc7;`EDSZi+uEx}7P(-6E@yG}N-k73(HX(#52*#_HE1{vzi z{-wXo8!@zD;gr?gg08$wg_I94sX#LD-CGtPL$&qA)&N5RhfUnpSFJ{`2*t%&-VMbk z`^A2=Wk&|3oX#-h!{HKIbvn}c!`rm)jkigiW%Bz+8xLZ~dc(KbB;N*LbKCHli}plI zi3I)z+Es&p6c-PCXV>zR;k~eRP7BsY-eMpVGk|*|X5b_k{Uf~S8zUz}yzvkDn z6ik~TYmYB#2$6M4-la&EA_sso-B^m#_jNpFV4eR-$Er840 zSW8Z=xz{?N7zTv;ANmn6Qx97~0$3uKwPS z;$Ur_EVDW2ZQxzZP-5noT;s11`SiwjO-?wFW*h{^_30z1jA|@2&<)M)A!_-S{UaPu*<_~K5Jm+Ok}VxDtGw#*HB?KEDFKTtcVv}5dipDQ-Rg$d0hyV1 z8L+lw{eeb;lTYzv@%>tEQ!$8OqB$M`Sv(j}#zR6`!k|n(w9+|Apmezy1zd{Hat5zP zh*n$*0esm%0KP80qzvA?!w25{o_;bE*2mn&sM5wp(SE?!Z~n6)bZ9*TtQ}^xZ4k_X z%Mu=b&6bPjxDj<_u3m%VyQ4;5R^v+CB?GPpWFgrpeA@Y~Q4bbE!->Siq;O2{O|(S} zVU4B97&_+X9DhVi7ui*>P=)dU4@p0Z?hfXmnOlqz#qgW5=@ok2kuTxiZ!MgEqy2Ac zUpz4B;iZ7K^_r34@-=K;5k2m$x|uJzFm9-9YPN##oBCzYxmR-3=9b1UYwn5jXduVj| zmBIPDHPjOi-pc`dJwPMueN_19jjI<>oxaDJP6U|!yFkT)2X~gyaeCzPF*f}~ZJ_~? z%WR|0WfDCb>Gq(<>-X>i{av*va2<>C_qK5YKIdwG&4M%WzD;n6)7iS&v8^id3+|jK zaBSd939%t@;h7WE)8j;o2SBC%;+^%8 z7M9?0wk3<~Di1tYLG(1Kn>2$!k(gn zN1NiyfC0!U6~(8p&f)B&Nj73lA87^AR;BQEl>PSY6L+aErvL(*fsez*QUu8-&v`eA zkCxb$1%B50ds&S-SlC)&>e1E*@YI~Ha0$o5FDWsuH&n|fpAF5nT?%#ac z5`H+{Ky7m=MeRO50v)CW^|9Uw;zckHW zkJIKFr%w(#<25r|_Vk1)Z(NMWe0el>#-lMEKiTxX2Epq)&Q|ESa=sOBXx)u|bs?&k zgaYnTZe}pUU(XyG>rSL4cC($SN64%UiLgN%9wlfvn>H|3N98pqb8X%Kc5*g<-9Z#-DgO1TG>wwI-A&E;dlGDmeM zF~nG|2=n?4mBK?Pre8aqgK^}iF3u7bTe{ifA<;+@V=#+>p?*Wg#jR7 zV@Dds#^jcpDiw5l>SBapAV|oVVWOWh^&=>S?JT1t{qkQNFp*?9|H8sti9!N%VZ>pa zVAyKl!8uYk2!lXoy|jtKKs*V+1kgwFg9GR9t(42{qoBe}f-8ZW?+j|^xAz9i)U0yg zCF*a#W93>|V16+Z-6*}VOn`9Yq5%-4s*w9Dk4!YQoH#;WGTbG>m0e#J^;_(l{Si8n zTYvt_sr2TpBBIoyBTYTWtSTEwE0;OXu?zxSCCL)3_ z$O}2;?rgGjS-LCL|AK1;O9bXw;5nf6@R*0jKq>as*S9U7^Z8#$Y)X>_tpF5T@JU%% z-nh`2!J-n!#!`zB;jbf_)V?tKQyq@pg7EWk5p1tr7J;#~P+~2`LX)wDi4MTR?#Xx( z`JY|XZA%Ez&$L$R$iRTq+)vgM`LXW>Y^=MqKRTNUR%em;>0w-8%-aW%BWGO2h-w4W zNM#WoG;tJE?zyT|xbK97^Z?KvIgluQ@<^5ecQ4i!1-g&Q(c>M~vD3RTrrlmKY%#LY ziufNZUs6WztCSEKqc*d_i6DH$5ipk$gE2Q%a6;Mjg#uwSDbaxQLgqFc#0%hn$@Sl0 z+*9U7>vkN6t*GHhHCxt@mhRblNfKi-K130q)IZXavsCVY@mKdVP(Uft3`{Y`W_Eta znlBG;Q4Uk9yYq5#D5xPuwrowd=MaW)U!QQqpc4UMK1W3OOrYKuZ@@GwSZI`VcD@)v zn#sBTdBw*;nsN?xup&viUe<{b65-@Z=8ewgDgGpi$IIoPx(2p%nt>h)R8%@ip$!(I zNGKR_?eOy{InI9-y?{0o8j;Lf*)8U#H99a~w0zo|&SoW58!?AXn~WCXirAEx=JJe zNVHaN0GXMg5b;B3>X}+CvD(IvE+W` z$A!O^`>fg-`27yLQb`K7_$8`V<`VK%sS>r@X&>{`2c}ER^heOg8gU`Yr!AFO-H2Pf zh>GUd>gr+Uu_@&-GJRJPUM$s$h{+4@5D5GjLbgniV&1s|1UXX+bd!@p+PRZ+e3bxX zCtARoHK5&@ChNqRCBx__qhRMJn=rux0SrsWA7{qonGAJG8A7n~Z&GO?!r8wF4X-Ub z|1eCo8M#2T(uKji`p@04&F|Sat#YEJMBwYe6NwwyS3A*VA#uFiGB>=T?=ya0frxV; z+&F9Vd7f zVY$y-^NLTF!U^)L#`*ElIt47!iRy=axxzHj|KGf8OYgs_ye$`U@A6u~;RI{yiQH)K zjK*)P`S`_f$<+&xs+TE`t^{WGMQ?;6mzi>Co_5fH54;wQ>BFR^p%Q_DgHE8FZZ3`a6fqFoe$ct-Er8j82KGrdI34XMS3ZpTB(5N-@}`qDD>O%U+IgEEcFvLv&V5iXUy&G(S|b|ygDb-AiRP7 zrQfwI$}O>mnit+a0yUbA&RIlrvL;rWSAbvu0@S)jn>+u2y`9RQNI}o^%qsy8t6$fK zUF*fP2kMOc0lnDjdqTiQMGs){GQ4B)$& z|H3sJTq6}H{9aPidaiGYSJy_3OJ{L}csbkLq?W^!TFbL$U1)3jPgSopc_$|xYkHNt z_7zssqbiK8&G5Gye8e?pm^AC4sV|-|nhN3-3cPjr)DwnPG{0ak^qmuHM_@S=_b^@n zLM|7%y1j`bTyd&LMlGlYTvvb00DOl)WnpF&xyBu!U|pb+70LS-M0#usjxq7ERkK|ax#`9*S02@ zVsRH7NWG^*vv@t2NTsib_@xRs97!|boO{!KM*>;#5`6b>v%ACd89xNwuMK-QZ5^o- z16leb8ABTxUG8@728uiP5b}i<?$dN$zXHfug6cS9we;sato zOC*Ze^f?j#;EbiB(?EEZt9gT>i;|R2-M>6K1N0p$z;(?*Y?8Jc@bq$+Eh^QIt8!~R zxJ4RZexYgnIx`D&HN{Wwjw%MFHuF-^VhBvK z4nwa#1J+KkS?yhT9c(yHjvdXeWt=M(bL_)*BF?i34W7~~Gp_7758Jl$Q7-H&uVb(@ zx`NDUs$wWkDwUNn7p%^2g?MEEYEd46Iy)zCpv*akeRnTZjf{_HW43SeX z#Q`qkh!v=4K}0WvKhgW&cx3hzpbc@e3k<2#wbQk`}31X%Gf*AC zv_iE}|ElCg;kTfVz?+kVdN}hT3++;YlIGIdAPnRTqQdxdk->n#%`u#tMO<%h$Q?)o zE1~N#vR-r>MPmIznac10L`Zix;i-eNS8PW{;>#vRWr|BA4q*7W6Kq4{(?_4;Z)i)` zuo!0~oO3~l+WCrUx!4ozO7(<$!K|G3qk@9Gs47Ithe8kAfnCoYIdOncD--uyLSpVg98r132YB$}O?;4WHC)8GT@`p>>ZpZH$y6ZP`7ZCh- zyd;a;fU5dud1Gd&Cp>-?I_J4MBhWIUhnAoH&`S_mpSc9!xZIjzV3c*815Vyam@}g~ zWLP7P;CP?@1 zwvT*kr=tz%1jS@J&Ckx)o1aG?UQ%M?_Wq=1D&@%hZC5=%IqtO*YuQ$4WGfIkYwz`9eKVP1Fo0m$$lUUV#8i8PG%oJge7N%h)3BU~aaS)Je$edX zn%1?-Y|G2dnatC&h0%3iK0Um4SrPhi5&Z7L>&a9Q=2*mn%}WR%>LKb8SiHOHFzL(A zV$TqtrePEtya%N;i$Mg1K#=(JoJ8`ndAS1)9W($)w`rxJGm(IIQLNG|zf`O3fd?Af zF?|{9p;c)@#iJE#N?n*#i~flI(ZBNFxIp73Kxk~8QMzbSmM;6oxPaJZB3eqkw=$0RefdvdEIthz2w-*ieTQD23(49BA0Ktb*^>~kMZcdbU4FI zLhcig@LQ8@&av+&=(c9~UnKoR&)wGa^c#|>qXr5)Iut6pM3FtWSlz*9qh^Nc}e__K47>6zrDH&z67>*f3*;EGMGT2_w zS~X(?Yh|!}6%N@JW$do1rg{$B<6Eb={uU{9C~zI|ZNrC~{wd)C5?<^j%M)e{ZYED| zfvckeuR-A=t?xisJz}5*rw@iho|A?{h;CXA<6pV4n8U+rc**EEL)$7>O|=3v*B-LMgZ(i2112S#9ho#}8Y> zpMJFm$3wTAmu_5VQM3!0tz*fJf@WC%pl_tXW>CUI_Hj`jmD@x1A=gzC`rwQH?G>V+ zwb1w?*2ly6NMqrO6gk`L^TALe@`%a+)HRX+faB;Yiy=nu4;j!j#Z2Z{mqGljGF0H$&9U{Bq`zVIMr=6@|$G2$^EI z!+B{|!NaP{X|V5mPxw+xWEaX%gnuU>Kx2t8nSC!m$1suLv0~sLRJDgZC5j=--D?YC z`uCs2N!n5sl33mZt4zkKmE@^!TkKSZ&!|~+FOuN2?Q{c(!#^lf1G4E9v}%%>imFS^ z$V_9(zW!bfBK>aa4&$u1eH!Zpgd%1BVSJh|*IYQXAWj5bv0gdnW1d2M&tqmp>Q~lO zliNwfciA38c%IhQbp%S``M)&mk|U}wb{Jxvif>R^!Czu+;Y^FG;r!*ShaD>> zQ;o|t++oipm6RnPuHL#7vgY8zYr+K=-@%^Zg;nAvnh01G(hwGawY~o$dbZuUDQrQ-7Y- zM5CO`U)QeuXm}1J;3Dq2y?pN`hub33RV8Bw&6iN8N7LVzhmJy>B`4dis&zh5?Q1Op z<~46&bF4N)fvq`I2npQ7|4^vZH(SRg)M3Q(M$Cgd+ApxI zoxU!Pvn`5k{s3=<>YIGFD3f+4(qeo-8n=XvV^PCC0IdDwTWWS})b=hjS8L5Pz|!3} zqZC45^Eb8K-`Rx4Uc~|>U^9BfFJ|);5<6yv8#XFl9C9|QE0d#tRvHRYK)ydW_rGaX zo&{=il^H$0elkI8A`_26>{yHbsp1MSeVFOKb;S}AfN~UZahQ{{6E!pn+D3=bs^*)+ z{o&D60Q3j?V)ms_M9Vld!n2xC+pMDmRVH|p>CA{MW4X^F6|x;qNbe8~RohLVmc@sp z>2D+q)IS)d@&4-!V67b#K&^@Y{T8(!Vwy%T)unpZgYx^)s(&5yg9%)m46*d0A)Yc# zyf9Me=B>o%yr7_lI_eUOe`aDe4(25j+|%7X1walGR>ZSvI=H5{PJr@<06h>ORdVB;?uJG_N&L?NeAkh;kW?s1>VD@tG*7Wz`luPb+XLT5v&nqa8vpAQ+!BM0`)OX0+JX=PgM+4)_3 zPdW?6oJ4AYL9<|YK_HWN!X1cWi{ z9x3)1OyR|rF(lzeFj;Uk4;FR0I%<7Blq3boC$0b97*Z5hhc=$J6g}>PC?Jjs+Q+iAObMWk!kt%@JKwb=6;+kin$#^JLzt=`i;8voV z7?5$bp`Uir2UOI<7eR)2a%P&$EvU!mY9Bup=໨pQG&Y+;E?&q}zD2RxO{;g!q zaD$WJhDlP@`R2*>Aoz=FVR_ka9lj{o_f_E_c-XvB?+3|&rok5oW5{AlDwf(e+{8W&aiFokgqv2n@DDJ?d8^R`i&>dv~fli zZ#v-_LZp0=BA&96-Zy2aA{s5O6R_S_jPqI9-*WPe+43ST zmB^0fUou%VYq7q#5PN0yMebM-e6L?d>~r~a?D#dA7v(J+)!%ZY0N@p$6C#|p60F9KVF>|?%w%m&)^S(xG$z76O~d` zRwd*D0M+h~r}`hr{y(^7<04@p`5*8K2>jpOn2n2vhva_)E~V0t6tJudbikKJ^Iz4P zB8QC3>ovUpD`N)@4-W6Ox>3QyLX(spStb)sK((-QbCyLk6E;jLosJ0|aO<>|TXoLo ze!fsv(7+t687%*V&8Uz|o;S#WcDQmh^MyQk#p@ z<2z+Jd1j}xy(Pr>02nv*{xWZo<+k(|GTcrhzW;a(d~?a4rH*N)C^&4I+^OF&?C$D) z{Sq@H_<=ZtnerYR$U-LV`j5a*-1&-kTOYCP*m}>FjrXJ}Vr+F__1Np9F#y9)zrvKm zaNdxJyZ+P_#4?MVh{?vp@C2dboSwpmGrO!=Vdo;toX001KvqarN1)E~>=?j=Np$z& z&^tgyupCGqS<{Jky8FTDR9qE=GUc1KPLg%syR>_Eo9CSO2kL@HZPU}xCU?7UiOm>^ zdzua3jmGdSGnubRh=o-BO^(R$ZHQS;wAHAL5zEFxqde0MmZ`1gh-=5sU{fGK=|Xqq zHW6HE_h|nNV50>hFN-cUsi9X87q+Va7S?Vg+U{~hZLRm#zOoYAs2=%BtTi2XR%se& zQ=7a-G+z^=rERLRVE&?~-#G{uv;|jYlIGh({cm~L18aZ6WqJAllh)aYsKJUsfvgWu zKSmKznsAh zgx7`T?wcz-rH9TQS~|CIbUhc_5wd{8mdW>_eUZsJ_A}98Y*glTi{lmf57O$(OSK8 z(yzHYU)8TgK9}u$yRvrFS#AH;?Jt{vHh=yG(A7g0hemA2LsHV;Cxx@%c}?hUHLk-- zZ*Qa9kh3^1b8HNm5r!>#K#ZH5;a(xSH`F{FoXpo!61>{cok zVQI(|c8}D5Ni{9&Pyu%J|NuiT=X@ zlzzsm6OFALD;yoc)ASksrQ1To%TNf7IkM@<85A{d z0tl4VfXd;cE!fz!yRV}&(&pMxxDTA50A+)AI-cm-z&x`mNy84=T{)Q$-!C+%S`z2^>?Y9QaT0M?Y{EBX{@s67Qeo-51So2o6K(~akF_G-KmEP7fCtqD8|O*yH0dB z&&(U#!-18HDVcUoh%-gk4mQEJeAIAWuY{z=a^x$H3?SJKe8s&Ws;*dEnkNNlRp$$e z{zmrU!olGvl#2GG$IlC3ZfkE)^W4(w1AifYrL%V}^y}!O_>FNZH~9ln(7Xf?MM7d& zW4E*;iNT}FrD=eblRCLnSKD37BWnAqt*@hcr&I`)Di~1ih7d)%*tm7EwEBuG=X|`k z1m!oXiz!(vLB7|WS~9@gZJ%w~qa$!s^Yq!enIP5IYd4fZXrBt`Qi*MhtuQ^NFQFkJ zJLt&3ZgnoikVM`vH`Vg@Ld9lf=k)@N^ryP*S)PGT7Bn;Uv1P1T@Vy9#s{nWeE_ za+qy#2lFHBhS|yK2C_w`iFmjE0lle?GAXR>q&$zuz??c)x3!dSh&I9eTJoAdtr$u8 z06%*zTGxv!_{9Ox3Srzpy*jqRrnwd=K++(g6j!%mz?%ybjIcMU+uYNHmI{}* z8-EJIy#NNP6HV%0Q=Kv=v?>w#oQ?zM^~>X_$84ni`ORmLAaE`aKDWo?D1n$s66fp1 zP+b)ldG`hWtPw1$6RfWLK8bHyS^}AEF>-DJ7}Rs{yc_gbDQUzmL2PdC`4|F6Muc$P znF1~KTMHQwKy!;t_OKp8tbWpAFQ~;sbQA9?Al(~cjD#ryY_y}Vc_4)r}ed;jS# zN8uzMczoi-?&@kgpmCM272F6v@Mw*{olcv5ECPA6fFVv7$(=J(F`6;F<)N)p64_YJ zUaA0&)KidAUo4Vp4#}$d+28e+ZmJM*eC$Fr`3-Le{9s;?W0)y`9jH}7-Y#tXD5W>_ zSFjEmZH}Z@*udfYU!(1%N2^&}v@TZbTdtTz-8-WQ72|;~sWjbA+Dae{#|>Y%(P|_i z^I_+ruUw2<#ITWYg}a@nXh^}>({cp41f76>Zzg)uos^T35tK^nQP9ky=OsZrgV0nr zfp10S#E_Y?GYDeN(gpS4KEd?8nB9UL&z_R(z+`QAw!3?hln1H^{s?}zzqlo5sCAw@ zNh^iQ%ut95o-@szv|Nq_`PVH}AF(iXn_rl6{3=ik^~;H!CceMu^{08<&f)&Dzi9#J z5#@n%JDzFM@Ac`IT^{0TOV#VdwcH^@nX6Opj!1r;q-6WK{4Ybke9)#ZWA^P2%S%0S zYA+g=mc0z$1Sgl{zVaS_A%1}atsi^exP_li{U2^ZbV^>PkGvT%mJw{@cMeSLh~N?m zjr~{w3AzjF4=+lw-@L%7dcKf7RCd7ynLwz^V!=OJ=VtV_pTt&Pa>t`Hjk(qHg8L)(cY{{COVuH)@M_b7+jN>1Y~BE|=f$ zM0#GB661fl*Zm{MQAoUQ^KSHti0heq{h2jNlM-{KRy~srWvDn*V@bx7Pkm6ohycav zdf(1pd%&0I$8xk-v~jXaDt{+-Bi5+WLG=5#7yEBLbi z$NMh0s=QZ$=}~#zf}%UGY4(WZ8!s?h7fnl&?&zGX{1`Mi;WwT!t1i zHJwc`v92)x+oAC5gl6*xR=DXukDKN&?}oETW!TE#^e@W-La zn+QPno22%PRXsUHc^y(^zR>ngLz#Bf{S4%H#s!(7WmQD^Olyr_9+rcXL4A!+&hf=Y zoJB&8y`~1Q08%7x39MhJG`m09N6t> zuB8DA4bsweltnDTfEtOy$~;H;qT?UU+tb$V8qA-c`muS#IT1JxmxrV0kvvR^GcFQj zsYog)Qlrvjp3FK1zh6*ESgbE3BQl}ayqjfoDY5F*sPm(dJ_f)0hH_Pu6Cfr4aRLY< zc`@Glf`|1enfE0d!2(sXg%~Ol`~gEcGfPIE)t#WS#7`QCYQ*jVCcGJ)AbvePXW@- zIqlf3;Q4JYl=Q8N;CLds#I?g~7XJtj<6>)gv!Dhd^YzmU#dh`Gzk@ZUlOfm4m zz{@HJ5VV)d{PuLtLm8-w>p6X$5= zWqefvbR{cXC?m;)Pze{n6M6|-%quaygw4WVAkQFP<1(ouH+%RwiHmhwD5jOu^g%5x z%jb6ghGu56yn(!3B0X@1`AFMx2(;$#sdaoi3k(1`QbBU-soNWi;fgpZzq4E`ijG{; zZ%`q1KAbrqB?%LXgAZ&-HDIME%P-*%Z#-Y=@05ee|%n4wN0qG z`a-4H=Aa@Yf9Psf*fIQW4v1kXhdA70$Y4R>+B1uapeF+(D>$NexF1c@#Y)5xTgztv z_REHP4y-n<(=r+LYbjnt#tH1t2S0Ridpvk~pb(>2GBUK)(@y5y4`6I5ImZPGUv2>x z`0locs$iik!s-y#T!D%U<-S2ql(e=`L35!s|CoqjoJR17V_}*@$orwb~U-P zVx$SR_5=CM)0j*zJtz^NVp)uKz(Id;P%*S)POdZ+tKS1clm+VHoE4>|s+b&@j2NL= zLcL{zZcxK(C%|6&J>)fT^LPLG*Y+nhs%Aj`w@Eo#zSP>t>rP87E@Eq_y;l61)U!a% zN<7{y^HRe8y^-Y|?;$}o`mojP^~iu2VeciVA2Q$KN_;9sj9?oe+n)&6;X!y<2r+XX zF1wVLZsQEt*ileTK-GdCL>gIAV|yQn)-`9^Km3MmPxpUB=a?In9Jiq1OP5A2V_dRr zN&-T^Gl+`BBQ+~@o&!}Fb91%Av~5R!i+1qMJx~x(3oGJP{@6bMF{XMiR#L!+zZ+eM z@%ZMU&up-QPW`X^8X>(lMRDFw_krg^TbKpUgA4`05g5h}^c49K7u8Pf(VA3InTqR^3iZZyRFbTUuLRC#AYJpU{Rl6f=t~#bI0qpu$bOw1eEF zxzzv)W+9A?u`{A~uvvEE?b{9(wXMntRt=ETAU39s;qrmRY`Lamb0G0@2cJG-_XqNb zOVkz(a^XcY7rGyY36Eehb|q4yKraQstFG7fFNdMMz+PEPUF8hHP7VFvsMB(r+*;p9 zGV4Dtb$rLY-TFezyswB$?|6+!%bPB9E@pqyv5(?!94Ql@Rv#BC93Y@Ze;v{cIz<4# z;nLX9o_q0Bl#ZTfxjOV&S(Wd>*iY750iFpOKOA-29@f662RBJwI<#L5$y1JjZ$gjt zy%$@oR?+i%(XED64QuJxd5xmuI#O%*AQU1kN1KQzERU5S%z|gn-xg`Rcr#RdRo$ZI zFc@c67Pk0M5{|lcd-^H#IBq6ar3nDD1lunBTkB9b_)<5O9NW9a4#LKAhy|4OAG5+B zSQh;J{@2^ZhfSd6#m~u@mws3fNaWCi2V%sOc-2fYBtu(wK|5jOy}--&hk*6?-pkqv zAPvLeDa=2$;yPtvUTI3-3wB*$o0^eAg_ERG3Bnp2=%wvo6=*rN zQH4Qv=z0a$yI0D{nLv)arYk;Ky26a|r4uI!y(wuq7D@QzsQ4@6^;~SFiw(?2 zzEc2lA6Vk2U#9gZDlc^GV8{)1mis{S4*|iGnfKKqz%=!(rZ(EHD<-zU8bYD7$`UL- zMVdCpcR%v@dtnUN7!0A8{W!zJiaO(9j8md9u#NP|{X8~(0P7{m`wUP2j>rs_GBnEh zj8=t~4ov$f+xxlDtndQdl7msJEud76@=N{lc?t}JcrTWr3QU&#CbJ6`ph~28rIvhDTI|j^n(*&=Vvh5A$0R4afRUvW71HR39u39sAFY6g8bvBikp?9tMVSuQp+ht2olCB(>jIKOgaI-&n1(8xd8_ z{NivaEe>(MvS>ad?{hOobmzOaDyt?g=C2))x=~>|vsLk6`4zx;LGHyY^vo4=dtQzK z90;3Q)rk}SXaK=hP)iFeEwCRQ%nnK|d-6f0jIJQUZ>8dwFB>8U-CSCRwI}dw&4<`o z0^UG>vhZ?eD6_98o_%S#*qYXK!RU%tFi>jz*d`=%Fa$Mj;P%F_i{@VD# z4CtE~umQH&vlakYxEYv*#VBj?06yY4BqY>DAt`$da3OhTj+L($P1Vs0-)V03G3Dpj z9A)5~9Tmifcp0M4)at7~hp+Cz_;Pf~yFPd}vUTh)&d7rJ&9<83>up4=$4oN=a}Ulk z%Cho%fNw0+{S@p$vT)o*=q;gR5)D&oK=d6QqBVL_dqC)2iYPY$eK*X87Rcc6`T~!%iz@a9k2TVKC4e!NOCivOrlih0X&d^0VA2P+=ynH z9Tv;qNZH4Ri6*S;$9iffXifdAy8{N^)yRJ-ylGx?`7#WLCCL7Kp9Svg>-spA%wrT8 z_PM0L)qss-4yHD6;1sg!$8^6q403iyb)xK@8<|-=DhTSaw@(c=K5Ly6jM5RTZe^*O zJUuYc%X1dQmFN zj$o6Qd2U|_ViD6EdB;|-xEpCNeZvqdm9&s4lqNkn)INi zj>?1^ih#dWBW$4b=SEAEP$@D(q{nANGld2@LZ+Tq}G7$a_U1 zRut^qS!9|%&~aRlou%hazZs@fX|n|WIrbrn2noTZ^UOCEto27pnWziSm}?@2i%98{ zbp=KfBgm<*tEF6Di9q9VFp_CLE^^c!kys_hP>DTN0n}sAz=3gnBroOfuPliSg5z-6JDL)<9!@*@W z>3aj2$dn2uMR}7}^v4o?5jkUWc2CaArDmcUP*toB#|R4E=E%d6(a#CZl~p1)%0ClG zLq3;z09yyrEZ!p^lEuBLsvMJrakr%=b^Y7fS}X7C#{5?m+wGE5CZIH6$-Lb18^3!) zI2UNHfw!IJO<=yp4lGk+`?vdrRDP^NySlSR8c0N?b09uLxCS@~RwTKwbZE|kc*P9( zE*;K*-+?c$1wL5VCSbjM&jk(wf$%p*P&cV;k-uF>2k&zcgGt9$sqWrN7B2*!GqYxb~{|z-`Z+-#2Xr z_gTQ29!G@T3y3aXpe>_$MlLF4xzgOI5zZoqLzLQ2)C8vL64+1pW!d7f0 zZ#QI6e4_Wuh7c^u^sKnlmn0%VLs;p=;mh3M65?N`tD3+3R0z)FpzG>Pu_3*na3&+O z$(00MF_TJn1d%iCdAWR1=s;Tp2Tg&KG@72X1a#G|_tMl5FF@3^?G+)Vun_;@p2|fl z1jM-dVFRg*az6Ci%J??J?+xYl+}J?TLHltMtV~*VURKyEQr2HG!tjxAC+G-%EKtl( zejBF))Xms&+UuvEoLH8kwzPc`5@ce^3NY64F-mH3*wTM`q#1>1W!)X^knC+b!I3Gm zI>cODW(XW>m86oRoZ!Dt9w1;N0C$GPP85{W%HiKpQoKIotzM?(IA0~deK*5VkFMZ2 zduSS^GYzPv1-D{b^4sCgYTF<~U2PxNsgd}=cGd+v3MKNqD0*PqD8 zuX7EPc%h4V0XFa1zL%f|04K^lMjvNwOtd60#Ipx%C-TeuJz!_W(%@th)QCm(@ zkw!yir42!aM49har0RIeJw2kRs0MZS*%JR`nbRrM@PzA(c26r|;JG@S$hV~AXnp12i+?AJ}iu?Rg z)B2-?sVtXCUGu9Y;EHapIaMLf5iM~lSwV@rn2fc1yy}x{u9v_w#(Klgr|GT;X}&Te z&daC0PTLeHSBJ>#rmA3m$?q{ai2U(g>3P2{pFPHlhZEfa8mG1!0dEG1?RP+S3Ap^` zfT@KFNN`H3fYgxs9c*x`9D-QIJ`MtWA5lO#mN>-KtY3>4pp(8U%f~zAh9-PVWVCQi%gkZX zQEvz-6gt7MH#gpT3}nNCf>3Z_q$?uAMs#$~&ldhv@Yp-A&&U6dA@{ljb7VI+mkwAI z1f1yN&ldG+J|FnhY)4av&l(#<04nQi^r$GFRcyjL;8xaUEwm_Z@O)vOMDv-@E18{* zkNwHol}2%vU}u=iv7EO zbH}S4;I;S};eRxs^5TfuJ7?FP?khzy~#V zeW*!)EstI@30Q2uQ*?$nqJVnzsVSv$plqDAtjMZxT;OonEZI0>;}v396yu zvYv-YBlukVg9y)wB z^Qc&{k+GA->2|6s-8vV_ADhNXK53Toi65>jP?w5po9ezjSWLRq9J4NhuNan4ByE1 zdkR45vxC{@N$=5_d1>O12&5_;HKb1dx~05K#j0wnrY=v~pR~zC}6$k<~J_ z;QnOteh@{kNYQc(DPGYMLEt5sBHoRif+tgn+BZ$0WT-1Zx}VKJNYz*GR)^7*|Hx1} zfaRCb)PY*fZbZMoP-%@u8fO$&3Bu35S_kxMe|31Q1(F!m7t}}9toqeOS5m|@Ca6G< zqppdTcy+mcAsu_^mY&#EZ%|dAh_>-x#Ea5!Ylz@ux;T$Z6mX~Wu}NFIK-)=e?Z3-nQid)?WVnrw2$+ zyf+^A_55%6S(l1bZYT(yd{4dXn}O%V=|#yqS~{if>Q~lK8bUQ^- zIS1n8waBvOY!!5-?^lzG8orr*lTY?91HUgg*qCPccMUEkrMOTWQhOwn)Cl}^NZk9- zmB=ycJf7WnfdztdScsN+m*PL49xGs<5B+9(-sP_ul1&X?4tC0?*LWe#_gam6?FNQ4 zCofcop_@O7Zk0mlnA8Us8FX=ubP#%y>iZEBP6@JVC9DiNafqCS+*5w%*%Mo_91@0J z7f>e1uaD#~|4)5eG)rcBZHTWAyUh+%GWYn{9qU67FFqbqxHSu$+QY}C{+PnIZ zF%Q3AFg8p8y&!gYS94{gmCHUY9P4=l?8nPHSDAynzWUf!P?g>+)QYj8?GHS!Fm2T# zAtq;$!|qqwLGxhrrm^M40a4Wi@gIAA{!-){kJfADd78BUY-n+npN@D4i=Ks4L~w1l z-klwU&U0ucJ9=pAs(r2^z%V*xM)8xz)5Q+ob#i~6R{Cfw?S1Xfey}mSaPOC%n>eMj zZX9UB07RJTL8b_6T!9945mC|wpy+LVPRxWQ@=y^mX5liw-AY?jcvqKG&pb{69!*T}yks zG34)Ag9So*u**+4Fi@U+EeR5+L=s*KFyjuqgy>Y>r`yHUudByDb95b3#@wZ&G6G=B zZgUHg>aOa~Rk?}O5*9|0=%d)n3hP=*-UqG{_+s}ygyM42S~cPv!s&Wq2-5ko3m9?A z-hF3*R363;;}+dbn+GJ~2TXwC1__VttnflIqiTdfoVbW0Nmagw^jW7(E#4y4NWZzv zap-rNc#*^aN^)bqKU?8OmqXF8KhYAvJaYSRv78phjz?^F_nTqS0nD;Q0}y;y*CiypSv#d=RbHiplXer7!Kr)gPgJwpByLzl{M2rK_u-hXU{!-lI@{^-K zkSX=13y$`8ur3D$KAi*fiHKk;lMv#;y+j)Gv6{%oPNXp~u@#xn+ePcbM;Dyo=P8uI zv?h}~%83L|pa}APD_{^fH?U%D#9NifU{#29TLUyCY6;Z1C}%qI>!=-$!(lmQJrV~3 zMzpvo$3dn~MVL+Jq8iN`TsllRVhgcmW3v*em*8%e)l(u%6IB62h9VM>a(0#yr8LSH zZ1_W>j__pDZE9XrAG<}8-j_FLO%ml}kDgtds`j&p8qYs>l#g-Vm(pEaHW;6osqcS$ z%l?#?eX^;3`ziL=mC`mCG%us2E2@YhkV{K4h^E$}HG9z!@S|MDC;_bZT1EI#_o^u% zn9R3-Aeq0_d0Hem?-x9(3G3;4>@jP{nDAqhCxHK04{i`rWP4u7Cqhb~<&TG;I9I0Xui3*i`j z2bMkZFd5Jnc&cM0D|j~UVA^E?`?IP}v$=!Sm?izZvw4@G@1m~%aya?i?mu4nO_-m8 zV)`2AeK!EY+Ym6c@bwXz)b$hk!{It36y()nQD%>Go~l%r%a3_!`)EnNYhQI$HKE*8 zmK(Ti)~ka8UeBB2w2{kLI@9$dx~6VZ>#Ywi+7|#z!G)(NH=dd;u)s zj?!=-xgDO|ABq*ArTTWF+;_8+S^mke~Ao!Eaa!)TL8q!uv10wD^zb7dwQ+@-XLkV@>bv(YMQ3dBpG z<@H*wWfoUH!;13HuD?F~fXRm77^=-@FI98fEqI+uA8U>l!hMDof_0pB6RFN?Bo}+@ z(a3w#Ca&EEamZ#4XpX3}6H=h|zc9`@L)71iJNta_5zM_Cd;Ingh=obd=dY(d0MH?+ z@*@niMt;u$pLKRm?cq3A3GcAcGlX;uODZ{>*Rm>y!r=!Fh4i^%V3<69!V1vfUOp5_ zy81kO$l$8jFAEys`%!AM|Rfc@y<_~~K4VQBe zrAu+bcy7q?hA~r6g)Et+$F-bvq_p+(C{YHTk6C@LjMw|?L|@P+0~ytfRjPtZujZ7& zn@yu)mFKfT@kd013U^jyRRareq}EA8p$#r^52o?>>)4Zu8POQc`m%#J0M^&AILKjt zkU5Cc4+qF!K9Ua^G?_@C!G(i3tWmNN{7+u&P_D}nCEi$i?&P9>J`zTP83i^`G~~j%pOb7_^Q!FI+B8!<3NBNBYToTl#n@}c%`L` z3;(odx=@4X2A=|}V4>dq1=#tC=_CPp;9LVyM|+9QEH%TToL9=ffa)dnMz#jwN49e6 zZie#*#P8kvS6tiaIWo_yKI4MwSoP<2>1>`8xlCE;QsDk@ZSV3hcEfw`VH%BHogpmz z_kI#k|4%^jUvi5kg2QG4`7kRlu=q!S!J%x|K60}jDyY^2k}=V+X1Ev-iH(MHMzw_I zFZFpy@LKm&LXi&ofPQ#kA5WBv55ho*7`22>%@u|hPWuplx0+U*V855Jj`FF#Z&CX{ zGqpMihD*I68wxlpxGJSL#^Xr8${9%o)y(OW9$b$&Mt#X+UWg5&!ujTt**Sr7vo27f zV|l{{aAwE>ia~9WGpWJ#tHN1biqi&e42`~MjqgTb7epK(j7t?h`elc{t~4)@SPg>x z;a#!+2@fcnhmZ+)2wVf1dt?cg2_OZM_4~1$;U@=%w7j&X7dZls%j+*gHpo$dE5r0x(f*`6PSz}$eNM7w;{L<-U#(= zMW}U@%kf7;X}-U9HRZIW zjG!Wbr^U37)IOS+-kDMM6IA-q`+U}C)7N5JV=%g_DIhJ6B}PlSk4~^$DPL^g6jA!5 zC7(Z2@vv_@`fhA)rU(vaz8&0a6ghGiM~vh{e!NrDCRxI!!DgXR4QqYzBp21D1AoGD zVhu9*RadB3g3IO78wu{@>-BDP+&3*QtX9zhA$nuyp*=Nhe^ia55yA1-9@SCYG+je` zbt&6gG(1P!IR%$`t)^;O{vCN4+%D=2fsIWS>h3Cx>tmmH)}^u4R`NVE6{;30q}1sn zQXdFUqjzmAx78qI&Dqm(hV34@H?6#6&2+%ebsfg&x8>PJyq7AB5@nw#C#10BzNmx& zyybW2Z(wM63fxn7^)(|K3u?qw>Dyk520Jp8Z> zW$eDY6@F){4egADDIFBRdv>2Di7JvMC&ZNE^o8P|t+?)k9<6g(6+w2HgMAI5vr zaEh(wJam__bzJ9T0$+~N&vAPUu*C!&FnY|__YGVhQ=K3U4xIZ5G)W;DU9#8!>(U;L z46?Cz=bECsGa7xtQMM5$_5se*gS%Aqp-5sMvyZ>}&IbNv)fKc@>FjXY|E9^9G$TBl z*_XK11oT$=>CWV?$JHOz75S*kek>id(+{#~+p?2f_2C`S|U-k3;YRyyMs>*;A=8 zrA|4rn`#_&Yy{tb?-YL>L7z&^8odd6H+?L-I_@9EYAQ~M5kHxY^7?GIMjSQKd0w{fS~ebj-8l*}Jo`>p zSSX`GH3ifx!CahK%skYS#>@pTNGt!d@!rH(Fmo&=>?rSEd4$z+L}o>Y)e56kL8?{B z>`ECVzVMtPQ!M=s@Vy3`7jK)O&+pTTyJDTwXD2sLo;(I8OSLq>r_$Te%_wLmzHMVg z_xeM3T|R3&l-`c8s_YV5bX1COxJ(#Wt*1B#JuNt%EQ^&M&Rvrp1moM8eu3Q8J zO@MY8aGt9^1hxS-dpaf*MnJQ)LuF*&8IzTbRbajEbySG8$xZ}9H!`=>v zIIQj8rtTvQkhf16-QA6U?>YmvJ6Bfpue61Y6 zzd(tuOvYwl;h;D2`qeY^!qGtD%BP5A%DlY&eNweRnDMmZBlsq>UyK1kAuZhFz&7yB zpZy$=Tpe6I9a=&CLYRy|>wpJA2SEf2mMT`z;*=J$m1H#X6gD8M#7i8j#zUM$6d-nO zOKkXOL_&C4Yfb;EBJg$4a}W@JL6#<<%z&Q&4tG{iP=RPd*;mBPxVM@CjbBa(R-q;I z;kN*j+fx&B+ZTIk;8+GAXKPJXUP;Y1#O1i`0SzMm<|5wlk%1r5006*He@D(%h!Bo2 z06+%q*1++3R(u6HFL|OTZ0H|SGzFR0GSp`-7%z-aO9V8(2oCmvd6);{gHan^JNm zhzx{B|HCdrCHob13%GnacxF63M2B;Fw>X8&;2tM<0~CzMx%`T9+t?89d|Jd@ zgmrku3U6yC^F7O~K@4y%IbUdld#|b9bqK1W6B~i`PoV8z77U zo&WjGj`>}aezSM(|H_M2v2$~i5&A@&{RJhr19y2J|M+zR-_-r@b``*772+FLpeC^> zihurAu%^*)9}pHVhEFG$Jp5sxyIQNVnoH!2Ze5>&-Vb8&O1ukrWyhZuW^h|YAVQba zyaI%UM8u@r3EB{?eFGZjB>tbYRx8Qq zXc4J6fZYBXlDPqoCmSKGLo)74DI~b}`82G%3wq^q37j%c1IjlPtC`tw z-`~lIbM;4Y-`fz`S`v~}>0i2We{m6Ns|}(k05Xx-Y|%GV7v|7k4CMg{@*RuQf$1sD z;0+kU-z)~enrD_jZkAc?isxMq^@pwxfziR6rZ;=~d_)aucfXTkx4W zfK6FW->}AE!HxpBQe<3cwQ-1YNYk*IP8n~=KAARRA)N8xiv2*lP$q2&wsiM_ZQVy}=VG zMkw(_ep^-{wPFCbK{9|`^y(FK!`6ioU?fe*JB+r=yV}jjBix(mXrcfa&3z$uNgRfe z%2xtZI-n!M3qU1^%HLE$5?ME(UIoQ?6fyvlEALjGQ|>L)KL3gmfI9lJXd*HbM_1lV zp}c@F?)VnzG;PM+57Eh~otzUHqzJ1s?UX86=FpB`9Ije?#R(2Suo*QAutDzvT(W<6 zOCYuIp!-g3L@Eb6daQ&jpO?opHAX;H zt*GJFoVKz!_2cUf{!EZK9(oVyc!&=QubmssUK8kxEkya?j}f-QOC!REc8F822g4?QLc_ECaTH z8w*6+;|y^}h-9R>U~0N|8KlE=jd`8&Kh|g!xW4q)N)Y-uuNWGi)VG6sK4N&$(#o>R z`boYPiT`2)(i(A6@JUZqdmvOBBToJ4$>J3Lxzc z%m@0E5NK)*@#oQr!mBK{zTh+C+4AJnV8=PR)7sE4U#mrLaErgA{nlmdO&rQObOZWX z3?bJ}vrkCdZA1I01VU*6hhbG)>BviUjyc+1(HNA{8h;nB^FxU$-Il8%sSwFbOT_&{ z;t|4-D9wjKXf0%VS3|?MYastdk`|S)l%^V(=Nz>uPfrm{)vadK3t$WcE#rYqUg!3u zQNoy$-Xo^FkVSo{7E5{yOt6^uKK$A1`Ztsy-=+11=6NgZbznCKD4n>l{WY7~IAZ>IVVI+2+-1!a@0RRs`h3tu6>63DT>7U?VX~ki zO(kZ*<@C9M1Oa}hP)u`7YL;o2-N!eEprB&D=>;9{nuh%p0qx?J;UEKdJSEP$Z00mc zYK2_|#Y+1Nc8e2vVYLt#TEZqp?U`TraWbl`S2BG{r16mla5r}&Pos*mj_o|MZ;(y~ zry~#~)=co8K0_Y&)_^^T7!b}K(Sl3;;gxDl_vq?5z=Ro85=3jNg4CBY5T*7kMJGP# z!p9QP8W3%Izf2{F!0nL&6y1%p^=Hap&)~KW6|Qj%rrFzvnqI+vtXC6O^QMsJWcfU$ z!sf38w#Uam0GjO7iGpEji-9XsaG{T{P06yi`J$&BtfjGo>rT_(XF)I{; zNf4nbgFv5@yr2QU=iDq?!wXXLgebBs7pYhC1Xg8xcjK4?-?Fj$ZW3_muH%BAA-J2_ zZBOrHmAOhT2v(|9_PNbg*dP8qC0%k5P6zstnPJSQ>-<@8>vV|1f>}{Buf=4&)BXj- zP+lrG0A~1WzW;hC8+1}XpZ$W~(!f3Y(N^t*mbN&|tU~YYsDVOl!gDs-AxM0bl6)W{ z3m2%6Yys&|SMPvuOg8)8F#N9}=XS_CJ&!fZS>eC%dudDdLron}p(p+<@}`e241S zo6||NA0x%Ce5;%V8w%5NuLS&35wm?6YYgbh*4ew~}m@hsu#7%n>;h5hux!g7Gx>xC$<40))4^oCq>)489zw()h^R({Ltf3@_&jI1vqbZ zW0zWaNe=2x#Jfm#yac^>^-B)3rzAC-ZdYgQi^Zt9(rr?Etisr5Jx=-oyPi5^Gfd@1Z5;$D+aT4d=m0Y6#)rYHph=ovoSbO0C*Bp z4tN#kY?oYz`whFdUb{pTcX>9+7D0hAyrd9HjG@$8`(dMUB)3vp68ym0BH(e8w-}cd z57EhsW#Yy>ua9j4D`UN`=^b2EK6le~SOnF2@9AaN&n9{JP4Y2}&=NP_nUn6pP@i0- zgex&k9yz;AtrAPpEuyJ)zl3H0P?7X(Xg3L~Uw>Rw%-EXXkp2o%$~t1kRL z;nG;C`k5FB#AKF-I#T>`dRf|g7EGm7e}1VKt8?9sop#*b&G@NXn!KzmuTRIAkjOOn zXF!b^#J9B4Sh^}(Zag=gFKihX^;XtzUD4oa3bHg2aQ|9(X>b7dvl0_+&SrSr{p6xc zWO{QKU6BJ~nI_ zdn$mvVkzgKYtwA^Op!2470F|7c+XQuC7ksxb-E~%d3?MOX-mEj;MdF}(7?_)8Wp23 zwt<8>GiooQx?SM?7jsujXLKk1R>v3wa<1 z!_5;;^zZd*WGOS8IKuq%62*l_>r)cGcFI^~r*zsoq|%POBd zh>(&9X9~x2q!@vtj|zsyjt@-e&*WTdNpyq z^-ll7smm- z9X~gsx(^7O5e$+lw$p-n0s)6Q(rVtWz>EYgQa~HL-_n#(=_CEjwBC>tz!vzC{`QU-C<2SY2msT zOdykyeKupkYuOWBoak4F{*3~|71RxJ?<(lhe=(Q-qtfk^(9P#F`+Ncso8+{gD9Z4PnEH+}su^EwWO7Y#WDwg$ zS84!2tHzqw2u(mUSXMiKVKO)NqQb^HTohKRw9rPGRcR1!(q(vj|h%`9!4E6YtPtX1>G}Ewu z^(GV!C6jZ&!p{QYzh{8=20d9W&wpGcAi<~vSmg!+dhi&s-cbG=Wp zXWEUYsbp?DKABz&vqo-I#b7QK28sj7Q+b*8;oII5{}iM!@j6Mh!TaOyb@j0_43%g) zMh{xCGTZi&J`P3Fmu_y7@noe5gsaJuU%;)Cqq}tT(EuXbUYCe7zjZ(4VYae8)ng<9 z(ijtUTs=_(uMT$%CF$@xXrANNBp-QdWuldGm{}#;PG0nJL>IJkgh>Hp?5ecE9>5*O zHyVDTfUH5HRy-orUjcrRcKnM#Kuz13zhFeFue)qfBVPeqKgK3T0*Z+M-DLZ<*YqOz z@a48Ov;2G*BT(bNodoj&wfaH@O>KNY#{C|eT%wO1C_^G$vJ!v0-jUlc(4ITU@CvHc z-`Xe@5)KcJLA;cAFG3lz%nc+XFCk=I_IyP zwf;fU+Oq6GVz2SGD|To_ei@Yu5x2pfiKTb0eQdNulq#O3Ob#UdQJk0Nl9(+1)q;D& z1_)k!J~-PGZX#7xkSPA}4(svYKp>>Sv#zBtZZ~d};G{_*1QW*!r5L~+il(2S!5mnD zbDq1EdrkH6L)MFIr{b&OaDoPiagr@$%*%a`;fj+C^)CnDcyp$A&tKu$S5~aM#2pbF z#6YKwbVL}h2cj%k)8Ctl%23(oKm~88`4aE9LDHzxJtN{r(3C&gp|w+G&SOLqMVn=` zLQy_xLyHijQRMPsljo6>fl@Ktr|se_y7x+qx)&3`TuLZwuJ*oc)b#<@t8>HE%l*Is zGF>hrC~B~F@noR~5o6tyySr9L8hS)YFbTnk`{5_4P~7l_2Mjff1eoa1Qy4~ z5T$9MW;8UrgFLmKjgg1$wS*;fOlA1uARU(}g@ca$p!}4Y1tsdU$1G7VDC&=>JmZc% z8atZB4SZ+mZro6^?k0fe*{4`c)|%#Nf^&=*FoN_V<**UcY zlQ4L67lQk$3`eo`q|;e~(SjM&2IBj9Rx#Z4CkY+`={NCttzpteGt*hSp$2*PtwL!J z5vsQfw!lIcp-j#Z5tmpla5m684*bLGLeLgZu%WP#mG`+*(OJ$8H8D^PvZy?W)&qpMS z5}SfOdRr|h4I{XMyEpr6j^_x>$5%BrNR> zlOf0uO>2HuB)1oGt*{QWRgyfTqv;3L&P0xWFLtumN+Pl*L#S5y zHfJ@Svs?gI6c%N>>Y`a+i|&m`x?kB4dPY(pI1OEH_Hy@)%ua>R4`p zMVipZqd!q4IsbwSzJ3scNG$vOC zXB}|G@B#djn{*f|HZOG+jYDV;KIsuNpxI=qj)Jt@5BuP0F;>VMG1udcm63kebBASl zKK5QZJ%vlxu?+uJ!&%uXii^P=LH3xlK*P&i-Bf5l){1tH-YR%Q-(!t036x<_&ciX4 zMVzuRf+E+;A_g$*gXcwLg2F<3(zNv!l7NI*N6C~+_>YA9 ze*j59w!c_=OuV2fEd{uj_j0~b&BEOMyx>5d3N?Jl;~AYclbrW7?Tg5Sud!Pf;j}l- zq|0;*!kcLcE`AFHH~Zg&q?2HaMatoW_h$}w)R+pv%#M;I)7OU3=G*9;_$nTn9>lOu zzX)RFLLSOL)k#kIliHhTu65&*t4i?L%LC(5yApY=%m-k(0db%O=;o_^BXM)KV6Pv4G$8 zQl6uovV+#yn#iL7HV^lnn1K9xo|dP~&1vST;PsSwcqMvx9LwNW5?AD8e6B$ydiEK= zf2=oc!4vr91oZTBoE_5(K&5ykT8N^7DT(STg|7^ z!k=VTCy+ub{kp5UD#(}W*uCv>I&G=Ve>4e8OV2gIE4Vkw5sYWDp9Zui2bB&E(V5`o z{gGwMfc( zejHN;z3whQo z*w&6#zlQ4!!M?$EXYsj^`m;^be+=kS+~m|-QdD0S4=iid9V+)@ZH^cM9T=DUcVG8Z zmSx#3UtET|7pp%XMv~tbx+yYYbleC=Y7}FC*HFo2^I)+;m7a23$u$^Z?DP{lvw+*jdd`CeG5GFPw678w2C$(v zp3nD_;I8Lq04ig|_bju*bd6ldiHE3OsC&%IP@Z{lfw#}fEJI!A4&}{O2^(^CpJSU# z0E2{3*o=gtj`$w@8OxvVe<*3x2~<)apO~tKEwlrA&YwDWG_($f`gb!>v0#*7tcGUn z`U$af8-lO!NP3W<5Vjy!6I7i}+x4Qaj$9iv7FhZG%6Ck-emH z;nD<+W4dS(=uUfdRW7`nTPRJ z?2UWPMAhiQcyK)~1k&fu!Paw;cag3u~yHLzan z8>0;y^7qGPY~J+2%EuL=f$d+(+DQh0*|q3a54yQc_w6789MVqRivD1c{6Ui1;krP# zDYm%7lAMupC9(fOomow?Z{I8QcV!6an*BM2R7|(5jLIWaf3PXAi3dw6c_~)uwFypC zEXa@00sS=MYPC=~%56UFEJ>RLa{7nC(h$e5n}sBfrzutqRQ?R$NEY=9!JV03bKz%@ z(M{xx$i9w|#YVj7IMQMJ#Ck5gddPB=Z7Ycr5QY^6KU1)0nTcA83V~-EYHjZ5G~w;* zmE-ZLs-`tce@gAh22aK6{o!lTji?^`Ud<{M6dg4W{DDCB*q!}Ny}s#nu@6r)Czg&V zi=t%^_9_pbeRPqJHnJYV)Z`*(VMK@8Q(}{9kTZhlgk3JfexJ*$I0lYDk>-jiZ%|8J zM##tI?sdMJhMM9GF1Bwq8b@Z5TwxGB|APDBUdr$|e`jlmgEz#x8}-?v@$cHEMcnlL z%rK2j6>eaiFB9eOgvd)1gA*{+RgyEeTq+eW^TUa+#7ing!|D4iUsn*rtvCCUw(%YE zg5WC)y>j|>>{08W)if3-(FFUL0FjhkJD>#+jg@eSqqJ6`z_y#pL(@kUzpDo}QXRyCJ(w%-Cf!VYcl zE%To4>|~uv+{hTg+ec|@%Oq;=>!JZpL$cu1TCkOTkZPHub4X!f)C)#n?R-Bn>d}nj z3qy5JFb|)x$Zg0YI|D7S8WTmjG>#C*s3!I{e<3Hy8>a$LJ*>sW^~3CvTL}8zTA(}8 zQ!utt&C`3AxwD7~vkr9*vh4D!Tg3yN^{^%Ekf(^%C>r+QWL^VZh2OXVK}}#Li2p@? zgW;`{o(!V7Fkl|M~mI8VFQn!$Y;A%awm~Tys4q9_0TnVoRFI3N`Rn ze^A_2=Zhi5&nI;C*kc#mQt@>!&6>nY_+^Va-Xt}&U4T?tbiITUOl>rPYIL8acxn{Gf} zyXBR6?mDWXgb;|bZDEx+1f&X?o7=G0e*l=w91U(R3jL)a5~$nJ5yBrrE~+!HKiiR0 zMPQUWFU)u0_)2k`$Jv53$YtX?@uT!mL6t1qyl>}3W_#fW$X^0iNyRQq8iu=p1v-V% zuQCU!^jn~rW~W^5>=LJHMcRV_iVP~}FNkv$;)U}Ar?Vu0_a#T(qANMtGyH}ve^ee; z!UJ3r%+gSxFBvxqqne*hX|9c}qp#e(DcbUSx34(7-nN-wVA$!ci!-bG=(u+aIa-w6 zML$aXD&MuuNbQ>n1-wnC9yr*hCk$&xV=ypzBg|u%8AF^3sRo+PZ*H;ndaEd2tQSc^ z^l$f{Xmz|yD37R>!#YfgEb?|`e?b#Ov;<;zN};F(O0k--pyrbK$FGvSRlWGU`#s<~ zu&G8X-RJ$rcB)xnLwx;ba7#gMre2ylS16&`bS5Dy6xLPk%W5WQeOoX9`TiU?JNGJq z*cR&HOzi%oBk>u)cdZMz{awbo?dD8tXmI*_OhGv5xb76RJe}F_&)J6ie^@<=fZi9B zas={gwuwpkxT4>Mc#1HGr^(iS%gU!5l*bvzNf5_x0w)3Ht*M;mbaj+Ls9H15cLnl# z?t_7SQ;~+Dx54#!=)NASt8agvQfaLs$#@w*|3SYE?bHoDBns)V79&35fftvoOg6K1 zUS7|L4E+TA;{m#GmI5q)e_V81u20onP88+D`f0)K#Y-2vgzTxoh z>SZ-cyERX(OZ(Jp>9RFnRz{YeXv=%3xd+!!C#gN#%;6;Up~H`FfH~%GGFM_6uaI+8 z(s%9KTW~TC+6$b5H~dXD#e&%OoMcps9b5bH6qj^heJ#^FC78Q7RS7y`{3c16avw3m z7lg=geMYYO2tB*Fe*lypbQ17QpK7jH#KQz9PS_oS&jCg9kWHCkwJg;EmJ z1$+G@((eVjf5wwOhuZdO)CZ*}JZ$(4$N<&Pot@0=)H%Yj^l`5n&D!n?i_@&WUS~$h zYR!G>``H+1wv<4<1B8@&JhNYM>&C1{Ai!dwD5aa#8D3+)ogBpW_#)aQc?M}gqs7uM z*fdir1m+a!I+4)h-hH5*A*voMf>^2`O?a@_lQO3gf26KrV+ZiICTfs_($~m&f~Dq7 z*@A{>RvkIuyA{<2%(gG-gY?%OsV>^J+pYP0DQ6xwj3>LxACrh}sqdcg#%)pysODJo z;}D@`_D(SInLscza}WkHnA1Dat?}QKI7rlPXCXBpBzIx0?{D>5JdC`CsD{svRAi$a zQ}I}Ye<6ju{D_4IH7kvS{gOP>;RuPJeD(-)zXr#{YmQ3zRTxoiEG>l7wVH=8URqb*K>XP7?|uI3e{;0u$Dl4au!GU$vTqlP9MaLMHuQ+= zIub-8GYp4~=1^8F1qp@_@x17#Xh#_?uAu1WukuCZD+z67GV3J1<&3a|PX?Kk1P$6j zhc`y~oYr3j#)j>>jenOqANJQuinM4I6rXH33YQwn)&9wVQwJD0@cS9#D1^*1#Ywwxkdm8qqIQzlcg$nD9IA%ZR8aaq^jonda zE#&i-o_y|Y8{Mgr3i@64g4k=KX?+k1&WuymoccjvDHB9s=^AD8KAcpyY*J(kw@UnO zFX(AQAsG;(1Xm23wNU!(dxM&5Hjr6$f1oiVElWVlkIoU7rx3|%GcT)H+Mz>inY$5U=TuN1 zD`9FI}sbZ!U)AKCFk@^P*0biK2E1-;r+MkqC`hezrLL;RKa9>2y+ie6g2 zQbM75FCZbvFQ1#VlAO%F`CetrB)Q0F_h&BL=rBDBiV?@YgEY#_laA2+f6sxBTC<~k z)89@a{K_`6RVVMN#H<{)P3$l%Nn@HcK*p_B_p-3e-L72+4+c-1o-1~c5_%4^p`k|W zylk(qyhrYnD7{dm>35Rkx2##HhEg1!iETO*pKh=CC$bUmfL8h)RIV?XU#fswjR?)DkUl3x#X z7!)%4viRo<%oZ6XAdV3@d&V7GV};&k>>ezTFazrb@yY6Z18RK@BTC{To02~t_LTc} z-L&G_zTJ!i&GaUF&@R7?9n!|rbk}u6nIafvCK?o68>t+Fs;++ue=x+UO&`Lr(fwIN z#su}ef1PArf+`NiJ~<(P!wOKC!abac^9Sl3F+4odYE4fu!JFZt258Gh55mRooKPf7(wY*e4iXYEO};1TrhmPPGiFOZ`2)&T?i0bz_MBq=tbnu81^& zO!KNoSvZhCpn&U8HGsZj`lFC=nXQR8s0;e~E{U?DL+0nrc#_QGVwlHshH-`Kb=<|c zDDd6>&?Y*`2OMy)Wi4-GGb1oM+?u?K2HSQ-i|8f$a`>sUfA%X{Sd?;25>ZFqOJR?2 zy{eOgKY8(Pe-hGK9Vo}kLo%-{P|#+!V#Hqrv$tB}ri}RTxMBmcW$58|=@PbWegq7H zA;(xM=`e(Y_sK2vkD=Mai6i7LTdWu44E0)Bh{YbBUqe497EB|9%VM`qUWAVA#l?5r z!)RDKPrJUce=q_32*m8>51<({@58HN%=+fo)wf;wnE4lQkxMCkTDN!KuHOK8POFgj zhLpw?k!pNA&Fh4-G_Z@*A^`qahleHD>}#a%=JxSj36g7z z4`$AO_RgH-As~nKg?`c|o7wIfcnemzMsAZj>mZ&Tf2jTeG1z@yVyEh!Gx%V5vzSq+ zJ*AAGDF*F`>Ax>2V%)gnR)2RYhTTFY6MH|pcsPb9bZ(>8>&(rb{YJFcS&e;EQt{`u}OnjStDpcj1 z6h2>jog|CICsyx&*zzzD`JEk*KLAy$`;&lh2vcCMY<%q0bh5DI?JC+K_K(I=INXw% zEi@T{l5R}}?>9OwFi#a2S7wF z;fcpNrSaTdt;{B>U4=vtBw<+jbs#(Ne=EBOakKqMRfBpn%x%7(^DXcl`+S81D0#SU zLMD8%@V<4}x;Hp@x6Gngl;pfuGfnfM0#m{nmC7R7(ZiNlK3i-d=-0Ja{bcqF#WeVJ z&L1EnG4Qfruf#*1p*)@SDY;thI+mGY(5Uf-_M1?pDaxZ2n9!*>OdxwmT|}k1e{$om z{V!-Im0>DIN!7m7N;$}Gxo3z+ZkETRr?*QfGR2N3p9Q=Fv|||3_3Q|h7bxBav(ni; zT?$4fv0P#+w6(<|_Yz6maQX@318o-5NJ@9`WZC+bZVLvjU1P%_>Rbu<(!b1u+&)dDJr0`!;7ef18eRGyFf65m$6F7o> zn^D+2Ptj*}S5*5!&2T_K@bJ?(%zBI8RVGnpLR5*C6VysiK;*z*X!p>EkY&{owUNv=YvvOMFnfQgEWo`>EGRN zy}4OPk)=`IX+tXR2@jRP3s%=5OamRy z14FI}gMrbr8^KU?@~JMZVliy7`H;#MW;z3|Ugu!NRswM8QRLA$SkNc8{*ve1gnfmP2N6;NQX( zU*75oX(y%rvjMtJW|s<=Kh5i?;8#NzZ=+?BI>156|nfAWe*nIemyzozI?%|wVE z@Ve&w93nu#(#q1%!XP+o924r{kF7!r4i|`Vt_iO9B`*u+(xemT^g0w3>U$uI_%m>3 zHeTtCW>J%aDTp0F_r4k;+4d5v8hcwmMp7Z$E*Rp=-v?&`8`7io+r^Y~q8aEB7va|4 zybaB5|6l_oe~2V}rVd74;Rr_BWr})htPfRg{&~_>Y9XLOfy2ROc6JDYw3%{s7t@vl<)UGd9{xJ9( zlNHv0v3Vpp#MnX~JnA)^{7I`7-8=z_Bc`l#!ALD5f35)yg)TQDRER0INZU*(9^!mf zDk7R{bA+U}dxGx3lKd|0<^G;3=W(NqKMLo?Y!9Yz4d-iX01?YBX+h1qV@JKhxs>T5 zkHz)Opfhkg;*LaK8PmO+;&DiwMqzd$iRCsCv#yz8V09$H<{0|&amP9-Yn%iWV=6Wv-$QDtG+e9 zZH8RUjVXgAAG?_vVuQ!qZQXmiqRTPlnLHe_#1n{WCcHLt9U!TbzXVQA!G12vTK;vP zH_!3csKe)x@nQZ+N3o*NDf9M#Bk=c~6z}71e+ebycxlfz*wNHWL~(FgpxV?!FAXh9 zdrvX0(f}Gn*WZhAM;08xsyb<;+RudBWq+iO7}*6n5dKuS!N$IikeM*Xh68g zN0QgZUX2G{&qs}oJ&)KH3#UP5)p=S7q5wTuUIc-8;;~P9Sr8;Dj#*umZyH*iCPdY_Wbcl9116n zG!8E4@-2K&`qkavsmT8OH&#Q;7^{6V<{V3_A9JoehPzKcfv8+I+*XhlRRfLWCqrHo zKawY@a(sSvvLIjgMX7FxfmW+If2A(RF)ix{iiK6%K-UIq{JGx-igH%tJ{*SyLreB8 zVeb$>5-MJ76G?a6i;wW^h1Fg$x4?#xKPk)1@#vfE04q+3e8-#~=U7m?Uypt^>Kdf- zegT#LMt!!_?6^6wwB{dKQ#bx5jGfy#l-yR^w|HMxm?sB6KY+d10TITbf2j~E?ksC} zk0UycMuy=?Jxglu5jku4T=Ta8yvur63l}GUZXmX@c|&!SeqmBe1~WQ7M(Bp+gn%pC z2>5x0-@i;0ZA{xT^#F&$WIenafiHr-)N~mq`}+79k2E@dCTC+P^8Jf5dNa`)vv;nN zi)UslnuYY+k#t*7=)C>(e|9mgG-RfIjC)trcU;&_a0gK0(|(MJcBj<%ceid}w(Tsv zy}o+yU>X)@WIhw~&fBXK8Sh&N{fN%9oAsc2ap*h-&rO9pdo&U+VvdY1DnQVc317sI zn<*EUiu_8&sj9m5Mj%+2*p9uQ8Hz%&~ff8x7^ysZE3faoo? zu?T9he0RPuZh+D9pB@UrmXw*Rw0e@$N>rr0OQFWN@7W%La$zt!BoJ$i)rO-82U}36 zOgy-uz)%ro0$XKwdWOQ})$j0EMfmp)vqA%}NX)%oP?sJTYWWzy_e2aX_;$#4_kRz+ z;YI2%zOE}lCZ2Y!e;AiIv%PzoOGRiBRvLt2Ps+V|!NOCaV(p?(*s*|s2>J5x9Wm9= zYm^pM>q+OKuQ@MVkv|od0NR3x)U5{*Euc(vWrz6za(c7|W0Ij@R*9ho%e|(C%6D1> zQiKHYDskHovwtODqKT)GC6|+hKFjb&6G^N=@5V*7ZR)7`e;DULtqD8&<%vVM)a%A_ z!V?bivpaKBZT@QWmu(u|207cneC;|fRKQVj2aGN|K;PgZJ@Oq^RM`rBqxNub&ON-> zQK^ullRE#Uq84gBljtxsP%Gu+6{%ISDwaQcchp5obDQU@gvO+To`O1FvUMX{*tpV@ zhq(v^JkSFme<{7=;Sjf&fvUCA5-zQlks7{MAQ_JDXo@osC#&qzKAMr!ih=gg!|NLIP zv5#hs9lg}SUMjB;%S*_VC8oUPR>#4AT?bX==QU3bo%oto+42@aHLc=l$|XiQuDc9i zuH3qYe}8QV?M}(^TTID96h;WMuh&4Sj#chIt=yWJh~Mlm+@a&4R1}fuOZd`%E%X^n z#*vMyBn;wpQG>2Un&_4AI~|6PzuVL7Dwk`Noj2=R(})4v6pFW`Nq){)ivCiJ_fG_;#$@ceHH z?pzD2eMe()F57v2$!6OWl8v9k)1;1jYH{?=ocwfD{Vth4>Bx2~2GQ86G;CuMX0T7Y zAAGNOUd@B5DdD=^b)&pBJP`7*EJ(E%7#wnoOKZtc0I4Rv?sZk zf4^!LY~P@t8HTBH$Z~Or{iS3InEFkfRziAm&EmFEhIwu=_Dp_ZG()}L#gH%mm>Cc2 zCRDDmc%F=`K714HlVtO>sl^%M8)2rjMt3$x112;rHzq_k?hCkNb=Q#>61)&e2HD0h zu*Dt`6SQFG*~n<(e~T!&8-&35{s`{wf8d-UOxzb3&jy2Vghr4nlBU6XFrdcjst~iu0(2wVH@SwU1d_c`JC8twJ*s^oJ=k5I!%-& z&!rFtMsitNi)Ycp=!r?G+;Rdc(vt~-qxtBSR_B6aFJjDRI8+tdya7vt$9e<3^A z`R3|8#`G#^4N5R`O$PBWvUmX`3j0{vF# zG&@9jYD-TYGP-Iq%;_?}@xc}ZS(3-;=Hd7=nj{8vEZA3F{8pyVK!u9=T8bSL_h`fA)REJWs`XH6)dOW)bFMQTzs+W?TX3C#cK&eGPZB zJgc*VMwm$>@=?D@YOjfxhhI@rTdGGW2~;3hbzIay8uiUKCn7C`2u;So5|&LyVYNbr zt@w0v+|w{WgkxRti$iS?r*$K)ejN-Az9Yk3w%#znuqg>pM^M}r8?Y?>9NjVUs>z_McJH)zdopcErfUa|BZk@`5JYnCpbz+4c0R?E z7`{w!&G-Z*`0O@!wDws=e{|j###$NaF@De~VOBh_4hRxxnlb2AsY)Gqz$=lUA2!oL zwZMP4h=M0V!|BPVjtE1f-KWwX%pRVUffVI@2HNIn2(&4fO_IqR-<2mH6|pQd6tGe4 z*Zh@3!S+qK*~F}2>oMAyYr`bijcHxbTx=S~R1@D4{jmb$k+;kuf9t!85vc%=GFX2) zZhSb!Ujaq;?wU88>31~Wk5C@Is2E0hLwud_$h4q!RA!#?{+p?a^NeG(n?`A*b9n;N znK>zI($XbFgPTm;A_Xl=pbwR3<`G{kD-G2^%a#`UMkfEN#S+TNOGe7vhx(FNXzq+B z-3_z)P5=W<0G4)ke+(19z9neE!SdL$;wqr=Rur5s%2{Od*hLeo)<12=NMS#@XB17k z3ag*Jl}3g)C(}H`;6w+#oEr>nHol|yRID$@#8UzjC3D=PwS_)xSR~7}tM%YeKLt zTb6UPd-<-Nn(|hkl8`f1N3J`PfJ<9YF}_5=M%= z&0*FKvLr|L$dg;G2uZdh$z^|=7qiMThQEOc8izi*GZmDb3r z4Hv$Xu#8liccAM8BdcDEyRx`$dZuYOd$d_Q7H?pTf5f+J73Gbbn_Tqgo=8^)8mPK^ zB-+Qb43Y*~sDZ0{8LzWWsy@LTk_%lDF-FUt=dn8OzJ(pksZW=m*K_(qLc~EHjuSl- z%#V9ip>yKG4z4}K)eHY9J-9aoZqa|2R^A|cqR~r?T+Z6UHhb>;sxR_+kPH^6*@F+K zfNo|*e_o##icy>pO3?u0iU0fEbG5?qN<%~|cMVIp zV9`kx7VUF874j<(&>o4$8Z15 ze_UDG0pvD_>&uV+0!x`})#u_48;#qm$59PST2S&mo!v52^lASAf1=yJ2;JbOG8ht4Z}wl)I9<#!~QaFxOPL4QfR0LHIWvH@V$5&e-5L) z7vyCXj3lN%8Z(0jPMPh0he~Dj$m6PW{Eq++0`UDE&Q|{@uX}sZqY#X>J2a^{(g3Dt z3OLjAf2PcrNJLych_Y?5a4%_u+ZTwSctK{{S!|;J+=y>rWmj0nEez)2g zlaO%j##LJd?|z=#@`g?EnJo-Ye-eS!oD~@gMg03&7Sr!mdH-29Vi|O}ND$jOW%%5HvEbT1j#90rUpdsk=TEO^SA~ zb(oYSc-|(LuwSD`i~^sE+dR3|K)3(`<@&%__{IFvsze!o>YaiizzOwE`e6d zyQ{H)(^EcXa1-MZax)T4e>5SmF={{%#zo9f{#fIa!~@Da`$Tg#Y${(fuRaLtUe$@D ziL`th;=J2#<0ZX)c#!&+1S`aCJyju+)y=xcJ;k)a6!QVLGMl(7lWx_E+nEEsIL)u< z4@tp+5IBJ~(dI#&&w~;PbDV|IILq*louHeKIT{gp`bedVAhvmvjG&B z)2RUzmljn45CS+em!F>j6$LReI5aks(M~6SowsFFTx+l`in~M5KpJ;NkM6P7S5UYdMp1KnQ=pVR z*oBdmi3N$0Qrrn>;sUY-m z``Q6CJRN`lR={5v02L>DOD7Y%ce}W~gQpY7(#qxU0Dy@zzyu6%1v|K!+Jc;|faU;q zdnX%!sptO(NEU3y!~hUCu`_i7nOg!G0E(ha??|Gywt&BpoB>WiXP}cC(46US0>ZpyKo=7yPk@Vm{l9SE12mb`nE=wtT9Rr?ijqni05wT<4K-PD z4M_=rnyj>phWfjYh84&e;B0T<;%?#u1h~8_voJ9O{snFBYUToXH@;uGz0*3mvN5r-aWk^=0%*)=0W@syKSdKyhW9@3aMS*kn!6Pc3@~x{J3mv~_d37l_ZRAa zAN`}!`L7HB_7;B|C6p!pMt639efRpC^BsxpKe)JASlR!QU=I2x3P5A>&dSR9{wMn0 z6WhPZd1(J4`rlsMwC_m&!;k5&=DIkUn7PW6>IhO@n*aLX~Ieu^Sf12JK`j0L)CYHa}iT0hs#M~Zi>j^LiS|Bki z*}J?q4nXt&xEue!oA5vOfa%|iQm(ePN+x#ioc|3aZe`;1t{NcgV)EYZ{}o|k2eS42 zzr_68SsVDb3K}JQCp!~=+kadCArJ*yz7G`ZdpX`e{}@2dQXmhYxeCa|%nD#(V*5VH zf1hiD&4Es~ATUtH-Wl}w<}k9d@czs8zM^I}V4$-zfQ$8S6YzcX|E1x*MSm+`R+H9N zmXfCbkMzYf82`!XA2$^f5ZLAKrx(kA$Nk6C?7!|6P2QK$1E9x$@}58IyW{)!Kd%h_ zMJow5vo{BUE#JrReH~4l%>V1)ztF_Q>^%V9jBIRN07f=;uJ^KVa{zdGSbYB{l$ooO z(|bq%p09U#|9Ni#daoo9=m9iCTK#TsMkj;yTod_N5>Mks;#B`OY^o9rEiXj4vAM%s z+$48&Q`V*(J~j@2Aw4!lP%CVu+sszXc(D1SWgO!A%L!TtC**+(q4WTr_5oEdf+SXGL2$epsn=!fR_hHQDm z1See8USh53>5#?WdGPc<{BWMzO{P{c5DKO*8&GY+T&fy>HljWzL=PLpbd?M;2b2nE zU}jOQwJ;-QChS0Lgj4-l`U+R?Vg7n$^JT5ux}Asqq;jYu_&CtymA&QU8ITYEW$v{B zt5h(378s4VX-GDBGf6N=*z6lW+GlpV?08S?MhL{G8BeG$9~JpwAssm9q0>pQ*Atz% z<$cWLKo~ZE<#8SLF}gmWPPk|49F;$WT`z7>1oUoil^9m?*1VmJs(dfOr<^W3xK3hD&re#FWO9dq7q92PsiS*Z);jL?|u6sGS@kl zl&f`4pW6NiR(}@Y{V3cX|F)Y#iA4Q8XV+&DJn~}A$2`A=>!p=PW zdevQjWn;UqJ3-_u%V9hwDl)uaeRP5cJJT98@_Sl%tAFzdv)!1bZL8JX%@wB``+|)I z(FrNGMA?oZ)o$^?%1KvNqWvbB#n~Wwsx$4MKIx(&*Iv|;Tf$l=?BO%JlHyEI4@gahiz$Jo336ejQ$OrBsjNarSI~ zMji2jQ@wm~R!p#=AgWk1Pgk9cOrzN=HHwKF*=5S zCTMM`yn!R|n*&k>&m3a-!EfSeINLpiw(}tYM85uV9Gnm-l<+*h~ljtep za;y_k9F|hp=v=c}RIlqdK(@m!MQBxIo%}E^pCzsGy)Ne-)#4}|vnHi32IsVYou%Hj zBx_+JXGV9eg*u{1R9H~h^l293ew3Yg$Vl%S>KsqhOP@;cxEhgIWWa0y!wOK#6(B}m zkZ$tOTC$#U1nc{tG56F1!FD^U{&m)4=i%UoMnQQP+X0!hS|zV3gM$IayD)0rJhQ2| z&JJ7H+*;N4kLyw8Eb`9{$vd@wa{+58E2yy#r(@kqb0)bW&;z~vTC~`1brNC4&`mLC zQ2;HTA5Ok7!8(HhG3D3_%1J-)BoOhnCQ}8=e=>eO=W0vnrspiOi1Lz{TSLw9KAR&& z&>M&dK~1Ub`#!IkvujD-dqJd}iNFo9LmfR6M(}&gew8Y3lr?eld2wccGebkm^-!Ep zJ2OQa#MH_=B~%+%`+7t$0PN$ZznlQ$xe(v`*PxR}34hn}`@H>EWJeWA#F zHdD?07GiRv5(GUqS_il5Esdf*QKC%NsC-iEa?hNpyuiAYvX@JL*EQy`?}sb@Ctv3a zRynbrmQ@)OHI`6YHRqCKTNO2j<`3!`G6P8Kk`i{6VlN!nwjy|cjlZiQjz|#ihs*Q6 z=~?PEBtx+Uf}g^c_6P-ydv79p($Wl)Q7CsHi^Pte-30q48;zxZ<&fj>#=sQK27e^y z_qMMZDebQpj8v5VexY>h#nS|VCP%OKTfi#$s*Jmsg5kaWtW)RjoV+P!LY5d<`npaKiaiT7=6BcR8 zRP~jf23`~CqDiR8?Ls1El!him)U9F--Y_>TB6`<$aZsZ%WzPXga|3biER zDns@|)bzuS-ERMY3m3G@wlBXZ^eq&v#FbmK9jxlBK`jw~#a7HAMo8xO;-AlO0l8rp z;@X*zjQB5JPI_XK+Y&kGM9Nor`w;nEDjKrlX^BpHj`hi^ej#vivL3Q^LNG)6TCS~V z{UbW23H7n0_@(Qs$xS4!5J?yU*+h-TP>bphNbo~)d=B$})D=EKQt?1&M-GV{BYg#PU)z z*HF7A4_nE;D-2nroD6+&WL%~dBo+>vM#bvH_aKOmT6MuL!*gY@v3uGq-Xl?iG3UHN zC0T$ZyFnTW@OG3>W1L)G7-7ZHtRuBvBGtLZ;8FU2V;(JT&*CO7F?H3x@5}2VPM6R$ zVC#uc`Pj$Zy5Vrn2dGtoQv5DBG0O-*;?VxG;_YKMq;&HMeHL53_h#2yS=}DgWjFg` zq5vlBm0s%VR!8tIOJ$yN4cqBi>{wKO?ZYvmg*_!EO`^$f|CwD2z7P>+A=dICD`<`` zpYbn$2wTJ+OcY=|3`btk2BR!pEK`u`FN$4% zGp52o7rAbyN0yyODtY$Q`o1$}co3GAI6XE{3BKE)@8peA1bvT@FyxMr;oykW=g z8wN+hA6SYtgskL$KK{V~Ya(%=i#_!7X{;9G*rQhqDFY)+xmHP_d`iJ6|F;_Jlxx$db2h90e5o5+6ma*JqbgYs_pCnUhBIzI-Qw zU9&?T^7s9CF$opE+lF}mdQH++H+2``6hqjT+#+DhCJWi)LD499n0~BaHkSR9SVq}T z)=di{a4gSL2`fqDQ7YS0@}OBpVm;bRQ$W<}ybN)AkaUh-gLLjI_sebFckd++deg~Zr|vbfndg$}p<-R;h* zY3IDJ>pQNjeyN7>Dk0%wK=WgNURJh}&+^INee+?fYY~UfyA+vmcl1!->y$u$J+IP|k8s?g9mwAP>eQ=h&K~-xCF@Xdm-rj=HB<28j53b~ zcBg0xcLWIKPidpszlGycBoOtQFut=^FQ#%}DxCyrXSZR`OCmC}dr^hj@Ppn&Z3Cf{ zL~y_6)mP}oA}xg=jSNS)!%xexD)kPodJoS3o@^d=W3NS~nUsKkkPDb!{iaIbY6tx# z=z7m)?DOn0QbCGPuoh6Y^k#kKA$Z^|Iwx)yZNSkR3(c=3l{=rB(UgXB2nWqu=-99i zzx!;^Lk(7;=)zPKj|4)LFFnI|F_TW2VXN{=!;2AKj20?BXnYDj-IgofM64`*@jiRN zN3-AQkNs)3ufVl`swwUb*P4OO?KRY6yg9ONk%STNVTP!bN>cW=O2FI3v$f*{n^*f~ ze2J07m-HnFDaq!>u3)k%xIxmhuREOAM?4wQ9d;Umv6RYZS#OcURf;nFX(<_g2Q-6{ zBDK2`D{xM<$G@F383M2Rnl15!^Pp^;f$Ow&VThfGl@<$s8``-l49$T-;#VUgmNbyn zY1EmBet64{sM84sw*F`r-ROTv8>Yc)7Rl=>jLuaydr$5yp7 zidTLt@zrU4)$}liSul=_g3dEQqXv_I;zqE4tQ3?F_{Iq*#38k?{UqJ#BlUb*A!n4t zJj1YRTL%4qcI0DbV{o}GXZ9MJ<6fTfq^!(XDShk!Hi(D?%v59OB~ zsvL4)l4xrs=I&;cJF1_+q$b7p5rf)~t%wZh(Y)-Y>6$w$B@J?eqK)w57+`$B(^YXO zgH=6-6apX%J0qfH!*NX1Ni=giEO(PvL>S8U?rCa&g?gC&SjGHh!{^A9a=fklK>YsV z2VDU8akXt#SJ}+g9Bid%j{YQNiN`MI-nW{IFs+VP&%Q-(CFMmItmUav>ixDg^3 zYVact)zo%XKF;A=fwEP`_ddK7on6WG5#lS2!btp#{5Y14JvvJ_iS>s(L7?G~w_*+WW2zWy= z|Hk33`qfSI%N}z_Z@2JeA^X?I&oMPp->s%*J;o5XifcTcO3kpyZy)7g>`GJipF_ug z!mpJr2BrOdnGPKD&anG}Ix3bQ4%4AkcZD9TaQ*ujudsMyKb?+mWPW$YH41+se1^5{ z5Z_o#doZ%yw=aL|@j!)EhyYpo2Zx%L)Nf%kyDTYjBCeAi!yF2y;W=)JP%I1|v*TCV zS`DW!z}*mELy)c{8=klf@%wf|hRP5oU>dP~!){jsv5+3>8W;Sh(HtJZ1eG29lylcUxQ z{!X`u$KnYySc%zmTz(_0-tv0ngyXF(xW4+$5Co1?Ryq2mw$&U>fw#H3yW;n%Kp$;y#BoKhzlVIvY7{D61e z*8m`Q`5$b0D)2x8LKETi%KkABSzJgL;HpL>T9cPY?A|0SSo9~S2$-MR%)Zr6LrwCG z++VzcLsxhbepofoWpk<2RhY4&MOp@vuHSkKN(8=)s&;zYGoQdy=lGvIDo@=jZ)~&w z^d6NRNWzI+ zO4ci~F~?i*W3=sO1br~VQnBCaVGJEIO28@=?wf^(*Tqvsx1PbrYj0m+ql2Nqr~87f zc37abkSm*p3fgiK<%x+GGjY9<68*GIYX$FElT1fgekO~r&=SB~i{j?xt}%)xcds_d zJ1I?MYgvi~xRy)JU&LQ(C8Bhuu%tT#Ntw|@KHJjVXD2+!K8rHRZv>KGBVw0~WifBK z7g@R;_&}HWa+Zo15&Y8H{I!z&7i{UpM;OHvn<5oul~5}qAe|$Rsd%rgdl>*Lu?{8r z3(NfS94&`sJ^(;o_ZYP`=jt&JY;e?*UHawgosp>nV9oe3ukZ{$Euzkys*9yOM`(-! zEag#xw4ge&V&p?J8nOw&AAPVqblpq5Z`^(G3*ZQ?8!=w7{<>VdTI>K$Xl-Sk za`bS}glec0SWf{KX#+LiP5ybC5lzGjruclfiJT8xaQX>~h6VX>G`W}Z{qk@;a zv20HO75pdg(M&SNW0&bE+!#mvx}&+?kn_-s1?F6mz3u&Gc@QfzYX5SeqsMB@UqH~h?p zP|E#-n|VPd{B$j#$*L4x`xp?(dJTksb{GVAet-*4v@}_AQI8lb|Z)rmk%O zFWF-QDM|B-C|Gs%^GHMXHf*Ns)SjjcsL_*qH@Ub>64q^@d%Fbwfpu*uaAJgwG!m1t zth~ntx@a)e$HQ;+KvPAX~p$U~t9W#gZ3mv$iA zUBBlTxn9UyNmJ};uEAoo0SKACerI<8g{wczEJ~QW^bx*gA_gJzwOaIF7`Q%w3Bx?? zx})ryW|R&eZ7GQ2ORQ>aRBr`Ijsi>nspCvgrP;imZRr!7pK7={PZKjCx&w0jsllim zFO|%qLY_3{3>g<^XW{`8`?i2Gl_R2SMXA}=dJDK|B*MW9Drp4ik$2!qao0Ye-*!8! z#AtD#Rl$)OEFPN~%f2A6YrhNE`7rX4^_6Y3h<5t=RY-agwlmpzsvdpaK7W3M zK8ldUQFxd{3`p12YS{sI2FYEQ3)ub2@8uE|A0aC#c(Me#nJG;va&1moj4r_rl+Yzz z-sKyxHAll{gY0@YZ4Fm=Ztj18zcSI|aZsJ(subt!E{yKJ+po>rjrl0aKT+2`dC z?g*OjG(H%Hzr!#C)lyq~=dA9HFhp!16}eMV+|K6_22V_J<8!1r^2n}YLfn5HFoU7M zM=E(p$RzJM5t%;%YOd-%25T{W0 zt77}>rlq;hQ9Lvn+lE58L~jLOGw{9^KI`)_R255Zs*OWF* z*x!kF4c5AEbV3PD*Y;ilsvBKW_j3#E5F|V>t8yt;)(^6kOMKENV%vKtH0%>-8;)dN zd6Rp+eUGXS&@-RT8&*D~g95``3!lAy2e!=!cs&ghyW=fMy0RouODEP0JVlq6^#u6i z*qxK%UOs=Cp#8RLl=(Os-S_e>|A3#`Bz0cjztR*KHA~KwEt+frK+t>skwZ)^aI-E{ zNg0gW<~l^y8#4?mj|#M(d!-PxCpMBJ0Ca^*HkId?9mr5{6)Zq8xh7BPT{%qv^%4vEbSQ$?uL?RzIdV z;()WMvE$zuwQ?=Q42pW#SS8ttDF&X=f0xcU{j(1~M7fvofKmw>5&fpPEUdUvlS8gu zrHXBDf(954EGiwVH`~)x})%rM8CwH+CWU$Gdcj>!o*6%Y$L7H}Q= zpRJ*DO}R|#7Fqg#@G;ih4~G5)O;K)a=+Rv80_^t$omsY%fUGdP*M1$_jx5-|t3nz# zfxehT4W#-gn4;%fQnRkG4zZ+f1VV)i=@<%ZSvt_0^=o-wnGpIPuf+-M|G>;&=IzKd z;{d&)8U}|(`sM5+VshA^5K$7-;av4WLKmX8iqwziXZ^t-I&~rQY9Sprs1ZS8)N->9 z0oZvr>Gd=DcAdN6C*;KFyl52xg$*Y{nfNJsgurw>q0B6c7Uln0h8fzqdNV?N(1@$) zp-j9jU#{NjSXyvFtCLx~?tv&jXwQBz8BAq&Io|X{XWw_J4kY*eT`qn%9y%X-w#iim zC6KDE=D%Yitj0(KFHOoVI22=~I3iO)2OvbqiR+$DEIHW&PN_=x|IU({7?6r_2Y%ZJ z^N#f;n(|44zj294i%6A17CCr18@$stIcR`?b1qx}LrLC;-1G=(R9!g{4!?qTdKJBa zU5EW)xdGXDl`oGaKV&0q5eGi7*j~2mlvPf68RaMQoz|+#Rp`SgHY;iRU{mNw0Rh>0 z*2I<^%#f#a+0?}hqt6GP&M^MqyX-V;7A1bHh(%ckLTy)=3Zv^j5nXK(xArB4;pEmt zOb)83*`|<-ZyER{4r>e<{3m@A`lYEnlCj$zXna#rlsfT7Vg_^VrZcYHE@1(~os6mx zRhkWEP|N7ks$!g}BzxM07b1E~fCHk?D=92_Hqf_^3YN0^qs=>5g*|cq339j=P914^ zlhRybbH^dU zInUOMiA)H;N}_wIfGI1C?gC>76eQ*U0Idx)RA`W+HSvCQ#ym8Nvs)YwByz({Ynf4t%|phou0Js)j+eC& zS_PAN8DNyGwP(Wa#s0?H$_OK(V9=F^?iFJX0=d#X$dVWa03-1YwG};V2ETM%0c|vb zQ09Oe>deGl!O!oZN+#G&vlQjE>0xjpQE5lwdPyqAf4}ilKl2hp9NZB3UIIu#rvf>f zFm+2HH=7Ia&e}Sc`7b|n&e~)e%36wluZNTL)*o8a(tO4!Yc0aP;zHo(YiOJ@7AJe` z$1j<^7SJGV0_-^g4{yY{gClfZ$-wEH8%{NEe~;^^NjhCmFHtnIO46@c2jo6$t>n*W zYV>8SOcZ9TuxL#_nmF*g+Ye3gE&s5Q?-MwxIC#xrhC5*5m7lmLYq%C|>PBBqnwhh{ zy71aJi<2TIW&oWU!AOkof?B5S*oq>iqtMN&HCA#W08jy2b28`(uLqMuD-ia#8sS^O z@%(M66w4x*(83=p8|B65;&oZIKSvRvX$+2F4|B|Z^XA-WZX6`@cX%rN;0hMkW9y{Y z+SlR2`8TkuIre@`=>|dlV=2FYGNla$Ix6E*?*Xf}N33g>kg|UcXB) z>TeIu-(OuNjn~uRb9%k$TAw71lX8BSeAiC;Gyq{Wuj<=dHUHo%dGjM=hzGD9k&I$x8Q5bCGMs==#t-s$*L4WS`4Qi z%>>Zn&k;-=@eMz-w%tWsr<4Dwfdh=UjUVZPUce+!rOd!}HR)|C_ei38)|g4;Dluf< z5Bv4n+7f@{jm#x87qWYg9}i1?TI4j$h)0rBq7Ukg1kPHz61B}Z1W*sUq4n00mYWoW zm3lk?e}aTw(;2II7}V3ODn=Hy#R}$lk^;V}0KH|ISbH{`9IFACr}Zzbz?e+kgokzF zvW?$b34l@x-6K-AUq$H4HpAbVR5z)W8)Z6@JrN-bDhA%0L~X2<;f|XAbuiSb zW;dD`X!Y@S?Co4v&#vF4`~mEI{CVZCUk2T2sw)F46I5T&>5EFS)R}>}h(yngLeP6U zVw4qjI=PyQt{YA4r-;AjVeifjB>~Knf0x)BMK1+UX-(=ZtT^ttx#nlm;lTKA&|Kpl z2d*4qO~9Vh=(&2Xa)8*(%Y6y3KsTiMk-KQGv4*Ern|NAs#BouE$Epdj=7`0n35z3%Xw7vIdYM!C5KWhU9mQ^6YM0wY6mOA832CBPX=U*_l#1T z=AUm3$5)QaP zgVi@FYwX8S7JO`kCb}3gto9Nw=v!hLsn8joBUBmW@-@Rm>fNt=PDjl2Z>mfa=c?o} zecxaJhfLgk^iSG<`T$m}FBtZ(gO6SlHf>HNV9v$2G={gyx`80zi5Jy+qD6v%zXzpG zhMRMPoiFki8WGF&kp2LOPHeVKM{K-u%WnY2KA z&0_|Wf5Q!x2x@y2<)|1p5%gQ|LS^mGFW!{)Nio;t=NWRI6=AH1Xl2U61{8F9W>xxe zW0c%7{6rp*66kLoXBG0)hfP%@6kuf78kG;sAx_g4VnwcDE`J8RJC@N;jt+{vxHCct zfYgYrEsU_6lGfM9nx^stSCfa0__S#0>dgUg7lh;1+Rg8EMVaUV;Rnw2moMJ?g=TRY zxk4AmKhU*&Eh7KAKAOvl9GFgnrSI3FA~eg6TePNZ$^m?RZ`?H1N{h9fmPDh1PveEw zZDxZzRomD!tHXXxR$jaRBvjU*C4Ui_V|QLgGORX=?CqYnA#m42&3E}gRaI?y4mh1& zE$3^M6PMH&^o@Hyo-_wa8KwLDmNDo7%RS{_&%w>M@&btW{G`LwNzM4w(B~*3&}UxU}vOz}>VAD@Zfsa!1QW>_=#1e;i$B*qMdIH=2!L6>>66_jXXnZqXcW^<7xyul+*;iMMAmc zOUXB(Rg*DjOsoheo?93GqsBaCqE*OQoc2dMj#XU_0wOOOyH0HHiaKC0uJ3Tz)=cbH zfz;+C%yhQ7{ypE&aVvLX)5qWGHM}-yqq}di>onZrn+(RGdZvs&+A1_J@$pgiSyTHo zdjs@|Cful~FT9-^cK>BKGOM%xgj2iPA$yG-?C>t}J2J#d*hkr4V>@paE&~Ll z@-%;S5ytb;3sIXBHH)ZkIdFo@Kf9?Ss3^PC7O#+Xhr!&DCtRP-opRQE4Jv%ut1CEx zwq?#{b7V5%u^6Rp&^l0eGPccO8r|YVo`hd1_N9TFtyzoe&UEChu`ejJQTzQ>m07w>H-2bH`(g#r({P^<9K$W8(KTn@njs z{~|oX>AXZ?nrpsqN4`mH-rZ4>ML)oF2OyCLaEtVDf)+i&n`VluJ~U;J7OUiWB(^-Slz?J+daz&(NGC#%b$k`!w?}>_&K&_zYwQ zb-@V@vbP`}ofa?wDIU3D2wfhPvK#om&7G&I_H+6B88Ra~(t>5EY{_B9=7KW($`i<1cWCQ|d0?-! zWqO{yuB&k0url5bQ&rNNG}v6q<{yi-Dioxrj&~3}FVX&8k4f21#t-OSzLIK@+C8I+ z;6ZFzJ9P{kH#ZRejsl_l%k6kAd$ZD(thC*63S@wP*f36${?31BpbwnO`JFcP5cmqTCMpI2?Vj7FNw(h%ljQEa9^mPCxZ^X&N8*c|z<{1Vx)TT^|oi%9{KB(>| zQ!)p``G}Fxq&wy0uSFcX*P9=zGs>28%3@@|dCjpj)(+PBf8;AXZWX+?N@`gS?hF7j~4T(wS=b`S2I)ikN)ds1hN9=9_mMr-P(6S@?<3IM&RBOuh#d|?CtVk9x}0m9Xr|?MA~%CU@Q;rc zi-g@;k}EKnuJow_-44Z@O+@_F$mYj4fnW7zk_(rSln^FoC(4XM@Ao7w&xf3l?`Uz% zwNP2I&79Pv@(`NrWgzW`4b=eKcQ-zmqw71&<+o>+6DpnJs**1Vlja)H(wzTwNhI0s zV;I>)gviRDLm>8VVg~L8$6Nd)N0zS)8m#5Q#x`p*{W_E9n}c7TJ-`3U4gZc#Oy?JM zyye@UUetfq!P@TP2V9P33gQRnzpM>Ad+km;JZVkEW>P3(KJNUN=%?b<%+CSO#XJR8 z8mpDJLO-_Bukuj@FbGh0U|}@W5z2g{OU`^^;bVf{zA z>p#U}adqG{wUs{2;<6uh`=s2on!vZH17c=(w~AqRAK?;*t7h?$T^C^S)}>ouWi_<4 zv75}$_TnYt9y_`^)EM*Xw>yi=)7#@(%dyH$qaO{LOB)|61iBn&M^02aA7lSLt(kz()OD!annG@X>_`z% z!a_d(;4A*ZyzozQ!oE;x+?PKoYP;30P+or(BAq=< z(wwGU%(Z;5w0G4#_EV+J+jeaM7(A-HuQRiKy_Uz{9yU-F@Yu_QYqk16vzj#>pqQ=d z;h+gHX%hpWSgmonpyF_82~(ixtw-gc@vvz>7QSJ4BPbPgTK?)c?CStUfJtNB`Gz|K zpbcchQu3A#TUV_OKg_8C6!F}#sk2o9$3l3Dn`cC`j1SO^;6?! zUvpx6eLIDj;WMg@)dqmee(aBFYtAx(VEy*<^OxA`!F zd;PWC>`Q1!S9aebTui_xi@oOZV``-3bUXR7MyY$Kafgu${9h`uzoypizH&oIqc|{Q zZrZ?BE+4Ga4NMHjT7AcgSb^{USwB^-L;b}D{gEFW)lD_0y|t3vJI?eE2POqqPM86& zIz3kVxaozf!HphPyZgZ+&!y{i9I7+@XFG{%g_TSAh3l&^2zbDBnqA__M4#429p@8f z_yI|5c1rJVzQ)`CG%JcL3O$)B5*Vebmne^De($dsSI8lZXw=kO zT6yvmaolqYwm;K(5#0mE6vV7_JZ6kNk5~4*HOHraRj4R)LFHz8LFnVrcgsg?jf7U= z^7T-S@6&zdo9WX~_CQGiHG9OAEKZ8tp$0E!lr9y24=}hN@MXCF`5|>Z@}G@Km5eeU z1t`sO6&T2x4AVT}yvMMM2F91CDUYJ4F_kC$nC^n|MN3AW+22UZX9`*feRC4(7%H~k zDld@}lfn#dYB~<6&FB!p{5Taw`U3azoe2gQ%JO=_nLC)dy1AIASvP{hr+r+2Vzj2t zg8l&mV`Xh+S^%Z_25ha`OQ6!=V65z|g{z>s;E5<0ts0x4o8O-}TiJI&!@mJnYxf@L z%{Sm~tvLkU1qbD6jXwo-00(1ZZvDFW58z-;bG!isFmW++v#_yqvoO;$vr;oNQ`5pR zDL9&m8@rj4(1`Q0GPANX|KCT_2ya0%(|mG45t1`0P;fcf;Fu(>U0mHrIM~_$H!dV$ z<>E-I|Be*_Lpr*y3!`WOPqlxfTxi%bI)64dtG6dO$$`m`^kE@4{2(ASn~-Lucz?ZG z9=$(3j$Pw*kHSdOVcRkU2y87BhCqYfMci_u>J6%+9UQ2mALBxC2^#Y=i!;YF7gKCH z4S?nEN}^3u#u#Tfm4mh2!E)u`Ip?AhNlUa5=NUi&c>Tzlpn3gf%@Iyfj93%U94HcF z`f*4j4h1J!qom7kQ>BWInc**G&~H)EV@CU6282UR<^x4@Y5L{jbKa z(}N%ZJer|+!kzIB1J&^dC50m&<&>Qe{lEsnAO%qlKzTuP@P-3nm5m`*F?aJ+`szX8 zhf~nRbe;zmXbmbZP zJ*|d~x73rp1Xh2RQo*_-<}_*`i#vNR=9oSH##$u0lOf9Lj;+}CHF$d=9Q@+S8Ucmp z?-sdcq0pBfMl>~b+6u7}0aoq2L>mF1AW@xNl&-}Zn86N(i1z>z+k<0vS9W{{dHbBv z1IoxG%egaG88wFtL~qCdzvupfDpFjQLBr%|U2v<13EI=v2~qnCrk6H+s=3=$Ah5;? zc&h7&{*4m&HScJSg0;sEE^x~fro0FW+h~<8ZV2z2mWo$N<6pY7Lc1@bjoSdQLe*vW z27;$Nh2By_C4Lt47BIM*(vt8zMjS1zT^*gJqsvWr1DHu^GL7)0b#`2Tjb-)&waNb& zu>FZynj;v8jiHdd!xVQ$7mL}2_K_13gJ8iQ=eMfn^VACVbn(Bv z1Nj-QjfD9P z&?qHVfy!40dlxgUxjV#&US8gV9&J?MG+oM>vA@62SE#hPKd>;(r^R>-$pB37$yL#I?E52S`n;oWTKWneoh-3Q4Cu z6jUAb`%4TT)@N4I3_qH!x^0lOYg@qSe5hkfO`5&wpdAc<$KP@qV9oKvCu?WbCf(-C z1k@qFv{Ij(Xnr#(dIPlN=gmgI%&cOa?GW2KtF0C`zZp@iZsW7eH^#qeC!c$>4U}Y`DPOe%ejMrY8J~|S z8z&RiywPc{br^sTIJp3xSeJWjwwAddR*hrytcuO)($+3VJPz)ipVit+PU_uiIUz6l zYY?fiSRPU>N&`@c6%OgiOP?x3h}?PM%Gh;7fozD6I8G@=*ngi+b-8P1@%L>n*`#+x zD)&+(xl`GrNErZZ9R|~RLb)Z{;$RC4X?E+P8<~Ed9my5JZ}&9Ui!G#-g6w%HHm4Gi zx7pwWy@zO`0^&vXzV(RBh~@SX6HuNDr5c2`GBpbkx#|j=%4`Af;lih*LSIzgA!B*x zyL)-n6~}Mi^*|%*T55@x2vM4MDPy9&%sn+@a@)NGvnK$j51yrWP;k%(sz160a!m02 zhL^_X5%cnL4{yfNQ>dy-a*rXHI-7iU(3A`Ia<|TW3HWn)(GiI2o#WhFL2#l)NqtBCB32yPqm2c!HWKJ$|msIF1^it$hO-ytru=Zrc%LhDjb^7dt2h)c!luFz#? zV3=><{yzbg^H8)KB+Z@T&G>$`(W=++F1NapzSH7lXlPohrN!>3%aKKgdl+uqm9?by^`_)5md-zD4(O|4H=N|wp- zeK^_VIHH~=F&^X{y-I+DAhMoIqeg|2=LQ@e7RVsljntm?Bls9?gp!CgF+U+|q87E9 zVwU`(sdhFWG=SVRHesQgEXjN{=1P4M3axZwSWs2GWHU^z^gJrE?e3q2 z(i%f~@~9r+#i`m+E$^;>*~3QrzDsfb?71WGaS!Bj?ez@;83^fiG_%SEWdi7Q$}mAb zKCaSj4Xwz3keBP**>#J&jvm&HG7}R1O2?%!yO3f%)lA<%Et0Z)ZD9p%NE>eCbi5A&^-_Y63YHf~e+JX%UbBTNy&MMQ&j1u$eWf7b%?-EI zpT%8(RPH!KSn5PU!Ucz+#734tlyFl2{-+ZhD6|%Is^ck%lrQf16aHJai>qWg8BcW# z_98LOyg(`r6q(m0$fpgr&wkB5?%Kq2C)mB;rz+4r-{-I|n4o`~mE zv*JJkUfWl8B$X_Sf)kJ}Z{C$;BzTucD!R>i)QPr-wh$l|0x!WuZBme~Sg=&mItaCE z9O!>l!Qk3%TqJLCEX&N*4W%cqSep;snEdiF`rPla2*NyRe%%holKv7X`enpdp<$(D zHt;xjM69}2Sy9u`k#XM9xMHX~`zl;vx_xi5kT8>|!ZFD>SU7&KSpUyToJ5yjoLO8_f>~6ILsXQ5hntg?M~sD?gV@LkmUb=1o8W#|Ea{1aI@Jz4>^Rr6fro{qP~hR3%MO zl@Ulyq3BkQK61wio65@IaqlyZ<33)rT{^VnMXI@@0O z*I5IA$$xMp3lXnV{>QCsALV{TMHdVKoUP2ufc}@Cwk=sf!4N3ugI|UviU(YvFO>y^ zBj6NkN;bo=8fO{Ms$((4(Zm|Sj@XUnr-?WUj8G=XF-33l#>tV!Z=3iG5v29I_`Cp@ zT_(dZfwE`Sds-l&!11%{V=V~!v#b2psKP-tj`;)Y0jAr`XfYUj0QprNG4C#jn<#cs z9==Z=Hj*eY!LITxq?M-$3l1yBw(Yh~X zJ@3>VLe@V6>#AwjE)eW)O{_{e0;WOCo79nWx)EEaEnj>S_uzx6i1ep*h7dbqw%jbZ zfL{4qGZ#{1{w{)VqrGOdiab2dL9A6cjygn}e57+@zRSSuS&&X6uFD`vt8XjtS%e>T z$T}}jF|sB?ZhfGqA&lH$;rUyl8aZFVw4akwwfIN_q&R`7IKK*+5zw6opnhO1zy268 zimCJ)_K)&!r7C}p&{C@}G2t0W?msfl_64pjII} z`wdrOEdZ)4TQO;S#Np*{wf~!b8{7W}IhxqOxw;vsQQC+SR~7<9$dD>y4}8LuymeDb5~b ziI!MJk%}e8&i?u|W`-m%Y|IR)Aw{clu|)|2dVv1AzkXo!%hlPt4@MV4GHXERv znJTOl3}kV2TYNef7p35wpa1rC@p(3RxG2HH`G*T-&KF-Fmb2^U>0*9=@%z=scORrI zJo5%jn1>f70MpXcvs~X?-!7i&amL~}Z4`uY5(jC6!>eI8*K=IJ`t$qi`R!~{fBk&l zeDP&5n=QUg=XdqT#pCnzVfsfcLG_)-M#gP%jA9-H$|RT*X&Va6+84MkBn zmqlrqRiYmGy%{H?agsUiSNroXu6Z*?MPq;&DK=xcAm$OwIf&*FYwpXHe>trNtQ(vkqalmKOhiwT*61nptAFfMgPE zAv_bhF*pAt784w;kwU~USYh{y5W1Aihf!hDW*A@3wpkQs)82*ulxY^7t+y#MOiU_E zYv2?|$JDU08O zdPyMQYME260EaF#9u<5&LO9^P`lcfG$03?jz?_h-Z8Tzkd#t4oI2S81C}aYYc<|An zj>C8R9eyHvDex%JOqBx3gEoW27kQK^Cb=!5K?l~|5|0MSTrIth6smQ)NCG7~1}T{m z4Revy@oK{FSo~F42vkLA_UF%}{s@kmyRqVf)dz{3hM+!D>cmeZ`(G=1y#F%_Uaq2o z(J0Ea1IIIeZ`+?_HN}AY-qlLw@Of=G1?yGEdV1HG~38>Y~TbF8xNKGH=H#%}B%s%p~WR%2F+Y6@3fSLMNbxS-El18q2o(L6% zugTBP)MagBYWvOrg%3Lgb>L2bjX(q9W^Eg_%VeB1SZkmI1V4yaXg@&>cd= zF|A&IvWQr*k|kwWknmU?7BQ=Am>^w@?ldd9n|-O8ec8R)m+oR;7VUWzH$$GFn2IG( zyX0^-;wVy$;s{)gzpl9Lh}}^Xr@L8MfHx(D3S6c~iZxq{G=gMnP@Os7Z#O8FX|p(u zu^)OG;a~8mookdDm_bK}eowD_)+ig=B4J>ERPZq?QF5#=kTA7L+~g#&8A(VO5_Hg_ zrrUlxsJ2r`Bpr0C>{cGDF&)&WY6E{n6WBU9g$}HyRvXtYHm*6T29%1U(u9Ksj}M^J zdca@j)92~+tp4zy>)CSh)L9TvOmvk5jA9lsPzuHT3TRL4nGt7UkVkFO-ru)9xCnlK z7xzpXK$hC&!O{LyL@D*)QBGAW#$}jEpmo=&uB+rwlnSOO9ALAtkO|S(#Oxy-v;`H2 z2>s{pmz=f+0t4%4;0}y4PZl{ji4>LyYg97E$Dz;a*;DP~%pg2C?&wPUKwAoIh!+w5 zT@UNEysi3wL9{c_ivkh(fE5bVuXRi*UsUd%nU(A!`6&2@1?0V8ZW(GV|IB@<|jB( zg=i7m&n8Jd#@lyko? zV9e10vs?itc~BAjuZvg7Fa-R6N`z#rf=+(GD>hng#$`}sJOLwu9>g%Ju&lVR^h@P9 zfdGTQA}iPIgh)BTum7E2KTL1B=`eJ-e1Y`bq*V9|c`RH)!hog^k5rCZNTv~4be8x4 z8B8hHFn%U`2K?@I@1kx^ipeAAdKdDz*MmUcgNWC%dao_&{#oMz>LFf#gSCK!^FPs9 zW4jTVUy^lD4En*eA1md|7)-7P09mXsYj5z0d}imNQwo8GV^fWNNk%@}+Y+>P)nV$K zHI!CXg_aU9!h=@d;BVK@_nF}6+jRA#+2Y%z386kOmh;=bR08w_Op)d62$;|WFeGF< z1x%@9)5s=pag2tT^1YFNP%98>qud^+zBCg2+)<3$X<7>5%%1U0l;43KT4v*_bWepC zTJcKDu%Jq2O5DeHBEUnI!jEPu2gL!$w3ZesnM^JYloqXyZlyXqvX}}iQ^xF=#%$Rs zgKQXQ3K=XjR)P{%2}*Jr4M|(Y5lPq!;b~HMl8=YFqtdpKfgLD+m!GMP!0AHuVHiXY zZ@oeC*yg=5MAgXM5F3cvJVYgK0HhFIc0d#(T#aFPH(g-z1pAXPGo#&qV0^y6C?&U~_e0@@J~FuMCOrQY2O3SHUSw|koP=L)GFVS{ByHv* zsrC))Kc8LR(Jg<<4@#OHhc=^%a`Cni@4Fmwm0^f$CqoT-E+#r1!j*)}FK3dc6YLFo zFgMr%n;+}J+9#H?GVXwixYeZ*ffF=YgNaJ^nPg{3Pq?>#X^J?nV*|naZ4n05gQ{jK zS2dGu6Q$C28Bn%WH5+(hg|wpLH<1$;**>qpkA$f2eXDjgYf%1n`S>_${?;%h<^PkV zZy{NFpt|=CiPSyvG)s~+AY_z2pbOf$qi%nR#!K))z!6IT{B8R zf-_|Hoq7A^OsXql;>M=fd>`_Uj?RpKLflL4f!jTQ8r}<{ zWs*OCwZrnKY5MeP^7UalU)}s0u?1F+(gF)2yu?tCaA`0&*!7ANQmI3HGU}zl)@mu9 z!z&QVXw;AY)|NrpS3Uk!Jk`3)zP^el$Gcgi=nM1PHIm+|c#?yy%gG|!K_bE{Spuz$ z@9%W*Jk2>cDouj$=#*wXyJ_Z_MqT^gWVv_K6Phq za@Q+yll&dh&s0jUY58oct~07u-E1p_$K6t`n`a%pPr_PMD6?bl)0Tw~@3O=*sdRi4 z)r~r&sMo@TT7P?YTazFnQLWE9HDvkm~sqN>LKw!DM9H*x3WDH)-Y>)6#|4N%l%@2b{oYDLx9jl0dI~* zzs4H{50jxiErvb9-Tjb>QNj;wMpzAh+(9>Uen3SOid$P_74qy~RqydiIMff%pvAFX zHz7}mT}Nr$v|XRcL0VfC>iy6{Jz1$w{s@CcKGe@&G*@l@BDt};*4u22+dB+GeWSKR z*t0qr_6$cgr+X7?7(%S=AP&-5AREZ6%}{3TMq<_+Hv!?9J3Wmt^et`8kmjwLOJPVMNy<>*mozays>Mm2tVUA06la-#0yiT?ss z#gD^}K?7<5RDU;0Ca=g0xsU$=Z-_p;vjPoA4FobZHZ_ysGAMt|8p(3oM)t0+z??!> znVsGj-x7OfDlTWHCeq1q$_0_2g&C5N0Z=ma_49hcMm7P;c2X`K(1ae|z5_qsT>bbD zsS<;PFp+)FQ_sz@^Zdlip*XgcIh@>R{riP zdyfg<<#k@{s`-B(H*c=~eslHdiX<5RNTN9+Q~+L#v@ywYd-eMtI9b8}-Xs_)qmoAl zxlK4{ND2GgCb_=)&(+T-OcH95=|o|J80S4EvvNCMaEDnii{D! z;wWu8pq+hgXfp<=jHJ>5Qltp$(_S5R9{{-gu%0h8lWO)Vt$uo)NBI^Ae68WbK9p4z zxDc3xa5{fGWL1Ru1!W2mp_2un2y^xvAy#>{j0hna;*>;%xWCKi3#CWJP~gK@Oo?F` zCrCqFEeJuTiLXV3A4L!$v_WWjagKUQT5_aGOS$T~{d+8M%v|8CptA7557wypGOvG# z;N}K!x1cW~$OK|kwYaQvp2GzW$8{@EQAUt~PPl*Suvtr$S)EOD29gqxSrFN1IvToC zQgDpt=N^#|xNY6k$^q&FZvkm=@H;kN5RCEcRZ-OuRxwzeBEe+HQ+HVz5^35TR{44j zcXxF}DH>7**Nvp_Q-N*2&xc#p$Yyk?2esD(u4S^6};*Z-{QpX4rJ>`(%n<$!IHiPpg^0t4)8O z=L$1dsOztqdN*`It8X=y5*hTj>f-v_a`Pd^k5Gt9b^%9nEGQJz%T}zQdkQs5Q9acC zbynBD6~QXl63bb&Ntgfg_wKV@x~X$lrQoM4I9T-y4#2ksCjbTDl{Z}bm~1GhS(R?X z=`lU{|5;hxopiJDhfwz56e{Hl_(gvS7(F~&hj9mIKi()Vc zWB~y|A;4TC9S_AC+Ce!oZGp_t6A5U!Y_Cm@r!ArgKAN`RDls{ku_)nWV#a@J80T6- zts9%MqI?g0nObLN2I5d4tV65)E;1uP4Eb8$w*IjxhYF;@$9qsN+}=ey8EEox8%C>Q z4<-xI3stTc-jIb=3-|h$pZ*!kBN|CyGyv_2*gQle=!@y$STP|h9W)w4StX$odqKl_QGHK-PavTvkcxiL6gCyMmT+m;Jn~^96@`dWKh{kcNEfS(W3g z4qY&67N{tiow(rB{+qC>5d-@`ltRrn=RHV5AENv1L*|PBv{TRrDnuz8Q8wrShCrCL zu^I$Xykg0Ief*2UND?|7MpH^4OpKVZQ37l99HQ&{Q3AOnx+HjZOa*^j>1juRaaEuA z!BgB16hTAR?b>GVdrQe?Im(bbQafdMfHXXD*lsgu zp_cyVTN-YM#t)9ZSw76c65 zDAxXd0N@QZd#|My@q3CXGVSqR$Vo|WVf%o zt<1VCwnwQVt*T;~r?nrcZL%?-qocP>+ten*CY7Dj21I|koGOwkHdLJ{$aKuDdxPV% zhSgz(07I*3TB0jpZ{ib}n|?Yp)m_xkM$m6UObm&Aj1rSd{~5$?_wjYNF#Hm7>bc}T z$H;+G4>Xz8OVqwv@^9Vz`#?98aJxk2cGu{>AMh{U5b3{qTTny8;w&udjl*H=D*-1U zJb>Fwo9=(>BEr|A0b4+Z(#_C*9p46n3rlt3GMJk-i!_9f-+p4OC%AKS6Ypgsyvo+; zep7qRxh>)^u1B&Bso!ebCcnxe6b(g6nu}g7c3Wth)RuKXoUa>FS)dd)n7VzR=zqEC z!hM0U3QqOQvNwXK90^`m~2^8bE8eZ*+eT?LwlXpbsjKCcU~$ch$1YZ{34N z&hk23cmC?Rg~PHaZO>QiR(^YF+^%>FdgRcP{TtxQ$Gmbq8YUf@ssr6`T-J5J_f?Cf zrI39Fu6=*#=v4uSchf+~_JJ?qh(+5$0!Y_;T2b*(Mqgt%2|Hj*!2Ys|afiq7@B5AI znC*Yb_Q&?>?Uw~OVAK{9PMfmg@A*Ub8AIi7AIRyQo2-K`U8kc8%t z80lU(jSc3CPJPLwgxety&4KvwYMpY!M?QaK;vBP+B|9U+Of1=336w#Yjc?gw5*)R0 z9Oi03CKZy5k8FH6WYuA=bYIs%gnaOEL8#5-XFsuFfIvk*u{r*rsLc&uUxbvr^o=B*E<)Wq@76XGlYS^X*I6?acTvjEP0qdW@4Xhw z3gORSI53dbHGvke{mdqq_x~VG;+GN60TYv|GARx*3NK7$ZfA68ATc;KGLzvlDt}FL z8#fHS@2}voxvU5h1j&vkGx@07%rw(X>_c0}2ieiIp4w6(%bn!k_kogElJ&*9>+~RU zSBnK7KoET3lCdTjZ;cr8*PPhNAHa&ywMkj3X1AZ=5rNp9@9; zIx&*)QZ^A{P@15{dy}BWv&j)EB7d}#gDOMLTEm3ihlU--!Jn+-33}iOc!x1!0Hgpo z!pQ`W9%B?h&=;UDL0^Ertm8vp4$=tph_(vX@%3K5UJOL_s5yxyV1SmbfZP(?7*GXN8e@(d*EUVk6(oETa{ zfFCnCXaX!qHxFf``~VR(rxsmll# z;v2%OFxjZi#D&@k1#GP%9j?Cc141a!{oKDQ(wfXLL zbUC}4j9YqUo+(YzgoL6b+4i0^}(i{>LuXWVQ=!z3^`uULs!e_TYt6fq!U=C`_X|B-HuIX zso~GnA^JCY%lbH7Uu!q(S~ut9@q;EZ-1%v7BxkT=)tWiwMvvjifwSR z9meL;@5d#PS|#A9AX*odlBO2yAN<<2A*8)7as9zyYuoI!Jd-vm^QYJ*&~_GSbEj*$w0sU_B+C_WfLP>RD0vQ>+AC!g2AdFW=47uV??_}HRiCWP{G#72B6HS zBCBMXTPu~aPD7unWI2b{+B(}fz^lFv0|PH=<0?^yY3E7^#I4u^6Uz>(O-~#U+Bw(B zCW0F(Wf@fnR&kZALqc{`CriF0&Kg;l;ScZYWPcM1KU;^_Axm1~I$6w{NS!EQg>#*I z30teh9#$obJtq1((}-;wsLs9Qd>d_@ZDgfQxlT6aHa-Z3W3Z!=?T+qrinHUu9^|2Y8j=szu zGJm6o+%4J-?k4Gx+)WSS3Mmu6=ojQo!lIWx$r>d=E&@qIFCP0$_SkQ5k4VdYJ2M%5 zz8lWZ#}?eYAHIg2&L%xDMHVBOCPsSf_OxHNYemHY zHyqL$EfPG033X+V3bo2!#Xcg(trN-BOjeowvVLZa6$$SjR^y9;lWZm@1Tr}{Hk08p zD3iY?6o1*IK^tV#Hfv;2B!MxO#+Cp}a&+<9PV(RT@iJF&WZB+rx9N*TjW~zre!fG} zug^|C`&ygK5~U^2&Mq^~1(8-~hD%}u9!;|!M`x$jjEalv@^s9N9m&s6$HK7Dm#fV- zJXx%!JN)|d**BkkEd)2yM{Om&N9bujUE+FkuN(y0PTVy4-AFBuKBA9^IFl@K%RCN0dmN zW59@2k-tTXKTU)fX73!jW&9w6QW7Te$A1`1+d>;fD0{j$sSI*SV;lntl4e>OuO`of zAOc)d$90Gl%VVT`9t5!deXCTEfC|EB9Rt_%Wm&+_6yCos3rD~WH^1zPb*1c%2F4YE zG0RC_G4Z!$@XytH>b%yw>MDE|lkNPr*v6>d&XNI~6L9xjmKf!PL&}z2+X>@U_PcNkJH0onFRLCKWmT`A75Qw+n2a#71m+>8vlP7(<(2~MnHo|r|w zeOp|ui{(}P)`+#ZgMI`b{W;}Jnpkc#jj|Lq z!}bH38&?O`>OA~FSjSj+*x;bH*b=;^!3yE9VEPpXcbaccy ztL*%z1QnF0CiSJ5k+8n*FtbYvrl6?Aq%JcQmO9J~dyE&=;pHL83q!$3OzI?U9WstH znvC;)OZatekw^`kQNXXATf67LXck4^WjC3v%j~ko2<;^VlZ4}?_^w~#*N6Qz1jtd8 zjc2VPp)+Kz_8PyZ00F|pqJK({Ax;&>_i>(V)61bYn=!bcsU4rD(i|q{wK4DOywNt6 za=E)@hjn?GutW~%#T^bYiha6a+z|~a4B8P$qFi+IQ`=iXN+Ok2DePS`w=xf&m?gsM zrmS%5bF#03&<;_6kYnK-I}&?8E7z{32|8L7fXb634AjUs`N4=9PJcDBlWLS;?TCuv zf~&S2bzK_2Pb>w1hJheCi-IoeNoaX;q$%$-E+!dz647_kh7!;gUTRH(i}Iv!RM&+z zy&8pj+RLTtwEzG$PDg@@;gSpEG$r?GiL|R~$>kBMHue!+t4~YSP$KUxmj*U@$QiY& z0dP}*4UR3IShgOL+JA;Pe?Z6H*Y-nF+X{oWwim@sLffwAe-WUS9=;y{v<5YxUZPk| zlNg=kO~FZtqcNd2)M{CEBwbM;tWf)9t1XO>x)El~B}L)d+?1|qE3fZE(oOS-eubHu z`n!a~0s2uzYjzcNDk5W2@qo@KpYt4IZVt&5$dfqNXzOT=Aw+l&t5|)!P_S1|D zv;&T`0T_&Ly`3-S*Tou+&4e7i>XCR;+*i97FYB-^T2kQbvA{FSJNr?+9>FyG7XN=8 zwixcPEoMoXNq>_QiuYd9VOOMdPWYq!wew5$sRHxk+HO<^B^_vRQnw*PClxp=NQVh^ zoKz+P7-8wQ>BokMTnsnoSjxIM7tD4ibvF(myH?)W$4bn?xySs%J!mS4k!IjFQEkF}bM(sMqXp4o69=f(=HA zaW25B-G;lQC#n!6`EW^fg%|$y5o>BQiKBcA=wDFQ51%${638NyaK`@=-KQatzK79M zy*|gvjeq4*lq?ZiKZcLpR+M@y=uN`@J*EwH-q*|;0QHvWX8ZA7VmS*EBIRzflSn9v zaeKKzPZA%iZT_!1(hFGX+YK%PMQSP=Q0X#;2Y7B!gLHgj4IW2~20ZTO4B~O7495ED z{uPRf94IQi4lB=`0PK_YgeRyyWb_=8=eFAo^?v|9?IHWJI$>Srnx^X?cHEtT+stJ82r!u8w~#8BR3eL1PYx3HwP~;q$KF==`h&J z!GC)MTy+QINjts;$fPhuG?mGW*2SmFx zv&!uAy8B?f3Uef{y0i1}Fre6Y%*WfzK71f%0lsA~tGr9FAze#tJC_1d=Naz6;c4r0 z6t~_9{}Z=qy6SRt%$~aL&+F;k#H%nAPk+^zFfJgNyP)ymV6r+8TqtR#(@n@U{!x798AzgkHOeB8TUes;rKBu5WRdca zEXjP%B|1!i{3lnWy<1S6=1@s>2}-`;64Y|F`~>eoJ%=j>NW_Kxw5~$cf~4_`f`4B$ zJDhR%R#E^?!6L@v&26Z}V(9v1%9c{)mDZ%P2eqaN>nly^(dBMA*~ZI#I&S}B5MU$* zn_>}17sX~ii7&1EelbR2zJoZ+4GE9Jad#Mx!$;i7@MDiX;|hrog{G*H{d;o9i%A(Y zr8{!Q4HQ6l)hmn@)*Yjdj)xCgp?{P1he8-l=a&(WhwmOO<8wPJw#jCQB3uq0M!7RD z{>ZtQMIL*3$F6-d({9+;QHp8laO)C))PKE*!Y;~U8Rc80vZqt6Z4Sc*?~kHfNG|rT zk8WIK>U=a`ZnkAHtyl7&xAP)$F?{)fN!yNsA#7_ps3L_|5q30hLyGkAe}Cgfk04V% zeC!|zr|gKO)UjvZeE7H&c@rhj9S7Owp51_tAqnqYZWw?&<~eX@@9c%Qw*}*IU#g$g zAF-be6;>b>Lo~-e+FC(fl%Td&d*@A&g`cjA`Er}eGw94YU{SS=d{!^KDXVnqy2SXf zxLEBXJG0gMZq2Nsu_x}NwST;SfF`nNiR`m%%&KmM<+OP&!f+fuxN_5y8wx({+*|XEJ7Nc+Rm*au^`#PZ;yr`Nh=#ZdXUlx`CHVD5r>b0m9lHA`M$_Xk7GnZM9%^nNy<%mVfKCVzYeck+y^!jl;k zd0nwOU))qYz;W7F_#G;%>0hL8VzmAVW4D~f6`grj%hVC5+w?wo2AUJopq|07w)yeL zpw2H|rQ~yEtZqB6(q!s`q;grV!+)Zbte799NC5A{~5@ZG_W% z%cl-HdV^vGgGRUqG=Fi*Mj>?6=pQL(cE{BX^81%}mz!h4 z#iflHEn<`Zp*vz>b6{uJLXE{u6caFs8Zf^J|RJy5L4D=v6&&Ug$%{f za^!~l-0W`u#GD*kt$zdgKe!;1QDqYtF*hJEAa7!73OqatFHB`_XLM*FGB-3fli@Nb zf7M!9Z{tQ1e)q57qYPM`zK;Mwkj#PX0K3R$49r6&Fl39iiIqi-NX=OL>$mzMn^Nnt zJ>K0XkyNw0s;la&uZsQa<=GGKr78>(lGEbywxEO|!FZu4M~cCtY4PXi^4zG=v`Q!PRDKdIfH?4p2P)}Fz?_ZZ6e|~t+7))m*m3BHqkW#w9ex7+fpH=g6vb>r# ze(+#zNfGBf4z3q%RnOhHvv-$gU(N{pg9}m+O^~1zL?nnPS=>CF{rMLzrts&70wZNq z@y!i=C@9y+2m#l#;^Wyr&wky~muQ7Vp|C-crrMUvhx0L^0*^kn%W8h-^{l4lf4r?e zW5UZN>;VyG^mfut{GaW5QHF%c@$I(>)4cj<6z|3UH(MD*&$~3K)qnOePIQ zQcADFI%5ik5s}^Q-hl0{%E!g>Y7KfSAxCc}%`b1Oj9CbXsX2>p+Ly|v0o#Dug2>Uj z48|PDH6~0U%`{vPP$3BRDI*vce_(bq5bRS%49$=hohwc2mGeh|sopICMvRgmff#HJ zOf8W#u&$K=3D9p$VS|VtwJdLQTWIG|MKaDwyT0m%4 zAjV|@^OLZ#x!{9I6sVPqO00fWI{)5lcLVbC)9r3x*^OQQl+giZC+v_8e~f}{)V30z zuF9N`Xz|k8ytRhA{uOJ1FqY#F>Mh&4!}4tJ!Rq%9-FL1SpD(lZIs#OGenl(yeOuCnFj| zN_5EwXD4AqCzF7ye^5q8Kjjb;@B#!v7}A~}PKC#3A=7!0XLL>tAf6;u;{k_Te+`|KWFKA$+ zK+3&z@300if*M|M33Sew!)|t*pAqk9bl_;4iI_nMC!=n_t=i?)W6mwXbFkXVUW@`a zp4Yo~NN~jE=_XF$$)zqx#)wCkeb)n`c`}>T-(1x2fX{4z&wR96EXt+7 z3|PuW@J@Voe{CbI@sB-3a}UXU)U2){9Kv6>;hDpA8@$rQ;N@xXvKUJ|h7TV=HcR4; zyFhm#9JCsc@cqHBeee^mT<}u^B!FjwUx(m-m&qJ29sW$&@`k-k_%jKWBi64Q{!9oY zggQC=2O$mdjI^c&Fd;+)O@ey3rX5EhE*PgS5H}VTe~NdDN|K(AP47rFv5B*K$y*f)_o&hzZlw)y}D>NEcBc%tEcL+ zRd@h-k!DzTe8`rjb~{sXuOBb65<@wqNJiujPZc@u#l#lN^eGsE=FK8$) zez&nSe`)VMqkQ9Zm{jw&Ib3C=@FdB|_#a^J4#*`9zyr^ET!kACQg9LQ-G_fVeBtGR ztD8g~_aJicu!1F-49YZ0M`J&LD9afgu!{ifFb=AaWp$ISNtqTd)8c_sz}D|`il1}s zGz3$n4&m7!$OIb9n;F3E)Zc?TwU=wMTu#@-N2GDoI&zMr$iwy)$bViE~?%U^yiZ`yj)hY>IArfd(wxh>gc88zy7}+3RW4QAf0govqI|2|-cTYbw=Z(ghK%X@$gAuORGWP> zSQ)y#Tx9hCWe;pNb0iSQdf5lPfk+i5L_Iwm_3Tj8%RxzXoo$PNHasnr zaj{jlor^@s2eiYO%zC!A!7@TnAr5GP0#Lq>eZwTe=%%} zh&E)Iz9KaH0L+Bm>`rR0C4>0W|^-Pf<< z2o8+|=Q;;vKxru*K=Aj>@`GM;KD}u}PF8G{SImA5ekH|(Yf22c8|}H}fUS{@&g0)sV*EZH`si?Il`8)7#6CUF_xl+^X3D(rl05=47Qd>m;&v zUEmD>(1fPaI-j&+e+8dBT37>XN&Q4w`9RcFR#ak7JPvl&2bC4e^-}Fc+Do5t9z-#o{H!9oncfoiA*P5kc3!gtSj456CGvz1T&_6ZP3O>p>R7CwHar!EF3!nzY0 zgO8u-@U|Cfh^@mzh)sVAk?8ZW5ZZkKg-2AxFQAHyek+&d#m1*O8{t$?fKCG2L?I^z zmL_7t`VZ%Hu@;k2WfK84kr5LEGB`Gq;4&$H&01M+yw3|gWsB9iD4NqhY7Q+@DM>$08fz<@}1H=A{Q^;LDV-(6k&^=GLj1_{aO z(^iJ}}S22G2}@5$BFs3g5vWz!i|CNXcOGp0!LX)0urR!iSHFE(YhP4i8E zRr-eFzRIC(`p4DBi=VD8zFv?ChCebPN+E0%yn`U3E!waqtoUaEYNZL0hWCOq4M z8j_OaLt3T2vwFG*9T^cO`PY=e6kqFqe48x}sDL@Vos3oBMjuuI9_g!~kRfs+4MkE) zufj+BQm3m#(r{x3azvGw%qSuj7h|`ob-ly-&}ueh7T;LDH6iU z=Y}qd8XSEY#);lI#*hYYg>j!hO^HeV{Yzv*VUW`8z)j(Y3{;*`!jRBvG9v_k84+~; z7BRHJNEkYiN+Zd}b{63H#?BIf+lE#iScOuUL4i3nK#UCRvWnWpXhiwQF4LJHQU#qr zcqS0X!fQc-7GJ>QF_kfbxPo8IOi$gh?-XKEH!ltH)z6b}EC68!QEII5ks#(U&g2kh zbsT33$8lDFPdL-k1e^&!w2t9_j37+G2=I1_$swQ#MD;xMp$2vzBdvZNqyYs<>5&$&@jfB~2V;*UcprN|43qNA_cOR3c>P0M0Ni0Mi16Wc zL=XUXHWcA5PHnK%SI2Kf}oLqKxUMh<~@7gI_gCFF^JxB~;|W3VG! z4`6o}gPn01euTSciMMNWNTiT@9qizx?zv@z;2<#71nk{VHjciJ;h!LhMt5ONbfESQN2_K9&*SXpIbr zDu8Z;=0_N7w}k4fK@3NK1n?pl2i(y8CINgI5Dd~o1BC`%)*2B5U`Vx09|0JU3$vk$ zoxKks3^FL=HZO7dGT#P8c3oRPSCLrwYg^y+bL}!F3U)DzBM7tA>tTF>C&bzC;)oMH z5UIP$eFZ)-`niSIPmviVV1ga3ynvVZu)sf3Y?4OnIxWx-0;bkQm$$A?=uS zv+$;<@9(`;$ca|L49YzAI##KpR)K)x;zX;^SG7v9sS0m^O|hA+@=cZo#8laKoo~{W z@9p*seQ#I8lu@41z=lFaYL_E5U=~%%ZXWb&z`f?-9cz4x%mgbWPJ8BwPeNHsQCE>k zAZ>_aHU^P@-4<7f%ebiRB==EK2^4N;yajp40fh-}2_6<$&93l^7>e$=$1{{1;5u5) z5WCLw6cysaanr6O6zU|y{x6=RM{Fvg_*BE_aGTN1UinQ?Zx-QxKW7-@V2}6imfGEW zYUvx+kXp(!w@U|3q8tni5zPceO0q#5ja9Q{UeBF>mJ_W*?eZ5&q27ML@vTukaMlPm zoYP2DkHM?OK$?JHyAjA;VP+xBUMVHT-tS*B}@!gBE$6*GR`ZkS;7Kj!P&em2q|w1Lfd)>0tC{yel5h_MJ%q6f{A(n z_+OSjP?X3)J!sW$;^I`J0Jk&pvao3VS4VAPkW_vDy`)Ay!y+Nu4RI1PQ}(q^S9$g1 zJ3>Z`php7IyTw^#OI=`!IM{+=z^tKXZmAD{V+N*x;9#)8)kYmoJHukqm1huh+L+Ta zAhGq;?%w$*gc;H2r@%{VQk_6)eV@%|9yMGLSe1^xPgMCswtAWp#v2L(T9K4LBWu2o zh!1yC9TR`Io;XzA(eJsu>!tEozJz5_2l=iDj969?sMg2<$TJM#FD5VxBACAf@eFc* zJpuestq{iMJeXO?Kw)Y5;WWtWlOX>L%vf*V7pteLxX1A{3Ih`%iQA|u=J(fOVueY6@;84;=joy-uiH+m{2rtd0ZEZ}bp|}IlfPF% zB7iQ~r}QGFs~~=>2}u^2Jvp<<{mCBJbX#owurgoQtJL;{>IM7VzyZVf{Sv9dV{lWK z>0Rb;^Nqh&%gk>&{rdisZz+q_1B4AB#L6t0NIqxbp~@djvbThc<_;67Bz;JK^Hn!6 z98Gdl$>isH3j??7Vw>5`E)A7zmc_OuH7sa4#%axs-0wAjtDaZU?=%on?Ni&x%rl#^ zESU{$HF7Ij$392UK?xI>$131%9+znqj$>IJ{jEFwv})Fy^K=vVCu<%Kk38hzT+|}p zLg5maY(CG*5=Fx&2s4Nt8KUQZvv=VPESUVoUw-XQh#d(jDHFL0vyC@T{_3LeP3&VZCx{O`5A(xJoKYKu_F}ySswTl>w*OEZ zGL1-=Gmzc?GXC6JahC;GftZiEJ73q=GK8b;g|;$Ofeff$@X>*)&Is0jaogbEy37_0 zI-?4`rCHBbxhOW)fw zUes`wq49X7#O+y|_G^1th+m6OBu zIzn{Mb!=kWJ2qibCRfgXCvIG4e*5$`wEFOZmVDzIy0cC8L=NHpYZs(P+_J{oslcEQ z&{gse_@y?wrIF?l)dGEj(fn-+iA4+##GGF|78L(vtl6-WC>W7DP zRcAl$Th1D!MGxIjLydV>@W9UuP}bwlp``W$uiBB+{v04&U{l?HeQ^l;QRA8I@rf2k zJ+5^xh*7OQrb)X`^_DiR>^DINA6Cq+Zc5*h`pY)E&9<4(|M0KRPB6@Ivp29Xy9VA% z*li%UIP_6~htL1BsO&gnX~HD|xGRfwXzQ?P0+YIdSu?I7YZCGU+}wmth*p1qcH#d| zZ>x5!WmSI!p)G2EhBI%Ax`M*@P4u%LL83bv6hY%mP;~@&_RviSZ9pE!3Ubdn&?MJD z$gvX4C1A5Em<}9h^2x;q9EWFkczhjLs;JY z7iOPY2a{1{6Bsr#ATS_rVrmLJJPI#NWo~D5Xdp2)G&YmrGAVyp+iu%N5PkPo@GTM$ zZFly*c}tuWsEeR!;y%TJK})nmK(~-oYUk^FNG^3nDUfdkCM;5>%OtW#R;hfH&8z%| zlgbKMVg&Wxrd8U0tR9!JQfO2tNPN$RKtu{z82I>2$4wUAlwLLwNNtP%qyD=EI!Nj!`(x>T}s^JjWG3g=&HHK zeg$DBJus_gbY%m{&g17=)YAmMUnH$h1h7Mo5XYJNnLSAocAu%^7Y$1 z7BGM0nUK_}UvJCG5=9Z^#%TSN2?`k1QNB&XNsNXbeo=`g#R%bZgoll_$7!etC)E|m z9-|>KTYFD6d0>ZzlP6LJ>bX3X03G90haCuZf{Mt02&e%X6!ARYc9ukVc&;Ufe&kHn zg?TIa9WU$lL|HH6bsd3+E~>8UyOvz7<#&I}x?tqbF6-|iCmO+wJXzNb({7K|XLUIw z!|rk%cP#O`mdGyr*JzC6U5;YL{Sr7VG;GrEd0?1bZcO4}2qj}JUpe`OV8okgr3qmz zpEnK&1e=l`-3it`qVP3Zn)<8=q17(>3)QH0WT2WMxH3UHS4;7B0oJe|desSTJc)-G8ah$=d3yx3S) zZ+_W6uF7oGKHV>hZbBUe28^?LR-}Km(Ls8Y-KVQ*^(xi{U>xR~BK~4AT;4WUzKHcJ zHkiB<`a9fAB*|aJa(~}^0qs#DD^N`*8c291>5Afk%=8`S+4 zD6+T@e4T_BEq&^0MoKpYZfk$OxZzy??EHIzQu%B-&4+mv0{#)XA|Hmos$YN-r@;C1(cxM+>RhK>GcBrg^lO>2#dk6=^=)18<*dvhCo* zG2f$9lUhF;9N)CPA$x8J_itWJHi$(jhlw}BxaHaKNb6K@nHEU>RaSqLF;KVxA=Wl8 zqo6po4$uRto|BEZ^4)|ZeETN|<{Q)XuB`dO>jA{Olkbq<)nUzeJsRb;8tD}9lT^Kz zyMMg4>K2QjcvW{m;VlJG5mp&i6;>Tq6IL5m7gpacX;+1ahY#s;*>Pc#6w7?ew-u;et+&%o)A55LE_iV6=Q{`d{`TUV zA49&15DRIrx?QgV#t^1_#eIQ%!B@B0>YaCc6>%@QE9BL6z#|U_-(Fo4j=h_@_#_+i zu->Y?uG*{jw?AL}?e^m11%F=o@DH!T5Mf^vq=*r`O3RCP@BLKtUC?K0V^`qDv-Pz1K_x8;@L`FEfB4w{&tAUa4g2$6_}ZLb`3C^*K*nre3P z9CX%6(K-ncjED&OeSaVucF?*Gq5xbW+&4%D_KQofW^p!KED8J-w)k(+VF)o#0=HBD zUx{C##CoT;I~8Yn^A#HO5%bBw=G`tYGAElM3h}THLO?Out^w$CJ2`_eXPk}_`7ds)i(SAVA(DH4K>zN5@0_;s== zK#Yg|p1(NA2*k$?7+CZvR8=2Jl;G6cRr$JZN_b4Mw`uZBS6ha?YFFNM)t35Ry*59$ zqnPlt6Z1P*GvXzwYRywsZ=||6Z({EuSNG<*tTMYHFQwBNIPyoQy>$o@BF2VDS~qp6 z_h|oQh+#hW&wnnsk;|R2fQStD@@g+xJh9#UY+aZ8v+KqkyG#sTYK(hrI27PA;OO%c zjol9(jDaozCz!sQ)jNPkE*GP0>J9JSyRrvE)F1R*)z#<$8XbTKOd*!VU>1Uz5VPSX zHS($QaaZRi@IRQ}EZQewVK;yaw9ncmz+-Uf-Ephr_J29``2Qiz^x$+^8{mg3Y0dgh zst4KUuGXD2oSBO;jsy?RlDQb=2!|FIz6NBs0XXP%={+>q=4D($aM#&aSCCmWH)9_HWqjQoD;{uw(;qgTi$i$nfU0>QHLm-U`zNC;C(k1w4 zvT?^S9Dgq0$t00qlYmi=g6%P+&)=>HhfKVY*S}oh$lEEE*cPKw$a+gh+ z-EY7Bf?tieBAEUVOn#u#AE-0_ETgkJ^+d{rNL&&UA3n*UPx+wgD$b$rc*$Ah=(DtK z<4h{ZXCP9uOV#wzw#<3{$ zfPuW+*-|xNw@Dcq+(WaO4AYY*u>xQ_Abe3!RTnzXxr2pu4n8Zzz#brF4L6O@bj6^V z0DpC8)kg>mydsDa)~nz52g;L;2#>}LT}LxeF#xOysaDn7?ND9QMvLv9dAJebp3L&& zA5G%C`d^k=IAzwOfiufY&nGiIyPf4{7372<4^E6`rEVCY8$*oygsuq8l|8IKn zl44VX#_vlf)AraI(@=Nf?S0b9Q&ijm!`s*9?2d{X0d5-}4v~ORCS3aHuS0FAYKqLZiLB?VaF^Ng!{mBI}pnu^C zhOIxC_D*WAj+pImVexU7WLoX1`E%RU&`g!3iB5RX_IDPrPPz#QEYiBlWYvzF6p)ac zN8p8e0QV`h05{T}pb|4g*i*)MJwlES{6T>oRMD8_NS6#E9(v47jM!nQF+mu{Ir|NJ z7B~4TDTGzL-)|^DgVX~rhnc@z+1w>xGpjQ1sF8oE$BuJxAzeIU-}L|S*u z-n@SE4{N@yOuK8o^aK_jlBSysH0l&CrrMz#v{z(i)lqz9hObjq!B6_c$tJVhHhJ0k zC#*juO|I`(+wOfjD-}!co8$!xUE4=8CO1J+r%^Q5K(a80bEl?JOYu5yT8&ChQI}=i zj7ypxdVG?5-l%N}hwPR1A%AV18C+mCPd zLlgm8we!({kM}j}9Kcft#GHLK6nZ*ro^x=`LOxbK_)B!A(NCAA0zN_GmDhoz8G+_s zJU1PH+8&KlixTj&iZwa{meLO(yo;)ckbZkIC;)#5iFOPnoihW*x_{Ba{9fY8S+1i9 z@<(a&9!d{TugC#mB#q7ddATj1R#d7}E^?1AIHDn&7t^EwKp6w2mvlT#cs}wOEGgq2 zygWhyZI0^}>cFeM6DZ`Tq_SbQu5GD2`D&6CL_@pngMntBt!+7hVP+4WC)%2neO80k$3TAFTH5? z_VnZk7$P))q!9JTRJ!acDS3_J6xC*JDw^@XzksoP!_% z+Qmx6I&~H=xzeJGS6Wb%*`Zr4oy|zVZ8sNqp!mDG&6Tzp!zR@--st6J?5aXmxSkCD+vz)kU{w2aO&{PqMR{`KRY=^RXMlyF%uvE4?F%r$Yb!*pV>`C9 z+wHIKv7PKTS;YjNEKA4wzH|GIUo0k1Un`9)mP#uw>V+qF;E!`?t=So@-N^(skS6L5$rjSVpeCP|uPWfLGA3qyf1Loub; zN;#O{CLI@Tf1}(Nf4gj0wYIB9*$c7iBK^lI!IT-!&-JqS6Fi~T}B85m?8%>qDyccFXkM%jLTA)h1MJUCqn;a{H-Aj;Z8W3AN9t8qQX`JP6If zz9#?%ry;;iLZK)H=MyQ$I;sIgc>z>hHB&p*r{@67Ts zNCwSKe@7t8W?P+eQxbj*xvj4L`2E!!92M*vjuJkGx~;NZ;et)sGd8EV@1M^*T*inx zmrrZ4(&y5-t;(c13&`n7$y`mTjh^@MwOWoKYIC-NvSf&CxC-?tvZ<=kHg1^#2h4t3COmzqwynMVECAhK`bb=avut^ zueGy+8Vf~Obmf|~_C383cASAYiBXLWu{$1P3@n7{pH%EswkVemK@P-G38*gfpo%dU ze~Lv}S$t^+mrlPvf{ca0mb2qt*!a3G>i`z0zkcZQ#_fye&nbl_b#;@jcdm8?c&bBK zT42UbhHq7uf4MYNxO?j#1)~sd_)Q9;K}54%x?H;^qz|-91A7p&+U0)Zi=@5_;aC{1 zP)SEHpb0nbAHTW_xn(gU{9?Dl^}lIGLw*L6tmd!zA}@IX&0BRB>@ou zIF}Ke0Tu%>I5wA1Udp7_RfRU4nfq{#W`Fp|n?FSIDba8h1_O%75csiJW0vG}RU;q@H?9H7F zZNKfp_70v-mgW{N{~iDsIs**t0Iqfpu0}SN&K9O70C#&QYk-mG{|}I)oiQB^K-kdM z$jQ>g+>{0&D@gZ^Bxqv;_!r3;;AHA->f~l>LiaC$otdSHshx|Zq0Kk83BbY0-oeSz z)Wy)r6X0V1AGqIt2UO{l=>X#LYNASVvZ8V-03}gn6(vbw6;Tm@lBBqVit@LQiiM>! zz}eo+#of@!6yWlmnVF%n=|9jWuEs8aZ{zpU?VI*HeoGgN|A|2dP<1w?`9?Bvb+EBC z{dnbU2rL(b(y|e2#>UYjA7N!7kdpA=jJKOIB{(*IWb~Umx{bu+M{5we(Crjgh zPC9=BeOJ!e)CFK>@AS=QY4`8hZ)8(DXH$Toxs$2szYzZv;M*uBs03hTqGMuWr)A^> zP#9AJD44##vWA{C-+ka`@fq2C*ZDiXe^CGL)_-N`{7(b`d$WIy zBJv{tqC2~PetZ4P`HjT%zqr^LzJ>9ff{EpSodQr8ezP*Ne*Xx5_r&I3at_LWi2kP+ zJLNahfAgdJr@1aphQ==TPV}~hcCOz|aQQBs(?6B^554>o1tTj!%+kr(1)%(GFm?G4 z4FMRK7+IL;{+njMaSXo;ZEor8V(RqW%x^LiQ(MD-Z$*Bm`ya|-Wc=>lcWaEk-R+?1 z|IxXmotZs=^S`#g8~wjc-wpk*yqM@1{uw9AZwf;bdpjFXfQhLYG`*a?%Xi}d6#pM* zQ$6eyfgrE{dmc!*{Ct8Z=S}29f5&-q`$0|GQD@_^zZ?J$z(; z^oRJ!1Xc~dg;o>OZ`#An-R99Bw+W~4A*?`$F4*FIFwWM=DTKlfJ6K{E9I4M+3gH1y z^ziM?7>6Zd@%1YL6!Y$r{R4aKd*H?>X?BWYgahuRW%|3SOZC~(dWlZxirsi>lanC} zuelJ^yMCx|ZH5!8h>-b{SM_k#VJ?+_^&3&RiP3|)F`Y&I^Z~^@Do9x*Yt8gfnTdaY zY=o1&FIIrpd6<0OSSPIgv1;R>J}n<;4?YPr{A6xEeFNk{B+Pu)BNy|gPn$+VZR!#A z-;HDSV>kK65BC_~FFQWsxnY}PQj8|nl@1H+nu!O_cxZHB?R7;bZF!&2Iber>O?cc! z;YQa5)bbbZWnjb01P^4c+QI047{*BA#!@f9-HMEc^M-BKgk=gES_O&08xFw5%e&AW z@Bb`I$G8Hs^IDw{tFl?fz{w=Vvqf&&%CsBav9z*w=TT+`2? z_oG&$qHi@zHWDWmv$}u`5x#L&G6Aw#vnyW7zLB**{-^V03MQT+4h6IE6q!gjGmILS zl47I9+~4$Um(IWZe#ru{!Uw}@n1%d-cZi{mOzvH{QOlg2r@^(V*gp^Y;Mnvl7}7b0 zv(W?c306Ys&P6_S&aOazy#pA5xaE@nqWX3tB3%`&?xC!2mxQM^jdx4O-#=0h=wCOv z*ial>Nz)0U56D4X@DrPJ7D2{Rt|7FLe$>d4HTsy@zzsSz9xSc*6F-K1dJEX;6Tp|i zJ12XSC-UhtPeCL2=%JU&h8DDy^1!h&=FphSK-7--6_z&RK8})qs+wdzYke94qnh_; z;9-Mxe>Fpd2nV29{b@*u5rvf~@|kPOB9Att3VFx@eZ4eO_KXzt)F#C?|EqraL(8Rw ziyrG*KJa%1!+<6?c5Fr4_JZkzsL5o4l7FtjrL;9)zegQ>-yj7V;&CgLp3bq-Yy~9! zfDL$?W2QIHjxpAMvhWy&fG>t-V|sMI%3VguDMG9$VUa# zdTgSUJwJwSRi5)v?wtu$ZF7m1P6(yvnu1t{LcvIrub-Z0Uuf`dr^R2cKdm-ANuluk zj(xkj3FX4$vWR7&Su^9Id!;S%SDcd3_-TmF6I*W=bDr~mWFjf##n_zY2GdZ5gsv8p z-sM|Ouj$KZHEhGSe;)Un-b}7awfXYbShkP)?qLWZ9}ot2H6H4PlJ3`LMOSTR@(P&o zy0RVUpVOu@&+nJ59wiOczbN4+hSMcP=(|uT?21?k+(BUfMR3WJ_98CnLNOD#$@FI* z4MV_x?y=8*d=pA;{SO(4!>r5~{EF6<_fkk^KItGP8lljT@+xI3k>>{zX}_hECUD|{ zT!3FT)Sm3mX%H<#%$=T>(9PyM2^$X;x8q&>WuF&H`uK7~H-#wA-Ypk38N^b$yRmSi zABzwbpxWEuP7GVo_&qb0uq7)wb6+Q`s6J*}UJQ7D!x&u3U4HV|{u4m&hOHoWqt1qP zW;NW_<_GBJbl9sO?Yn#XqtX_Cr4myeZWGEeX*WHuxOo#l@2@sMrphYmlgp(@;IgRm zsxBvDK@7gGCLVhQrkV!+?AKnE9{ug;A3T(w#uTffPRRMmbSIe-gB5nRJe56<*5?m1Z~x@;bR^lq?Q}MTdAoie zH7=UJs_ZGsrW9pR+`&XQxcpV)WC5;8dEO>h*C00<03}>w8`<<$&1iCg;x@P zWaeWCRHH4Ddc%qq+$w{n4q7c)uW6#Op}O1n(56So<}apMYg~9lSqKZY0%Ta^(|7OD z!u2Vb$5323+A>~BdBhdaqD_$|A3}ULYirnH-Z@_bLZ?qQw`Id*&B-}QG?h_#`J{4A z$K|`q=(3S55f6=vf37{yZqL_UMU&KjpU{=uGliyp*doXxfcO?&pwMV%fbe5WNBvO1 zMR73j+TRb_PY<9pBHq9DDkNy+?sUt^gG9IDxY+Wm8xT(L6GH|3s6&d*3Crv4cj%C3 zuxq&TP*5bdP@^z7&N0hV2Z7d=8ks}&?Szx`*_5J^AT@G1OC0&Zno~)4g9S%_^nGs}ce-hmd|F{(Wad*4^d z6(l;0#dY@>>^a)4@%}xM(&PSrIA16UDE-B`BOiHfgk;9!glJ2hj}xa7jEM0{DTuIQ z8zcWcYF}yhx&0O(gBG~Pu-xON03qvd!thjJAm~Z;g z)6Bbe(fLY|$5T5vDdVacl(DWUDay@qLU6d-FY_f?^P}jXeR2IT=i)hkGKQr}`%pww zI%o3dE?MCoIWWsn5)VBxxUkuWiWNTdfaT3SDt9;x{vm(coF+RE;+p7*J@nKA!Od^oYq=MnL=t(q|^C4X7ehrhvQozn#=H%bJx+e zj=|N76!k>mQXCAZ_nLEmdQpBBYfW4EPr9rD+k^O2{BcRd6#Kb|iQu#z3kbwxrd&vc zkLm+zz?b>yn@Ku|2z#~xwRCRXEReCtGa;>IR^)dJub)m1$7OqKis6XaQ@rBW5g^cF zoqt^2m|!PEYu#ViY>nG)fdxP75Xp+W#Ry68#^b?v} zhlGSBhD)pd?2<=Hhs*5*N^!R`*6o6n_~C_um2G2*u{v(-Ixt!6j_`}61^uM+;RF97 z%UJmG?|j1qND4-sV=gJLP5of9U`m(y8Kqbkce>G>Yh8+eafnwT>PBhtyET>d6`fCh zG$|Ec2BC*Jdd+En=GscPz8F_Mms=$maJ)3UT@u~h^R>`YB(R(iR#Au6M0U!Rc%O|c z#`qHcOkD@p#K2(fKSl$0^B3R=#xm#WGEg7il}u037g+&Wh*@Gk(O*WoA&cY2736&| zMFn5TL8ou2LU${^pu$R#7T$H4WP5Cddh0q{-{oi5X;^xHl(Z51>o+K_PEV^EQxQK9 z-&lebpA!Mz8E!#h0$zjPbOAR8;(%1fLyfZ2)*xNA;3KN~!w3~}7Z7;(6fvnLwCQOV zDyBX<3k;dL*9_#4SH0XT zH>b5QZQMwIk|S#DUo!dA;UNqcp@4>^hX#>aN`y61Ca4CXtzH5T%b7@;j5*nyuXgEIBWn^2I_FKeKpl8k_wH32}MDfbU@%}EE#m0D?xf9(^Yff0A zbeuoY2AJnS(Ee`u1Nh*eeyL)I;>vp@B$x8u9AFj;lZR>3CFIG8_bgM{Wd(Q70Eugm zx;_JP3sDzfp%rJU5?~1UVNB>`$n_IkpyrLPEER49ltT!DFw@=vfeK3+cv)9!)4$Uf zqJrLk_4Wz`tS2<<>mGbEu86gKXsz?>6A^#CyT2LDP%)ncM5iX{Qj^R->e0a_;DJ}5 zC>_1j$K~a!=hb(6s%DgfHX1EZ);eHMTyLR_n%sw5LV*L@WjEei}wd>osIhFUu*$=#J2)xT2t>R`y-j%x_xle1m+QodF z<0$YLc~z;4dGB7h!OCzk{_H3^U!8R8w>g|$=d2Jzmw{|Ajrq}31n02#kbR+hU4=A% z?nag5^A3VbjG{prnP^ccx7sc`f{K1~K$u%o5`+C{#7$&^^%TfLHz%kpy?lqhj2g7} zgWY5yv+7HKfTrjYy}Z{D%$KP0Sv`)ROKz{y%VzG+e-n>@J<8IH)+6NslNLi19h*No zLNc6%LygvWNN^cV3H0fDr}Bv6g0-K2jUZ4omwSEK4{c$iZQmW1xm)FsFTNNXcB8T8 zYWs!Yb!xdz8Je0-T~o$UdkdtzcIxXK;|s3D{{;ti-fUJU+-n)h&Ly!h& zI1ElQ)w;*Uyy1jb(p26vLo^ql)#(Hj_#TkL&xCAE-?sFc)PTpQelXh2KZ$OC&W`>T zelR2>3hW+M)1&0%5P>76b(w41Q8>&T?szTNg^;6mNB_jcU28JEASb6DKZ1AL%qO`% zZ;ws=iYDB}FNrV7`!W_<8%`u6UR}3NgNf*9aT)dF|~%e= zY`|%+YY@V_xYTT)4Ztf9>)Ni+?tmj`6hg^AJ>J{`(SPBBnYEi+J|e_uJ&=6k4HQX_ z&Z}OLs}dhuJQqbfqafIQm^EjX0G*5Jps>Y`qt-ydiblIuqx+#*be;o$Wi6F)$~T?1za8O*-3#L9+MO@uSr`&+IW_=qZS;tV9r)=k3t)cwC4a zO@FLiMd36u zw{!mYUQ>!r6DCe1plvE>A-4Gjiz+ex0t4u)ZbQk`5w&Kbf{zE8%(}p-4D1 zLs)Z1n~~(5$T9PjpVVTeEx{od_O?9gaS?uE*$SSy!L*7iI$v%53BmV^$CSdX?vXoC5e_5Ldxf11F= z5CI}`dG$Gb7R{S6TW&K=n;$$)=+f>7#$_!qaI{$Y9o5~#-orGNerC~37iO&p} z7TS`IDV_@W^3c1M6zBInL4M`lm@Ls9dSPDbL+70Re5xaVVbKmS6&0O?GR_#{_CT38 zPe8M5O?JgeAuCz)a_WKBK;4aA)%U@SL>NrbF74)L`uqp&*MFI}*Mm^xg+Hj?5-m5w z0-{@cQAO!35N|@M7Fwws4B`8q@-TAXCh)KO1Ki?^htRQ`a=hD4XS|WsZ0>xqiZO72 zyulGJX_JY6JenL78qQRYe$rGCTX!Z?Mf6h zxoubZZ34XC5!#Yir=7K)PoD*=!8DP%ap?-PWDc~dGapi6;il=-okBtuG>xM@@%>>N@YFAkl5NsFH*5c`haKvTT%pZ!R0WCW?J z5@bdrg)ez=_OYAx3dFVm0$#IyY(V`wVN=(|D#_tYNCaWVEDNvP>xc2TW0glH4Ldcn zp!rKB^ke3)d;bSnOxt{;_-mwqJ$5>qFsCbxT;7w(|NIZ;v%>6)^R`7MU z2g=ERHIKWvsU^kSUMae4Jhs46xkFA+nk5_+`KW&}@NwrLLub@?r;t)w!w`;Ad7iSc z>m_SX>4O~++7dwiz?L|;cP=dWgwobQ4c`{C)k@h(Z2UnZv2uV#oXZY6`Bn-u<p6p=5-c3hyVq|d6&X#2hej=>s12&He_XSda zFnb?)AQFePQQP$Cp1K7gMM!iF`{*O(Ra8H7DK5Y~41Wp)WpV>)fikidjxBT(sdoiCDhq%LkDjxOyg1r(b@S^Ya3$O?`?Rf}IY_@k|$UUtx zJ_IoF#YFYcM4Qx7XF$E(vC&6Dz*1at{gbAjqC1175fMH~P6|d5XuYGNU*^9j6ek4= zEFtXGrO)zbxTmz|1#I%8%A3x0pdhqfi<->`6d3;fRzVtFXz^FWb0}%jVv#z~*M8sB@3*-d7Q7LI?$1G58 z7&+*dUuL-C><^VN@1GAg{yPInDc|qM5|V_(Ht?j^J=NScc>Bs&0T1Htd(IeI&y$&{ z8;TGuHZ$d!NcD+xDPO<+6#NcRv1q<j%^%G9I=&s>FxR_&)nWo%CIjN%I zaeg=8Qo-S2jzQ%o|AV?3(yiU)SKr^voNlkjqw(5n=k`U_9dXGFXdD&}{(BqUX zk~$(vg*EkC5@ZVFR8J;+fJfSuXf$qlz1k2OiFQxJjE~24T3MxqWTrV-A-#hL4^xK< z1mBTwcwv!SqWGIbA9E6a*I{psU>>UuyH@(bNMq$d?-%^qxtr zN?3FL0eiU-4{&Hk`;@ujXsCj1}DEhl6#FWhOy?G8uj=9|z5hT*|4EcuavWjQ2*<8e5DY5QP3qWxf_X<&+% zcHR{>n~_;)pp+@s{e+NLaSlZ(!W8pZT(y*t8rTb54>^{uL6TNgR_dkqLxunfx9$pDw?- zy~lW9hUD?#kNB8>zjT(j#5d&{en-w3csH%`72pi2A%ojvbEa%tP4#0)#wSoGr)aFM zHZ1dz(=7<`tuY1Q!DpT!ZeXLh=F9dQtjb!;*S<2=K*`87zRn)SWm`Dj@-Bat?;kF` z`}$E?HQ7Jbxr((RmI6P^cC9nFmp5)x z5r=lKc}kXapEcH>sL50|<}F@urfPH#r&gc@)h9I9?^4DW-Ryw0;DM4(YgaF;xS2aL z7?~!cs>pSJ1QvGretPX%g^oseTN^Fh;4X`_EW=Q76Lmc;aiQT|BZ#bfJj8 zX&sXMusMuK@K@RDP-;nF_3$Yb0>i~&BSzyDeq;4>23j!C5pBY_%vU#`4HQC^b#Je~ zfHsLn%SBN$!I=6m=(p=lSG2G>903vsRvA>FYV-7ej+p`Gi%3wno7*<_+J;N)jql5a zH-21pnL)r&QPc-Ngl%O}LSD-~asM^!5*#4c*r($ZHgM%JGbSGB{t$HB$+V~FuB;n- zSxgN#yU?ssRl1&)#nJ&p|*kenBd&#+IsCu)M)eMZoCsEi)+C_(l zLX>-do^mGfau)pn8A7zL+S!u3$3XE}Lhpy!o0P zj;yDXB^d`ilxpN|rABK@>;PcFgN^LVEecNzmlG1}DPh7sM#|*jKIXiJWcxFW;>OuX zXw{e9jEYcXhODRT4d)_CV91kqDE>lXWBhb~bpV0Q=Gna_x|RM=><-T zfx!Rk{M_jF2vcU17|}~+@p61U?^=qs1306Al(jmBx7kAA=kM`PB0H_HFH0C7i|)jK zuZp!SK``EC?;CruU2K~tRIOH&%k%~t=^3BTbY1noAhk0yd=qPtfk{zi?;07dL7b-L zvh+i7L%sWJjF^dcoN;6IJEKKy@oYYtPkxe4S0e70wOUfWM>R??m{ma`!6(#x2385A z^Q#$St6t==^PTn}{YJX9KtZMzX6vDUeE6yAYL1iyX*Lyf5riSHz2;zw<9cwGFgI$` zm-hm7H#A_LbUESitt^W_M|l3MljhC-jy!{@BewL*7I`?dFv5eYcy?~abJz@j!dnv7 zA1di@!VNZm?bIcT zj4E9#^&rc^45#{ue2@^kb_ttmnFYWhWYiS zZW3P9f{^oBe?eX}4`spf^ITDXQnSN>UdXBx@%^kmwZUVEWB7!5YcS7Jgz#x(7&vqa za1jX)tUnb|QpiT_{Hf|nQyEc5|AJMz2A#3ozxv+#JdL_+FEMLM_8YfOY^8VPdEmYC zuRM?GX<|fEt=FxWL{7JZf##+hyuQ!NM&MVZ(&(X(u6(f<=F2Oy!I|TKzLI^d*?>1} z>Nw5gqxe-ysfnrF@V35#198!-v-E123fhMx6^suiUN}Fr*XSLzxwqbMxX|bOzVzd9 z+<5D(V9E|}OW&EEn5bvnt)x13HjOWdjdjPc=d-l!dQ6bQ79C9?CDTghd({zWK18BW z#SEUMYVGr8W%N!?){{7Y;e3LzIz_hDwzKf5>Le>tOH5g$3Nqg`mn5ej34dg(pTXT` z;!L)3F9Q+H&;+gMK^o4rE)*uoDIZYHUByg|t{0pU{s?;qxKuReT0LWr0MWgsbqfBa z;BAYtM%hc*3nc?V32^zoQL6T&$}1p@K0WYO^1&jo_C4=_BW}@u9{cFz*?szP^0_t4 z%TvFI*FE)4SQVLfzIT!LSm~E0@i@L{Aum}+$u=BVb-~u;Q{^q0ig(AIK4_xuFS7PY z#mGS#TO8^&F!hCKzWGa*G*VP0`E(7bF;5L+n)5G2a2+hirlJOTEsgY0iHtvuTJLyu zCJEzK4qt8J&dI}nhK)t)(_ut!p9Ss>_6%X??sTP)7X7I|%1iDo50yC!L1PwG-&1V% z5jIDI#eVuNqB_)05?E+dz#VUh)9&<`{3hZ)YM990X!m)bFkIWQ9MU-vCWqD!C`|Gk zeBC4v5FJIWVDq@71PPC^?)W31!lab8y5}^1*YD>$Ue;z=bsZV{#|6=sdkMT3&hFX#Gn<+K zf`%MHRFXD#KTPG9gvq>8_h6g*Lm^QylL-#F8J`lH(?_fc$rN%D`-6n5Pw-sm>InN_a z@g|_Jzw{k8zQ+D^CD!BpLiO2U*V77zRZ9{y*@`K*9orx%>e7R_%N}Mj=}tEBx!g=p z(pM0LWex^0Oq#E2-!7xtvg(MroN*H}$$XE0Pa$EdiSCC;Vp=oRR8ULKWv&MIm1630 zmg>WtJ@aSa4+qj^C<$q#;G|;D^RBr8(VJncSr$5Cm}cE515o?ErG#@($j<28+y(j2 zhqha96-`DzujT|2*k+q=-oO6wSPQ{~TFf1dD^l}$YsR{5N1m!;mA>zc>xbp8b4vQ#;~|Dijqk}Vl%nhSoA~6{?MC%nz&M`*{!YeO8I5Tg2AWQ54QI;* zTXRKGr1jLxj@6A!!y7I(BleDkhpg<7xh+97#UG>7li9h`dw2UjFG{P;p*o*x3e2?ji!oWa)@hcg z`ql5cL2%B?giOkdctNbBL4)+KoUF4Q)2GoZLcrI+88|dzEYodo#;fVGaa$sPzuXO} z9MgA|>j_6g58TQ2oDJ$I96J4DRTnjRbFCvI^!`$-=!c3vK*NJ0Noi3>Hvr<^QtSWH zLdYmXq?#QgA+v_sAYOqwY2_pf|^*6O5O>$;BRPUmjk^2cZ!PWC5fuwd*j<4P*h{oXo0 znm?>;_aSCRw!hEM!!B|WW7`2tfT$>qc?MfQ{4M`36Cf)3&V&N~;;d=`x!OiLo97pc zuwU0PdU>Ha(sP5+>+PW^L#_mV!z7xPZX z%cZ2X>NW}3JVrGbfqz&Rhk2(;T6jN9&14_SyuQmQvP$bWln{~TP%QpWnrF=@|)uVWjYQBu7+UDhM4 z^YLXa-RPRd31cbEYK^_hGXF4}k{;NWfJop=G0rm&S>>}z@{<)Z)Rgk~mIprN@soMS zsym7S9Ez;Xqu((>3XH2~eOL+#4mEY0!+33Qz6in9o#hki)!Gz)7MTjjD1ews(ddbo zFTx#bR+pZ^`~+`Yp0R2T^)Wf|i3}^hBSbl&wKJ48y%I(!v99&ryJBP1eKgE8{&>ur z_;0>efTbG}C0sLd`;ZzvshV3*wEU4AMAHp>A6e2b21seioYPFoMGqhy65|?9KaE5$ z83Fl_uFys)aem8xMXURC$`0n-WXQ2gcUOiQuMdsw5*hY3HqQH$)e;7+^@lIUZ0AjP zFhrohMMrvz+04a60daQIp`EWi_h|gE)uX(slw&n`za2Ft{UFdRkQ6QQ`uN-~H{4n{*D&tmcw;;P!c$ zAx3iA%-MZ^=0qoy7@4OjZ3zp3S2YX9vY$XlWclzvW#$I$%RO?Z8=BUhNgaH)oN|<6 z5^D(u4U|iFdqC;(I&g!0fo1Y9k9vP+`F)}>$*TkKCfz%cOw8e59tjFbJ#Plpx^P2L zQ8NW~C$5U?*+!;&do=nd75Rar2v5DC?I)D{CuysH-c7hA*az`(cN7ZqDf=Uu2$ZV` zC-UN(kn+mH^YGvTW3Qg0PC=oEi;&NvYj4~wjG#qt6oHcpjSRsY;~{e(SaoCR2zgm> zvKNo?e-@GuzZM4S0SkT1%OV6(hwLcXpG4oY)eo*{#EwBVcs6o_GXAw%6J2zH#%k2w z+@5=XPspw;qv){3>3ghyl<7GzY`@ITB`#oo7*6+@C+YhrrsgpGY|$xH56v?l4!sdgFXfcP3|7TTEYwt>C=(bsk_ z&i)8rn2EofLF5L{tFKRi^is&3+#jkI1pfSgg8hma;CswQ1W8#tdWY?G0bmiV3nV}o zhS3F(NL^7v`2|yx8-Rvg8@Wzn-2NH*Og-fS!lbK+k`^s{$uMzFr-$`(uBbwCihG$D zhIsy5(pG^D8{HC&?^EI_^KD%>32G#L9#6dF(py#riFlCk zS2;sG7-|U2BjloSYNj1^kiRh6!T>0LkLi+jvF=XwKacZNbM}8;h~q|#7v4OFU1ABd z!`;9)I^Hml{zUe6Hx%TB5^Xxa%j!kqklkto0zc-b1vv&Q5YR`j`HAs*S3*+t%D z-mM&s2)7an9VGx!K(4=!wPvt~*4GGQquC8|TX2kks&pEiGn4xoP~W$55ZBt3?Wp0h ze+C6~Y_a-gpk|7zbjUhGR@zJ;16JRjN#GIv>VGRwNiCtI5qE4qsz1(oPy}7D=YO8Q zDP(ds3$-|{&ed4erh`kC*OC+rmJr@#T^&T7ZioIeKEo!@nzB8h=L^AI1KJ-mo@U03 zcMb2(HZlCSp_u6z(5zEpIRIN36BpK@e__Sp5Di|s0Ycu4n^@qNFubE^ zkU)fKc%QhuFD}0QNAIATm+ZFl+SU?xdhGFAIPH?0gcnHL$1@IHEJgm|IQRp!KbV&Z z;`x;`S+zTH3Wh_dKtHQ&fBE;Jp!BQzqka0BW<%1g*OEoKH1O37>G#w^x*aX2 zddgPfM^<|?#J-;u<#w6E^7uwv_AK&8^kQ4KEszbZDxkk6uWBgNeVh_dgh%%_YP%}i zLiiC!UqpP=-m5Unn56@DyMpq6wsN=b0&n_K@UcvuU_78i!Q{qg7S2%df1e=@#FAjp z7?+8vxK0{&3YBmNAn(BG=lyK;migdzq%+u3W)ig9g9&NIr3L0bkmtO^Uw}NzY?;Mi zZcNAi%~#yB6bYKE>JC8$2zF0(*3aIe_heeKh55DItiK~uo?#RE1uIH?SH#mlqg_t% zsVaSdbyMXs7K=naAVbN6fAlD+=os(D71cBUGmWaizHsX+qcx)s(i6n# z)D4fIDD8HRM3XPgCn<2w4`S3WD$M}y@`|HC7ll3e+}}Tc^A$j9qkUgU$rr#XYi)Os z@Te0#9(@Z4JVS&9zT4BVY-F|4a)j|oc|^BZ6N;&4>-cFJEHAfZe^c2y$G6;NqE+7H z5N~FBs_8ru!r?@BgPgJpxR5*0VhgE|{o80)^(7IHys`=(f1TR=FA;b#V?V&XIgb_7 z?f1YmZ6u32E?Ip;cg0HRD~GhWaMasF#*RLDW$JgbEG(;Q3Ig_7i*GTQ8S)Vbk!X#E$KWOmQ%Le~S-)_WgLo z`hWw^4Vn;Paa=PCUKR?k&N$BV7Jw1f{!|F~q>KC8ZDN@pY;WIiAIwyqgG5Emg0B1%!b~7?JzV zpu~S(A3~|4f1JBPVQclaz$w9cxf0NX2r;61X3f_~k9F^q*W8J29`pz>Jeqx&?7v6K zMAfmfiK8=kjnN2{Z`jx85*49`^DxKwofNneuUD7=x2}ja+H1ttfmd07bCyH}zD8@m z5oh@{3L9SKnO+fn9zfT(HyRTPFv7k%s*g=f9OOs_#@<+YG;^>o!~?x?EtA< zp#Jdv;0$->9vCGGr)3-L#YIQo{Ob68d%;+QI6v>NDpm!h!Sf>2ycx79vaN$BWQmZu z*dP$BYj1k!t%hBn6%7AJ=2c2^@Sc7KTVJzM6aYc8uP*_>wkU^st!D!z;1 zFI8UVf7SLJf*3;%qZ&K2&@uCX*=(h8sZUy}ncq=bT&9P))xfim=e?>@C48jHs1lowN)?VtuI|`AnX-E5=f`?|<}%Fh-Fwt@lZ0kpGP>TPZv|;$ zSNWr!qT%w2h(N#m1g(rj!**OsP(Z-XBI!#XCr59mp}?J2U)9FsV1WN3mr!hZ{TndS zf2YYC4)oSA%#`v*8!=osA_<6akxq^iYP|j3{Fiz-?5VL@Gl|e-68SWfx(FuO_n0ct zK;we6+%b1M+Vh@T5Lb3!Z>G7{!ay0-Y&kfe?+`SKH|5uNPz*qS!O zbXGOz@lt8p-Vf+*x`OaqLKG-QAqb04f3H%+XT4}9bkKRrr|Ep;aPMA_VGmj3@#Fm| zypxofLd3bfFVS{s|4hl9AfR%trq4{n?$8E*z}ToBftR#jP>boy3L6xTTE(CAQN;=1 z-3Pa%qfZn6@q-y>RiEmZ8_IW+?I=oI^{WOkQAo&j6<1vE!;V8Kb?zT0nQJ|0f6B)Y z{fW5ZF#-g+qNUo8C?CKk6qd5U+o`8PWMF1PnP%b*&zQWq=qs_ zbq-PoOGvnjh^)y!Vp*Npe6>XF$e_R=|+%IxcRwIsN&Bh{_K zry#A^j|ijQ0bG>_xnaJ`cb~wPB#E}RxqIc(>@i*+Qx@cRorMp;==ZeMDV4n#!E{cj z4s)lGV?lB0X&(h8g%D{~f5-f3ic5=9I@=zD4bd@{&8#2k+tZXa$bLB1M>B3DaE275M0EMRj{>c`!WG@xho zk<58qXQT3&7I||(j3%UpOidw-oEFxK@6+dE=je+p%$zJUYB;@#r|2z%^+ zurQDSV>z5r92Y5F7g{c;@D5LJBo?x#l})5ck*hL)R{B0zsvm9(h(YPbhVsKb_HGZ$ z^dhR6DU){J{Vn`ck|i+VV(2WIhJh{F#bjqg4?H>=SgEXXRmcvnOwY@}IxV<<0{)h<1#S9d~>)e+&5z znv<3|o4RZ*o~B9vC6FE(Jcvd83q~k_QuVC>nKFCjO2>LAkQ%mM&m2K6r=q)nQYGDxKP~WFC}n|1*zj}! zkn&^xJyTQKe$n}o++CPRLp6_jmYe+JS8esH;Ie(QIkJ#2qv&09Nj97@dyEWWpfJfJ zsCe|*e~#zkr0vsEf9U5HO_|xMC*e$8vjo{>YN;ybCIwY{vDYTCO(#spDh^NM+F9Yo zGalvmf&UcTk0jZLmZbskt7|&QS;p0VBI2$L6ts~rl??nTs;W49GitVAQ|o|SzFf(= z22X1F#w_y)7#QS;t?IYEW4(m!Mz)m4L-LE;e`pfeV6T#=-vi*JS^~KNh~s;{Fw5mO zf0bf$NP?sIjS2l|@RakSuPGUE7FWj0bsmbHyE|(B@Ym@Qt#%r3(eYo4&DjcaCxd)gV`xlk82nI3B(xgZE ze`=MM283kXEJuHfLLdxr?mR!3VAirm4TJtLs2jkpqA@6(d&@#t;TTs4BZq*g>L*4h zIELQ*W3dMGN=0*iTKVbQo!07#N;e~Tpomw0&vC$-<*r1>vH|M_&YJ=@TZO*=XqB^2lMRUXl9oDc zg!edv6vT184&w79lMGF!&Ta&SU9(CFdqk9g24Z%M;=xD!-RzHcie++9i z!AQRB|Jw|F(eYRa(MqY}1S?PEd1_L8b`+LLH+nWn@tf?1xG^iCPv3Y0)$JjFn&@U^ zra&6t39{dlRRHWNH1e^$24fp}M9gN0mhCSBT@cc+nR>`9Ri_C=!f#1P2r2n`c^0bT zDMVm%43i@+O**3Z#)kAa037ZNe;6Nf;^Z$m6+{oBiKIg{z*L;r8e9HmAi=E#?H5dj zjL}9P#Zf|iswgfc%s`tjGPs&qe^%z{?C952+;TbSdsl}oB2`a>C`tRdP1d`Sn#92O zJ17ij%^6Z>v*r1Z(`?U1X}3k^^d->W21R*8o8ynrO2Y68WDF!*W!d0Hf6Q94kV*)a zpXej6t$g_fT%4wZk8UvR z$O{;qs6zdGk97JKN$eE|VG^}(<;ahhDsy+TpFUyw%6@O;Wgfo(2@Txx*zxh_Ly(h1~aH$F#i6cq)|EP;~6vk3br*Mv#mv!+e zSGpQamkBtk{lZ7z;;JKdsFj9RxqmCHU#RPp^}6S2U^bz#9XV~nK&&og4*1eev9@SU zq=PWoas_*N5ZTR6L^VlIo0Gb+xoa4HM+M9CnXLS}Lopd|$tRIbe^UAp1s6Sskj!xl zp#Tf^{yS9JT>kj2UuBNDYUn`LPd+bWW{#7|=#?r+xvd8sD1|!>;vi>cZy^4omr;Z* z=$x0mE6C`zO50eT_1q{?|*Pa42@Ob|R0g&F-x zvj2iz3gusb3G@&YtHdj5iA?Ly6Ub#}$?<1>Lht-x)om%2V>K zKs38%hjWr4Z2QI++6L^WHze;#yH6-@dX@YxRyGq(9oyZ3q zY$Q~1!E`VazZIvLe%Ym=$LKmRIN$nM1>w4Xp+0&uBKtM@$uz|B=S?gUb?Fxr-zai^ z>mb>ePE38*a%tLM(rUgB$btHuQyE~}&)#LJg zZL!rvi8`Dg6a%)f8Fax!cWMjRC=lfZ2KFOwc{o# zEK68GYr>>PYm9Qky|4*Lb~Y_BYqyy?QO%^+dVy;2Y$5X`EF0%2LwuvyBtzPaNuHtl z3-QB?g4(#ln4e9Z704}+BEjLPfH-P)8$OoesSLFDpgnrRGPJ^?-f>bjSCdThN@$ar z5|miCe@NOV>nj!zM9mXp{T&u;!hRpbO-Kj4oM@pCt^C6|Z60Xwp{5eJ${CgJf?fL< zx^K#pP&_`ao`JKWyVbg82{BKH#8!cuDI2Wtf+Ywj{J{x$4wGO3^bZQ}jlT!TueF=O z$}uu!*(FR7o&_>Y_5&3>o}Gu4xn{tol=4Qke@^uwr#e!B+Nuo4rp9)zIt%#$YTn1X zJJzmU&G&QQR5?c>WmnGwTZ@Ye1RTQKR*I5YsySCVO>fU)UFLzPE~w_@jPKVU0#1`g zQ;dRI>f84HLg?~^&Ag)7{LO5VU6BhQSj4-N!YGU-uO+8_+6(J)*f9eI5yeZ6gDA&B ze{18Jg7--SDSmcYX*0u~j9ZwtBH^{@2E3D)TN?-ioSF1*>V{QN@(*>SEcDZ#zeuYAsOCWgaS_*i z6;xBMSnVicwjV5+nEI6o3JNwihUHi>e?yYMd4j*9BvS2RTC{Q70s7gl#&iSpa7qpJ zn~wMfqGCI&;Djw@=w-8-UMo8(bm6K^i*?OE6AQwyS1LHVunw%6z+3q^8~tVQUw$pY z5slio>>eq363+WO?#GyE@)#6=_8a`{%p#lDU~bIYgLE@VpV5LapHIy1!30&9e>fb? zKt&9=#WgPR*SOByQ~6_at}0zMPH3OW{znYxnu*hHnR9x)4q1Y~I7rWd;u7M1G;+A1 zTd0ucibzDwFr+^D5FyOz%eCqZJY2+i+Us zH~e9XWV@ZWa%k4#olp6jJK)m0dsOmeR=QP8(l@5O+x;-@ix}EcU?MEaeyYL~> zn2IFet264ht>Mthpb?Jg@d(_&U;j@4`~d_0wLzbM$nKRq4@tNE$RgFUz-{W zEW)EbHGHK+GK)z=eTH1JDyM4F;Lre?ptpMoL{s7%Fe-cFOm6#M(uB>G%e$_WoBKd2 zay@zmQy*X|H2Ih6$y%LCe*|QR<`l`FEFZk_grA;=M0S$y@I{SQsr4k0 z2*vQe7z|S8RD~PH^-bh#CF-Zpk7Jdq)+n!msB|gW*Fx1uui%OVb@r6DzRtU}vRX$g zv~IEJ%LT~t`d&?{efk}i(@TWyuB;StuvfQX{DhIw`kJ&xal2E7e|%TnM`*r>ph)R^ zbGL<9HTfHSmp!E@q87Z@UQ~5aCbuBtc6;fQF|O(js#kDs1xOBSEP~a%QBGR5J3jlC zG>v2RYez(C9vN2}#YHT1S6{@%d045ls(#nvtZBegWf=rWB6ZuOTU{J^;T07h;Z6q@ zgfrUml~;G4)jXare_#0N|F*_nV2hi=y*=CJ9fm!`xT*D2dPvGwljieX5 zP9t=Q85pvt(UQTVwpnELeiG*PH~q20fGdIQ{3I%-5rX%7KavhYmpWy?r^f! z+VbtSzw_rLS8_e?Gc)%+Gxy9(NA*#IRl>r-3?%CSabe|T<3OXMlX3z9UBC_yX`l;8 z5FqOW2BMF`IDw+Uw84XQ!c_~d9X@I)?2RTg*sE?*K*cssLVCmux zbOHffpp{ty%|U-bTezCL0H8+b(G5xq%^&Py{l78T09wu<7ATU1tD_y*{O?u*9Gn0a zU}tkX2WM9(Dzs)7YY^argB!>RVh=6ge=k^PS2G(BlmVJJv`7~xu=!t+&QKs|=bS+< z080laC?6Q|cPtbc1aSrdfL2Z*(BBY$H2`Xql~4!paZC_NkBER`e{kOezAy8twx29V3YW(dH+#mU3P_CID8iUWi; z+6wIK0&;?i2_>@t*#n^y2`%?uf0M(>2~`g&jTzJ(g2w*WoXbNj9RLFVTtkKaPZLzo zf9m35zt-~ts6!0`XL8~?wX@IUr|?ca>Du6A}RKzk_X ze?v)G1D&8%1LR$RP`UqC1kfIA=lOq$`M0wU=|$;WumsvcC;9JtErR+Tq$cY>IsN1I5eSC3{QdUg`0u#?c$@v# zvoa96j2-|34ruP5*{tHb~(!m4Z#mdF? z9>B`Q{T|vDJ|2JoKZno%gfe$^a)K)Q_k2Oi`_E@fFtn2(kO#;dZDrBHoJkJ%u{Pqa zB#yz2!l~hP*z98vyrL+{`o=bU@fU@|%d$3|u+cG?52KUBbz;`~f6ZLQtos|gEn_ej z@xQQwd13cmNIndpJKH8DQ%O1Q5X%zsr`&CR4D-Kb$LeSy+%J=jYg`s*m~)>R9NOdC zLo&xpgQ&?;4Y|`*nCxmTHfAdtCpZzP^^$8(O$E3aJT$=1mq*f&%QL`mWrg$fTB=0jHw4NCx{10ntkHF_L*NTeYzocBLNXH zj3qRbe-+=g{17nfq1#Ek*Atbv>2<{BND?~faS=%t)!<(*e^#`YL4u_eG?cjlK{t8^ zM$41MFwbLNNRNeygl^P@W=a5U0%fs)Lzr=@E^LQCQY+F4&k!M>S0-f|^QqZ|I`DMU zfH{8E71P)E9%@Cos41lR6k{+9p}LvNa(U6Y08M|2l`X<^9`@M8a-hFGO_l!*PRqPH2TL``##H{k!Kr0 z_HV2BPMOp`iXN&gfH%t^#Od2VFZwH7TsQT@0^e!&WuJ)LY|gh z8s9xa?bc@)+v>D-a;2C?rVNlPq=(k zXfJBXE#a&e^YEToPVuXKYva!6!R#V&yC;t}JlFgkIrps=26@Lft@0tqHN@Yai0%7E z)ex6Gf47G8+amYf`m`Q(l}C8!SB27qQDB|BDD+dNh)(krJR$lI!!!cKWyqraSxCt4 zV+`Z|gfz3;Lb?JLDybgDW8B$(th!PKzYX%GIB_7xBAAlxjXTHkXJJ~;c~6cUGCFeu z0);8dD3;8A?xZM(%@4dr(YnS!thQ8vfDz=4e*xJ7cqN{zC5EFz03JbOIz^+be}<-5 zIw~E`!ka&~1ow{l`t+|&F-sHh_s?=Oo=EB=rz?1bwkx*Vx;35Gx>n3>DzAg4d>OV+GcIl1$>?BWE!32RS ze=_@;B-KJ+r`jsPL|@EQos9==6Kh}F)gKscn zNS{pbI3JOoXTfQNAPUnf6re_(Qf=@vT5EZ->ZL=A;lD&5M*_6@cb$9?f^-M{qs#G>RFifIrBR8rCsIYqf3jAc zyl+eBX67xjjQlJ;yNa3Pbv#RjVlWUMjG0o|xA;vfXUB@B_mosM6NL|En?7nfl=xxP zVdY)kSI)$Z$NA}v3{7p<11S=nf6NpeFk7p@q-b4i-OC~I0H{xh`D`3Q=t6$uSNn!0 zQfyJ%_lZ-s0C!}{rbB8hZBgh7zZ4I1#R+Fc6J^W5W^00U`vE~IRpRy+H!V%Cz9tMIiP`$twjXumyrUy2tG%KJf8>XKWfOXZ z4P92Bdl?wxcm9X%2Ra*K=0fpr*=)5po2bc6Dlp7=SRH(>R}9Jyq=|A_Ulo&DmwIN+ z6ouDhRX@A*cU|Bd`Mf>%yZ3QE+kI4bY<{buDK~(&CL?WM zDf!HUXD3eB^iTtHNP&7Ye_WpT-N4GAF&U040CFF?uty?d+Itz%la^+bj6t^zTO@h- z=qA!P(PaAJPYw;fKr}+pOb{83ke5UCNNInANQCl-#Z#55&-`CtuoRfpAB3%w&&&9V zX<5$Q(@uQ)4#{2Zh2pcnp$MSba$6&eEyrQ~#>n7$kAQb)HUG|7f2c}SEKv?i&m6`^ zchrb4FHLCixp@WXfFF69oiNW(re>&eKk$;s6h-ll#y&WFT4iWlT*ErX=oM$(GQ4+n z2Ol#ENB#tmG&`U$CqRTlO9TtPtTyI8z)U~r*y;B3KXt)6Ym5IwYiOx#Ev4F;?P%Rl z18xZ~wq_4DL9@7#f6_Z90OW?AO6g?6vJyRib~2Eh*pkk9L#le7_X8%s>!YT;R9d2w z!Ka2~HQ!*QSa}cmdQpTSLv7bqto{*QvxJ5iDx%W0mEG&jPDuT@WFvp}VLfz7Y- zWDzChz~Lq(e?58L{=-MWMT#lm%YdCHO66T2U+cQ#i6Ed(1x|TUWPFAdfX1T}zwG60 zKcsR=`DO-BvG;PvOI5=G++{!W3{--U^nO_A>efKRQR?Xya4>&VC z9c`3x$-$V37k_M>v&SzuD?~22@%n}#5y<;il8wR3`FcmYEQmnqeSN&4pZBA6*kqfF zj*^S2mu8C2@8NuGsdg;Mg(>g$T(DrWVTZFtkk)7=_b~CM);gcV*Y`xh=rUJrJO#8u zf6`|iR?*V^Wqmt5m)Wehx~lVPAA~PcG^&HUM?uw>L;(mouWzll3RrB zxa47bJZPIl4$_a5%ty0-lFO<3%DZX91dQf+s^BJx-^pfs%Ir7GNv}nH))JPmJ}E<; z8l;+K)})%P;(OldV#n?1zcKot<;^U=e-T?dJl7zQP{124BpUcWG8P3-$+JCq^t^8# zwLa>+oYM7|yTQaV2)1N$#!haorUm3P{j}5-t+$D02>XI%BKmcj^36%#)5ug-0>7Uo zckeafj;JJ;Xciy$hUmeTpS%5W4dblWMMKBA^&hoR0Tna?Y zSz(coXYDQ@N4N(8N$IIYE`clmk7|)VJuwn47QZ|uRTTkPJ65{Xf3&=pKRA9!_>FD- z2ZQwO;cpf4ANZ4gE_YZMpV#+Vi>m?A-J0Nk;MJK8C*fnXgT& zjse+Df*{o&hv4eujUTEdIqi3O&u*m&@b}{iac#|;-QPYHVPh(TmrG=jT!&|bX9Osa zcq5Tf#T>ms-agG=1~8?G^9hkK95q4ne%3Km+k&T;f@^djgU_WUWJr7xe;w#vej4;E z>dqd9m?dj)NM}Ur-)bk3$5`d=jO>47DP0qzl;5X)&3+JzO_4@5_=3I2Su>x?gQM~* zP(xJ#;``Ka`HnUHc3F||Ds@T<1*%RUX#zJRXe@OM{mkBJy5IoLQqA=3r!!0TFEYdidhHu&MAA^(ae)_(; z5-NyKmaQ;L!&FnY4lH~gWFlZ<@zUMOPHLTt+kyy)JL#}JMzZRjYUnlDOIx<)JPulJ zDJIrSI?!Ap6iuo=+fm0L9@bYX{k+9+TW&6pB`Nu)prjNR+4e5;e`hY0*$bg^dN}o- z1SL(ssJ8h1jOy^O_07s#nZWXE_^`4oxux*Kv-*oveO~aAgEu93z%oZ?KqTx@72{$x ztGeT|M90UI?CWu@>{o`Y<>8lvbrmZngnQkDZ+E}+GjLz=>8NXR`baP6J}|X_W!|PJ zlksuorgZ3-3I?9xf65j8^9M{pxJIEg!t#}mf*>y$Ry9mj?aovNTwru<;&EdhU znAl2}NT5N6(cF@49C?W75uQZg17a89=hoV!JWL}q9SFo2)7cLQ(|M!R07TEV+uh9wiNDD}e=5Bx=)2iX5jnCh zpa9kpObct1rcWY9_n-9|HkOSEh6r?Go==2d+z>0%m47ak(x^b060h&ve9h7Iz;bwV ztZ}>0Z>ljGf1XK~4!hqQjOFj^V5I}+fS)J|iyIz|YkaexoX?<2VbIL@4c|4~CdDX~djkY%qZtvI*;HS!BOjBiafoWPg;uNEm0S=AAz4N5Nsnt^c^X&$Wcjk-@Y( zo52)hrlyHM?`IP-7$|3SK1M!xhyK;Ow_0I%IVS6NqV+ZUw*eAAPv`2*_#wTBKr}#| zvZt2LeYh{{kyXxWAb4J^Ypll zg~?kJm#3edcbLa-_bkJ1Ef(S*a3l)UawR1YQlGCbZO`LHeD|}?^X>IRd;mMvoxk}# zb#*h?A^^R+D(hY{5{&yBDDdG}6kEB{IU}-}e}uJqN484>2~FSqOL^9>RGf1T{f}{~ z^vdHkA`R5twPEP)2F0R3!TEvp%n~9p@M7vI&95G|cW33U>jM4K4Ll}1?e|T96|uYp zb9zlB%q#GrAK(NlL0G=hGIi);Wf|4t2;Zx=cesqb8u51+h^L}|B-~apCmqVn;pJ+o ze|?utDHzy!Lm8jCc_<&@jS+ROVRC92T+8#m)^Lt2xJ)-+^cN4<{^297j#=!^KITLp~iwCzZ~8YAn`e=zH#DZcO~JZpCRM+S4lBZ${8$d2a|gS^;< zJxzRWlUh}e7%J$iKDU6(4^pV-Tno>A$ctPxV9w@4xT?%Fe`H9xQX1&u%pPDk*99863*n}eXu|-%*@vYzR-!0n zeUz?-6tiw>eYwXkuaxpOaV&lEq55P>Vp;7dlg@_-0+SPr#P)iCrAYdtck=d)dxy9& z1U_48^YioGT;+Mm@4o-ISui=r*LApd2y|6>^A#>TI7j^LvoyBBy<-50e|uTW&bScc zEWI)Iy_OY0WtBU3Cdp53K2&`J{@@|^o9Yh?flP4rIzP9IAN6BUGSF-@k*z${I(?8) z;Ct4$5b45W?6t8rmMdVX(bD$1@9uQe=0C5?5*aW=E0I_V^^z->+&NUmCI4P*ri*LU z72;ZH_BGF_HAOcktjd#;f9!qBqhUUbO=K{rP;EsGbm!I)p;zu>ZGk^}owU$yPkL3B zV|i?TSnP^A*+|thGMy_`^`hR5D2AQX(jh~Dc=0eYmypF&k)eKP@1iWO5Aay###qgg zf85zJ7azoYJ;m`oDDBe@}6^;b*I^>!K%$8XYPe?o1^9I2HdCr4+p zUAmZIYEI@)Hojg__zEYzP8LLAso{+}JTCbuh)8?f9yfKIB;w&ijA}i9CH6rjR!3wA z3zm4X(IU0@mp8kAJRoVwX){cC=uSpj(#i9isSmsEr(&*nPU&vT^`Upe8>sC0x}((m zKGHx^vA(20P|pdPe|BU{E~cgDw>@CT@+LFMY!jwFdY|nlxT*sW*v^`~13h7xw%Za1 zu{;82W1%gK<%6DP97ATw{+GPop7ce#iV!jMy-pW5h7s*Mo^0A=i@ACC?cV8@1bz)d z$b>!CDkg_*`)}DFiAlt%`|634pLR;J~qAkca|tYQ@s?T^It1Pg>x?s6-b-hTnLLax;_}_;n)+Y z21}bzeaob9fA_c$7AjA6?Kl5CXZw&7GB$yL|KRm@^4G|@p9g=^g-JBJ`_BQqCG55e zmTfbbghaGJogQf+>t#^H`SdWeRqRo_ zz$I3?m*ojO&vIn{_gDKfDa-!8Saj47U*%8L!8Ew_fAK9h#Q7C1?t`XEwm;S|2FyOk zCmZJa{e-u8vQT||V5yu|*HTa#O%zNOuI|JXb&dUY*6nO-E?oJ&9)Q*_4A0#IwkEG! z=^h}O5Mra;JgMRpsgZ3Z64*tHwhb}7xfLn#*88*ii*^(%0?Unwd4O4ihCrE&XT!MV zF&?EWe~F&8WX+|^7xLXjw-9FL`+&LKo0q7m9^qQ*z}Qbi@{15Q2^-!R^cV_EoV%0- zbDjoB_l|wV)8vc%1BULhN%;?4pGCCf_(2?v{rv+}m~Sfg^o4&0%X=Vp3x)0ba%8#V z3#rEkcsv+5s8k>P@SEiu4o5NHaq2ztzd_Pne@}vgY+)uxrZ$UYtObpz*;h^z-8KY1 z&d!!;apzrww|ogtHsw{$P}#7I1!En4nn%$wFadINqI!ysSEpy_Q@u}89Ic)=y1r&E zuDK<}qEH!!z=@zc>uvvTo`q@qnpp0AHbe9n{BB3dI8JeC1vG=Eme*W>I-Z078@n~+ zf0UcB$KNWUtlw`T>#8uvbm}DJi{*`y`X9nZ=;~StO`W;WIq0{W>jp(q90kJ~-Y~kI z)oBC}5a?BpDIs4z>DK)eCzVS2>|>dcVO`{=@;GW-%5^P`!rVR9>g~FrkBzc~rq|%T zh2h%#Gt*e+mzeHGvtg*(cMH!j;LvoPe@EY&Ipn#Gd;=I(9W?TW?ra0Sja?2>5nZr|*g&D|wmK zy5#+T#5*o%AH5}g;E1b_aOhPl2tGL!8ZuP>XlRzw<&Drzxn^yg5P@vp~<2 z&RtUk^Scwub+pHWWu_B?Yd-T2)ycr^T1qNNbXN_6auZgxL4F zR-I#64l(EuYXV zeFDhx`|_;m@;`mVM)*#M4Yw-1=25#KmQH|g@ziV}^uZWGiR`_x8duS~<7uC8r>(LP z+F#+C9E2v}V?N`kV(|+dOGf^p)F64;7B3RJS^Ze>)sNl5B!9v5(_0`>@V2))I+|hU z)O|%oirR;`)?J3cz$CYxe=*NeUs7g=-iKDq(9~vD@NZ=a)(gSrR}4&@=*|IQuMac( zGm8@@>K}etkrj_gUYx5+`-gPq*l;LuG;Q1o{-Du&Gc)Bkj?#7+5~M>bfwW2@_Z_Re z@6adSlP_2fF?BaYFoPNy8)To-I4X{q)pNTuPNhw88R!Ez-XANQe=c@;NKjjqE>q(+ zZ)5C?M;eXpJ@vLY(eA-Cs6KnQ*RfQI&7~S}_YirT<&nA-E3Yml1oTD1!TgDDP;z(u z`Iq4SD0i}$&DgKPAee7?`d>$}W5hQE+SrligimQISUeN4em*3Z;mgZ2%CtXwMHC~C z4PGPKuBHmJXhiglfA>$;x{=qVZ{0eEj@Iv|iE$J0Xui8-66_SWXP)Uqm6NM~?9u}y zAHiES{+X<^!YnJP?)H3E8|5{eOOjwyX=z<*%=g%}A#k^^KvT7y9!T8~Rbn)kHRrh! z6GQAGTu7~wHR}3A!oK6EPi?~3+mI-Ha(DBdb9e9ud&eane<$m~=KYm!hFp4NeZ|sG zn!pB`m(7mpyu+tq2la?em!9{WbO_70H`R#3IOOj+w7jR|tsBX}d#J_&iFQL({LSjB zo!WpdI$6v^M1>{JE-d@lGf>(TQb&a><)vyNdvgyD{VWcj?;7X5i z(6k#eVOU`zf9eeX;<^^IQTcB*_Jv2O;otd8!RO8GORkP+Vus9~qL}Lw?Y`N)>y4JQf@Qx~@!8e_*6yi#_|?Jq+>9v?WFkmq)ov zymcY%wFEO5%+snr$G0M)ry3RP;-EY1LzILhKFyvYeQskZ^awF<+tjr!a0e*Y^Qebyx5n`wdpiAHwC|u_Un?AIHsA{c!X{ z4Mp?G7B|}wdAx$$2fm;9F}%dn&m-CHCf-lue+RBneN#Yt`@MrHr-irii*1}m1P>PE zzAPMX?^U}GL(d5{C58EWjOv=3xaL*e*FVDeWY!MKL0O|%W1q<^WO8xWEzKl#dL0R| z*y)4_($-??r7Q2(?@!S5ngdA88U0I()P_ao&Ta)i=8C)LU+h0oOtRe5ZP*w6vB9ww zfAn?BWUy%Ak+w@noJF4-F=y-k1@qu3%*biv{f~amBP+7S0z?k~J6IQwjvocUaw{Ogs@Te?oey&L%Wns@6?E^sQ_)tf6t+FiVgFnhiap0Nz2#F1O7)XqxJr;y?@x) z2;-0-UN?cO5!iM(4xHju3Izp_{JGI^1-o~I@Bi3Q{XmVlt-mc`jlTULj=!E6Q8R7w zbl0%rsY;q!U$y=cJ3)&xxyTlMg92)=3DG{2^s-EKXV&!-!exou4KPn&&8K2{>6uV+H2sTU0woKXwzxsuVE*G9v81HrRW zhD~}th9#$E5GvBTns2OnbV9M#c63?%GsMnYg5IR}MSmkTTc%|rY@5g9f`1u&o6!;) zptlppB;mRwW43fim;bW37a!_Vf82Lcqg*=V|4#TFI7(SaxrAXvYBX1m-kac1voi3= zQ}z^qhqz9HCy^EsWFXbRsPVIS&?)#xo@B{{X>j>_ka$$D0G0d#LQ3~%tld4!kD~TH z20cjT9;Z`FX%Q63=kh!3|Y>Mh05TuJ*lK=>JY3o@oUbS9AuI{tTa)Zk=yiCp zBeew-N6ZBEN1u4FjvOV>(L672Qz(PakqbnLie3AZ%$N&CR3DLH3Aoy5-Fh?_7}CGF zFAWZ2SI&0^2)J({XDYYK8<_aFjQ>1%!+p5|w2xhl)c(X$VuX->n62OaWnBCsf$2Ll zDOVvrE9RYHtLsF5fBe@q4wb$=>(pEsKsq(@b^*Gv-tShrJ)Lm1H(`O3XF+!}AS%o0 z4u=CBOOAITQ_}plD<#rGx!Bb&&G$2&PZm-zLIe!tsi7M|VLD~arnwpZ_NAk+WlSQ4 z7h@O?va#|%x8H82#thtF4|bd5=o)B{@_5C+OvBxQ@VjoXf5zFkzECvs$v5|tarfTtv0B zNWR%N?oDMdB+(7e|NVMp!lZT8VB<7Cqnctwqn5t9KJ8s;B0A@K(LjFBU^)+>v?Jaj z7L!ick0ob*_P4XNq)Mny2$s5(XnZ%TlH=1SAMxH~e|Rs9m`v_~9XWPCD`ok+>#B2H z^RK~wwB-sicbQtQUQx^HdVdZ7Vf2W>OnWV(bFiSUNbt%{ViR8BRY<<45b{fph^F)j z8)I~>h?fCQ?kq$r_qptOsN_x?Vbga`0RPWXBB_)wZz==@|4N^rWd1{op=6q*>}CTh zhj!M|e{MzoV6T~_d~t*bAHm^^olZfYhsOg}XvSUeM_F*F6PYp#io=K+4TYCu$L=!+ z%5|gwECERD*XX;=xI8>tc}~1{Up*~EDNlrY^k}bEcC$Ipv6Wl)=n1l9hO=5SxagSZ zKRwYRH@!Xir0%4dQOswb@2pt=MoCCo`j?ZWe}Nvzw*k3xSHpIYdHN-2TrCWyFx>_0 zyKxifByDpQLAmqe*~cDJU`G_yS3_<__npZd0*64B9@UFOv)&QjN8p95w~h8;p4og9mZC)g9N0D?rVW|}L zqBV&(!o!wg5s`7TgS@JcG8AhiEOuwM@aMEGlD98lhHsxXwfsumA!w&$3xtL9n3&6W*Bf(gz9HFj zTpYaRDPV=lTNuG}f-fdHC<=f2HE+9gK^-b%rg8|e%lR?xa?k!G#5uL|l_N$+-^%pJ zvsvB(;B7Xnkr~!YlW>@WFUcFndWB`8&DqC_Bsj)U_BV7zb3m#xP)P8oevbE!uFdC@ zJ>j{aVcFN<&ku(uYhMOnRb{fRCObF=hcCEg>%h~l{Xqe6kEzDVh#le8z08Z_QF_4y z5nc|OL%}s?Zq~)6)AHY6eS+!uewO$YUi&!e$^DMG;rc2ke?(KV3)lVP5|hv27_9o8 ze@TVyu)Pc~yRu~fvSJnI8A?@5M(6BKF!GX?!qI1LnH?_V-nh^@$#)w(Iga>|!X|RS zMI2l*vs7Zu&dr<0@lKXP)T)ehbvr;jJ;} zBDCZ{{x_`u)zmk>!hF^?EuuLxH)SzKiQAL9Bq33~HuuiOpGZEn_WnP_fYGw67{sA%m3~Atu zgOW%$j2uK=Q#p&Z3F0zoMe1@o&H-jpA7eSUfL5d@ZmUA|1(L&@fq5ilUKN7hI?CUs zPlNXyR`S}69UC3x>AuN6T9LXddhMu`YVU1o9#-ayt9%-*GJ|A0q(y!IXBHcbC!?>M z9Ws%~td)OwlpN@xk}N=v{=Hskxz-N+^%r65o#3vs@4l)jh2h*;MviTsv!RD(DayQ> zB(#-icTCf8U1jyY3TEQKZR#P3GPB?2us7I&F`~_aBm~)=3-t|^I6zx>jplCdJ?`A> z?~KxFdRAbe3EtoNIJqhlpsJ}SZrZwpOZ8lR1*6F%df%2_GEHWdUp&dxn42eU|>)tI)ZIBSG^s0NyHu|6}w@E)o~l{vKb zxfOeGPsSP&e6~w#Zk`y9)35@Tl#PqFAyNz-<7woCYYugA_U~^vWe%E&VeZh0X7yzL zDlwOpKsIE@;QxTuYh&O^gq7v^wOME3N{n7%+vQT2-#V!WibYUWlT(R0_L8_(REE6Y zf$kwbi{d#}tZm83P|c-ZtR{p1urQ@eS2vHCNz4+h*nH6evo`INj5z@8&%Yy<>9jCN zDc=@LM8^NxTAHixqC;^!QIeEW7WFu5{EpVd%5~>S=C?b8N@ujMJqD|6w?Moi>uHSj zSgGzGSe*QT(WbOS8*Hi=v72R$+5AFGK$>eJhUsgS zlYaDtNM5I~U3@XE%-_F7v-;9cwFI$Uwdi`eurNpVf;;$(?t&l&E;iQH2Twa1{Ykp&rt&cQipxO0W(U)^7TN$E^2l)a9&{=J-Cdw2fVl%o$YVi8**r2gma% z9HahA0#^LtFy(48V6GljpwS_%wo2e0ei8L{^!FbPR|1t$L9WMVFwMquSfrg5NNcgWr~$tMq0DR7JZ?C&yC?scZDu|*2ZmOkjH8o9R9E!hPhG_MgSSWHlVMJ2Zgpf9^2!(D zzZNnR6NHdA^X(nHunJhx{>xVqj!w3S?CeV;_QX{;t9vH~+B)s1uXeH*bU&2)Q^|1+ z4g2OymJ{e9X47bxTD45Qm{GRL;zu4Gj+ibtpV&rI&h;9XD||vn6G0lHTN2C z49`Ler|7xgz&gOp4D6mbJ6okgUL+GG?6mU{a&>wn5R##7ZKq%b0hM{qwL|HNK-u_X zLtN_NjHPjZZZgzwJ;A}Fz)|Ld@B2_1^>t^ggVcnL?JP)s0r|geo|C61AHTszOyB5T zy_8!|#V~>3QJ{0k#qrvqf0RmD;+WMLG(gCH_DIcjg3reC`VQ#v1Vi93tX-RJwGNrs zu3Icb31fe+PH)r3kTG%eHLd;&UzG-0rD&24_T;yh=0McuXnsp)!ULDP-e->m^&v9K zyG_c;(ULB=D68v|7d@A563k~Bb#5zMmppz|p!7YIuwSkAkC(;l`wZKTQlj@|}ss%06582aoaANbd`= zlvbDD9}AXNa_38&R{t{U>t{hqj+xo1!KoX3ta1BmH+WX z!Vrd`4UYW1c-wXVL8~)AIloc~uReoDDZBk2ZwCaV7o6mXhU4gSUv{&fa}G~A_!*ZM zT9FnWYsfghS>G7pP#9)MFOn9f}r;WS{WjTU)&)1kSy1Oa>zSaE-rw zXyCSK6yH^nZ%;&3#%x4Kxap9_A|b+bu0B*6Uq|!EHQ_9X^^ocGLs~DtL8Zd->iYA9 zpdbC-_Vc0y8+nB^hwhkP-1o2go&*6|zXQen@#To=tX5Pz>mU3MkAD>UF?_Q;KKh+D z{=syQBNydoMtBHy!nTi^CBVY6VtF?J#GyrBK$dXJc8+%Xv#m~*C;Er3yNs`5W95p1 z=T0{LRrB*L7|Qx-bn3tUk@Q~SG>H`fk`Pmhb{Nq4IgwcvEuE}EHb723-jodvdhn^f zz4Nj(?(3OxPXZdU``T|Q72vmdrADPCf!{RZD#IM+_KXTuR6pdvuX&us4u2a-T^E^f zb?|e(4{wg;KJ(qLW!A{oB!8^}Y z&79nZ9s0ZGoub^^X*`x7wj$)nUifNR!4=7`2o{UQyYce{5UPpSpTcDTR4#e2OSwlnlkhNRfZoG8=A z*wto8?0@=o4`Rise| z-SQCe=2>i4*{{x){scR!x0T+t1TR}eJvtlO8`>?8q&bRAhidv?39w)Z^FD9 zKYgkCkN$ollt)rP=!S5qB$_s?NroRLpNBP&j1`dbgtC^o0v|}6NjMQ`!tANjI$Po4b}Xe+AC*6-=Nkq^m(Pc1`aeu z^qUsH4`vf>(P~4UcLoK|u-C(JT8&_1mOFq1s<4h29UnK7PilGmuNR4&XHAt_=`|BdOlcl3Xd-?0wK)H$lt&q;>dnY zvchFGn=P~@o7dDqS`R;K&corz=P7pdNRPY0$!=!0QTe>^yGll09hOmeO)f=ipRPJl zCq<-AiF~F6M<9QwGY*{?a5omZc91)f&?nS`T48YVqCv%=41#R=#l|j;zGK=xGV&D* zi|Ha}lL$-|q=Sn8$7SZ2W6^`9OIgOg$9*uB8%YwBWO5UJ zcTpVx0~lsC^@*&d9B4yp7*3O~Y_$DJ#kZlJ|JHmQOey?^$FH~V#HVL{c4XtBgaY~O z=13%C_fbDCv=Ipd7j~okyP-hUFUin815)vDlRklJ6-LLKMpak+GRAwP>_4NNinx>u z;4pb;z8Bpw1G~~BYjV<+uKZ^_jBqZ6OT~6Rzp>-&nSm|8Hw^Nx(lIkJMQ(h;pF%b_ zyabH3WVR2J_=v{v<`iRr4ga12#k1|Nrw-Nl81Vtw=y)L*b61-nuearYH_e0)>wBLN z^9Re61vGgiM)90up*pr=k-@5M*90sS@Cl1SQUMi*C{EM&o}26lhOGT$iBG3bjGgXNx$CHrJX7aVjka6J>d% z)E?3#%*1hS7TOr{zGjw+&fHjMzx_J;G~Ci|0ex*a0Ea^bKw{{IGu9pf`4)5j4)-XS zu{H}eNg3_MR`pUuq{MX5sY)fv@OrSb0J5gU>!DPrQc=!2pi<^dIJLSBk2*4im?J0VV@kry)`$13R?+pKgLj4 zmWN1z4B@b!lP)(GJ`$y>4<}mdKAfuWKtwymQR9Y0K0$?9^THO4M(;55gNbi3AS#@f zS)|*O`pWVXn*SLgP~1ydM; z-}EsTlJAt|8llnO!0w?#=7*`{H6;84U4& zq_1Jw-vgT6%g(bfSGdVLX6!-sF|eO561~*mYVx#^kxCg_(0@fzTwZgIZC)1VfU_`u z?C-i#Pq4-h7MY?W?r&LgXJaU{GK?uI;EY^v-`}6*;q!tjiUDBavt*~J6V|SQmd`9sePbx6V=f5A2L3J?S-Zip$v~NNiC1JnJ9(FXlIU*h)rv!?H+2l z;O#IhXlP-oKxeEIS2BXg3a_tap^%X5aoTYgGBgW49V-Q))=&;9b-VfngOfdE>TD*fc1RdPtZztcf#p?ducBYlqxLukI7ZhIlD}T1+9y@h`8j|kR799EuLj8Ap zDs|0DWQPO)&wdMtJePFUEPmP6U}-VYu6ejwwqm(HItr&O z;GVg$=@rSamy6uYTaD_-E5vbY?)7v%O9K4$H`I)Lp47ayKBbng_Gve#g}Bb+JFOtt&TQ&9#tL-z4CyF4 z%}&=YC8Qmdg_F`s=Uj}XN$s@LD#2^VrlU^Vgvt#1XMNFAk>l#e#)Q-_@ielO5%teFj^h;$EocE(1(}RTYCLt7HI~9xOf@oVkCVN^d|Tx^ z4nW==l&^a$0NEmxkWuIep#=D1ot<_HildYyYiGC9q#HpA2lvO1Pb?3Z-c_mBtQn}6 zs1;$sHC3*;KLUb=n=vx@r!y<$S9WGvs3&uFDXYOJQrr<-QJC?cuZo%N)FP8mw2`J4H8FjJO%aaF5DK;QJOtfbOqmS(stJu_ zT@5%>VxZIsC%6?>?e8|VDvCJfxRH&t3OptVy(Gt6v)6Aw?Qn`A^q-k6X=Zc0%i@$Qk--dn;l*dX`86q_c3W znRWc6T=7B?qx&C>3O@y6ohTB#)$DkVqo{XhMWb|ShA1bz8;Mgq(&4QNzevD%$nQ}) zueyl4vZgw>Ec{uOouF(Q>5Xhv^-W)jas4c-vBzgkilI)JXAWyrIeRe?$>@6d!l$);ixhGe^`bwc*kwnEZuNa7I; z2N4!#hkE5RqkGQ;{xsliJjS=~UE|>3p|r2kpS4k-VmpW%nv5!z{+n;gb$G>VFbk5@ zD1?5e@8z};w~(V>Zcx9V(bgs4jE$J{<0HytEv*yS_7dRh%kJoi_-!QedUt6Nsc0)e z$^;LNJ2_he`Ne8&_xx$E_PFlI$vFo@A9{KV`nBT&X?@xF3ADo`1DeVvj5th|vATH3bjhZM4owDy_KDar)9|BeG9rII zNR0IxF!hH$c>Sh1FbNF+{et`y;6FI}*ZH*YHY4-AVC}1uYY>Z2r%%fy=Qj-Qs z_UY1Dn_Nu8kKVjFaRA2musaFG4ftLL_^^MX-LlX^YtHm%_$r#4ul330W_`=k#lv8H ze~XFJQ$T!>X`*E|`FXq>xoM6EIB>sYEBr?A8B1OzY>`!lG%o!bX*{o-9 z_01M>XlB4fR?h}oSJf1ZT@-%0%{XCP7tQI)gFi8a@g|KqV2v*mkWHH-~WJ zpAD-`6#7c6D)Q#>zPYK)tUAxsWtc9MK0lmHn_-615pp)dQ6A4^shuuwi0qywr;?b! zk@f0D-)qgRAy^)_k#&`CT=)`^C2BbTFljoD;cV35U2}h$(z7M<8BLltW%X4?p=|y2 zuw_Zp4QFe{__}K%xJjGoh^;K_&J9Jl>BV&*hbMl)#lOubj&;uv-aw%39V%4dwhF>- z3-}Dlcn6@SWZNP&9aI1$kRg(`fR9IaBOne5a-0poZQAYvP$EDWi$0pfLjWX1$lr<& z0f9+CH8O;$5r7S;x&R0^@h$<1prP40n#|V$<vo$niDhUI5OaA&36}pPLGMcm2YUJR(S+vWgeboOz^v?SeC!--9PAv7Z0xjbY_#;qtV+%nlBOU_Af2SZ#|RhO z{}zF~z5%jR$~lM$xp|RUrET5ZK|n4({{OKlaB%YTr)+Z2flGAt-Lr?W0~UT~42{dt z_pN-lv#;=rN^vk7a?Lr`B25gn{EA5zh%ML^&_)m%o*ln?y#ei0+Sc{v(`sw6$-afP zDM#T4udP(?ym6G$tuD!yz*dUCDgB8Cy7>~$bdWRDHQz<~3Ah*Pj!qOtW$<9t8wxbA zoxR#n-oRdY00Wj(4qzL)i68*{ZAn>lt?A$Jz*q!He6hanP{gTtElHoHY{ZEui!UMN zfkf-Hdf0zTD3&O(i&O}!ptO3VkpiI#G%%w=^-IK&?rcFw&rk$9q0FR%aN3FPi+Di2 z1UhA?uWY+;$YNLnP~jNqSg@+l8o-aO1qoF}s!4}{g;m(#zift=bptiT{-A~vVKQ^U zBHT56@c@e3lhFb2mmtklk(X2(Fel+C?W+Ay*Pj51alw3{Z2dN}K~R2!UWp=D-Dnmv zVqSv~XeWFC;3E+amfO{S{wE**u6RV@(Z5$*413<~EOmZr!p5PDI^M6B1D9={%9DLp zxIF#fQIOA-n-2~%uUv+5{(73KUcat@B`F>CW-aiq9T}Om=T1Joi%8fan;IWSki|O9 zO<9JFEz)7;REoM4A4hd^xp3===wUPtLSbOs&IE{LB3udjCL)aGNp z7RWg84gH(V2nHu!yi4_wynaLN3#GX=2p6P#-gl#JxYX0gV^fx-VV0>fqCBQwQmVmB z+uj;h_F0lrrePI)tDiv)a)FmSc~wP16S#+Sp0;eU_Y>C1*Hy^NTz&C#E+pl)^n>Ji_Hl6BlxoM_&W~81=iKs7H z{B-Z{^4D_?JoZCGH{1Ss6LnHKEIsOe?l3YUxiWB%5d=@>DQQ^sHRX95O4e|Vt@Gp# zzp^wvtiw!$Mh85-vZuWp^}=rM0{n?eJmjV+kYeQ7pH4@;wj1ll$+4JUf=M}LU12Zs1fFR5u_h-ll71lP@HcJ|9k%V37}*vy>NpNW-g)7`d##p)ko(1@Z1?= z>+7_XR`@l8qezDwaPEdC90?pA&R9^0I0M&yKsG>L>=i5Ka>-dJE9_)pq?TPdA2A{uV@{qt^+?b-~hTC6a@(|8nf%Q<(M{0e>{^>i#0>%N}QyT12 zUJ&vPT3+2!SOR9$FK zZ0_>*hEL%mq+u1CbkRs@a;u%rmGeUMyL0bTkSp60y-{it9IAFB2G`@S!C`r~Tz}c1 zdbrOR=6&O4Wb+HgqW-TgLVr2doYnz`JK}gPH^e(ZC^`40S2Eo~Ce?N!IHbqHmW5Jv zZc{$~^;<6W7xWH7Fu+4@I|Cc{OZHP%|J*ljjZmfUq1?~0gip>>Vj#4J-Q43av_quTd?%0;lBqzow(kidO1a{P=x6QRZMP;Oq6~3S?aSm*rge3nnTt4VYG~y zS0Os^_-D8`t^ATXR5DjyTUmZ}UpBJzDg|0FvHho7T0^P-tuZT&U;u$js^~DzUVa@= z09ublZL}&T@Y^ndvkK3V+ zXSs7b3N3Vqur`xe8`QD~V^9}vzlWy#^K--s@6M4w_o0t7dp(>Mdw+-jevKSF(Vd2_ zb4S_bK0MgQ5}adoefW%B8cw@0+1M+3aoqfIG6cSZVh$Kz^-qFUv<&p)pLe?h;;#VL z(7TnVhR%G8ku{Do;PY~u~1 zHAdWUC)QZ*$v(O|?PDkAY)X7@Cnno=ZN95w^Ql#QhUhlp2KLIc4y}Wj5qB7XpGN5558TqfPCPxg zYRW}KF9jE0Pf;jOl6DmC4LF@o{uoQ)PmN;{je#S$3vBlqrr#X`GKf zF`TIAzGiz*%1)okHMk1OX}>2mY8x3#`B&zma4%{2m^v#R_nBAHLaBB!ge?-OPa^v* z_0fUwB58CXuWh4dp>M(%J2hGq9pZ&w1W`zX0!OhapF_>@$OcRK zJpW84hf6;^Es_sAB~>bh^s%G;JuI189(6^qm{KTdiZG`+DTYX}W^c1BDzPRQ;mU+m zWGN?90NMba^YT7-JkKtjXl}(#U8FPa5vLfj}TLLvQ+kdg=IWrwOxmwG0DCc^jE##-P%9+^1|!p8E@wJ z}sv$(fIFZ|Nps_=+k*o52)476wv)v3{K-^YY-$wH5EkTM;@ zR!1Rzfz$YcqalH4SAcs|KuTDEl~q8Xw*e#$?wdlE*`TZM0khjgpmzeyaSy^t55hza zB9J1*Ak8~W&oBsH*>R^p)IPe{K4Qh*&x(Dhzr-{QzSXT-;^H>r^pWY99W7E?@~7>7 z*r#;mEV0t0H0G5Z4PVR<^qbRa<3>8^pG*Hx5E-8a$2FZ|Ef+NkpTsUruwB_@_Xd=m zA|ya7eOl0P0`r>4&Ef`gtIUi2^P*2j zT&LwQ^6LG3Ftx){q{ za=BpNaQ6BwXkQ|GUw!!6d**t#W`CJv^1kbC4Rtt_nSw4Hn+{I@+w(bgC~|c~xv*3P xIV`sdiiZjY+7zM^h3LdX!i)RND?$d=y$oal9hwA{gP(_oADNn3N?98DKL7~sk1YTI diff --git a/docs/problem_formulation/problem_formulation_ocp_mex.tex b/docs/problem_formulation/problem_formulation_ocp_mex.tex index 1923cd09fc..903777a9d0 100644 --- a/docs/problem_formulation/problem_formulation_ocp_mex.tex +++ b/docs/problem_formulation/problem_formulation_ocp_mex.tex @@ -101,15 +101,15 @@ \section{Problem Formulation}\label{sec:problem} % constraints &&&\mathComment{Initial values, see section \ref{sec:constraints:initial}}\nonumber\\ &\,\,\,\quad \text{s.t.} &&\underline{x}_0 \leq J_{\textrm{bx},0} \, x(0) \leq \bar{x}_0 , && \label{eq:constraints:initial}\\[1ex] - &&&\mathComment{Nonlinear constraints on initial shooting node} \nonumber\\ - &&&\underline{h}\initial \leq h\initial(x(0), u(0), p) + J_{\textrm{sh}}\initial \, s\lowerh\initial, &&\label{eq:constraints:path:lower_bounds:start}\\ + &&&\mathComment{Nonlinear constraints on the initial shooting node} \nonumber\\ + &&&\underline{h}\initial \leq h\initial(x(0), u(0), z(0), p) + J_{\textrm{sh}}\initial \, s\lowerh\initial, &&\label{eq:constraints:path:lower_bounds:start}\\ &&& h\initial(x(0), u(0), p) - J\ind{sh}\initial\, s\ind{u,h}\initial \leq \bar{h}\initial, &&\label{eq:constraints:path:upper_bounds:start}\\ &&&\mathComment{Dynamics, see section \ref{sec:dynamics}}\nonumber\\ %% dynamics &&& f\ind{impl}(x(t), \dot{x}(t), u(t), z(t),p ) = 0, &&\quad t \in [0,\,T), \label{eq:dynamics}\\[1ex] &&&\mathComment{Path constraints with lower bounds, see section \ref{sec:constraints:path}}\nonumber\\ %% path constraints with lower slack - &&&\underline{h} \leq h(x(t), u(t), p) + J_{\textrm{sh}} \, s\lowerh(t), &&\quad t \in (0,\,T),\\ + &&&\underline{h} \leq h(x(t), u(t), z(t), p) + J_{\textrm{sh}} \, s\lowerh(t), &&\quad t \in (0,\,T),\\ &&&\underline{x} \leq J_{\textrm{bx}} \, x(t) + J_{\textrm{sbx}} \,s\lowerbx(t), &&\quad t \in (0,\,T),\\ &&&\underline{u} \leq J_{\textrm{bu}} \,u(t) + J_{\textrm{sbu}} \,s\lowerbu(t), &&\quad t \in [0,\,T),\\ &&&\underline{g} \leq C\,x(t) + D\,u(t) + J_{\textrm{sg}} \,s\lowerg(t), &&\quad t \in [0,\,T), \\ @@ -220,6 +220,8 @@ \section{Cost}\label{sec:cost} to define which one is used set \code{cost\_type} for $l$, \code{cost\_type\_e} for $m$. Setting the slack penalties in equation~\eqref{eq:cost} is done in the same way for all cost modules, see table~\ref{tab:cost:slack} for an overview. + +Slack penalties for the initial node can be set through the appropriate fields \code{cost\_xx\_0}. % \begin{table}[ht!] \centering @@ -227,6 +229,10 @@ \section{Cost}\label{sec:cost} \begin{tabular}{cccc} \toprule Term & String id & Data type & Required \\ \midrule + $ Z\Lower\initial $ & \code{cost\_Zl\_0} & double, \textbf{DIAG} & \optional \\ + $ Z\upper\initial $ & \code{cost\_Zu\_0} & double, \textbf{DIAG} & \optional \\ + $ z\Lower\initial $ & \code{cost\_zl\_0} & double & \optional \\ + $ z\upper\initial $ & \code{cost\_zu\_0} & double & \optional \\ [1em] $ Z\Lower $ & \code{cost\_Zl} & double, \textbf{DIAG} & \optional \\ $ Z\upper $ & \code{cost\_Zu} & double, \textbf{DIAG} & \optional \\ $ z\Lower $ & \code{cost\_zl} & double & \optional \\ @@ -238,11 +244,13 @@ \section{Cost}\label{sec:cost} \bottomrule \end{tabular} \end{table} -% + Moreover, you can specify \code{cost\_Z}, to set $ Z\Lower$, $Z\upper$ to the same values, i.e., use a symmetric L2 slack penalty. Similarly, \code{cost\_z}, \code{cost\_Z\_e}, \code{cost\_z\_e} can be used to set symmetric slack L1 penalties, respectively penalties for the terminal slack variables. -Note, that the dimensions of the slack variables $s\Lower(t)$, $s\Lower\terminal(t)$, $s\upper(t)$ and $s\upper\terminal(t)$ are determined by \acados{} from the associated matrices ($Z\Lower$, $Z\upper$, $J\ind{sh}$, $J\ind{sg}$, $J\ind{sbu}$, $J\ind{sbx}$ etc.). +Note that the dimensions of the slack variables $s\Lower(t)$, $s\Lower\terminal(t)$, $s\upper(t)$ and $s\upper\terminal(t)$ are determined by \acados{} from the associated matrices ($Z\Lower$, $Z\upper$, $J\ind{sh}$, $J\ind{sg}$, $J\ind{sbu}$, $J\ind{sbx}$ etc.). + +Note that all cost terms, except for the terminal one, are weighted with the corresponding time step. If the time steps are $\Delta t_0,\dots, \Delta t_N$, the total cost is given by $c_\text{total} = \Delta t_0 \cdot c_0(x_0, u_0, p_0, z_0) + \dots + \Delta t_{N-1} \cdot c_{N-1}(x_0, u_0, p_0, z_0) + c_N(x_N, p_N)$. This means the Lagrange cost term is given in continuous time, which allows for a seamless OCP discretization with a nonuniform time grid. % \subsection{Cost module: \code{auto}}\label{sec:cost:auto} % @@ -295,6 +303,8 @@ \subsection{Cost module: \code{linear least squares}}\label{sec:cost:linear_ls} \end{align} where matrix $ V\terminal_x \in \mathbb{R}^{n_{y\terminal} \times n_x}$ maps $x$ onto $y\terminal$ and $W\terminal \in \mathbb{R}^{n_{y\terminal} \times n_{y\terminal}}$ is the weighing matrix. The vector $y\terminal_\textrm{ref} \in \mathbb{R}^{n_{y\terminal}}$ is the reference. +Additionally, a different cost for the initial node can be set using the same form as \eqref{eq:cost:linear_ls:l} and the appropriate fields \code{cost\_(...)\_0}. + See table~\ref{tab:cost:linear_ls} for the available options of this cost module. % \begin{table}[ht!] @@ -303,6 +313,11 @@ \subsection{Cost module: \code{linear least squares}}\label{sec:cost:linear_ls} \begin{tabular}{cccc} \toprule Term & String identifier & Data type & Required \\ \midrule + $ V_x\initial $ & \code{cost\_Vx\_0} & double & \optional \\ + $ V_u\initial $ & \code{cost\_Vu\_0} & double & \optional \\ + $ V_z\initial $ & \code{cost\_Vz\_0} & double & \optional \\ + $ W\initial $ & \code{cost\_W\_0} & double & \optional \\ + $ y\ind{ref}\initial $ & \code{cost\_y\_ref\_0} & double & \optional \\ [1em] $ V_x $ & \code{cost\_Vx} & double & \mandatory \\ $ V_u $ & \code{cost\_Vu} & double & \mandatory \\ $ V_z $ & \code{cost\_Vz} & double & \mandatory \\ @@ -320,7 +335,7 @@ \subsection{Cost module: \code{nonlinear least squares}}\label{sec:cost:nonlinea In order to activate the \code{nonlinear least squares} cost module, set \code{cost\_type} to \code{nonlinear\_ls}. The \code{nonlinear least squares} cost function has the same basic form as eqns.~(\ref{eq:cost:linear_ls:l}~-~\ref{eq:cost:linear_ls:m}) of the \code{linear least squares} cost module. -The only difference is that $ y $ and $ y\terminal $ are defined by means of \casadi{} expressions, instead of via matrices $ V_x $, $ V_u $, $ V_z $ and $ V_x\terminal $. +The only difference is that $ y $ and $ y\terminal $ are defined by means of \casadi{} expressions, instead of via matrices $ V_x $, $ V_u $, $ V_z $ and $ V_x\terminal $. The same note about the initial node applies to this cost module as well. % See table~\ref{tab:cost:nonlinear_ls} for the available options of this cost module. % @@ -330,6 +345,9 @@ \subsection{Cost module: \code{nonlinear least squares}}\label{sec:cost:nonlinea \begin{tabular}{cccc} \toprule Term & String identifier & Data type & Required \\ \midrule + $ y\initial $ & \code{cost\_expr\_y\_0} & \casadi~expression & \optional \\ + $ W\initial $ & \code{cost\_W\_0} & double & \optional \\ + $ y\ind{ref}\initial $ & \code{cost\_y\_ref\_0} & double & \optional \\ [1em] $ y $ & \code{cost\_expr\_y} & \casadi~expression & \mandatory \\ $ W $ & \code{cost\_W} & double & \mandatory \\ $ y\ind{ref} $ & \code{cost\_y\_ref} & double & \mandatory \\ [1em] @@ -343,10 +361,13 @@ \subsection{Cost module: \code{nonlinear least squares}}\label{sec:cost:nonlinea %\newpage \section{Constraints}\label{sec:constraints} % -This section is about how to define the constraints equations \eqref{eq:constraints:initial} and (\ref{eq:constraints:path:lower_bounds:start} - \ref{eq:constraints:terminal:upper_bounds:end}). +This section is about how to define the constraints equations (\ref{eq:constraints:initial} - \ref{eq:constraints:terminal:upper_bounds:end}). The \matlab{} interface supports the constraint module \code{bgh}, which is able to handle simple \textbf{b}ounds (on $ x $ and $ u $), \textbf{g}eneral linear constraints and general nonlinear constraints. Meanwhile, the \python{} interface also supports the \acados{} constraint module \code{bgp}, which can handle convex-over-nonlinear constraints in a dedicated fashion. + +Additionally, bounds on $u$ and general linear constraints are also enforced on the initial node by default. On the other hand, bounds on $x$ and nonlinear constraints are fully split and have to be explicitly stated with \code{\_0} correspondence to be enforced on the initial node. + %The constraint type can be set using the identifier \str{constr\_type} and \str{constr\_type\_e} for the path constraints and terminal constraints, respectively. The string identifier options are found in table~\ref{tab:constr_type}. The default setting is \str{bgh}. %\begin{table}[ht!] %\centering @@ -366,7 +387,7 @@ \section{Constraints}\label{sec:constraints} \subsection{Initial State}\label{sec:constraints:initial} % Note: An initial state is not required. -For example for moving horizon estimation (MHE) problems it should not be set. +For example, for moving horizon estimation (MHE) problems it should not be set. Two possibilities exist to define the initial states equation~\eqref{eq:constraints:initial}: a simple syntax and an extended syntax. @@ -403,14 +424,14 @@ \subsection{Path Constraints}\label{sec:constraints:path} % Table~\ref{tab:constraints:path} shows the options for defining the path constraints equations~(\ref{eq:constraints:path:lower_bounds:start} ~-~\ref{eq:constraints:path:upper_bounds:end}). The matrices $ J_{\star} $ are translated into arrays of integers \texttt{idx}$\star$, see Python documentation. -These matrices described as follows: +These matrices are described as follows: \begin{itemize} - \item $J\ind{sh}$ maps lower slack vectors $s\ind{l,h}(t)$ and upper slack vectors $s\ind{u,h}(t)$ onto the non-linear constraint expressions $h(x,u,p)$. - \item $J\ind{bx}$, $J\ind{bu}$ map $x(t)$ and $u(t)$ onto its bounds vectors $\underline{x}$, $\bar{x}$ and $\underline{u}$, $\bar{u}$, respectively. + \item $J\ind{sh}$ maps lower slack vectors $s\ind{l,h}(t)$ and upper slack vectors $s\ind{u,h}(t)$ onto the nonlinear constraint expressions $h(x,u,p)$. + \item $J\ind{bx}$, $J\ind{bu}$ map $x(t)$ and $u(t)$ onto their bounds vectors $\underline{x}$, $\bar{x}$ and $\underline{u}$, $\bar{u}$, respectively. \item $J\ind{sx}$, $J\ind{su}$ map lower slack vectors $s\ind{l,bx}(t)$, $s\ind{l,bu}(t)$ and upper slack vectors $s\ind{u,bx}(t)$, $s\ind{u,bu}(t)$ onto $x(t)$ and $u(t)$, respectively. - \item $J\ind{sg}$ map lower slack vectors $s\ind{l,g}(t)$ and upper slack vectors $s\ind{u,g}(t)$ onto lower and upper equality bounds $\underline{g}$, $\bar{g}$, respectively. - \item $C$, $D$ map $x(t)$ and $u(t)$ onto lower and upper inequality bounds $\underline{g}$, $\bar{g}$ (polytopic constraints) - \item $J\ind{sh}\initial$ maps lower slack vectors $s\ind{l,h}\initial$ and upper slack vectors $s\ind{u,h}\initial$ onto the non-linear initial constraint expressions $h\initial(x(0),u(0),p)$. + \item $J\ind{sg}$ maps lower slack vectors $s\ind{l,g}(t)$ and upper slack vectors $s\ind{u,g}(t)$ onto lower and upper equality bounds $\underline{g}$, $\bar{g}$, respectively. + \item $C$, $D$ map $x(t)$ and $u(t)$ onto lower and upper inequality bounds $\underline{g}$, $\bar{g}$ (polytopic constraints). + \item $J\ind{sh}\initial$ maps lower slack vectors $s\ind{l,h}\initial$ and upper slack vectors $s\ind{u,h}\initial$ onto the nonlinear initial constraint expressions $h\initial(x(0),u(0),p)$. \end{itemize} % \begin{table}[ht!] @@ -439,8 +460,7 @@ \subsection{Path Constraints}\label{sec:constraints:path} $ J\ind{sbu} $ & \code{constr\_Jsbu} & double, \textbf{SPUME} & \optional \\ $ J\ind{sg} $ & \code{constr\_Jsg} & double, \textbf{SPUME} & \optional \\ $ J\ind{sh} $ & \code{constr\_Jsh} & double, \textbf{SPUME} & \optional \\ - % TODO: Jsh_0 - % $ J\ind{sh}\initial $ & \code{constr\_Jsh\_0} & double, \textbf{SPUME} & \optional \\ + $ J\ind{sh}\initial $ & \code{constr\_Jsh\_0} & double, \textbf{SPUME} & \optional \\ \bottomrule \end{tabular} \end{table} @@ -452,11 +472,11 @@ \subsection{Terminal Constraints}\label{sec:constraints:terminal} Table~\ref{tab:constraints:terminal} shows the options for defining the terminal constraints equations~(\ref{eq:constraints:terminal:lower_bounds:start} ~-~\ref{eq:constraints:terminal:upper_bounds:end}). Here, matrices \begin{itemize} - \item $J\ind{sh}\terminal$, maps lower slack vectors $s\ind{l,h}\terminal(t)$ and upper slack vectors $s\ind{u,h}\terminal(t)$ onto non-linear terminal constraint expressions $h\terminal(x(T), p)$. + \item $J\ind{sh}\terminal$ maps lower slack vectors $s\ind{l,h}\terminal(t)$ and upper slack vectors $s\ind{u,h}\terminal(t)$ onto nonlinear terminal constraint expressions $h\terminal(x(T), p)$. \item $J\ind{bx}\terminal$ maps $x(T)$ onto its bounds vectors $\underline{x}\terminal$ and $\bar{x}\terminal$. \item $J\ind{sbx}\terminal$ maps lower slack vectors $s\ind{l,bx}\terminal$ and upper slack vectors $s\ind{u,bx}\terminal$ onto $x(T)$. - \item $J\ind{sg}\terminal$ map lower slack vectors $s\ind{l,g}\terminal(t)$ and upper slack vectors $s\ind{u,g}\terminal(t)$ onto lower and upper equality bounds $\underline{g}\terminal$, $\bar{g}\terminal$, respectively. - \item $C\terminal$ maps $x(T)$ onto lower and upper inequality bounds $\underline{g}\terminal$, $\bar{g}\terminal$ (polytopic constraints) + \item $J\ind{sg}\terminal$ maps lower slack vectors $s\ind{l,g}\terminal(t)$ and upper slack vectors $s\ind{u,g}\terminal(t)$ onto lower and upper equality bounds $\underline{g}\terminal$, $\bar{g}\terminal$, respectively. + \item $C\terminal$ maps $x(T)$ onto lower and upper inequality bounds $\underline{g}\terminal$, $\bar{g}\terminal$ (polytopic constraints). \end{itemize} % \begin{table}[ht!] @@ -469,12 +489,12 @@ \subsection{Terminal Constraints}\label{sec:constraints:terminal} $\underline{x}\terminal $ & \code{constr\_lbx\_e} & double & \optional \\ $\bar{x}\terminal $ & \code{constr\_ubx\_e} & double & \optional \\ [1em] $ C\terminal $ & \code{constr\_C\_e} & double & \optional \\ - $\underline{g}\terminal $ & \code{constr\_lg} & double & \optional \\ - $\bar{g}\terminal $ & \code{constr\_ug} & double & \optional \\ [1em] + $\underline{g}\terminal $ & \code{constr\_lg\_e} & double & \optional \\ + $\bar{g}\terminal $ & \code{constr\_ug\_e} & double & \optional \\ [1em] $ h\terminal $ & \code{constr\_expr\_h\_e} & \casadi~expression & \optional \\ $\underline{h}\terminal $ & \code{constr\_lh\_e} & double & \optional \\ $\bar{h}\terminal $ & \code{constr\_uh\_e} & double & \optional \\ [1em] - $ J\ind{sbx}\terminal $ & \code{constr\_Jsbx} & double, \textbf{SPUME} & \optional \\ + $ J\ind{sbx}\terminal $ & \code{constr\_Jsbx\_e} & double, \textbf{SPUME} & \optional \\ $ J\ind{sg}\terminal $ & \code{constr\_Jsg\_e} & double, \textbf{SPUME} & \optional \\ $ J\ind{sh}\terminal $ & \code{constr\_Jsh\_e} & double, \textbf{SPUME} & \optional \\ \bottomrule @@ -525,7 +545,7 @@ \section{Solver \& Options}\label{sec:solver} Furthermore, the struct \code{ocp\_opts.opts\_struct} and \href{https://github.com/acados/acados/blob/master/interfaces/acados_matlab_octave/acados_ocp_opts.m}{\code{acados\_ocp\_opts.m}} can be used as a reference for what other fields are available. \\ Note that some options of the solver can be modified after creation using the routine: \code{set(, )}. -Some options can only be set before the solver is created, especially options that influence the memory requirements of OCP solver, such as the modules used in the formulation, the QP solver, etc. +Some options can only be set before the solver is created, especially options that influence the memory requirements of the OCP solver, such as the modules used in the formulation, the QP solver, etc. % %\begin{landscape} @@ -628,11 +648,12 @@ \section{Solver \& Options}\label{sec:solver} \begin{tabular}{cc} \toprule String identifier & Description \\\midrule - \code{no\_regularize}* & don‘t regularize \\ + \code{no\_regularize}* & don't regularize \\ \code{mirror} & \href{https://cdn.syscop.de/publications/Verschueren2017.pdf}{see Verschueren2017} \\ \code{project} & \href{https://cdn.syscop.de/publications/Verschueren2017.pdf}{see Verschueren2017} \\ \code{project\_reduc\_hess} & preliminary \\ - \code{convexify} & \href{https://cdn.syscop.de/publications/Verschueren2017.pdf}{see Verschueren2017} \\ + \code{convexify} & \href{https://cdn.syscop.de/publications/Verschueren2017.pdf}{see Verschueren2017}, preliminary \\ + &does not work in combination with nonlinear constraints \\ \bottomrule \multicolumn{2}{r}{\footnotesize * default} \end{tabular} diff --git a/examples/acados_matlab_octave/README.md b/examples/acados_matlab_octave/README.md deleted file mode 100644 index df6d1468a0..0000000000 --- a/examples/acados_matlab_octave/README.md +++ /dev/null @@ -1,39 +0,0 @@ -# Running of the Matlab examples - -## Linux - -This folder contains some examples to use the mex-based acados_matlab_octave interface from Matlab or Octave. -This interface uses the shared libraries created using the make command from the main acados folder -``` -make shared_library -``` - -To run the examples, navigate into the selected folder, and there run the command -``` -export ACADOS_INSTALL_DIR="" -# from example directory -source env.sh -``` -to set the necessary environment variables. -If `ACADOS_INSTALL_DIR` is not speficied, it will be assumed that the examples are runned from the sub-folders of the current folder (i.e. acados main folder is 2 folders up from the current folder). - -Afterwards, launch Matlab or Octave from the same shell. - -If you want to run the examples in a different folder, please close the current shell and open a new one to repeat the procedure: this ensures the correct setting of the environment variables. - - -## Windows (with Matlab) - -You can compile Acados on Windows using MinGW as described in: -https://github.com/acados/acados/issues/411 - -Setup MinGW as your Matlab compiler using `mex -setup C`. - -Download casadi from https://web.casadi.org/get/ and extract it to -/external/casadi-matlab/ - -Run the script `acados_examples_env.m` in this folder to setup environment -variables and the path for acados mex interface. - -Navigate to one of the examples and run the example script. - diff --git a/interfaces/acados_template/acados_template/acados_ocp_cost.py b/interfaces/acados_template/acados_template/acados_ocp_cost.py index ea4408f6bc..6ed1a8859a 100644 --- a/interfaces/acados_template/acados_template/acados_ocp_cost.py +++ b/interfaces/acados_template/acados_template/acados_ocp_cost.py @@ -35,11 +35,11 @@ class AcadosOcpCost: """ Class containing the numerical data of the cost: - NOTE: all cost terms, except for the terminal one are weighted with the corresponding time step. + NOTE: all cost terms, except for the terminal one, are weighted with the corresponding time step. This means given the time steps are :math:`\Delta t_0,..., \Delta t_N`, the total cost is given by: :math:`c_\\text{total} = \Delta t_0 \cdot c_0(x_0, u_0, p_0, z_0) + ... + \Delta t_{N-1} \cdot c_{N-1}(x_0, u_0, p_0, z_0) + c_N(x_N, p_N)`. - This means the Lagrange cost term is given in continuous time, this makes up for a seeminglessly OCP discretization with a nonuniform time grid. + This means the Lagrange cost term is given in continuous time, which allows for a seamless OCP discretization with a nonuniform time grid. In case of LINEAR_LS: stage cost is diff --git a/interfaces/acados_template/acados_template/acados_ocp_solver.py b/interfaces/acados_template/acados_template/acados_ocp_solver.py index 160cbc5fa1..052a637b1f 100644 --- a/interfaces/acados_template/acados_template/acados_ocp_solver.py +++ b/interfaces/acados_template/acados_template/acados_ocp_solver.py @@ -944,6 +944,18 @@ def load_iterate(self, filename:str, verbose: bool=True): self.set(int(stage), field, np.array(solution[key])) def get_status(self) -> int: + """ + Returns the status of the last solver call. + + Status codes: + 0 - Success + 1 - Failure + 2 - Maximum number of iterations reached + 3 - Minimum step size reached + 4 - QP solver failed + + See `return_values` in https://github.com/acados/acados/blob/master/acados/utils/types.h + """ return self.status def get_stats(self, field_: str) -> Union[int, float, np.ndarray]: diff --git a/interfaces/acados_template/acados_template/c_templates_tera/matlab_templates/make_sfun.in.m b/interfaces/acados_template/acados_template/c_templates_tera/matlab_templates/make_sfun.in.m index 23eeb7a1a0..877604cf02 100644 --- a/interfaces/acados_template/acados_template/c_templates_tera/matlab_templates/make_sfun.in.m +++ b/interfaces/acados_template/acados_template/c_templates_tera/matlab_templates/make_sfun.in.m @@ -468,4 +468,4 @@ % end % --- % It can be used by copying it in sfunction/Mask/Edit mask/Icon drawing commands -% (you can access it wirth ctrl+M on the s-function) +% (you can access it with ctrl+M on the s-function) From 23bedb357a9d82a5930bd6169056a1ac37402a2b Mon Sep 17 00:00:00 2001 From: Jonathan Frey Date: Tue, 9 Jul 2024 17:09:21 +0200 Subject: [PATCH 05/14] Remove `t` slacks from `ocp_nlp_out` (#1148) The slacks `t` that were used to slack the inequality constraint values are actually not needed in an NLP solver and are thus removed in this PR. Instead of using `t`, we now directly evaluate inequality residual using the function evaluations. This results in consistent inequality residuals and will help future work on globalization. Related interface functionality such as getters and setters for `t` and `initialize_t_slacks` have been removed. --- acados/ocp_nlp/ocp_nlp_common.c | 62 ++++--------------- acados/ocp_nlp/ocp_nlp_common.h | 4 -- acados/ocp_nlp/ocp_nlp_ddp.c | 18 ------ acados/ocp_nlp/ocp_nlp_ddp.h | 1 - acados/ocp_nlp/ocp_nlp_sqp.c | 14 ----- acados/ocp_nlp/ocp_nlp_sqp.h | 1 - acados/ocp_nlp/ocp_nlp_sqp_rti.c | 13 ++-- acados/utils/print.c | 4 -- .../getting_started/extensive_example_ocp.m | 3 +- .../test/test_ocp_wtnx6.m | 1 - .../linear_mass_test_problem.py | 1 - .../non_ocp_nlp/marathos_test_problem.py | 1 - .../ocp/nonuniform_discretization_example.py | 6 +- interfaces/acados_c/ocp_nlp_interface.c | 12 +--- .../acados_ocp_layout.json | 3 - .../ocp_nlp_solver_options_json.m | 2 - interfaces/acados_matlab_octave/ocp_get.c | 22 +------ .../acados_template/acados_model.py | 4 +- .../acados_template/acados_ocp_options.py | 1 - .../acados_template/acados_ocp_solver.py | 20 +++--- .../acados_template/acados_ocp_solver_pyx.pyx | 18 +++--- .../c_templates_tera/acados_multi_solver.in.c | 3 - .../c_templates_tera/acados_solver.in.c | 4 -- .../matlab_templates/acados_mex_set.in.c | 13 ---- .../matlab_templates/mex_solver.in.m | 1 - 25 files changed, 43 insertions(+), 189 deletions(-) diff --git a/acados/ocp_nlp/ocp_nlp_common.c b/acados/ocp_nlp/ocp_nlp_common.c index 0221c5c583..12a042bb80 100644 --- a/acados/ocp_nlp/ocp_nlp_common.c +++ b/acados/ocp_nlp/ocp_nlp_common.c @@ -779,19 +779,19 @@ acados_size_t ocp_nlp_out_calculate_size(ocp_nlp_config *config, ocp_nlp_dims *d acados_size_t size = sizeof(ocp_nlp_out); - size += 4 * (N + 1) * sizeof(struct blasfeo_dvec); // ux, lam, t, z + size += 3 * (N + 1) * sizeof(struct blasfeo_dvec); // ux, lam, z size += 1 * N * sizeof(struct blasfeo_dvec); // pi for (int i = 0; i < N; i++) { size += 1 * blasfeo_memsize_dvec(nv[i]); // ux size += 1 * blasfeo_memsize_dvec(nz[i]); // z - size += 2 * blasfeo_memsize_dvec(2 * ni[i]); // lam, t + size += 1 * blasfeo_memsize_dvec(2 * ni[i]); // lam size += 1 * blasfeo_memsize_dvec(nx[i + 1]); // pi } size += 1 * blasfeo_memsize_dvec(nv[N]); // ux size += 1 * blasfeo_memsize_dvec(nz[N]); // z - size += 2 * blasfeo_memsize_dvec(2 * ni[N]); // lam, t + size += 1 * blasfeo_memsize_dvec(2 * ni[N]); // lam size += 8; // initial align size += 8; // blasfeo_struct align @@ -834,8 +834,6 @@ ocp_nlp_out *ocp_nlp_out_assign(ocp_nlp_config *config, ocp_nlp_dims *dims, void assign_and_advance_blasfeo_dvec_structs(N, &out->pi, &c_ptr); // lam assign_and_advance_blasfeo_dvec_structs(N + 1, &out->lam, &c_ptr); - // t - assign_and_advance_blasfeo_dvec_structs(N + 1, &out->t, &c_ptr); // blasfeo_mem align align_char_to(64, &c_ptr); @@ -861,11 +859,6 @@ ocp_nlp_out *ocp_nlp_out_assign(ocp_nlp_config *config, ocp_nlp_dims *dims, void { assign_and_advance_blasfeo_dvec_mem(2 * ni[i], out->lam + i, &c_ptr); } - // t - for (int i = 0; i <= N; ++i) - { - assign_and_advance_blasfeo_dvec_mem(2 * ni[i], out->t + i, &c_ptr); - } // zero solution for(int i=0; iz+i, 0); blasfeo_dvecse(nx[i+1], 0.0, out->pi+i, 0); blasfeo_dvecse(2*ni[i], 0.0, out->lam+i, 0); - blasfeo_dvecse(2*ni[i], 0.0, out->t+i, 0); } blasfeo_dvecse(nv[N], 0.0, out->ux+N, 0); blasfeo_dvecse(nz[N], 0.0, out->z+N, 0); blasfeo_dvecse(2*ni[N], 0.0, out->lam+N, 0); - blasfeo_dvecse(2*ni[N], 0.0, out->t+N, 0); assert((char *) raw_memory + ocp_nlp_out_calculate_size(config, dims) >= c_ptr); @@ -2154,32 +2145,6 @@ void ocp_nlp_initialize_submodules(ocp_nlp_config *config, ocp_nlp_dims *dims, o } -void ocp_nlp_initialize_t_slacks(ocp_nlp_config *config, ocp_nlp_dims *dims, ocp_nlp_in *in, - ocp_nlp_out *out, ocp_nlp_opts *opts, ocp_nlp_memory *mem, ocp_nlp_workspace *work) -{ - struct blasfeo_dvec *ineq_fun; - int N = dims->N; - int *ni = dims->ni; - // int *ns = dims->ns; - // int *nx = dims->nx; - // int *nu = dims->nu; - -#if defined(ACADOS_WITH_OPENMP) - #pragma omp parallel for -#endif - for (int i = 0; i <= N; i++) - { - // evaluate inequalities - config->constraints[i]->compute_fun(config->constraints[i], dims->constraints[i], - in->constraints[i], opts->constraints[i], - mem->constraints[i], work->constraints[i]); - ineq_fun = config->constraints[i]->memory_get_fun_ptr(mem->constraints[i]); - // t = -ineq_fun - blasfeo_dveccpsc(2 * ni[i], -1.0, ineq_fun, 0, out->t + i, 0); - } - - return; -} static void adaptive_levenberg_marquardt_update_mu(double iter, double step_size, ocp_nlp_opts *opts, ocp_nlp_memory *mem) { @@ -3008,10 +2973,6 @@ void ocp_nlp_update_variables_sqp(ocp_nlp_config *config, ocp_nlp_dims *dims, oc } } - // update slack values - blasfeo_dvecsc(2*ni[i], 1.0-alpha, out->t+i, 0); - blasfeo_daxpy(2*ni[i], alpha, mem->qp_out->t+i, 0, out->t+i, 0, out->t+i, 0); - // linear update of algebraic variables using state and input sensitivity if (i < N) { @@ -3192,6 +3153,7 @@ void ocp_nlp_res_compute(ocp_nlp_dims *dims, ocp_nlp_in *in, ocp_nlp_out *out, o int *ni = dims->ni; double tmp_res; + double tmp; // res_stat for (int i = 0; i <= N; i++) @@ -3218,17 +3180,21 @@ void ocp_nlp_res_compute(ocp_nlp_dims *dims, ocp_nlp_in *in, ocp_nlp_out *out, o res->inf_norm_res_ineq = 0.0; for (int i = 0; i <= N; i++) { - blasfeo_daxpy(2 * ni[i], 1.0, out->t + i, 0, mem->ineq_fun + i, 0, res->res_ineq + i, 0); - blasfeo_dvecnrm_inf(2 * ni[i], res->res_ineq + i, 0, &tmp_res); - blasfeo_dvecse(1, tmp_res, &res->tmp, i); + for (int j=0; j<2*ni[i]; j++) + { + tmp = BLASFEO_DVECEL(mem->ineq_fun+i, j); + if (tmp > res->inf_norm_res_ineq) + { + res->inf_norm_res_ineq = tmp; + } + } } - blasfeo_dvecnrm_inf(N+1, &res->tmp, 0, &res->inf_norm_res_ineq); // res_comp res->inf_norm_res_comp = 0.0; for (int i = 0; i <= N; i++) { - blasfeo_dvecmul(2 * ni[i], out->lam + i, 0, out->t + i, 0, res->res_comp + i, 0); + blasfeo_dvecmul(2 * ni[i], out->lam + i, 0, mem->ineq_fun+i, 0, res->res_comp + i, 0); blasfeo_dvecnrm_inf(2 * ni[i], res->res_comp + i, 0, &tmp_res); blasfeo_dvecse(1, tmp_res, &res->tmp, i); } @@ -3266,7 +3232,6 @@ void copy_ocp_nlp_out(ocp_nlp_dims *dims, ocp_nlp_out *from, ocp_nlp_out *to) blasfeo_dveccp(nv[i], from->ux+i, 0, to->ux+i, 0); blasfeo_dveccp(nz[i], from->z+i, 0, to->z+i, 0); blasfeo_dveccp(2*ni[i], from->lam+i, 0, to->lam+i, 0); - blasfeo_dveccp(2*ni[i], from->t+i, 0, to->t+i, 0); } for (int i = 0; i < N; i++) @@ -3413,7 +3378,6 @@ void ocp_nlp_common_eval_param_sens(ocp_nlp_config *config, ocp_nlp_dims *dims, blasfeo_dveccp(nx[i + 1], tmp_qp_out->pi + i, 0, sens_nlp_out->pi + i, 0); blasfeo_dveccp(2 * ni[i], tmp_qp_out->lam + i, 0, sens_nlp_out->lam + i, 0); - blasfeo_dveccp(2 * ni[i], tmp_qp_out->t + i, 0, sens_nlp_out->t + i, 0); } } diff --git a/acados/ocp_nlp/ocp_nlp_common.h b/acados/ocp_nlp/ocp_nlp_common.h index e647e59db6..5614c4d02d 100644 --- a/acados/ocp_nlp/ocp_nlp_common.h +++ b/acados/ocp_nlp/ocp_nlp_common.h @@ -233,7 +233,6 @@ typedef struct ocp_nlp_out struct blasfeo_dvec *z; // algebraic variables struct blasfeo_dvec *pi; // multipliers for dynamics struct blasfeo_dvec *lam; // inequality multipliers - struct blasfeo_dvec *t; // slack variables corresponding to evaluation of all inequalities (at the solution) // NOTE: the inequalities are internally organized in the following order: // [ lbu lbx lg lh lphi ubu ubx ug uh uphi; lsbu lsbx lsg lsh lsphi usbu usbx usg ush usphi] @@ -463,9 +462,6 @@ double ocp_nlp_line_search(ocp_nlp_config *config, ocp_nlp_dims *dims, ocp_nlp_i double ocp_nlp_evaluate_merit_fun(ocp_nlp_config *config, ocp_nlp_dims *dims, ocp_nlp_in *in, ocp_nlp_out *out, ocp_nlp_opts *opts, ocp_nlp_memory *mem, ocp_nlp_workspace *work); // -void ocp_nlp_initialize_t_slacks(ocp_nlp_config *config, ocp_nlp_dims *dims, ocp_nlp_in *in, - ocp_nlp_out *out, ocp_nlp_opts *opts, ocp_nlp_memory *mem, ocp_nlp_workspace *work); -// void ocp_nlp_res_compute(ocp_nlp_dims *dims, ocp_nlp_in *in, ocp_nlp_out *out, ocp_nlp_res *res, ocp_nlp_memory *mem); // diff --git a/acados/ocp_nlp/ocp_nlp_ddp.c b/acados/ocp_nlp/ocp_nlp_ddp.c index af79e0ef35..d9f0dbac32 100644 --- a/acados/ocp_nlp/ocp_nlp_ddp.c +++ b/acados/ocp_nlp/ocp_nlp_ddp.c @@ -123,7 +123,6 @@ void ocp_nlp_ddp_opts_initialize_default(void *config_, void *dims_, void *opts_ opts->qp_warm_start = 0; opts->warm_start_first_qp = false; opts->rti_phase = 0; - opts->initialize_t_slacks = 0; opts->linesearch_eta = 1e-6; opts->linesearch_minimum_step_size = 1e-17; @@ -246,16 +245,6 @@ void ocp_nlp_ddp_opts_set(void *config_, void *opts_, const char *field, void* v } opts->rti_phase = *rti_phase; } - else if (!strcmp(field, "initialize_t_slacks")) - { - int* initialize_t_slacks = (int *) value; - if (*initialize_t_slacks != 0 && *initialize_t_slacks != 1) - { - printf("\nerror: ocp_nlp_ddp_opts_set: invalid value for initialize_t_slacks field, need int 0 or 1, got %d.", *initialize_t_slacks); - exit(1); - } - opts->initialize_t_slacks = *initialize_t_slacks; - } else { ocp_nlp_opts_set(config, nlp_opts, field, value); @@ -556,10 +545,6 @@ static void ocp_nlp_ddp_compute_trial_iterate(ocp_nlp_config *config, ocp_nlp_di } } - // // update slack values - // blasfeo_dvecsc(2*ni[i], 1.0-alpha, tmp_nlp_out->t+i, 0); - // blasfeo_daxpy(2*ni[i], alpha, mem->qp_out->t+i, 0, tmp_nlp_out->t+i, 0, tmp_nlp_out->t+i, 0); - // linear update of algebraic variables using state and input sensitivity if (i < N) { @@ -733,9 +718,6 @@ int ocp_nlp_ddp(void *config_, void *dims_, void *nlp_in_, void *nlp_out_, omp_set_num_threads(opts->nlp_opts->num_threads); #endif - if (opts->initialize_t_slacks > 0) - ocp_nlp_initialize_t_slacks(config, dims, nlp_in, nlp_out, nlp_opts, nlp_mem, nlp_work); - ocp_nlp_initialize_submodules(config, dims, nlp_in, nlp_out, nlp_opts, nlp_mem, nlp_work); /************************************************ diff --git a/acados/ocp_nlp/ocp_nlp_ddp.h b/acados/ocp_nlp/ocp_nlp_ddp.h index 3898aa07a3..242022c774 100644 --- a/acados/ocp_nlp/ocp_nlp_ddp.h +++ b/acados/ocp_nlp/ocp_nlp_ddp.h @@ -66,7 +66,6 @@ typedef struct int qp_warm_start; // qp_warm_start in all but the first ddp iterations bool warm_start_first_qp; // to set qp_warm_start in first iteration int rti_phase; // only phase 0 at the moment - int initialize_t_slacks; // 0-false or 1-true // Line search double linesearch_eta; diff --git a/acados/ocp_nlp/ocp_nlp_sqp.c b/acados/ocp_nlp/ocp_nlp_sqp.c index 093e23637e..42bab2e9a7 100644 --- a/acados/ocp_nlp/ocp_nlp_sqp.c +++ b/acados/ocp_nlp/ocp_nlp_sqp.c @@ -124,7 +124,6 @@ void ocp_nlp_sqp_opts_initialize_default(void *config_, void *dims_, void *opts_ opts->qp_warm_start = 0; opts->warm_start_first_qp = false; opts->rti_phase = 0; - opts->initialize_t_slacks = 0; // overwrite default submodules opts @@ -242,16 +241,6 @@ void ocp_nlp_sqp_opts_set(void *config_, void *opts_, const char *field, void* v } opts->rti_phase = *rti_phase; } - else if (!strcmp(field, "initialize_t_slacks")) - { - int* initialize_t_slacks = (int *) value; - if (*initialize_t_slacks != 0 && *initialize_t_slacks != 1) - { - printf("\nerror: ocp_nlp_sqp_opts_set: invalid value for initialize_t_slacks field, need int 0 or 1, got %d.", *initialize_t_slacks); - exit(1); - } - opts->initialize_t_slacks = *initialize_t_slacks; - } else { ocp_nlp_opts_set(config, nlp_opts, field, value); @@ -708,9 +697,6 @@ int ocp_nlp_sqp(void *config_, void *dims_, void *nlp_in_, void *nlp_out_, omp_set_num_threads(opts->nlp_opts->num_threads); #endif - if (opts->initialize_t_slacks > 0) - ocp_nlp_initialize_t_slacks(config, dims, nlp_in, nlp_out, nlp_opts, nlp_mem, nlp_work); - ocp_nlp_initialize_submodules(config, dims, nlp_in, nlp_out, nlp_opts, nlp_mem, nlp_work); // main sqp loop diff --git a/acados/ocp_nlp/ocp_nlp_sqp.h b/acados/ocp_nlp/ocp_nlp_sqp.h index ed0b0a5fc9..6450a69e97 100644 --- a/acados/ocp_nlp/ocp_nlp_sqp.h +++ b/acados/ocp_nlp/ocp_nlp_sqp.h @@ -66,7 +66,6 @@ typedef struct int qp_warm_start; // qp_warm_start in all but the first sqp iterations bool warm_start_first_qp; // to set qp_warm_start in first iteration int rti_phase; // only phase 0 at the moment - int initialize_t_slacks; // 0-false or 1-true } ocp_nlp_sqp_opts; diff --git a/acados/ocp_nlp/ocp_nlp_sqp_rti.c b/acados/ocp_nlp/ocp_nlp_sqp_rti.c index 190ff6bfb7..cc666032e3 100644 --- a/acados/ocp_nlp/ocp_nlp_sqp_rti.c +++ b/acados/ocp_nlp/ocp_nlp_sqp_rti.c @@ -1097,12 +1097,6 @@ static void ocp_nlp_sqp_rti_preparation_advanced_step(ocp_nlp_config *config, oc // perform k full SQP iterations for (; mem->sqp_iter < opts->as_rti_iter; mem->sqp_iter++) { - if (opts->rti_log_residuals) - { - // TODO: evaluate what is needed!! - ocp_nlp_res_compute(dims, nlp_in, nlp_out, nlp_mem->nlp_res, nlp_mem); - rti_store_residuals_in_stats(opts, mem); - } acados_tic(&timer1); // linearize NLP ocp_nlp_approximate_qp_matrices(config, dims, nlp_in, @@ -1111,6 +1105,13 @@ static void ocp_nlp_sqp_rti_preparation_advanced_step(ocp_nlp_config *config, oc ocp_nlp_approximate_qp_vectors_sqp(config, dims, nlp_in, nlp_out, nlp_opts, nlp_mem, nlp_work); mem->time_lin += acados_toc(&timer1); + + if (opts->rti_log_residuals) + { + ocp_nlp_res_compute(dims, nlp_in, nlp_out, nlp_mem->nlp_res, nlp_mem); + rti_store_residuals_in_stats(opts, mem); + } + // full regularization acados_tic(&timer1); config->regularize->regularize(config->regularize, diff --git a/acados/utils/print.c b/acados/utils/print.c index e50ff4f8e4..8869763e70 100644 --- a/acados/utils/print.c +++ b/acados/utils/print.c @@ -464,10 +464,6 @@ void ocp_nlp_out_print(ocp_nlp_dims *dims, ocp_nlp_out *nlp_out) blasfeo_print_tran_dvec(2 * ni[ii], &nlp_out->lam[ii], 0); } -// printf("t =\n"); -// for (ii=0; ii<=N; ii++) -// blasfeo_print_exp_tran_dvec(2*nb[ii]+2*ng[ii], &nlp_out->t[ii], 0); - #else for (ii = 0; ii < N + 1; ii++) diff --git a/examples/acados_matlab_octave/getting_started/extensive_example_ocp.m b/examples/acados_matlab_octave/getting_started/extensive_example_ocp.m index 7b40a7f34e..163148e745 100644 --- a/examples/acados_matlab_octave/getting_started/extensive_example_ocp.m +++ b/examples/acados_matlab_octave/getting_started/extensive_example_ocp.m @@ -282,7 +282,6 @@ for i = 0:N-1 sl = ocp.get('sl', i); su = ocp.get('su', i); - t = ocp.get('t', i); end sl = ocp.get('sl', N); su = ocp.get('su', N); @@ -293,7 +292,7 @@ %% get QP matrices: % See https://docs.acados.org/problem_formulation -% |----- dynamics -----|------ cost --------|---------------------------- constraints ------------------------| +% |----- dynamics -----|------ cost --------|---------------------------- constraints ------------------------| fields = {'qp_A','qp_B','qp_b','qp_R','qp_Q','qp_r','qp_C','qp_D','qp_lg','qp_ug','qp_lbx','qp_ubx','qp_lbu','qp_ubu'}; % either stage wise for stage = [0,N-1] diff --git a/examples/acados_matlab_octave/test/test_ocp_wtnx6.m b/examples/acados_matlab_octave/test/test_ocp_wtnx6.m index 51f04defc4..9cb43607d9 100644 --- a/examples/acados_matlab_octave/test/test_ocp_wtnx6.m +++ b/examples/acados_matlab_octave/test/test_ocp_wtnx6.m @@ -462,7 +462,6 @@ % test setters ocp.set('sl', sl, i); ocp.set('su', su, i); - t = ocp.get('t', i); end sl = ocp.get('sl', N); su = ocp.get('su', N); diff --git a/examples/acados_python/linear_mass_model/linear_mass_test_problem.py b/examples/acados_python/linear_mass_model/linear_mass_test_problem.py index 95a27e9971..59b25ff111 100644 --- a/examples/acados_python/linear_mass_model/linear_mass_test_problem.py +++ b/examples/acados_python/linear_mass_model/linear_mass_test_problem.py @@ -165,7 +165,6 @@ def solve_marathos_ocp(setting): ocp.solver_options.nlp_solver_type = 'SQP' # SQP_RTI, SQP ocp.solver_options.globalization = globalization ocp.solver_options.alpha_min = 0.01 - # ocp.solver_options.__initialize_t_slacks = 0 # ocp.solver_options.levenberg_marquardt = 1e-2 ocp.solver_options.qp_solver_cond_N = 0 ocp.solver_options.print_level = 1 diff --git a/examples/acados_python/non_ocp_nlp/marathos_test_problem.py b/examples/acados_python/non_ocp_nlp/marathos_test_problem.py index da31b1e254..d94b138582 100644 --- a/examples/acados_python/non_ocp_nlp/marathos_test_problem.py +++ b/examples/acados_python/non_ocp_nlp/marathos_test_problem.py @@ -122,7 +122,6 @@ def solve_marathos_problem_with_setting(setting): ocp.solver_options.nlp_solver_type = 'SQP' # SQP_RTI, SQP ocp.solver_options.globalization = globalization ocp.solver_options.alpha_min = 1e-2 - # ocp.solver_options.__initialize_t_slacks = 0 # ocp.solver_options.regularize_method = 'CONVEXIFY' ocp.solver_options.levenberg_marquardt = 1e-1 # ocp.solver_options.print_level = 2 diff --git a/examples/acados_python/pendulum_on_cart/ocp/nonuniform_discretization_example.py b/examples/acados_python/pendulum_on_cart/ocp/nonuniform_discretization_example.py index 99237e1e51..d9d1d2dc4e 100644 --- a/examples/acados_python/pendulum_on_cart/ocp/nonuniform_discretization_example.py +++ b/examples/acados_python/pendulum_on_cart/ocp/nonuniform_discretization_example.py @@ -142,7 +142,6 @@ def main(discretization='shooting_nodes'): # set prediction horizon ocp.solver_options.tf = Tf - ocp.solver_options.initialize_t_slacks = 1 # Set additional options for Simulink interface: simulink_opts = get_simulink_default_opts() @@ -207,14 +206,11 @@ def main(discretization='shooting_nodes'): print("inequality multipliers at stage 1") print(ocp_solver.get(1, "lam")) # inequality multipliers at stage 1 - print("slack values at stage 1") - print(ocp_solver.get(1, "t")) # slack values at stage 1 print("multipliers of dynamic conditions between stage 1 and 2") print(ocp_solver.get(1, "pi")) # multipliers of dynamic conditions between stage 1 and 2 - # initialize ineq multipliers and slacks at stage 1 + # initialize ineq multipliers at stage 1 ocp_solver.set(1, "lam", np.zeros(2,)) - ocp_solver.set(1, "t", np.zeros(2,)) ocp_solver.print_statistics() # encapsulates: stat = ocp_solver.get_stats("statistics") diff --git a/interfaces/acados_c/ocp_nlp_interface.c b/interfaces/acados_c/ocp_nlp_interface.c index 0a043f631a..2900a9a0fa 100644 --- a/interfaces/acados_c/ocp_nlp_interface.c +++ b/interfaces/acados_c/ocp_nlp_interface.c @@ -528,11 +528,6 @@ void ocp_nlp_out_set(ocp_nlp_config *config, ocp_nlp_dims *dims, ocp_nlp_out *ou double *double_values = value; blasfeo_pack_dvec(2*dims->ni[stage], double_values, 1, &out->lam[stage], 0); } - else if (!strcmp(field, "t")) - { - double *double_values = value; - blasfeo_pack_dvec(2*dims->ni[stage], double_values, 1, &out->t[stage], 0); - } else if (!strcmp(field, "z")) { double *double_values = value; @@ -587,11 +582,6 @@ void ocp_nlp_out_get(ocp_nlp_config *config, ocp_nlp_dims *dims, ocp_nlp_out *ou double *double_values = value; blasfeo_unpack_dvec(2*dims->ni[stage], &out->lam[stage], 0, double_values, 1); } - else if (!strcmp(field, "t")) - { - double *double_values = value; - blasfeo_unpack_dvec(2*dims->ni[stage], &out->t[stage], 0, double_values, 1); - } else if ((!strcmp(field, "kkt_norm_inf")) || (!strcmp(field, "kkt_norm"))) { double *double_values = value; @@ -632,7 +622,7 @@ int ocp_nlp_dims_get_from_attr(ocp_nlp_config *config, ocp_nlp_dims *dims, ocp_n { return dims->np[stage]; } - else if (!strcmp(field, "lam") || !strcmp(field, "t")) + else if (!strcmp(field, "lam")) { return 2*dims->ni[stage]; } diff --git a/interfaces/acados_matlab_octave/acados_template_mex/+acados_template_mex/acados_ocp_layout.json b/interfaces/acados_matlab_octave/acados_template_mex/+acados_template_mex/acados_ocp_layout.json index 1b986b608a..b61b41b40c 100644 --- a/interfaces/acados_matlab_octave/acados_template_mex/+acados_template_mex/acados_ocp_layout.json +++ b/interfaces/acados_matlab_octave/acados_template_mex/+acados_template_mex/acados_ocp_layout.json @@ -875,9 +875,6 @@ "print_level": [ "int" ], - "initialize_t_slacks": [ - "int" - ], "exact_hess_cost": [ "int" ], diff --git a/interfaces/acados_matlab_octave/acados_template_mex/+acados_template_mex/ocp_nlp_solver_options_json.m b/interfaces/acados_matlab_octave/acados_template_mex/+acados_template_mex/ocp_nlp_solver_options_json.m index a5de988a61..ac292ac16d 100644 --- a/interfaces/acados_matlab_octave/acados_template_mex/+acados_template_mex/ocp_nlp_solver_options_json.m +++ b/interfaces/acados_matlab_octave/acados_template_mex/+acados_template_mex/ocp_nlp_solver_options_json.m @@ -60,7 +60,6 @@ qp_solver_tol_comp qp_solver_warm_start print_level - initialize_t_slacks levenberg_marquardt regularize_method exact_hess_cost @@ -113,7 +112,6 @@ obj.reg_epsilon = 1e-4; obj.print_level = 0; obj.time_steps = []; - obj.initialize_t_slacks = 0; obj.levenberg_marquardt = 0.0; obj.regularize_method = 'NO_REGULARIZE'; obj.exact_hess_cost = 1; diff --git a/interfaces/acados_matlab_octave/ocp_get.c b/interfaces/acados_matlab_octave/ocp_get.c index a3df79a49b..36f90346ea 100644 --- a/interfaces/acados_matlab_octave/ocp_get.c +++ b/interfaces/acados_matlab_octave/ocp_get.c @@ -96,7 +96,7 @@ void mexFunction(int nlhs, mxArray *plhs[], int nrhs, const mxArray *prhs[]) sprintf(buffer, "\nocp_get: invalid stage index, got %d\n", stage); mexErrMsgTxt(buffer); } - else if (stage == N && strcmp(field, "x") && strcmp(field, "lam") && strcmp(field, "t") && strcmp(field, "sens_x") && strcmp(field, "sl") && strcmp(field, "su") && strcmp(field, "qp_Q") && strcmp(field, "qp_R") && strcmp(field, "qp_S") && strcmp(field, "qp_q") ) + else if (stage == N && strcmp(field, "x") && strcmp(field, "lam") && strcmp(field, "sens_x") && strcmp(field, "sl") && strcmp(field, "su") && strcmp(field, "qp_Q") && strcmp(field, "qp_R") && strcmp(field, "qp_S") && strcmp(field, "qp_q") ) { sprintf(buffer, "\nocp_get: invalid stage index, got stage = %d = N, field = %s, only x, lam, t, slacks available at this stage\n", stage, field); mexErrMsgTxt(buffer); @@ -169,26 +169,6 @@ void mexFunction(int nlhs, mxArray *plhs[], int nrhs, const mxArray *prhs[]) mexErrMsgTxt(buffer); } } - else if (!strcmp(field, "t")) - { - if (nrhs==2) - { - sprintf(buffer, "\nocp_get: values %s can only be accessed stagewise\n", field); - mexErrMsgTxt(buffer); - } - else if (nrhs==3) - { - length = ocp_nlp_dims_get_from_attr(config, dims, out, stage, field); - plhs[0] = mxCreateNumericMatrix(length, 1, mxDOUBLE_CLASS, mxREAL); - double *value = mxGetPr( plhs[0] ); - ocp_nlp_out_get(config, dims, out, stage, field, value); - } - else - { - sprintf(buffer, "\nocp_get: wrong nrhs: %d\n", nrhs); - mexErrMsgTxt(buffer); - } - } else if (!strcmp(field, "z")) { if (nrhs==2) diff --git a/interfaces/acados_template/acados_template/acados_model.py b/interfaces/acados_template/acados_template/acados_model.py index d4193515a4..d8f0d93766 100644 --- a/interfaces/acados_template/acados_template/acados_model.py +++ b/interfaces/acados_template/acados_template/acados_model.py @@ -66,13 +66,13 @@ def __init__(self): """CasADi variable describing parameters of the DAE; Default: :code:`[]`""" self.t = [] """ - CasADi variable representing time t in functions; Default: :code:`[] + CasADi variable representing time t in functions; Default: :code:`[]` NOTE: - For integrators, the start time has to be explicitly set via :py:attr:`acados_template.AcadosSimSolver.set`('t0'). - For OCPs, the start time is set to 0. on each stage. The time dependency can be used within cost formulations and is relevant when cost integration is used. Start times of shooting intervals can be added using parameters. - `""" + """ ## dynamics self.f_impl_expr = None diff --git a/interfaces/acados_template/acados_template/acados_ocp_options.py b/interfaces/acados_template/acados_template/acados_ocp_options.py index b2b996755c..a3b13d7595 100644 --- a/interfaces/acados_template/acados_template/acados_ocp_options.py +++ b/interfaces/acados_template/acados_template/acados_ocp_options.py @@ -75,7 +75,6 @@ def __init__(self): self.__rti_log_residuals = 0 self.__Tsim = None self.__print_level = 0 - self.__initialize_t_slacks = 0 self.__cost_discretization = 'EULER' self.__regularize_method = 'NO_REGULARIZE' self.__reg_epsilon = 1e-4 diff --git a/interfaces/acados_template/acados_template/acados_ocp_solver.py b/interfaces/acados_template/acados_template/acados_ocp_solver.py index 052a637b1f..92a452e065 100644 --- a/interfaces/acados_template/acados_template/acados_ocp_solver.py +++ b/interfaces/acados_template/acados_template/acados_ocp_solver.py @@ -717,9 +717,9 @@ def get(self, stage_: int, field_: str): Get the last solution of the solver: :param stage: integer corresponding to shooting node - :param field: string in ['x', 'u', 'z', 'pi', 'lam', 't', 'sl', 'su', 'sens_u', 'sens_x'] + :param field: string in ['x', 'u', 'z', 'pi', 'lam', 'sl', 'su', 'sens_u', 'sens_x'] - .. note:: regarding lam, t: \n + .. note:: regarding lam: \n the inequalities are internally organized in the following order: \n [ lbu lbx lg lh lphi ubu ubx ug uh uphi; \n lsbu lsbx lsg lsh lsphi usbu usbx usg ush usphi] @@ -731,7 +731,7 @@ def get(self, stage_: int, field_: str): su: slack variables of soft upper inequality constraints \n """ - out_fields = ['x', 'u', 'z', 'pi', 'lam', 't', 'sl', 'su'] + out_fields = ['x', 'u', 'z', 'pi', 'lam', 'sl', 'su'] sens_fields = ['sens_u', 'sens_x'] all_fields = out_fields + sens_fields @@ -867,7 +867,6 @@ def store_iterate(self, filename: str = '', overwrite=False, verbose=True): solution['u_'+i_string] = self.get(i,'u') solution['z_'+i_string] = self.get(i,'z') solution['lam_'+i_string] = self.get(i,'lam') - solution['t_'+i_string] = self.get(i, 't') solution['sl_'+i_string] = self.get(i, 'sl') solution['su_'+i_string] = self.get(i, 'su') if i < self.N: @@ -1162,9 +1161,9 @@ def set(self, stage_: int, field_: str, value_: np.ndarray): Set numerical data inside the solver. :param stage: integer corresponding to shooting node - :param field: string in ['x', 'u', 'pi', 'lam', 't', 'p', 'xdot_guess', 'z_guess'] + :param field: string in ['x', 'u', 'pi', 'lam', 'p', 'xdot_guess', 'z_guess'] - .. note:: regarding lam, t: \n + .. note:: regarding lam: \n the inequalities are internally organized in the following order: \n [ lbu lbx lg lh lphi ubu ubx ug uh uphi; \n lsbu lsbx lsg lsh lsphi usbu usbx usg ush usphi] @@ -1177,7 +1176,7 @@ def set(self, stage_: int, field_: str, value_: np.ndarray): """ cost_fields = ['y_ref', 'yref'] constraints_fields = ['lbx', 'ubx', 'lbu', 'ubu'] - out_fields = ['x', 'u', 'pi', 'lam', 't', 'z', 'sl', 'su'] + out_fields = ['x', 'u', 'pi', 'lam', 'z', 'sl', 'su'] mem_fields = ['xdot_guess', 'z_guess'] if not isinstance(stage_, int): @@ -1392,8 +1391,7 @@ def get_from_qp_in(self, stage_: int, field_: str): Note: - additional supported fields are ['P', 'K', 'Lr'], which can be extracted form QP solver PARTIAL_CONDENSING_HPIPM. - - for PARTIAL_CONDENSING_* QP solvers, the following additional fields are available: - ['pcond_Q', 'pcond_R', 'pcond_S'] + - for PARTIAL_CONDENSING_* QP solvers, the following additional fields are available: ['pcond_Q', 'pcond_R', 'pcond_S'] """ # idx* should be added too.. if not isinstance(stage_, int): @@ -1440,7 +1438,7 @@ def options_set(self, field_, value_): """ Set options of the solver. - :param field: string, e.g. 'print_level', 'rti_phase', 'initialize_t_slacks', 'step_length', 'alpha_min', 'alpha_reduction', 'qp_warm_start', 'line_search_use_sufficient_descent', 'full_step_dual', 'globalization_use_SOC', 'qp_tol_stat', 'qp_tol_eq', 'qp_tol_ineq', 'qp_tol_comp', 'qp_tau_min', 'qp_mu0' + :param field: string, e.g. 'print_level', 'rti_phase', 'step_length', 'alpha_min', 'alpha_reduction', 'qp_warm_start', 'line_search_use_sufficient_descent', 'full_step_dual', 'globalization_use_SOC', 'qp_tol_stat', 'qp_tol_eq', 'qp_tol_ineq', 'qp_tol_comp', 'qp_tau_min', 'qp_mu0' :param value: of type int, float, string @@ -1453,7 +1451,7 @@ def options_set(self, field_, value_): - warm_start_first_qp: indicates if first QP in SQP is warm_started - rti_phase: 0: PREPARATION_AND_FEEDBACK, 1: PREPARATION, 2: FEEDBACK """ - int_fields = ['print_level', 'rti_phase', 'initialize_t_slacks', 'qp_warm_start', + int_fields = ['print_level', 'rti_phase', 'qp_warm_start', 'line_search_use_sufficient_descent', 'full_step_dual', 'globalization_use_SOC', 'warm_start_first_qp', "as_rti_level", "max_iter"] double_fields = ['step_length', 'tol_eq', 'tol_stat', 'tol_ineq', 'tol_comp', 'alpha_min', 'alpha_reduction', 'eps_sufficient_descent', 'qp_tol_stat', 'qp_tol_eq', 'qp_tol_ineq', 'qp_tol_comp', 'qp_tau_min', 'qp_mu0'] diff --git a/interfaces/acados_template/acados_template/acados_ocp_solver_pyx.pyx b/interfaces/acados_template/acados_template/acados_ocp_solver_pyx.pyx index 6f2105f5eb..9b8d718656 100644 --- a/interfaces/acados_template/acados_template/acados_ocp_solver_pyx.pyx +++ b/interfaces/acados_template/acados_template/acados_ocp_solver_pyx.pyx @@ -434,9 +434,9 @@ cdef class AcadosOcpSolverCython: Get the last solution of the solver: :param stage: integer corresponding to shooting node - :param field: string in ['x', 'u', 'z', 'pi', 'lam', 't', 'sl', 'su',] + :param field: string in ['x', 'u', 'z', 'pi', 'lam', 'sl', 'su',] - .. note:: regarding lam, t: \n + .. note:: regarding lam: \n the inequalities are internally organized in the following order: \n [ lbu lbx lg lh lphi ubu ubx ug uh uphi; \n lsbu lsbx lsg lsh lsphi usbu usbx usg ush usphi] @@ -448,7 +448,7 @@ cdef class AcadosOcpSolverCython: su: slack variables of soft upper inequality constraints \n """ - out_fields = ['x', 'u', 'z', 'pi', 'lam', 't', 'sl', 'su'] + out_fields = ['x', 'u', 'z', 'pi', 'lam', 'sl', 'su'] sens_fields = ['sens_u', 'sens_x'] all_fields = out_fields + sens_fields @@ -527,7 +527,6 @@ cdef class AcadosOcpSolverCython: solution['u_'+i_string] = self.get(i,'u') solution['z_'+i_string] = self.get(i,'z') solution['lam_'+i_string] = self.get(i,'lam') - solution['t_'+i_string] = self.get(i, 't') solution['sl_'+i_string] = self.get(i, 'sl') solution['su_'+i_string] = self.get(i, 'su') if i < self.N: @@ -710,14 +709,13 @@ cdef class AcadosOcpSolverCython: # Note: this function should not be used anymore, better use cost_set, constraints_set def set(self, int stage, str field_, value_): - """ Set numerical data inside the solver. :param stage: integer corresponding to shooting node - :param field: string in ['x', 'u', 'pi', 'lam', 't', 'p'] + :param field: string in ['x', 'u', 'pi', 'lam', 'p'] - .. note:: regarding lam, t: \n + .. note:: regarding lam: \n the inequalities are internally organized in the following order: \n [ lbu lbx lg lh lphi ubu ubx ug uh uphi; \n lsbu lsbx lsg lsh lsphi usbu usbx usg ush usphi] @@ -732,7 +730,7 @@ cdef class AcadosOcpSolverCython: raise Exception(f"set: value must be numpy array, got {type(value_)}.") cost_fields = ['y_ref', 'yref'] constraints_fields = ['lbx', 'ubx', 'lbu', 'ubu'] - out_fields = ['x', 'u', 'pi', 'lam', 't', 'z', 'sl', 'su'] + out_fields = ['x', 'u', 'pi', 'lam', 'z', 'sl', 'su'] mem_fields = ['xdot_guess', 'z_guess'] field = field_.encode('utf-8') @@ -874,7 +872,7 @@ cdef class AcadosOcpSolverCython: """ Set options of the solver. - :param field: string, e.g. 'print_level', 'rti_phase', 'initialize_t_slacks', 'step_length', 'alpha_min', 'alpha_reduction', 'qp_warm_start', 'line_search_use_sufficient_descent', 'full_step_dual', 'globalization_use_SOC', 'qp_tol_stat', 'qp_tol_eq', 'qp_tol_ineq', 'qp_tol_comp', 'qp_tau_min', 'qp_mu0' + :param field: string, e.g. 'print_level', 'rti_phase', 'step_length', 'alpha_min', 'alpha_reduction', 'qp_warm_start', 'line_search_use_sufficient_descent', 'full_step_dual', 'globalization_use_SOC', 'qp_tol_stat', 'qp_tol_eq', 'qp_tol_ineq', 'qp_tol_comp', 'qp_tau_min', 'qp_mu0' :param value: of type int, float, string @@ -886,7 +884,7 @@ cdef class AcadosOcpSolverCython: - qp_mu0: for HPIPM QP solvers: initial value for complementarity slackness - warm_start_first_qp: indicates if first QP in SQP is warm_started """ - int_fields = ['print_level', 'rti_phase', 'initialize_t_slacks', 'qp_warm_start', 'line_search_use_sufficient_descent', 'full_step_dual', 'globalization_use_SOC', 'warm_start_first_qp'] + int_fields = ['print_level', 'rti_phase', 'qp_warm_start', 'line_search_use_sufficient_descent', 'full_step_dual', 'globalization_use_SOC', 'warm_start_first_qp'] double_fields = ['step_length', 'tol_eq', 'tol_stat', 'tol_ineq', 'tol_comp', 'alpha_min', 'alpha_reduction', 'eps_sufficient_descent', 'qp_tol_stat', 'qp_tol_eq', 'qp_tol_ineq', 'qp_tol_comp', 'qp_tau_min', 'qp_mu0'] string_fields = ['globalization'] diff --git a/interfaces/acados_template/acados_template/c_templates_tera/acados_multi_solver.in.c b/interfaces/acados_template/acados_template/c_templates_tera/acados_multi_solver.in.c index a614204249..b849233326 100644 --- a/interfaces/acados_template/acados_template/c_templates_tera/acados_multi_solver.in.c +++ b/interfaces/acados_template/acados_template/c_templates_tera/acados_multi_solver.in.c @@ -2175,8 +2175,6 @@ void {{ name }}_acados_create_6_set_opts({{ name }}_solver_capsule* capsule) int nlp_solver_max_iter = {{ solver_options.nlp_solver_max_iter }}; ocp_nlp_solver_opts_set(nlp_config, nlp_opts, "max_iter", &nlp_solver_max_iter); - int initialize_t_slacks = {{ solver_options.initialize_t_slacks }}; - ocp_nlp_solver_opts_set(nlp_config, nlp_opts, "initialize_t_slacks", &initialize_t_slacks); {%- elif solver_options.nlp_solver_type == "SQP_RTI" %} int as_rti_iter = {{ solver_options.as_rti_iter }}; ocp_nlp_solver_opts_set(nlp_config, nlp_opts, "as_rti_iter", &as_rti_iter); @@ -2495,7 +2493,6 @@ int {{ name }}_acados_reset({{ name }}_solver_capsule* capsule, int reset_qp_sol ocp_nlp_out_set(nlp_config, nlp_dims, nlp_out, i, "sl", buffer); ocp_nlp_out_set(nlp_config, nlp_dims, nlp_out, i, "su", buffer); ocp_nlp_out_set(nlp_config, nlp_dims, nlp_out, i, "lam", buffer); - ocp_nlp_out_set(nlp_config, nlp_dims, nlp_out, i, "t", buffer); ocp_nlp_out_set(nlp_config, nlp_dims, nlp_out, i, "z", buffer); if (i Date: Wed, 10 Jul 2024 15:47:36 +0200 Subject: [PATCH 06/14] Remove main mex template (#1149) These files are outdated, there were used to test the template based solver in Maltab without really interacting with it, before the MEX interface was completely ported to the template backend in https://github.com/acados/acados/commit/bb9f1b299d5d62cd0aaf515544ebdc520cbaba2b These files seem to be broken from what is reported in https://discourse.acados.org/t/building-issue-configurationdesk-2022-a/1677 --- .../render_acados_templates.m | 10 - .../matlab_templates/main_mex.in.c | 181 ------------------ .../matlab_templates/make_main_mex.in.m | 103 ---------- interfaces/acados_template/setup.py | 2 - 4 files changed, 296 deletions(-) delete mode 100644 interfaces/acados_template/acados_template/c_templates_tera/matlab_templates/main_mex.in.c delete mode 100644 interfaces/acados_template/acados_template/c_templates_tera/matlab_templates/make_main_mex.in.m diff --git a/interfaces/acados_matlab_octave/acados_template_mex/+acados_template_mex/render_acados_templates.m b/interfaces/acados_matlab_octave/acados_template_mex/+acados_template_mex/render_acados_templates.m index 74d33f68ce..2e26308bcc 100644 --- a/interfaces/acados_matlab_octave/acados_template_mex/+acados_template_mex/render_acados_templates.m +++ b/interfaces/acados_matlab_octave/acados_template_mex/+acados_template_mex/render_acados_templates.m @@ -72,16 +72,6 @@ function render_acados_templates(acados_ocp_nlp_json_file) out_file = ['main_sim_', model_name, '.c']; render_file( json_fullfile, template_dir, template_file, out_file, t_renderer_location ) - % make_main_mex - template_file = 'make_main_mex.in.m'; - out_file = ['make_main_mex_', model_name, '.m']; - render_file( json_fullfile, matlab_template_dir, template_file, out_file, t_renderer_location ) - - % main for matlab/octave - template_file = 'main_mex.in.c'; - out_file = ['main_mex_', model_name, '.c']; - render_file( json_fullfile, matlab_template_dir, template_file, out_file, t_renderer_location ) - % make_mex template_file = 'make_mex.in.m'; out_file = ['make_mex_', model_name, '.m']; diff --git a/interfaces/acados_template/acados_template/c_templates_tera/matlab_templates/main_mex.in.c b/interfaces/acados_template/acados_template/c_templates_tera/matlab_templates/main_mex.in.c deleted file mode 100644 index 851a3cc04f..0000000000 --- a/interfaces/acados_template/acados_template/c_templates_tera/matlab_templates/main_mex.in.c +++ /dev/null @@ -1,181 +0,0 @@ -/* - * Copyright (c) The acados authors. - * - * This file is part of acados. - * - * The 2-Clause BSD License - * - * Redistribution and use in source and binary forms, with or without - * modification, are permitted provided that the following conditions are met: - * - * 1. Redistributions of source code must retain the above copyright notice, - * this list of conditions and the following disclaimer. - * - * 2. Redistributions in binary form must reproduce the above copyright notice, - * this list of conditions and the following disclaimer in the documentation - * and/or other materials provided with the distribution. - * - * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" - * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE - * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE - * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE - * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR - * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF - * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS - * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN - * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) - * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE - * POSSIBILITY OF SUCH DAMAGE.; - */ - - -// standard -#include -#include -// acados -#include "acados/utils/print.h" -#include "acados/utils/math.h" -#include "acados_c/ocp_nlp_interface.h" -#include "acados_solver_{{ model.name }}.h" -// mex -#include "mex.h" - -/* auxilary mex */ -// prints a matrix in column-major format (exponential notation) -void MEX_print_exp_mat(int m, int n, double *A, int lda) -{ - for (int i=0; iN; i++) - { - ocp_nlp_out_set(nlp_config, nlp_dims, nlp_out, i, "x", x_init); - ocp_nlp_out_set(nlp_config, nlp_dims, nlp_out, i, "u", u0); - } - status = {{ model.name }}_acados_solve(); - ocp_nlp_get(nlp_config, nlp_solver, "time_tot", &elapsed_time); - min_time = MIN(elapsed_time, min_time); - } - - /* print solution and statistics */ - for (int ii = 0; ii <= nlp_dims->N; ii++) - ocp_nlp_out_get(nlp_config, nlp_dims, nlp_out, ii, "x", &xtraj[ii*{{ dims.nx }}]); - for (int ii = 0; ii < nlp_dims->N; ii++) - ocp_nlp_out_get(nlp_config, nlp_dims, nlp_out, ii, "u", &utraj[ii*{{ dims.nu }}]); - - mexPrintf("\n--- xtraj ---\n"); - MEX_print_exp_tran_mat( {{ dims.nx }}, {{ dims.N }}+1, xtraj, {{ dims.nx }} ); - mexPrintf("\n--- utraj ---\n"); - MEX_print_exp_tran_mat( {{ dims.nu }}, {{ dims.N }}, utraj, {{ dims.nu }} ); - - mexPrintf("\nsolved ocp %d times, solution printed above\n\n", NTIMINGS); - - if (status == ACADOS_SUCCESS) - mexPrintf("{{ model.name }}_acados_solve(): SUCCESS!\n"); - else - mexPrintf("{{ model.name }}_acados_solve() failed with status %d.\n", status); - - // get solution - ocp_nlp_out_get(nlp_config, nlp_dims, nlp_out, 0, "kkt_norm_inf", &kkt_norm_inf); - ocp_nlp_get(nlp_config, nlp_solver, "sqp_iter", &sqp_iter); - - mexPrintf("\nSolver info:\n"); - mexPrintf(" SQP iterations %2d\n minimum time for 1 solve %f [ms]\n KKT %e\n", - sqp_iter, min_time*1000, kkt_norm_inf); - - // free solver - status = {{ model.name }}_acados_free(); - if (status) - { - mexPrintf("{{ model.name }}_acados_free() returned status %d.\n", status); - } - - return; -} diff --git a/interfaces/acados_template/acados_template/c_templates_tera/matlab_templates/make_main_mex.in.m b/interfaces/acados_template/acados_template/c_templates_tera/matlab_templates/make_main_mex.in.m deleted file mode 100644 index d217948456..0000000000 --- a/interfaces/acados_template/acados_template/c_templates_tera/matlab_templates/make_main_mex.in.m +++ /dev/null @@ -1,103 +0,0 @@ -% -% Copyright (c) The acados authors. -% -% This file is part of acados. -% -% The 2-Clause BSD License -% -% Redistribution and use in source and binary forms, with or without -% modification, are permitted provided that the following conditions are met: -% -% 1. Redistributions of source code must retain the above copyright notice, -% this list of conditions and the following disclaimer. -% -% 2. Redistributions in binary form must reproduce the above copyright notice, -% this list of conditions and the following disclaimer in the documentation -% and/or other materials provided with the distribution. -% -% THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" -% AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE -% IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE -% ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE -% LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR -% CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF -% SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS -% INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN -% CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) -% ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE -% POSSIBILITY OF SUCH DAMAGE.; - -% - -function make_main_mex_{{ model.name }}() - - opts.output_dir = pwd; - - % get acados folder - acados_folder = getenv('ACADOS_INSTALL_DIR'); - - % set paths - acados_include = ['-I' fullfile(acados_folder, 'include')]; - template_lib_include = ['-l' 'acados_solver_{{ model.name }}']; - template_lib_path = ['-L' fullfile(pwd)]; - - acados_lib_path = ['-L' fullfile(acados_folder, 'lib')]; - external_include = ['-I', fullfile(acados_folder, 'external')]; - blasfeo_include = ['-I', fullfile(acados_folder, 'external', 'blasfeo', 'include')]; - hpipm_include = ['-I', fullfile(acados_folder, 'external', 'hpipm', 'include')]; - - mex_names = { ... - 'main_mex_{{ model.name }}' ... - }; - - mex_files = cell(length(mex_names), 1); - for k=1:length(mex_names) - mex_files{k} = fullfile([mex_names{k}, '.c']); - end - - %% octave C flags - if is_octave() - if ~exist(fullfile(opts.output_dir, 'cflags_octave.txt'), 'file') - diary(fullfile(opts.output_dir, 'cflags_octave.txt')); - diary on - mkoctfile -p CFLAGS - diary off - input_file = fopen(fullfile(opts.output_dir, 'cflags_octave.txt'), 'r'); - cflags_tmp = fscanf(input_file, '%[^\n]s'); - fclose(input_file); - if ~ismac() - cflags_tmp = [cflags_tmp, ' -std=c99 -fopenmp']; - else - cflags_tmp = [cflags_tmp, ' -std=c99']; - end - input_file = fopen(fullfile(opts.output_dir, 'cflags_octave.txt'), 'w'); - fprintf(input_file, '%s', cflags_tmp); - fclose(input_file); - end - % read cflags from file - input_file = fopen(fullfile(opts.output_dir, 'cflags_octave.txt'), 'r'); - cflags_tmp = fscanf(input_file, '%[^\n]s'); - fclose(input_file); - setenv('CFLAGS', cflags_tmp); - end - - %% compile mex - for ii=1:length(mex_files) - disp(['compiling ', mex_files{ii}]) - if is_octave() - % mkoctfile -p CFLAGS - mex(acados_include, template_lib_include, external_include, blasfeo_include, hpipm_include,... - acados_lib_path, template_lib_path, '-lacados', '-lhpipm', '-lblasfeo', mex_files{ii}) - else - if ismac() - FLAGS = 'CFLAGS=$CFLAGS -std=c99'; - else - FLAGS = 'CFLAGS=$CFLAGS -std=c99 -fopenmp'; - end - mex(FLAGS, acados_include, template_lib_include, external_include, blasfeo_include, hpipm_include,... - acados_lib_path, template_lib_path, '-lacados', '-lhpipm', '-lblasfeo', mex_files{ii}) - end - end - - -end \ No newline at end of file diff --git a/interfaces/acados_template/setup.py b/interfaces/acados_template/setup.py index efd0a973cd..abcff1aac7 100644 --- a/interfaces/acados_template/setup.py +++ b/interfaces/acados_template/setup.py @@ -81,8 +81,6 @@ 'c_templates_tera/matlab_templates/acados_mex_solve.in.c', 'c_templates_tera/matlab_templates/acados_sim_solver_sfun.in.c', 'c_templates_tera/matlab_templates/acados_solver_sfun.in.c', - 'c_templates_tera/matlab_templates/main_mex.in.c', - 'c_templates_tera/matlab_templates/make_main_mex.in.m', 'c_templates_tera/matlab_templates/make_mex.in.m', 'c_templates_tera/matlab_templates/make_sfun.in.m', 'c_templates_tera/matlab_templates/make_sfun_sim.in.m', From 7aeb5524656dcd5fce6e7ce68f2e04270905f9d4 Mon Sep 17 00:00:00 2001 From: Katrin Baumgaertner Date: Thu, 11 Jul 2024 14:43:01 +0200 Subject: [PATCH 07/14] Update problem formulation description (#1150) Co-authored-by: Jonathan Frey --- .../problem_formulation_ocp_mex.pdf | Bin 134912 -> 135407 bytes .../problem_formulation_ocp_mex.tex | 88 ++++++++++-------- 2 files changed, 51 insertions(+), 37 deletions(-) diff --git a/docs/problem_formulation/problem_formulation_ocp_mex.pdf b/docs/problem_formulation/problem_formulation_ocp_mex.pdf index 94ee678c3547d087b6d0fda0be8e43d2fe216387..2a683b58006fe17976184418d73d36699d4dfec8 100644 GIT binary patch delta 51065 zcmZs?V|OlG&}JLkwr$(CZQJ%8+qRP(+sTe?+uE_se){ck&gc*QY1I!{qgGvW)(Xsr zx-EiAqyXV!N;zPm0$l6My5e>s_g-pFD{rp!3mxTE9XITD&HE#FS<*DCFePq` zxWBxs<(>q)27H_w-M;|{c}*MhIABD0qvBcyPQ{z6r??S}zR#~uzI-^S4Grl}6_?&!8vUjV z$~{*iVtoDlxpmvUwA37LWQ7T*Jbw?ff3LqOzsRc?1Ly&QI~x4{`qLIMj!WTee4%`0r;<#E#HQRng9DsmfX&z}lz#aSw7czP^}E6Dw2Bp=MN zywY{rfXxKoUJGZ?+Y{Hj(Z%3L-_%va^cPPPw2@fWF_v~=R1H{v#o5{h8fFfnT8a99G4J6*5u#vx_XKadQN88wDPJ}Xu!zlC^~5wdpe zWvj8SoTEh|e7dr=BoTHEOzTpyF(Pu+ViSgB9Rv9{{20TuEFtw!n}8p&i-i4(PFq?5 zfR=yaxHZ%TX_>;87|U;2@z|qa$^Hop4OVNh9Iun!WBIqVgeqLeEk3;_LcvKrS#Gxe5`->XNQb?dyFZN4n3E^&BEgnzJ}7 zbSQJeELMeeFy-^2s4j|9WN}=54z;NG4*mT-O9!4w7z@rD{YCSBo41$}m-W5T+hG&B zhJG8oQ${ByWMMQ;JdE@twkeO5WI$BZAvk*Ln#yzq710`jIg(js679l6HBt`^@C2la zrKe{0H-?FIN_04qVv!|KA~qus48BV=lB;}$BP23AjgERKICSiSDYEj>I@pc5YpLeU z;iXLG#oTbZ*A4Tt$!ad91A7xXnpz8lT^7NYG@WFHD!zZ^&3(jP@+!WVYiDK>q=%YX zZJ&i-rDk2H6q!sn#AN1u$|6JskVO%*g!NhU2RR@{@*0nHtsjnu=gGJ0MY}}KDkL;W zd0=e0xTUdIXmFXwd5I#*J}ESmSQwJtrtA7o$b~mdRB1@vtV63QdwIx*mi@jhTTon> z>RG>xO{>SX$#r(hPN1H%T6V+y{ynf;7vWvT`;#>e2jyVSuik8W%GfMC0C+@fEj>_q zngqh7D6>B3Wjr6N5d*?|ndkcZyAu*~;Px=r8gyKxn~!U=AegF*fN!$WW~2j-AG+m+ zXT?2@E?Q*(EeyPd0z*gS37z><3esK}oJ8dJgksW1B?v)sfY$!X8 z_0iG%pMV#&PcBv{#CTR6fGwewY!LiC$>5y&(5+d;oH~o@^3Z`_xpr)@iN*LhT=$_o)@Q~ zo}x-5S@U4bx^ng;+qTCU|2h+A-ZZ-1pH12DJae7!uii`5Prm6Uz~zE(cf5|n#7bxb z^I)8V<}i~Smfecgv5=jsR)^>{$Cbo#-f(OQR?dtVJPgr?iNp>LYk4?^{;5yQC24I} zMTYzi{L55z@JM(^iJMis83!!PMTbe_^>i>!i3vtEv&Fx5GlekHzflmvhVW9XUX4mk z?Am2)i-sYLPGAh}fQb5a+JKz^;YQW3&9xB2cFeCT0~r*Qic9?fg)Z{h@5_OgrcsZF zLXvr0%!Eae{<}0NUmF;n^R=q@LWg$Xedq^t(B1|fsZQ8u75iA)J1qUHN-VfCvB{2r z@7u2j2cH#uJ0Zvf6s)gIw)r=iI+%>ayQ%XX{?-s8vLz@w01sqe$X7!uEt+5wI(EQg zRd5a6S9B%!KOa<^pJK?MUP$DKrnv}==M(OC;0s~|qXO4Nrw>UUO2;*lM^~2&Z5GJ# zcP(q8;3A(Lpz&IwW*3Np2}=(Go-!mWu2tWitt(G4*PM{mIxV>!3;43M5e^LmEJ4u{ zn#ZM+C41R3z`MQ9uXWoSMO|wHsF-xxEn-$hl6$_guSE zxfDa3`3mGn&?nm!227Tmt`j{yj?~V$w`XZHx>k8CV1ub(hp95WNLLw2CCj2lj(s`H zrU@553gkA4k%VssYzN0|}y4AX|BftQOUGWeJ|iI+)iW!#+EHgeM=QYIHj zin!}4kZSZ0r!eA)Yj4bl?C-%2C1tQ*(O$i zCiLPNFxfLRKkn|Wbgc(7m*e3jQ-43zyA|?KY*scE0%P4kI~VH_a{vBAm$99^ix`IK zGq>MlyZBAZ!Imxd*NXeY9W9_!rj36$u_Y_UY|C?9ICSG3UjMW5tMF@AU{S1JS-jJ0 zEAmwzp;Ib+7+1xSl0s(i&!xVfil|LNOgU96_V2|mg3@(NL>MNv!jCVxCE zZaZMOFDa6W2~=@9x>cz5`0x|3tk!HSGx__^9kAbX18fs?rUSBNC`*Kpaj&0zHHv8r zSP06UbdW)^x?6&_P|t1guil_#kh7jEq7`^iDZjsOaHGt+b{k3RNlNY{J=;CgiVzw>DG@@xwK0i2ulZJ01-Xcyo%jQ?!H55*i#y46{5FOI@W-UdT~br3v+=6 zbCiOT2wNlr3o~8qbq2d2o!pZ{Nh3qI`Mpw)DU}hRAReQn*11);t`Ff@#4(Bl zD#3p=VHIlMHkv~rP4e#pW){vww}U!!;I5sSuNvz_kphgEMRuG(ckCWPX^NG$H&LqR zXMfb4AN2-{4ERGZKD!1)36Q(v7dy^7K`0=t?HiSEBOI1fc%LWw;1|XtKHg(at0oM| zI5jeSwz|fy@ga(ORknz)wDIA6!~bS4VWQe%iPT&ZAuM(Zb0lg5a*C!m`t!`S4dUoyZ@D=eRFEYvj<>6gj3_-S6v|+FhB}NW zBI!wtWYy$5H|Iu!FW>j{#y2~3)~=eIngvT*ij@b6fAZRS-~SF7=Xz5CZgN4$lZ)cV zyMJ9-DQu;Z$(%V4I&%`sOQ4yJn+opo3`Jups0NDz25&*osK{v!BgoE3h@(&@nT3l6 zq-9V!E6=#m#mZw3$rQ+rV$jK%PsU!Gi<8Kbq%dhQkVjKQmmiv}s$6_QIHiqMi%mP> z55w(p`{i>7>A9nDd4qHTe2^R*LACIM5~jt0Z^-LS*R8!ZEGfMEr{e^1fq+%fJAnop z5w!1_@m;jxS79V^k>aO{tLw?um*n=jD!V_p`YXW4D(vaK{ziMrPAk>yuvfg~QEG~X zE}sooWJHnMj=TXz6>Zu-rq?h2;Ke4m9 zVNe?=1m2UrP*kXMUARdKXIDNR`@G?Zfn^9GkTjs9M_m;_-b>^~|FoJwkW;IqTEtLM z45c<>DG!XIG*(2#mn0y^aUIQ^&(Um|MUnM*&t~kEoZk&c9?97qfF18~&jW zH60)rVNKY8Tpy|5PG(&?80s!Nj^2gUE|*%Lde=veVv)5JZoBvEg1rvPa;HA65>|2D zwjH_VrGM*apa=fy1`f}&eOjJi{mj9-+q>OAo6FvSGTcXldR`AX=W7jd83)UItr;s3 zl~vO|+xEDPqdG4%#!Go^4yk=&5^4-M^H-fVL+$}2m}&BCY#Fty6I8A_muXgU6MF=< zV;0x%zYCqc?5!S(wWf2?qwol2vbpClQfb}=?B#S&PMKm;Yhk{~61XYtTQxi-sSLnQR)%8+5op^sMy$f4av>UP_U4zcO>F=jMV1I|B zhUMGD15LVm)?3(%2hftM`37oi(aHc!AW&TZ(?F*u3Rc~#PY2ijJt`hhglLyqX`yAI z87&dDWArEUtajcw%Ng?)za@>&rklMSEtYxvP2brVco@NsiW48AKz{gQM}}7XSbWE~ zublj1GHJOm)`e*t7{!MXZ9IC$Sq*5zANU^@uRuT_)ZJj_8`9YAzOF z&^SLA4X<1(`z0rIC?-uW03OmK{_W0KP_w}nQ3z5@wQJAT^@!3OAygltet?kC2M@$F zO@-0t2TLyg->5MBBrXzOiKGARQBvK&OSa%Q#=+w~6Z#&~WhCy*_KS|KIiFF>2yWAUps?a0yo z^OhK+KT`EWC|mh>KTh7eT9}L{Bs$^3<Zca5V z(q(a@1XOVx^jlv1=TcLcTLCVH`4P^CLrSZ=X&B+>?3j?L{>4z|nF`Ah zwYk8AUAsWN8;6--4f}Bct|FhALPsP~6qmIUPW*!bRs~h5C-?4ODJIm_bg&S<4Uar^bh9ACU}@;v4Ryy292zpT^n)abyed)M5Aex z)-Y|$-uqI7;!Fc4PV)x9k1nub{+fUL9dMa*_IDdg;f7AuQdXkH_x6FW;Sbp0HCr1E zzNEmB*ZaqaX3#a1lxFd6S*^T>zDewJ;_2jEF5cv;<7|b_&rwcFC@1;wvK7W(m>Vi(WkMzhKF>XcmjnS`QL@Iu+eT{J#GlcF0{2s4-Gw1J1q z*^!+aQMdmQVkeE`X9&2uosiU1*S{bWf$7jb2hb8YY$PjK>2TWt^f)13gI&yx*<)hZ zFp(KMsk0&N{%nzA&Al~v2`aVwlP=$#cq6xKopO((M67Ta_cw>S2Vm_R$rwux9$CJoANGWk#nqy3n%?PVcIRY z_c5`WV`rpEpo*#jHHP9Q837$j7Y^!})dV*U3HCyv$!6YwoSn5gbU1r*QWGa}R?@A1 zSdk-BnE1vGixivz0|>pw>Yu#Sj6!?BA@pLIM~&N6E9B76$N$3QGbP2{67MQD_4~88LdtFL|mCb^YrH{A|(&Rp^XYt^t zYg*w&`8nm=GpgI1{@pbIRW5f#yP?+zN#x2q3@RN1M2RiosK1X-?Oz}@3igXH8I+cf z6FZtF;P1DnV9+^FxL`j4mR0a9WgTDMS%*alTL_sbjc?>hn~<<4)az5ssznJvn$BQu z>p?;OAQOkAD%0gnCDMI}HJB+>=ZznQ&D?KqAcAQ4Lr&ey?-n{l{XM(BDM>k@yRxxZ zhCMz2r22#ypbUSHdC3?3^~3F@$Ne4bhJ=7P;48K~^OdtA^&Gvz{V|kDe_T;Ty$t9q zzLyyG-B=ADXe%Vb}FTBFIHGZOl>V;`<4H>x3^etzgjFeZkLXdSg2J-syIo2vU>lDiI@Vd zx#p)7v6PC7jaq^o7?^wHhB4u7UCalKTMyFqScOU-*W>75ZS#kWK`^$N?>|4GOIXR=nr=TXlB=?3kh5^)pR+`ap^j z15XOej)@G)l9hGJe^@!0{tDb21+sy~S>OCk5vmO!mqAv;|HT`Y zUn!Re6-{;XMZGx3`(wuf*H`xyNMGP5xW8k8yWXJ5-&zL!PO@;^vqaAIFCG@fdLetjv!X!fQ(RkoGKH{`oXe^)LkJg&Whp2{60s;~5rp z+*t?SJ_A>xAX5d5EZ!00rJ%3-{l+iQ7eM1Rg#?ERl$nj|e*(@7?u5$`$IDIqd@jja z3)4DqIZZ?0RZZZ9=R4Iwd^~vR9LlPJ`y~lQxVyF?2a<#EQwoR4R!FH!0T9c}`Q7V@z8|?n11>-nQm@S1xBp zpTXZS(Pc7G5f^|B!axf4f)wnz!dq9>mU&~CJzvghPFoEvCj;)Qz3m$e-;Uj-;z_Yn zO6Mn?PvPCAkLJwh_ce>-j#ZxHm$rP)kV#Am321J`aU=?Ghj#8w7dgsAtYx}~SY!S) z6-jcJx_K~Hbn1S}K(Qu-H*?;adUvfR^t>GLG|zZ9nHhj#S$Z4_jt<> zUT%{E`c8$ovI!_41x%62pYQF`{_l&N;i|i?2Iq~YI-?58Je*oEINu@?S-NqMIt;Cu z@4DG&tB4ruJbf?=@pe_np+)4~A8Fmj0h;KFGo=sT2-m(q(!BeIK(feWsY|=@whtUA z)p#b}ifBOhY8-^08sxi_Q#jh3L@ZcMMC>rpJbw*jlaSL6=wdxy2MYQ)qU-Cq!~}QKjPe+PiE=T!?GOOCot!=i#3fIhWMN*WlZm&2`#MNC zFe}-+83oj!Fm*ixEBlOK-IqS8p}}k>$=}ze=9oi%Jgqc|jaulxZ!Z^z?XVz7_n~rZ zlA+O2rFhJvl#kCNjD3d_AU`i2!AXwT+5XiN-7&ugex~?Wi6|m7#y%v_ z^8$e3#`R$46P(NQZjY@EAg2g*U7V{}(3w<>B~I_lTT9MOE>AGeA9$UTpfHZ42~ zAX+hN4vIj_4=&)OW7c3QJEW{Y+|Sv_$%($jLJX`xpz=z>{~inj6$EN-C-@ zF84Uo6WSXPJBugA6t>BCx^m2F%wLNG(9mH;{%7Yh`);0t|PgV|I8nQ##F(L*$B2s1U zS{9a&c3?s7MI&!S?S8u)Hr>b+sZpjSA2g9heMPe)28w%n!#Aqroy0?G_jwYt=N`rL zCNcLhqIZAmFGn2Iy{7C+gx&_t8gT$4@~$DSXccer<|n;Ih^__nUU?+pJLBiB5Ku}T zMq)*=@4j#ODoF@SG*WJVl9z ztWdv+BFUIke*XD)=hO!&A&bAneeG!psKuNcGzsE_bOj0W-*sE&+=d^IgL*(+w$Wj8 zq%o=N6#D}3mV9-iegqHGdPM+%ei#Hs4dEe2_h~Yg;SaORQqY@*_ryU-s$p_oP*U$J z6{@?8;yDsMHBbQ=(YXR za&ECW#_YEeKWo!xtFb|KJoJv6vY*}DfGV7`ie<;fiz%|qyP%p3{T*+SI*nQW7gOJ@ zHN?Dwy2N^>iXi2=rI!X^MV=KtgrQK7&t#E~<-wR!t_kAvCd(*IoXhG0N*Nv>42tH=kg<(QSTNCa8n2QHpR;u^Ldz{ zcCvg8Z#nL68h&mP&2=IDqIfY*YW2+|sMp3-Z<>k$QZW;5#FbL5{$|^@go_((rIko( z?~k@C?)pRKS=hJ2l$&ZV>QP-3pAVcolR@WZ%uJ*l{yTsXV>t9NURoN(s&qpjt$+M4 ziu9{GU&_gCeI8!~L|XYl>SwZ-Ad2@oe_W)S8H^7E<~w5ea+`<@SYcfc|8LPQ28DVT zS?GFu0QH~O=UKQ+MMtvZ@Ej8ZgFQ;xAulZiPncXEk0~LPuDOis_ckb_ctmLbuYJg6 zclAP4fmi^Z!g6KY2xN>3VgLwQU~X`kO1SqI4uLn4B+(;uVbO9~Khra{;kBL%EFNOQ z64N$&fbfmycKsT-8MiCvC%^k%V$J|eM$fJx%IM4yafs+{+NDdHqoxCkdR`&UTXK?= z1ES@){cmX&P%EmR8FelR86!{#=}03g{Mymvgec&FXtrO<6UQVi&3yaxkj}K%$jl-Z zYdUsjc4j!R(qor->FdPzu)Hf8C^AeHM{si^EhIZ=!^jo_V|{Umlf0pcMI02CrQe7n zEB~E_pCFVe-<@L4AsIb}&{mbxNbPf%h_gxcw9G_bEzXyM3BVMG6$0Kh1Qbr3r^tVR z9Re8oh;~Zx>qe!M)$dujd_6nFw<9s~zb}@@8x8~|^HJux56$mAz)l*AY61@oB`l%K ziV){=39ZEXXza_?y61wvNfu+S`K5ynzMlRVYq3eH3bOg60*FL@WFn2l`z08#$BxC% zPvwW~&Q5N;O1QFOhOy$Vx((bWQ2(hOhy$qld>kYNsl31ow-wMgL3uANyQ;?Oy%Dfg z4Zz*6H16N1?4MO|)>{3uy1SF_@LoQYo&!Xg z-{op`QbMwxU=VXWha<>hR?$TL@Y2*K^_qijlYe$rR6fED@O%U=@U8=v*Q51B!`#N5s?(LMe zXDX*sTP?-H&0pI&We(T9(!5(^-1eb$AYEwY4+x5S|Fvt z`kl`@xqoZ)C5)33a})+f3y^uVjW)^l29=eE(rSNMfI1ZXtpg|hRDsyTg`%M4{K~We zW35EL{FFVl_M|+58yA*ybCV(RioDQ-1_t{5gc)k4m3O4Fi~1ozE-latd#J8h`Ya}=A=@@#QLa7UgR*}^EHrk%~tCkn)#tO&;KPz zkqfOmlM;t&muDAsZ^0N&=#PYR3m+j6F%huoSZzeP%y6(WShVL}e*D2)UlUx#3;;2H z!GjV!*}ZvAZ_b$9j{qCo1_)yLmB;kQ6ZbfZjLNfq|5DVVLQ2T9&IOQ5$fthLop8Mp zB1-gFkScxJ$zY;9RXCDq&vxrA&-_gA#W;aFI&IO0DzV_@-H}A!TXz>TeW*^^*$q3`8kRl0h`|+9_>x^HVt0- zEmJJX7hBGxN(7s}56@LrUxvTmAA&{F>o1}ih#>)bnD>Y;8t$#t zGF;BrzN&b6OkEr4uw#BU*}w3&@~mCQMNu1qFkc9&HL1j`bc;yfs!bigq_~S)JRD}`aQEqbot#rzxYU%+q{lup zs|3|dK^Fc$v6Ck9k0_chI>+emD&dr*sZJ)lmkf9{;|Fb5-IbzNstXq8;*;Ss1Hu@S z&RSGcm{@9F0Ck4BDns^oN0)U3&5@Kb@qE{YBZhoyoNMLnr1&$cd6V8~ev&9MLA8x4 zM)x{HOuF>Lo{NHu;wce7I=BlVUd9Uz| z;>Pux{%?nFZH=7QgQXdd_HY97f6ahk2T#M56Wp^jKvTZ_PRfm@_>uVFXYWmi8)+(H z=5x7L>(NS*B-0YtykHwVod-i@_DZ$M{jHFTX0f4aT7Y!ncT(&;3!khXaI*%7H!v!m9C0i@mEYXg?~? ze2^w8fVqWc#_DwRrTUjC} z02#2;`-$pjG7xH~Qi(R?$O7ab9w#nA7;JwNG?k}!s^NzLxS>t5;^2`Uoh~fz-Sh=c z$~u}M&_HbZXO17{exO&LL7)>bOYB0-x}szxB10HpNj64c(CK_2(Ag{T@ewTL^02UNU|6UZ!m@yIgAQl81p8S;DX*iQV9K^nW zcK{m1v@=#iDD^iUoLu?8Oq9w;XEgmkr+=c5BL2MA`Cs&If9kGDf`_M1p1ihqaJZg6G|gJVYfFIvsH$6^wnl9q}h3 zv<61Ry|`D}32At9mhx2^fv=s?74Vjc1a^~g8AMb;*SX&;SZ*hcI%QuTg^XOap&D@- zPOLk@TEwl_uYj*Z9Abs9gM46rsN{C0MSV~^hB#3ICn_T9vTR)^;sA_AEYf-sLZNrI z_uGsE$ghD7rksuumgGYT*i*JHu5DQm;wsD`ZE8ruj`ITUC^`d6!a9$91TcVphz7$B zsv`PVPDs`C63AN=pveh8fh~BkwCo9RF=4-K>n&R`5T>{qM`A)3BU@btaycxRm3}G? z*15tGvF~EJlIQ7n3np&sE*~K5nzhk3=P*cPoy5u&>tX6!3Xazk7Q~bECy+Sx*r7qU z0{2Lie5K34?9*T*`5+{T0ZM&i-CV|*A}(sCn#<0ov&st*LcQAy6YxFYFy*+v2x>;^ zdZcS4;-6x=^@i2S>Q~bwi-AWA@zJciW{kWCO$KB@X6@8o5vBdi1%gb{p{hUU2W!X7 z389PdixVYgcQ#v+?ta?bx>0f)H@bwndZfyOHxFw0PSqn0B;xla0MHyyRa6WX?0S+r zVPm%_qQu$~pdOPXCXPHL(sBqD4-!XT$;2ozl}RtTiOxk!flw5aDTB&8;9E~tY?dVl zD$Ke>kn9SQ!IMMAm?6^NEKK;-IxgP9RdN0jYZva7I5Nja2a6MN9=gT~E5&=?vSjuR zy6#nN?_4Oct?00Fy>GX^$CxqRdQ3~hRtYxcsS zoS@j2>rc_a!^B_Z1!q8|D?q~ch;kE`7oqfgp?o$kVP=L9z}V2Ce1r39{`}MCoFhp5 zBn{4)-Uzi^8%MIsKWyJoNAeZ8vT>v0EwfJRWn9dn!xJr3Cst;%AkbKwF>cW1opRmrAr5$SBnGH<;7y~@OH$sJIdLh$X+>%WG7!1ZQGu^ zQz0Fue6RNn@Jrirav-u5EJMPp)G(lzuWr>|(|{!sZ3$~{nRU@>@ei`1V0pSuMC8;+ z*Sk+KFz6*PWLRlTcrp}rh?#uxnLAj60YUQ|Ym!G1^IBn4vp|a%?a8 z%Y^_jaBG9Vyc*T47#jJwVp{?n)ZA%kmiBS6#N0I+5XqRU)+8^IkOrVqJg;Ui4S7kU zf+2tQHIj@G@kHaUh4wv*$m@d1eOnuNkdId`S-C6}T5`-tMpRYmermHW*&WTO~*2Zm)SCimAe zlM6Z!KuP}fS}6p7aciBQU-jBayZmTsyns@dKa;4Rt1YKDM(K^3J8IH7g)0u+t*~kV=9SnJgV$oMxU+&9j6pz*Wv)>Jg}T z4?OF1rQsDo%PD@8DpUx~+7{SU_60oVpl&br`heOOu!~G;)IPyQ)*R z?;qdkbz#i8W(hFp(ABJS#uw~J5#Ni<7?zN`Fwyq_tr495g$JA&5zG}AF4V8g_ zL&tWQWm@S7>YP7Sj0W{34VO*pV()F7)VQHG_5jQK{XF7yhyi*ma3 z9jTx9BAP=w1VRsDEyTb3^VS*I_%Nj|X6Nn2kYeXY1X`Pa@P)2YOz%-8d^V)Vuxil7 z`P_H`{n;;44}oEw6~+0qzsGj~zw_^1t{iVW*}Wu-H~UH zz0f{Uok^{N0V| zc=-H=31=+5&T;p;BX56T2|~r2$6uC@6@KsO`fq>U{ndb%9W(UWy2F0K!R+Rs|M3(|EZFhlOS|MI(hQg3-@bg3-sT$15Qh<CBtSOA0yz8l0?Xc(*zgA17{kg zni3(u@+ABloY4&d+L`4nXRW5rwj9#}a#`=!1zAptFJm zg0MAnZ5+Bg%88pNn`Q6Y#A}~|i<)Utz&w&WgC%&u0#JG)H$nkSsXp;{OArsD*E?Uiy+Npyinl76;LQqoUuu$rvyuj?@_*?8|jsU)glqFo!m+# z{@6S%J=s-BI4%R4yFY9K`17oM>I`}+^8KBd_b~;rOchGAq*>EWRkCrdZLA&2-i_9! z0NXM%o0hM&Us~CnY-_dK$L|VM9;lPJ*1hSkI$`a#gS6H+ZB#vdcJ2z9bnQNsvl;i$!?q3%iVy14S#2qOcMbeWqagr;7(n$~^He~mzVc36<&Q<- z?j7yd%?Uf}bQ0eU3_K3t(c$O7L@yJ8%l1Y!+k%%qU#CD^uV(ui#yr;Gqx6IE%NHA` zktYRn*G5MU>pS>N2?f(V6IDvz^{X7^H|%bU_;#yR2Eh4*FBG>mi75{FT?XQNUG{%! z`>VFsASD1Tycl_D;eD$SSi8sc@6M|;ty^`g^4$@@D?|@DUc2rgZM$hNap4V>2Q4c~ zfxk=aPS%hg4FSKl-6Z^ao$Xsr2-&8~zU(}``G!#8B_%d)FVCvA5|l@Rmo`s6JXvcg z@AzC*Q#sA6`V+e3C{7Ee_T`<)ljg>Xy6mA*+o&026PVB9mt+>53=A)CjF@JbJ zc|3jSjdEfJf7{f}+9PZlJ0hbjLaNPU(?Jnc6F0vk5xuHh8-hXx9l%*z*4)WI8Lg$Z zD47EaieEVFA{w(khC0ZSF<=l-s_D6^r1BuzbTtygSC^WZEk^Ac=7ne0xOFSV?`_%DbE}UH2?{H2-*eKOrg+5Q1FWkG zwQf`H^ybO~6_-RaS65K=V>wq)@M9})P-e>vPM6$&>6{M;jE={C^@)tsxg{wZPZuo` zh7`S16D9xejgigzYAc-TC=UvAumDQG%U0=mGUUh+OdXev=GglJEy zQWvUiq5D`9>ajikqTz!=qzg98hl^IclN8|}SeE)mHaxLph+IOo{XjSuEpq@2$UG)1otC3f-;zC9Daku;T56QlDu z|0jOZxWYmcILaLv8W94*7LslvSRdu(^-zsso#Se~?9GO;+e!8lRFj|mhKXCKy~rSP zXyYk40zZ=1yw1Bzr(x}wLi%xc{tLyk2@C&(Y{cD_!ZBGv%OPi(t-S*7c^8+Qk6agp z&0>r6)^e%6LwuRbBOhlhWjFCs=T)xon&<-&iWYLe^NAF_ku>|K$QpdsxQLCNF_J{D zL5Q09yH)gL@(}?X-~M18QuhNmpHE(*qgL*ub1svh+~$u738kkj)h|fjOJDK-eu%M{ zIsQLj_J8p*7PkMhqdcRn>$oL>@gFbSF98!<>O`~*5+Jh=c4)Nj#w8VAKm(>#S%Aq)OKIO4Ff7#KM?$>%Z(_@whl%y++BM78&3SNN{;P{MEwI*5Z zxff`B?%HB%DK=#;!Pp!1%!7~RAc=883u`g6nR|B4SVc3Hgs&Kql!>8QaVEiB+l z-tJy*K;_L=gf{Ou>SKIvW2BtSDKEQNi!%zCM;$9*CqDRw0fp;Hr{ zz}Pj?0djzW5qSdC$fBk4MPay2EPXbRf@%;;O&BTVR=7X%@v|l~^R_d(RoklgRwGsZ z#HICKMU37ojncTEj>oWQ(=->7VWLug;uHPHf}oHMfuDwUhsvaSDGb z0{}r@IYWxwZj>1v5xeCW5aisBfEA^&Y)S1o8KjKQN*ifTmlA2%Hg%Fkhy=a~Pw^61v@!%}^ks;!y(WU*rp9~~%kcv)Fz_6S5_i>%N`6*u&YiLWS zrL~z;x!;5;oUn>ifLL0uFgG+)rjQ#|U_cpGhznbbD1RZ&^t(+WRGpLt=oL@YG!bp* zctNcEu~hJ60*I)0z-F*;@-L(x2!EdI3ssD_0+a zg}J6TH1O~Kp;`4F0K}Y*`eW63zJp2Y{;vHBT}sPxp##s890BdTzsNs--Ty__J2qFs zh3mRAwr$&1#~s_YZFDqa+wQo7j&0i=+qN--^R9KO&e>J_%lHYSp69;Dbqxp6W9}z> z8k3zFZxz;1DRJ%JawL{}r#u42vR5KEBW}Nq&HRI9B5J)A@fVUI>j(&xBCY?8F@0?d zI`AQ1-U=wN1wQ<;8({HJ>p;QNRmuk)oXx@Nzuxlso?4Ijv;z%Z4OU#t2xi}V01x9; z6_WD~gWdNv&IfZ4kU9FT8$3^cZgoTjkQ=LoA`<6h+U+WH$X$tvBF8U&8+K%2aC2|q zAG}bnD@$N_PWtrfK6*C)wb0(MkgLe%tjaPC-ju{|t`J?TrN=bZXo)?mu@!#x3$l-E zScCc(53!cad;-+@D8ejcMvtuPG2$6E_&M-YWYC1oMMdwzhDjCGe+dusBU`fUllmMd zm-q+gxf$X0&xjDGKcsV5h?we9?_m;l6-H8WQs6Z?gOxE+8Axn*pw8QkaMwG=Ab!Hb z%m(pQHq)O>C5I5<$>$cg?n`uqGE_w*h4qKAS$@9yR?pl0qkZ3Jt-vtv3;vIHa*rXj(LrkxN|3kMP=6MRp}S=$4-sL> zIw$u%cl3}S;;&iJ(}zGET+UsC>+iT0ly=*M=5J`_vM|N}nRqgSPQWlB*}3`t-w|g? zPc8*t3cY8x_LKsHY~m^4wV^)!GK8F4tP}q?V?;3CoCqUCCUnl*3rM54Q>MVza5)^= zokK#y@+iZ|(xNn=qy2pk=OVc;c8R_HEnT`Mlat-$ztB+Ll|vzbU`ro{Cwr6GYQ^kq zVC>UdP*X8hh=rK@$m{IDmWS_fb_ck;u|K)y*s8sC!qWMR&Andt5;vMg!{e6qM`&Kix$=xaRs%<^dGub5TgRbOts3I5ztF&k;ts*0Drx)M1e%gl?7; zC~vItHd#pgLnh%aaVp7h4EHKONJ=rO5j59%Wo63R6{Br#4R*79=7B<$ z3sabxEI1sxoShf``YuludSV_2lR1kMiV>Z&?-cx{2ZzP`{NLkvC=CWlvTx~= zi{5{)vxtwWB9`9VldHy$}SYg(rU)PB8!NJz1uqJlsmYNr`qnJj(?^@bRU zb)9TR!G_Hjvd40}e#({Sy>@xaSGqu9@OV%Icop|=1mUc$Szrqt);^;5K>9sPS%hqe zr29PM;%;$C1cW9Ks0E!w?&#;UIlWT#@vEa}LpZREgQ4yRsY%X)sde-GnqCjYomS(c zV`m$a*)k>5!ICRn(?=#l4O9aGN;eULZ2BPuk_qQ+YHNpCqguSaeA*0LbCR;l66gA$ zIY!umC*-&(E-*TQb$bhVP>lD<*SS&MN=Jv$hRmo5n}#k%XSrLhP?&xLUy*C;3U$yx zr7^@;Ut%e%fp8reh3To93Q=U1*oO5Z)r`8zrsh7N5wAq>bb{0rQ8hq`9>v^lLG9NY z_=J}Da=V_`L2lG-oo;P<%#wY>^iu5^?f1iF-P+7QPT&CrII1*FTt(R*cPOgP@X)60 zb&YL*Qgv2&JDpDEerLu|cq(64=(E9gyduOjVggkZFeicDCHhII7`DI8ZvbJg!rNaS zYbQ%ozgzQm6)fK7BzY)!O4$c$ng!v?^kdicq#dH`Na@4Lmc?7F{$8xMH;y6+^fHs3 z;-@8{!UFZY%j9v?49r(DeK>3oaAr^hWA<6yJGX1gB!>8;cG!y5m=N5PKa7*GXz)qa z!}s_C#94AH_{#cBAZ1Lf3s8mA#%l3pp4uNlKcBY{DY?4y>PsAT8mgPc0!$L+AC)_s z-ej6R+)bn^;s_<57j#1=vu$5Uo2Kqb&yiw#Ux98deqGqI8JLtVJ}>%R_)w)V=uMJU zlbDo?tkAMA=Ft>wH|TTPjkSbB@VqQhUGQ$t*M+?O|rV4xEMd?UAH)XVOZQtZfLL-PJcHVywF@m zCjqyg)Gtld2~3w6%aiaz+?-O_5TVG@5JJrVYtIl_;E=oN6o(X z%CsNyEf>9` z*T^_6sxP%78fAV;>+`x^%-liTzdWqJL~#C?bL~#m&-eaBO?2|GU)+(v;^Jo z(`iXGH#|06LRaruJvDRiS@v6zY}3139p~$K;Q<0lS$#D4@HKFmNsqA-CJ}X!duF1n%cM3w=c_ z&h3&&N3{sHM$odsRZz#Y)K3&+*S|9nEfGy1M3eWPiCe+=GG8rK zu%^5xWkGxh*x)(AaQ;Qrb=DIE6QH(GGxB!N;-`o;MhcSt8qlvmdYY;pfd9fMpv#J`Prf)Erx zhJL2dxV5L1H!Wg4dOniw-zDE4b)*YEa}NI5H7WOhCrlOT3e6rYC>h67ageC^`|k3g zBI!k{z-akqwXfwjN?`HlVmL$%S!UfKAtq26slR&SYWUV#abkdxif;%2h<4g6ti)HS z(Bb0W@g_2pCu=RrhpSDXKlEbly$Ndy9E&q_D&EJ9xgy$A2D1kYo`HzrIEu&vt-ovn z$cgC##fDSWkwb7~bea&YA!~LxZqq@A^?uX8r{M@32m9tDx(#ai}S~= z`87f0L|HW(Egv9#H%`AW*UfuYB|z44X?TdilfG#Il+PpJ-hg*dQPvT@ptg3rQ^d8p z5%b4g?$3*R^z??-pR{H3BsO!X`Cd^Qn)}4zW_5LtoW@(G`49M%(mUCP8{2&&t+Abn@uA#vFCO>RLL7McgH0-ED9Z*0^8B@jw zN$UIc)Bkp4SMpd8+*}<03)3v=>bPx4q6e(h_UVn$yLetxXn=NkWgNQF*6siLN2}3i zhDt03LqY^Lq#E@K!YCrkMEzUuMByeQ3=!(N{_23)+0y?!lA=QwL)D^he@lgp_5NR; z=Fl?jgZm(I8VAzsM`soR*JPzak3!5_Fh0Mpp5sNC?1O{aEU@<%5XP=zh?I=4*>2BV zl=Gk1d)Vf|*(iC4RazF>CGf)It^GM-nqQy6O95F9BrKGcCai5i!n(KN=gZUHeHIqn zn+{R98FiW9&#!$0ft`8!CI&00_o}AeClh>(P&Rhyq?2XlP`mC%;lH0VocuJ-=gpw%)d$7O6LrI2LnHO$acoiB- z$s@2NN)9{_G5|NIw}Ju?b5&D+H%<^I>llAAhbBs1>|o0ehFQ~-9dEy0{gVYr$3O+4Db-xBu4iG6uj3s(~ty*pR= zR#=Rv+>f~$k12l}5_E?HYlpS!W!oKOodO-&neH9Zp%)&L%vqk34r?t@I_azIaAYG) znajg7oMBOeV^O~pE_k0&`rQkX|FP>JUh~@$)|gkVh?`Rd@&1807{V!(Z+_YQiJc@J z>4puR1fuN#3X$8kjxp2It9xtZ(__8Np89N-P&!hj0Jw1hYHKV2;R<1vy0OCp0=RaHy4WYTl0b^=Dn z;hB5nSkZSuv)9W=(m!)EVh%r-gll`;EPPHWC;Iz81|3N~kfxicG8X*pFmOSx>_X`sb zxN7THgT!4thK4he779qU$*ErvCSe_7?DX}$mtzk-G-lzkE4Mj@hIh%I`1h|9A{lmd zxG`6NVfvKf%0slEoyjY(MnqULHgeb*K<3bim|HDvJ-A{4rA6xVyux|)(CMSdbi}cVkT<&{t z#dTU-(Y3!Y{thu(=v9zA5q}yLGE3T*7U*UIkwv{Cnw444VJjf<1Hm9^?8q$le==dp zQ@mzKYyU&_>3EOjD>buO#%#&|QHqK#*9h&kEkTim_W2=uYN6viUGRc!hK=;s7p8CO zrg7gz5!XpA@oJN{x4^b1ZVX9EH7{l39*#R1^qszqB>U^Hp_tZUkiQ7HnK4b@@)%ql zkOQ%h1>GcYSKPiAaDiwm2(~M7*^&Of_6lxllOOBxN%>b8j^m>sV3G~@9YIW%JHjf4maBM8jRtNAzRxd+Yjk68>S+Y;Nzu+R`wx7XQW(zEpn23G z(B<>iXv79?=4EV8wAfAynmH}aJ!~ri4Xb-Sz zp5JwC__4l=R^87`jW(yZhW;50oq!w9>C7rx9W+hbCJ9}FZ&NqQ+7S#DLxD}1C_wuk zch-aYv$8;l)>coWFL@!e{NZ!&2x%XqdClnWw7NdHUr^9pf0cBT`h~V=>Io%ut_!mn zdT-o>9cPigpqxIGQzmL~C+}-2kPyIkG`$J^`p%FIq)@EPI_wL1dH{i&j5ebF>)J4|5^nTmJ4yfWGV(-u~Kms+`;>erKlD z(6p2}z4XVv#&gepRuZGW@QNvYu`zt)3Fqcud^zX|Ca6+4>tQg)H_Vc76UJ1eJ_-^} z1bt(Rnf2Ni9c>~5A>L0a$JP%PMABQS;k%ej(s5w_OC!Yxr zPAy_QXYI2b2N9|4NRSgYPYNduM3p)bX%>#qPa}T=Xi1w<8H~AxsN!C}DIdQ>aPiM- zNXedvh`TmSd5wZtAb)Pd^Iw^TP#AAFZOjYs3jhX?&Z#kh=kzC+>e0LCC901@ry^^c zedx9XWJJ89-s*tfxd%c-SlFf9sh-($i!=ezla@KRUzXN$6N-iOY#z3jsA>M@R!m?z zb?Fk?og@tkJoW0#l!spd>DzR$haBdRRaySLeo>9JjZ24a1yq}-3D*q{n(dd)TLE;B zbXz#nt!(!|MpC!O&6gZx(9TdnZSX{~D<3kWWfOry9QXxwLuTphx_lHqFPunbGsGD6 z&T5L79Eb1Jxi#em(J-7|1qn|p%55$hjdgEwIk1=N(_!WySk@U_J$CQQ*xf2pym=+1 z;<`;*V1~qTOnmdE5dD5lxf*m6kPa!cHqGFf7HGFI$`>@7bP5Q*MHm^hv ziZkQa$%5!BLh%YSEl;h;&(0eit-{RjnZ#63#fJ0h^KX^WEd(_6_ zY}PyOMFhfap%2+5LV(wjZp#Zd!VdWLinXT|ZiE%!@yeA_%^Exy=H6;|2l!xqpnt?S zUJ(=Afmb0ef|^6UV}~DRb;eUfk4~~~4bcFNd;_pT7d`)H{>0(t`M;}SUS770yG<}U zV3@{E!Ui{DKyUAWQV94^c7X2k9JY1Dlga8b@}!;sA*PfKBJcBb`i=AVC#~8u6(5ej z^v@JbiGYuv{;OM`AN6y18H>1u4O?srv6WNOieXcp5tj&b+% zqXqHuPS4ekP7u*R=9H=dEn0CMBTld_P{%m-{+f6j%^XPI3TSuypLDeApP`I1P-Z^9DQ3kPXasXmuYc{ir7E=xsH`TykK?;fLQJ! z3Gtd>28YEif!G2#*8lAQYM6D9il$`Z`h@wjHwAb-uSQxWhrX6pYs~yoP{0H z*ol4g{$MNADVBxFx%9!hR;hp^FH%$jm^IvDJ>p0)^m)B`UnY8Pce&yg*mZ@GklrAL=K^hw}4{2#T1<653p}=OqH)X@I=~jy69gA zW>=c{Ls(o#4E$S9`L$)_*l`St(Zq@1T|do`BxifH-=K_s@LQ`W zJzQ61Mu2|B^csDSU6XoZ7UvtV|B1DKA5W?GQSXPsS`S2XA zdmSl+ce%66F5^i8IU;&otdxZ_@-BIvJ;CF-F-@U(kMf}^>7y#KK`71gDadFH5T5Mh zC2LL}$^L7e=BTW@ecKPVxhag2$)Z=o$&~RkH)ZuR-(L+ibVEGf6=BCW<6wJJ!&ujmNn~{Oo7AYUzukK&*)&G^kuY};WFiN z!^efMNMI{gxj}X7g5tt_NE@ZM^Yw`U%*WUBeh!IvPc$lmO)LsqmoJtJOFP5il1Co}3e1k70Y-dxPRA=Hfm`EtWmnC5)k~|e(Z|*E{s9!w@a;B2 z%OtX{7EW~t*0A(wxbx+UKEz76)^CWS$LCZtoneAvNCI|c`22YPYWO8xAV};t!ZZ;| zAYBVQMX;D6k{eIucvYMU`K)>A{f@spm!8Q`+i{+Ef}SxE$8R6uF^>j@#ieFaun+46 z>Kk06Ljg?i`CYgjPW0J_>G}|$(+t{Z`c3b0*3yZjW`m3mbI)56sy7$Bc%{*k*2=0B zTFjK5je+BX*vPL^^F~Eg8^bIcIJ0x)gv5KVzr7XJwDOG6iN(HOS(Z zh4tHEkqvGNKq|k;xhZ3=w=hTSHlP-Vc~O57j0`F-QvX-~b}vSU6ErO$aSO z3-$#mIp}jA{jW~$G`1W#FpTL-&mC86Dy8pg@mp(Oi?)8d;!1H?XWK6f+JDH8z3x}* zWX#mKWu(}TzaglJs1Pm4?)I5>yAoxUj>H*_c7UH`B{Rteq9d>fdRW&Nx=0>{;K&xYL^b#KNgnKO={QEybPL4d$ek&4?Hn3u02fyU{+$iWh!;uw3Y}euBUTW zeaDu%+gYlnn8)PK+@a$?=53safaMh4D-?XFnT(2#$xYR*a>W0Is!7}t~p{%Z(Kh09erJL4;BL2+OFs@WEjMcb)tZS%v z41y6v!v=uRz2lJ>-~NG}nXK*NlEGC-A_;fOIg5vcnGEeM*gHejNSJC0FuriB++6II zjC=r|J+OBtfiX6eQ)ytdPAN_r2j5eYi2IM~)w;oDl+_-{ygNggWRw!9k`R2wRx-O& z0~;aVm9)~Uzc;o)m$r&stUBf+C$;I56OPhWwX)T?6VP8PsgEX40+|Bi{vODGFw4$g zrKVJ(A2~!tcDI*D_@0VVS+h_09-nb35x*_B!97zF><3NG)v2CG0?#j=1rIAc=5PXQ zF(H0y+js@61p>_khabmb2HWXd?%c2N2HHQ{Jiyxkaj#brsNO-lav^wQLva%ZCFKdQ zSP^Wj;;0pJ@Uj23hDEhszRHBhi7<7wCWJ9!D7a&jc}yA*o;j(7{eql1v2ZmuX)Ous&9*|Ff~g-eBQ>XM?dz3#toeS z&3eT+7ICH?2_{`V0SmTIy&S_p&HSt60rKr3PXu+GaL`+|oYF!*>}D3mrF?^+%68yF+Up8FEltqf#E;~-1INwb%Ba*-Pe}Eu$Y8S$^~1c=~)Lg zaSn}iYW_XRjo&(b9{&_XcFC)&3cE>qSmmI>Qr%s-$tc^M=1UNiqwA2}-WB1kFq)Dc$!#p_1y9 z9}7A{5F;u-XVip5j}ntF0mbDv$>iUzhblE@Z+A$*NOFtcT<*m5P|1?nT@UC zrb-dRZpbw{W1|x=y+5t+{k?41cQH7LeTi1H(S|7QHbVjDzMP88vVC*(%dl|TvciG4 z%$4L~?^ok>fDbatb+%OZ86;fb#R$SfV-$^Vdkgs(N$IpNuV7y{IZSF2C-=k2QA?n% zN`+$knBc%}WVpSddBQ$txH~m&+7{jM65i((_G^9ok z2e~7%9S;hdL3@fugO1ao$+jJ-&Hb;S@%+*J0+R*?3oTr;n=monK@uq-xCv~qTd1%| zZT-`yjjmY=lZaBFxfFGX4g&1`h=0G(iq7?Y(!(XA*NQHIyFPCn1nHo=)}@uXmMef8 zFKT2Cv5tX^jDC#M4+V)r{IqA*omeU1M*@xSnM7mj9~!AX)Iu=IEjz&@=+r+ZYjh{v zCpWoeq|TPdLG$LZ;)86!hMfQz(E8V?$)mNmiZvp@e*!u?ANsw8T8(9f^z)FEWV4Y+ ze&=Nsvbw)I-J1Gh6)tu(;9SUw=wVkxsSRZ&1g7y#P(Y*Cq@Jjb`{$daW<{eATIH7I z%|<*M)zF&RQ$sOvNPklREm!$JnEDD>LHo}vcy7gbS_^2+^QAms#)UwL(`lz5lQ9+D zLsRqNd8IdJ)kCv*17M$wu-BnI*ZhYsEeRmCKbSEJ8MJ{q3}$%Q^>w+*FXo-Qm>?q_ z0>+xna*X9&blK#%RIyGR&c8f2#TBp)iR96ayS#wemW3vnKcai4$b z^B^Pobiv#YM-c*wr~W<(nS)&169nEAn-=YH&S>b`B!QFAQo!0M{zs2L zCn<0vp7~bf&dVc*!GR-Oq0-_LHU3Gw<+_tf=wj8_B?l)kx|5nGSN-j6k09dW0A&aI zyhkNr&H9pNFJMJ+KmlN(EHtsa$@ST2;=KaF<$s7x){sE&(YW=RSAVUDBWwfl6V~E8 z^d@(-whoR{Gjv}AfQ!7bXTNy!%JM@XIQ`3Pq~&Z9m22eGx=uVX@)i3so3$rz7I(o@u! z6cP%~+vc^@MU!a4A#}J{!^iK_V?R91K~Y zP?3IHw)T4%P+>9lNu*UHDhUoo?L=wPpBRj`w=7CDZfpkNl92hPl&l1>M`q@k3TX41rNEG%jw^5ftW%-) zNfu+}L}yAQr6I**&zC00LI@RUPtN{JX*KXy_Bbj8sE;WKyXz2zi7zcl*&FB{B^!Mp zGZ7k5U!+a%s|IhQ$0{k4qVF=eg*B$5;8!YX@C+b~eICH4v%`hZUgt(mZ8EMkrgwyG z_l706CLyJ)B>e0Bj}?kuw_lufTV09_n#BcTpLS^30+~5=hZ>_y(-jHwj#-tqf~RI4 zYRp?27^-R-8^LY@4z-1o4BdG#2 zNzWLKnH(%jz3Hg!T-nl!AQs;247uJI_H#h4YQ@WaR{aYTR;kOJvJ^du`?&eT*RrFv z4770HS$bxe&9dBBybzW~b3Dm{a(lDD7J2>`7;N1~DcWxqcUliJ?oUZ5s(XF2Z4uJR z->??XLrv0k2+l{0q$K$pLKr(l*>T1iBvViPp4AwaRhi4Qh_`Q7wIHZJzCqi?8PS8? z_qpsY{P9UL=aW-_VNG^@qV?y`%{2jCJOu`&**EWLC{i61p8$dlA(%R*ULejY3ij@Q zi4}VHlde=ClnX1nAS*kRUZHz^q(^-`0iyVv_AM(i@nb2{8s3}juO7!PA1JjWlgW)- zty}f}_B|LP^UaSys2AnYFR4O;ryLS*2s^=#-Q1?PpkcP!Z?IewiglFTx$buTnH^?Q z)iU3Q`?Rwjy^jX&8_&|m>C4ak0uX#Tka=c>;hkUc4`WTbR>s3{<*%OSQ6 zmNFTq=cW=c@Hb1(sP;O79+DNv|Du_*yeNb`4&V3Vo*N#S*{QFspY)fQm(iT9+yhur zEZjKj3#M*9A`#t482Bk77b^cj$K#f;)7tXXoOOlK3d;N>L)dK2OklsC(j%^hn;@91n&Up>K<5skeua`z!w-&RK0SW|Sdee`0W3(j|NhV8C@L+V zlfH%=MtmTv8k@4Bzds%%D0@RA&t-~znrcXamSpZt*$k>%UFOPTM+?=1wyIGP6)Ho$ zN-CGfXO{r}q?)>8*rP|GuuobSqp4^};Q2CS6l!5~jO!f-8K-$811{7v4+hBxNh8it z*?T&-B{w8qKGqtcdwhjxz&cvDjC%d2FJe$Go`%m83|_v>KljeZW-_d{?1cmjYq+=O z&+f|wa;leOCa)piecu)k-}$>f@9bNI@`yg$a%+KB-@5k1%qKX)`Ai8of1WSL&2^a3 zFUJlglI}R@A9g$0f6!q!+^Ue*Vn5_>VNh=n`@o0?HNmxDkDE)g?!8vS=9sHO z-ChoF>_CdGw@0rL<7tuLwevV@i7QJtdXMOyh4!jVI%GSz18ZXpny zG;yLP6RW5(X-t+s%cH8y5~VT7(a`#b2?%$YtVfA|ik8JK8>|(HtKv?xxsRzqpVw*Z zLBsT~yFkKQOuSM(TDpcnfZytm%$ZD#mHq^-o)Qo)k`WLG4GcxB+=U}Ht$mDe4oJ3d ztR;umul;)-6O0%UI1meGJEHjm{;et17Ym2cAOy*!3-#>_c$Zs&F`73O?Jdv1A!A3Ej{E(?J2P}ejL#ikV|BtR=FKG1%@qXd+jYo@vq-oxW!Ev<(BQflG+1i8XPF2aGz&;>Xo?OWt5TZxR4KO4R&zgS4F)v zY?+2A$)tQZHfJ(b9Agu;Mbb)%j33ZIK~m7<=|S67(uXU$sQ{8Qo!`F7>h;;mGYsb} zdt9=xLixEtA$N?r@H|m7VU6G^Kobb)y2f3zg2H>-cpm0#+LW>Kci!D|JHwblPmuCs@_Gr^(pyE|mZM zMFcSdlmEmK8F+M`{$Fad9pAA3-&%`0zEbG%^1)?`Xx4HqLsBBKO_{%o_@8^sNvDoX zoFS4%*b@t;%t@E>-NM?<*4^4clvqDpv&pmr2)m`1- zW2K%$mgS1%>n1Zk)Yy!r^HcJ=Uzn0OM7nmtKpW@;pZO%Hvm$NlAW3y8psve|*EbqWn&WNo%*m zn$s`tmQlfXmVPDJEBfB-mW1v(|JRq;*Kmn=G%ZsNT0%uJ=n^IZiI0=iC7tS7WPAdf zjgskY8NBKDO&L z$j48cS4UTn!}CDCWjeHnu3&+-vOq>$B7PZjlzzeu=9f`+-k>O=EoZWVmwLlBXn1CwDp z#idY?)Vgby57GE0&dH^0E=Q-*7x42Mhltc}CrOiLOt{u=OXJjdtol!COnj%Q>(%fF};TZe)o z>KIr&)&vF&q-ZLnJ3$LSu%~L z8i<{y2_{4~Va#N$v;NV4+KzKRF??p8|QL*VCXuo>0IkaXa5+7%o zdkk~CzU#_lesVXR?g&2lz4-`=yFPz>e4Y*PQuc&+DoOTvvjQWD@48F#6#9shAoIzX7oGJG}o>eS!1wG`5vo2xp{! zgCVEn*uXWe-uJPCv8N>3U}jWPfuTTfu(D^M<$~dWv$1C=AA->UbDPcFOB`01@ICAW zur^v82(UIT3l7}v{|L0K)jMolua3+-_z|4=zP!1N;Bi%sco^AL^WhwK#N=wrq#3R* z_OHqh^lzu-X9dBf=jt!6A)eYE8M8pUa~*(5^Xh?N5^jPq0xTVgsi}!Amun$jGDt** zCYFYuCRdOPj*qN?(8kaoAz;d`o^{U9>;7vJM1V^RPS34RruS1r#pbqcs2Ks1sbXlV%qCg}raESW85t}V+D zztLB7^s=(oI(5Mudg~Ox;%AWKXEZHqM66f>s|JC)0Z_nlj&gPYB^K9^2Ik=~)*^s@ zztWceUy<#;DFDkxhK_5Ag@j9v0Vgmfq`eAeZVhqwT_cNcZs?N4T8#%ot1sj3;`B=b zl-8S8b@UzA4^Z}ED+Y_?TfmK8$^kldgru!sM|^cbGi%lT`+vEiHN8DVW|dl(VW)?k_&?m~py9#`EG!l3Iw9R`E&U;7c z{z!r15D*!dSR2MFc(-76`$Rzk%hb+X)5iVEvFvpYG>U7fb9Lcz`@%oQ$*RaAx|K@; z8XbK_xMpVcmc4M{AFz1&YL5WjnH`+20lQzd7qz0_EDI|l-&M@m&}G2osP`Cf>vLnL z3n*4DjtC2NXXj6R!oc(I6UUEU#{u95MEJLPs&iwr24LOa<%@(?MXumMYw0_KVQyw( z`Qp2{v23mPOpT70cLU7fdx8E6{sSGDT-QCEk(~K;F)<-AFtISDK0dKDgl>%7^of4c z`*QwVW;xTM`D`hR%&hs%j3CH?@d8}!Y56xavOP5n)z|+~JANs5^_}#&qW(3Vry?(< zsi&6q45Vf*lC0gor7HZsR|VHy>-+-sn7#{}d_R0X_5MBzGP*c{o3k)AHZ=u)xqiHV z)TVp^>!LSucr$g^^!(s%?7)I%%DzGSz~ZP#UT^TOv#ehBKUOA309FpSM({R1ZU1k9 z)To@shZV$cjYTbw?~Ap~^QtgQ%X~}fI))fzYEISiT8%xWuzL0D(3$4n5F@gpyA9xN z7X%xzP)O{ft;5sVCW92D$%DWH-lgDl{y0Xc#|VN>1qxCg7n;ca%YulSw&ZSSX6`7N zp`v&JUUY5!aitttldpu>$Z7@ch+*`4k4Z6gH)0I`Pv2bML~84b=Lz(oPvXPU@XqrX z51j_+yP3=h14w)fjQ$6fHRYzxfYVy0zB?@Q)6J+!e#jizJ<6LV{gR+Y<5xHuHK)!`E^_FIXSSa#@O&2(tR- zqZE-X8gM;ThjJ<$OlIc_SCPcA*y&Qab$ly%0U}7C29JA5+RtG;ajvG_ysznxCc%uM zmH9x~ixITc=A6rH4lM9vO!phV|D)So|7Ux_S1gt<@28h>DrW%a)sKO=RcTz{sicQ> zIO`n0GC1050&3Oigmc$#)$DMOx9Km?M4Pt(G8}~yL$)UU?Mg!Qzj2V2($U8b>$o>x zCY7R~nC(|6gP!(^eQXMZ7x`@06`Dqr7f2S!59L~k*MVB}&Fiubzr5p~;Y!!*hB24%3X&o1k`rvb zSqrDaslTR_^6H39)mI3j4%dYYdgJR zlZrSqgNAx9l%~&ct+<*N_0i=9#DUCDc-E8P670>ex%tH^Y2esS)e#-O-;@IybS?oh z_R707iI{L#*dS`8nL1#>K2@!OZ!MP_K zn^=`&`Qr@ehZ|C;_gIRt8*uS%9}JKEG+K9Eo)Ci`kwO2M}^HDFwM;>UU%m{5wIUIc+2@98q>vZpW*yLgL(DxNs%y4^?&p*ENR`C`E*`;K!&- z-DBh^6=GtRA=vR~%P) z;+N%t6MwITt;QPfVwTDje8RqVMHRqMW?#?WRprVW({qiFO?1pOiyHu9jfq z?$5q^+ROu`a{D~GpkMQayy6b9ZUzR8gorzUHDI`y!dWRT?bUnn+_#IK{4gIClDwKL z`O%>&slL@M?j23Z@p0Xll}Kg({#y*#=qfUX_%|XN!|R+1&nrD{W1$SWoJf1CRSK?y z(XOuc@;bBHof~gjv3mK@Yh;Oqr^}8R1#Pv_mj1~ic zqt*`U*_h%=IZV!Z;#4I|x5Rya?#Cn@=>0~bWHJ2iBgUhv*5v;!)oWYnmwyt$x^OA~ zsMDnfW4}4<_-P0;nOQ46O^0Q5pri#a5v1%oHBkyEI8fcV)0KJk^X-aTnk1ZFx_l<% z5bh*lszm?0DegX1x%{6cTMTLC;c<@ z*tovTVt;jNXnTyj;UIQ?N98Q?)g6R3qb6aK@i-kdcB5R~d;@yufchqi5qqrx7Au^V zy^PGES37#JbVFY9!7_9ij+ZpP5GJvWOi#XKok^BCZer`Og0s=!CScR~Q=NFFOE3T7 ze~gzh?K`BwR)xz3O1<}kI{(`8ui*uHwy!6xmwDW7JwVj!OaU<_#TI|MtBhh_2G?fy z2!mgeTXzUZ^#5As+Lr<1^gqJ`kLNF?)cvC~lfG|m26|&*{_}#|2+$Oj9LcQlw{_wl z6B-08*C$2a2Qvq8-3yMNg<*-p(poW!=q5X`)9|86Occ{BjZ$74jR-armWYo6A)sK6 z-uXgR3*b7p`4v~h7%BdvZKkI;I4`a`781?I(2e(B{w}_c5bV{dOnM~&X`S3nCWWki zUrv3n8PRw0*}-C9HoSoGW_W^7NK=Xn!^v0xJwgVZ3#b+y2n@NSP2FSzL31Adguj2<(?aA)rX9CUB?j$GE9m~aN_na2L%2UEf`f@)IxQ4L95ncEQ zj!<|-&rdW#oJ@4UZqjDH1+OWkiiR7mR>t{4TcG^(gfz!h!Nv;Pui+$Tm}aEOS^`Sk zkLI<^LVw1O7RO!~kHT=%5JiQd&gQ3g8T5Gcn5jG#M*J$bW&6HEJe{|amgmPpilN~j zIYMbA_Spt)g;CJ945)NJF?t-}OnN9&r1+(tee`DnmIz_aY}QjTkL3dBa_)YYZqs(XTs>VZ8o;pk;f@)`z{sXn^2quGyBCSvOtp!RmG(>Xh-WTtr6x zsVsv2S(9_JxpGz3G*oHBq#t!^3Z3xl#h_MgoWp#xdAlc`Xj)#_X%mIZX;lH-#9RCq zmAFyXZz_@PSnPk-sEpJHpljDt^aS*1q1R8?Ys>{;=eEQQrZnVTXU_2xQH!l{zx=%DBV+Dayy} zNE2_)r6`^w0$!V#Y(!<<3vB1(m06r&iO^wsVIv)l;Ij#}5QP;-Eg<5W-ivUxQx{Ho zim(QxaUl9lWa6E37e8;ukUokMRXH9ZvhQ>ZWYLFYlJ;N}s92j)IqN4!Qwlvg!T5!P z=;F1>g0+9Ge~E$xP+Qp{<;jrVuHAsZR#%7Jt8U>K+_j}Z5Fqs^>H%8VcD6StN3OxT z{;mi1k#~{XhsC7Y>p5bNn_TZj*l)rkhaf=tA2+oH5QcjU-sz%F>gM+xT|2$=(Ms@d zLpMN5U5gnd(M%z-ovm)h2-4g2WyQe*uB(;OYPUQGjQF}7&PW^q8k8UI60jx2gyfLP@(B;Z_GAQP z1V4X!f7oU0w%^s}_Cp#H3w#=h(zb@aRbH7d(gOAHMALs`nqijz?yu4104P+TvFYpG z8Y6QvtD$GLyQ~iT6_XV9`6{RWeqkDJiBo^a_xB>qQo`X!ghT=O#%Bb!NO+Ok*50ps ziTtix2;v?Opf^waRT$1wd7c=Wi>CmCwU|Ay-G47`Pz&H zh7Le?Y`4ay9T`=%(DZUmrAB2MTYtEhFXS>ZBAvIOI{#`xT|4F%x~Bdq!f{#DrdEFf zhgpLhW@Avp016hfPP}iw>dJSp)Lx{s+a8EHS=h+1CJSqJ21lEWKS5OimmYE#I5Kp5 zQf|qOgYo2TTVjEP?|hASG7K@@ecba)sMfvUzMC?VTW>Eg*XmlYg-3_@9gpoNIWE z@HK=FYB)Lg$nTSzeLN~jQtyLc*JjEc+sn*2Sdz0i^$)H$U5U3hDlOo#v{5;sNy1rm zGK30DIUe6H@l}O+pX=A}A4U%&)W#75zXNlpAPvXw77s*q;U6`e3Jhh-VE_581gigsyShOebH7G7Ug=@H39f$fhzie^$4nuLF zmw~@^GTY(Kw~a($I-A?-6=*M$riG{P#*%^OmJ<%G11>~oFg7X7_c(u(CdyuLbuzYe z`{9AmtE=@Cnf@SZ0HeoE4r4RD?PFOA_HkJ^cF;CjZ^78qP-80sMSv||-@1S1s|CJ< zAh-ReGt_Ee%k(DUh+LYul2~`gg3W7mtj{5>l=&JBF%{R*&df95;U;$Rl5LdPHT|$O^ya%+#8}swC~n-`_+9eI%K5 z&DpJVr!}=%n2Zd$T8Q$D6G9o?8oCG}m}ekpJ?Kp(h(S{wWpaNQ!p4JR4dE((RTC%L zphFZ?ZRLRkbGwYHv-Rvf0onblRuLRT7^7V)%yq8yc@aV>L`~SfSx7LcPU139mer=4 zY0%I~9qm=p1X^h;mnA|T8~TcqV|X77Q4yKD&M{FTfdTg0vKsdvAj3jV zc*^rIt^2H*l}MHPNSov6oKd-eC@ewI;kpN>?L59c2oKRh)LlChLfDm-BI z2RSG@KQz|v$;{xUg>^%(BCPJ#0=d=us)l_^F3c-;zN^0_PD%4iUQaBf1mXH9G$8vw zq@ZsioEhYH+}nXffmJThQ{`R(qFaV00RWR&fvej}6Uu+S&uVr=M6ziW6!M?^gw}zU zQ`H`7Q?CaS3U@>is4>dZLJ3|{6nrRu4c%v(qsb-_wjvD91{Fb>x&QdL?lRsQfnglK zQEd}Z`ix4g*8ggTbm(j|K65VeL%|)zk zI%kqN=PW6fuYj#;U?|GhgU%EmjX5C*)@<@sBo7S@e>O6n59))l@{B^|i&^}!$&V)E zBVO`7!Kh_?g@^E~-7O+_kFHi^R5$E{kLn>6kPDUoncaOOYYBLF;5JFmY~4CXzP}7H zyady1$f@+ivr#lrMnVSEQ{!+uc`OZK0(LamXbbH0%EtV<~PGriDqDu+%a*o9sH{!E=0zMH*1WN`RZjTWZYRun)SqjA{lMPVkwo4d3PNxEq| zdP|eGml<5F!hWuu4gDU7rzSt$Fy87A%}7IUlx?rc0g?jvU*~9T?q6`Tm)wV~qrvUY z){cH{xlP^O!3;f4W8Aeem{hM#_Yr^cG3_`f`4+5PMT_gtEUsV+E(oJa^Q)^TerHY4 zbP-vxQ|rCa3|X^{;H74Y6S2k(%`?$3NBjL!5siOFD}*pW&Ruzg2fH7PXI|o*jGU3E zE;QUrwIawz5C@%Ld3YJ~2fD^tUVy@CE-aeAQkn1(L)$+jCpa7Z6ww#(TSD>|ZZJ?Y{#1@vF85n|2n;D3zSmU5Mx z4+*)=`CS=$zJpC;olE2>^^tmEt-ni!NVp$Ttcr5IQszbp5NS^c!BD5Ol4B7=PC9Fy zQ1D>*rTL>)g}3Za2;xj&F2jG}qjGYtXl%_#0^ z;kG7&PUU>qklgQrp}$pb38$01i}8=&Ltlj{%>mmTKmkrU10 zSAwY|<K`8@5QZ+vHn=f4=${PLj?3-UW5#{fwiuz-7J^Pva2) zE3$RKPf&dSo%F}SzGb=1r>wxt&53f?i{LMb5r-t`MNL>o2GI*;dWE)? z(_R|+Zy)dDL-XOH&H0V0F8!r&@>s^!Y7cPp!lD6hrZ%N8rv^2aiMW?i>|27wXP>(x zg0xQ&K+wR0*^4fp_$ArrpD_I4e6+JfE!4bonQQeE?eKpFia=4pgF;l)A=9SNr~c(D zpk^y}sHR>3hL^1h`pDbf(V3**amgZv5)u{B)f**&EO|C)mr(=-?c0Xym2$)`EYwN=44w#B+3#x5ftA&ULi1xzKXH zJ6b5w5o`IvO05&*kwKF!1oZ+IKs~{>Vt8zrqIezFU??X=uJ0vojnJfze~+0NDMffM z#v)jzyrk~1j`>9GVT_G;5+Q%9-^chXGB_ElO&^t*XuK4rFCN$}mZggl8K={G{)~7J zQQLohS?3&QC#Z2aIl++3U$U+uN^qrJBhY!R{q>LxSni)Nv?Pw(P`f2zze6$)U(?Qv zifrk44KUv;T8bZjLjSe{qJ;)h@-jWzGxUGl4-9#{oFo8MM8l8puQU_6{akv)-3O)p z#}unD>&1O_-}5YYjt?O2o78zq+c4Dmi`t%gRre#Mwv>m=C}W@$k-!xh&>P>t`+4_L zk5LSH;8C|gZ|5mw)P}3KOhzyfcY`!g$)qN{tyJcV3p+j@fFrL({+$Gz9Y6NfWP*R+ z4Kn-`OlA`qQyASBMhxa<6EmUUk9~CdY6afSZs1x5rdm7KoNOqB;diuzc;#MAPvvub zKbN`i)6|{4j39 zaqTYU!aubDIfqp>-1nB3sBFd)pV60gv(zfgu)Sl?L9+9be|NBrZpp~^ZQRvwYy169 zQv|~OI}cLRLHfdT1*J}Xn0EE0NYhNe=N3ET(G~`R^lCrkxLC8JJy`+!5ZfWDPTMriW^4yYW+K!m zFZo~gk2^6zpk#7%r9WB{@_v8pW{Y~JwW$6z{r32?ybs9Pi{`t%blL?z!edEPM8h1a zIKC8p@3>cc;{2$@ff`KTo~lW?i0KQG2(wLrW_j5}yHdbJ^Fn^Z~?tOj&#<-4aMnOz&|C&nuLI7_qK~s|=VGSc!$2KTN9u{OfZm`uW zGzcVZ^djf>vFrU^GU$C~pou;F<7h-ILf$g}+UcGf?a?;hF~8sbv>7++pfXk{v;SeE zmSXM&ygO_+#}M5cH`#w%s1^F5+S3vKUc$y+mY5-OoQwKjipm#F&7rG$N-iqCO{=I8 zH>W7h-j_n@M~2Ad-I|)4Y1d3of3Slo?f&KzxlB*8!Ynj6@BE6;5*2)j%n>zFZjnb2 zX2%kX$+QTGfWhPbbjgFcdMsDm*+K*H^ejxWzvoN>HJ1twuMmIZg5=Nc1^sv=LB<3> zcrSncD%@FU5o`V|+sWh_cn!pFar}cUv2s#8hh&IFPRI7^&-X|DhaPieseFPv1m+4Xstv3h# z(TwJaDU^Z2ugvJX{OJ%0to$@d3Zjb{IiCV!K*!Y|AR~V@Q9?7}COeGdsfHkLZXSUZ zaM5mQS2a^m$Zh9#1p#sK%MIxsFwL{SeHij1OEotig{zTlRw2P zs4LP#Bm~7xxKdsU#XP5ZgO=}IZ<4)K6$gm$WQur=x?R-O1?QHjFo!SBpb{!54N7OK zk>Gz**#7Z#i0*G%R8@^46B>ACjW0fiidZReC~>7aXdS+xF$ID{;(I-t74ABJVwH%G zOc?&0BZp@7Sw74R=_O7nXE5M8Q!!MtmY;kVtMcmEBM;`?uvXpfO7{f3o!@h%1rR85 zNH007Q$sG_HB=&7^n?>VM}Xb`a^O0%Q{aEmzawCZ(QW^Y&cWUzCd@iE)!_y3L6emT z3Qo;)$y>91R~(wvOxx%d)2C8aE$_WF+^VgmaJVBwq&PMDNw6y~B1^s%jQK%>c_&VK zj!a#ITI_d94;`09Skj-gj$Xxu!}fO-JsHH4zV_(vO2uvX6Rj#$8C5gO_X3;85+uY|B6m;1DgJbmRh11p+C)m3_zYR zYlvX}q>|WR6_U=(-w4fL);t^JBpJlPfwNoUcFEFlbWhD0!k8$OJ~|tmx#exAz^X%7 z1XS&{PE1C|g=2;h_9|G0{-6(XYl43kjK&62n#-A5sdg8=`zUl>gQpMHsJ^b1i;??) zes0KBlxAh#qF67?-Srhzh3HD+VgpCj2tgj?zIf-`ei?}{zU~y(MZCX}KT-$x)i+Qi zI%CaA1%6qY=HIhY0fePlHSFO}$ZD(xjw)Pp$oAwV-K}kx36=rUfM~c_aDsp8cxlV; zlntg`{rH~To_z8;+<28!;H!b>tGbR7%P4ja*o$Ij`=zJxV_lVP zgu=6qOR`MqkiOE*9glb4OUjvg7^XG~=~x1@;-t?ELa0!^5(4wFldyY!4NE$)hct+* z@TX`Cy3Kz0Nj>4KN)w^nC%b>UGBWUMO0cm6iQY)(E7O_%krnU4rB-(N^n$F3i57AC z`^=W@qE7^A7+WCp7}X%-@5GOttiQe-p}v-Q&7a z_0P^&O}J;4*;+9(5n9LZ8;}eQxGp`bNeeDoIgr#kq#zay3X`(o%75>l`o|iwyB$_M zx5HkUV8~T4Cf{;+$gXE?e1mzcoL@r}Z3Wdhk=cydUGd&TE-%gduc0>5HaT-J`yZ~qxCJm^_Itk5=r6Evw0ECvaU59Bl{X7!`m52Fc0 z{y02$7(Wyo@(+iX$;{ok6p(hIDdf`Ir;UpLiG}TUtBS}Ji|LIODPvc1{B9jvGNmAi z2tikvz&}%VMIwKN!T+&OZCP;KV&cs4YBg!HYw2I z;kTtrM(O}bLH~Qlm4B@a!PkBbvhKEDIk@U}@iFDwrGzrGapfz{k4Tb5N6xL&6Eb6U zPOG#R)f4jiW`RF8@&pGH8DMjv2@iof*7MP{5!(}@D6iw@j+8VLiZB|XOf9hI`q|I9GZ5r{U)5~2$FWVdwvQ^ccMz{ z+GRWo5C4BQ(F<|GT`yUQHFL2P;=M({hhG*xmj1nJf}sBJXo$3oS0G0-B5jEU`kl(8 zapj>05_&pVFcac27c8c&gJ@>LU5a496- z-=9CaA>`Pq;(hQUaPU84@&*hvy#?UUj`d{j?Cof}T|d8px}~fH`bxDs$YFF6jpjhh za^Re!5liDGlWHq_`&MG_Fs@HpdQRLJ{ZJ8ijHph9FVp>*lge%>rYGvJnh=3JOz-6E zrHp?RJB;DSyC7iRi5EJ2&KYEje;&L-`#kcfE-B^{d|6Nbcv}-YV%Wl_o>!h`Q~z^1 zha-q{=Dy|0@uQzSr)GudRtofX)11BL_!DSLTjH>ngr+zsP4Ru88Gd@dJiKkYn^54eF$?hLeFF4w$^h8z@%Da7c(U6KC0 z>P>*B@i)UK@Q;TiPX64EPFgMRvFd2a&A-b=LQ}8sfw-gM#wmv4$sF-J23|6)UdewC zaY|j=Xxzy5j0&)m1ehpG4rSNY>3c(w?aRxG^CJ# z3P>tA!`g!Ok@p)?(2-9agFn!Mkyn4kn)D+b+Mq>r9KA+btpmsU*9qvd5#Et*5P+9q zR$TV%B`oSR>z*A5e36e6Fq4d<>h`3U_0A8quG3lJwaBIfP*qO2G{DisK?3AadNV}E ze9T7uPH<>#LztJj=0WjQJ5%Oq2rdkLD%;|XTPMGxPMUsIzbF~k1ddmdFo}O!n#N6p zNvjSI3*!1~!7O2a+@Jec&$6k{A!c`yLE93J)Qy;~2rQI+?qmTvZGqrnqtoNN-i9AE zSHRR6g>s!tt@hS2cCohywwXGFwE=8B1X))p!yp*!4*3Wr+jIXG@(uT%A5FDh62i%x z+pPs+Z)veUh3aAQUAxU5RJDI22x{M`2INE|LDDRNyKTfECnIYo({P9H*b!Bvxf z0at3iB(sy@Q>{t9fE$8-7VgBy=^_=M6ouSJy~Wha`VR>bUH|pM81E{(r~r$aV>jDw z<8wa}3b&u#Go5?RW55(PuApqS?lno34m3X}HiJ>{6&e{EwgP{%7-fH;nOuJRsKsp) zl_(psGQzx{^~E^foZHA)PP(#T{kgdJIJVm|=bjo)lIaiXzRxh?x1en)-rL~n2U@)b zT5(S)k$~!NjgpVOnb&`3q$uMqSk`11$)?ZE4@eDYPU?8^es^e<2J#8^OL;egoE%C2 z7Bt{9r=(f1MDJ#`IrD##YA&^#I8v*XiSP>1+>mFDs(YUGS-G%zLZk00L{vllG*Q&x z?Z2Y_?dRKmApH_ z)#nw;#0x~qg-Lbm9{gzJST_phgC&_5Q;Fb7rtSm^Z8GN-v~7Qe!XkM+6$GDtPKP3A zXQX3QoF{=Y9O{=7*@Pc}@KRWJA{r^`p|Y><2_xf7$W00Ga!!+Mn}jnl%gSI*kg*A8 zO`K=8(+5EvmpGZwA8$mjGzd`e6#_SAO%T^uwlgh#Jp`Ckb7g&XDT+W*lysl?i9Fq0 z#D25&-+ogZb5(y~SM}3JWBW12%XikCS6+x1g>n`?XB~}}`YzW8%kF>O=xlVFoeJbJ*|t++tUEu&$96h}MqQMTbw=6tsSp zMpgMVj5Lvz=IvnxJqsmV3bMnR1$A#z{F}GvjVM0^ic*!)2Hm~tD(9*`)USjjQl0%~ zY;4`N()WK}m}%Wr-G74rHa|)k6YY4a$r=;<>4cVn;<0c%&hK68W?C~NXxr+-2Es}= zSpfuzXHn>|GwXiXs+6N#^R!Sdz5{_V1p5$Vc>KkZa<_t0=DV_d%Fa>8 zZ!<&23tOp#&Sp~`J}du?E(-obpko$jher_|b@W!)khK*7(^pW8d`$icQ zG^yZ5``}VzoQcMDj5*dc8_woc1CV(Lkhifhj_6bfiL*4k&weH3z1Y2;c+koxa(g0z zn70YH>R?@3cpIP*r0JjW9mlc0;C)CPG%7xTU!#zl%4Dzk$@QZ+U3RQYUH$ypbaz@byn>D_(_z zQWyKR5U@s8(<;HV%+^OD*5F1j;JA;YTx3Eff4yLfXK|4b^%uSCzIh1m;n1??dN_C3 z&fkdYy zF{k?AZ|tI&S&oMUH5gKGQ3b+hODv^c>X)sNpUCeuzzYIZ%9vkKecYGa;`wdP+TMMV zJY{ge$i2fOwiw2!xFGFaBkqQcluCbhv$~U&G21LPXJ}23Ht3?gU~`g1 zQJC2z_p)&gLQG37%GPGpCcft>dG(E*ThRU?OZVS|z6EH#d{=d;_~y3^#Cd<@MKt;Z ze*U{OZ0puho_%w7%7I}Oc(*YC1LF6^fUzmCkcC%MKLgS<0H#+aDa|t<`@H4q&ijOX z;g(c78M_Y~T%j%M#eg38MFrz)3ISq60vLob|2N}WhVHqto=2IQ!)|slegS3Wfa8RG zZX2YHrbFh{S~SY0uKfCLNr`_Mf`N*ssD7h-!2_qjh$6o~tnm}kAXFI;6D~cvO|e9$ zszd&)bZQ)6etWaS%3(FYNvK>Kog{#*?lZ-zCKHIpJ$4+!YPFh3wlt}=S&NKCo2Jul zcKSu1Km;M(cL+KQI`#7THxJ~EO7TUXGM28pAUfM0g1J_PSZB5;fB}E%AnUuVpKj2a zZaizql+Sdv$6=X6RZzioHidqWAg#=4fiZ}iPt$<`cgcbm*w=~B!*DLW74N1Yv%Pu} z^9N#C{G^3mD!787oQC;wCvkb<+3qo+gNZGI?n~WP=(mWxJh&xtRJLB&+Y(t#gdX}s zsGuHU^_~trFiL;oIJ$q?Ya}FP@NOJ6{<7X_;$u}e15|N|pVGq;>+cL5+?N?(tE92I z5_;YWSWn zW-L8-Xu$hccXw;*9EB{Q3Wtjanu?FAnp zqNz0{(nNP~p4WfNiJX%f4&H9W301DwW9o=BL{?3Rq5wOv->x_C%%#;@Oav(6{9x+7_v%8k$~N#{Y!r;nwD3k#x{8?y9a;t?!Q^= ztaaVVL!}4n17N)S9+)V{i()(kj#mPil87gx4juc%gVCbjnP>Ex2_wadu`$p!?+}5H zjPF+MCpx6yE?usnpSE>e@@(!}RjS4@>eB~A}cdJ14Ikz|;Mh532Cs#A*r^To~EzJE`Rzs5*;Lp41NnTN0A=8s-(Fqu0~~Cd^Nwjc+cwXxlYyT3H{EpIa^m zIOVcNSOY@I6Z0`=i7xvg<;zrF&d%8FHRFHFF6r|`8l3kQuf7_;ce8ABML55Ybt)q~ zN=QJ-nmF0c`k=V=HmF!4?fR>XfQ zuQ@(X^xCqjCE4zNiz(R;5L8=spPVs!lA@xma-L9;d^zKRkhEcndwgdCZ^kb zb(s^VI>z{kyUfQX>)p$0-vTz-)6sv&Om>_KovD71eUpZ(PCX+Ny{#>!6g~=sXZuT6 z`5}B=f@!2hi{y(w4c?0oK6lc%qfGVaW&7E}gi3~AM;k~a6V%eq&L$OhJ7v64n2L>^ zIS|L=k(3%_%?pR^c!{3AI&&hU(t%s@*Iv@9P+8=H)8ifMm*6f|2K zor!tHbV!y35@!oUU=ZV$wh5orvtY3*4N5e`>W(f_Y4qI|0V|ZtcIDf1;^KYt278?* zw48U7;7O=7-%Vol_N|TOqA7pM>L1VLP$+~zAq~5@T@C3>X#O5~1^@?I^+SoDwO-mu z+V*0jzl8okZS1RM)4|ZY?b_}L8AnDy9>zOW)pnLbcB4gPW%T49x>*gFu6}l@L4k=5 zio!U-bC=|H=J~rixPUxbF0}{V6O>^Kn$@}#`*XS{WocJ&@rWpWct7Pz ztzj7Kc&Ro4IjAP=GI==aqEdJDwb$)eENkZPRZp%GKdqYV3s z`cIyGkwv9~r(|D@nv93J=96h?d*jcy1PUEl%saDfMWfm@X zv?)!$Y{c<8uZwE7b)UH84Y?pumZ?OB)7-XSoVc+}K_IA`v4=l-%@4~e=Q#A|d!M8A zHCMWnYtYQ~QbV4uGB5FpTd2?mB*xWPdo5gXC2U=LA6dxoEF*vAf;da7w_@gRlZMY!&t7C}YmuU^WOD?%4j?r{5+RA^6uin8UH&9AcM)*6Dia zju>afYq&WZ3fxY!zty))=G`?u2C~*%V>M_<5qu7Xshi3*YT7pwqDG4@q}=FBqbJ$?D>%+cE6QHeX4F?4;Om)b9=M$ zmSx%(i%vrK9<+??U3MaLM~ZzfifBy<#tI?V*n2gOy=)*Ji9>=>4UU7D-#ypG*BPq$Cp&Wu}7RJejQ5NXS<5}V)!HIIKj{d0a@B2DFJv#qaFHtgbX z^bkoB99?ra4fm-h59S>fg?73`J;Gp{eO~+xVUNf+sc@teov4CKSBiesKUyxKg#2;@ zTG&1QY3&Y6c{n`n4|>GHFX3``FB%ES}LPWPpvMp zezF_e=>%Qa*A!?aLmn9HE_ezo!1lb^PW))fn853lDdisCJOWx2oiG`xV-dJQ1`SVQ{={~7UpyVn)|h6K2GXu3>OT(5Lc zDz;#Zy&m_Xp^7ssI}l3OSBEQ;3cJEagRfosxnSprkbdoP((gSNM~ZDP+;B9w@12FZ z?;!CZUeLbJ4s%TM#<-wk#~xGM$LK2#L%@I1M>&Qwx@sJKDudW6`utLvD5mO7?}WaQ z>WzlQm2=UO0`c=sUdbWTzPqO22_M0v5|eW;{+R#gIfM>ymmA zY6J$$;xma8-)8nh!O6EdhD-8?MCz2m+}UpbYkfnmYJ+Wu;T12`0q_fk<9c|FE4%sW zoj3K{j5)1+HSdrZ82!s3vuhgprqh4=Pyk9oY-Y8@^z>Px zSj0!9lR&u|JIg8=n77~3IwCh{V<9-RJwrn-@VxvvJV)%chBl6lP`~P;U z5Fqi`{+4#6;wjjtns0@B0u<(;F*csmz*W|Q4(J~3D94V`6`GM`X9*kU{f*yLbKuMH z2lFL!8ptg2YY(SAK|l)Y21DC;1otTzw{^#HOa1V(>{hmwCqRqP0Kc#N=AD|APOw?uM0 zES2={)JR{QTm`P(*|&2zoiAb{vWpKc9q%%r%F}%Ieaayrfk)`{@-5a5fB*utQjhF- zpWK=Mp)sL<%U%W=&+lp}j20lA13(l9tLMTG1ih}}Q;zwRY=pJRb2H$2Gj1nCOv3&8 zuyS1`hOvJRNp;7q&_I3dmUM7D_ZmMntdJVM`}t#7#?{9tV&5XQXVprkCXq2=J6@A5kX8u@m^mE|{NPlnagx+1TCf%Haw) zejy+A*RU1@SIX(VV~V_YNS85b0Th#uX%)9xX#tWl0XDbon*l!u0XVlUqXDG|0x>X? zkZBaR=&J!l3IQ^=Ew%xn2>~>>&%XgU2LU#>2*&{)2mv^^C(i-G3YXg40Th?7@Buov zH`)QD0+(Xn0TZ|G+yQg~mk#0q6SsBW0ht1qIOG8nw;|#I7Xp`p=K&M9OXLAJ1D7M~ z0TZ{C=K+obmlN&*6Sp?&0o?+ZobUk?wtQNp8;1VjXkNEyOa5Mv}<6=7UxxG{t&&fq2@%t%87 zV}u6*jA4Rs5h}P*gzE^#Fhh70L=(Xxl!7?qM2JX#p_m8*QyCA53{*f^Xo%#T6DBy3 zB9d?;iBuZK2tlL~Fw1BnqX1t8LD?mH|rz@1@xBQ{#e~6OPbRE(l0cl zSyB{qL6-mYmui!3f~X-Ui5 zb&}BXdrmiWvz#aEVwSHH`i*|4ck~DSNq;8m{DI~7I0a%jDEd(X=V_|8pxJ~am%zi^MT^0pY zmpxcK`uO6*)uqGYMZSoaV>GgwMiz-Kje$>NipKZDCtMN=f-K>1J*$8tghe4l7uoLs#+K5?RHSsxB3grx~5?4(f`IN{`eI78-zGw{R7 zSR2o=tiV`4tqR&{8^uefuwgz_nb66ARmEW0EOh$QCr9o>&hz)rUY&e@eE2dhZ(%@s zvz$JD+SL0gO07>*7K~MYj(ZhsGRCkiR~}PNx`*`@`NQdA4H# zvZ`_C*y(Y1W6{RnSor8Nbjr{;@9}z_f47_^S+c+#q3(+8s)Rm&uuNx3nXjs*$O;$f zas&O*CIiN^A9bNe2rz5zGqzW`J~=&kfBs>FvHxqjR(|`Q?Nw`!UtByrcrxNyU1xt? za;E}oE~{&<*xOUKbyc~phOVnkQ(TnsnwIg#_j<4T`{C&9LWcBobaRgk|O&RNx4II?$IiZK3T=zB=7W-NAjj z7k6sgkdhD@PzW{jqC|ww5#e8Q385Y%(zdgM}XKmA~7Z?4Pg5rt6r591=iH{<6*FKeq0Nx0JKak?%_ z91QGF=xJPkKQInTuhMyWTfo88*1k5H)mNfQ@+N<~1ghqcI(%fa+=X?ombB}D={mq% z{9E*)>|ze^8pVm#7abdk?;;J_1ImP6hHEPi7X`_+f^F6OXT zWye>4#=S5PY-Z>2O;SLon{V*!K7r>o_FDL7m1_EnbPjEpt}=iy9onmd@L=ji|5TuXN&av`X;9Yc)xkfl046Wd^-lQBz9l?H(D$zZz8! z4H3=66gpsN?(9owpKHvm4>j-S>*O1>-5$Sxb}DP8s&L0tS(`sg?piFK9%WiR($mw- ztkftzFjKTMgYlU%bO0#bS0kfFjnso`?92fGvSm;1VvlyLPc*TXt-a&^|l>d$!L0fd~2$y7EWt5d*PZIKDUl zxy?9Vj^pLPc#iS`^#bK}>7}RXA}u?ApgN;Jb@98eB`S;hMij_xRr2K;<*Y9^DCd27 zh;q?|o%=u23mC_16PfEAx5Kh!$0dZdjlO6ZHkk-b?#z8Aw~{+UHYz35l;yUORj$=g zBFe2pOCm){F118SoQiOEUgx~dkLSFepFZ!`^9MZ7>v?^iPm!%|k&lj9pBXw1$P7A# z^MKj8r49iFb*q)fhq>a*h!1gPi?e-Yr{lhN!ee#jW5FV0|HRXKLbmNk4tyV3bB$yi zcN1*( z;~%uBOyzHP@;e*8ZJ)!%=iaR#n1c8@F_pZSZK_R907%*$)9zjKI)p0cr6aNQA84af_+xfb-D znv3r_xM_PQ52Jy))X*7KM~tC4tAj9-0q&X$8Gd({L56mV&$uqAo}bpsAtI0$J_&L2 z3&|PJ*$%yhCr@;W&rp1LTLINbQZ}-P=U2QH5H>U3eC3?1F%K@%SE#`9@8s5_*?~O? z3I}fr5JBbFUh{LNA$b;1Lq&Ej9ht7bHvV)UZ$;gk$GmeLC8!96M{Ju=y`mKDmYJxY zaLYIb{EX0o9hX(lU?vK{Zb)sjZ_$*izbMU!&zDZbi9>J zN_+yWD2Das;QY0O0WJk}VELGK}0p{=pTqQB)t6B``j|66>d|DEjjqJh5? z#I%MV*|VG#d%q<6VzJe~6ZxGrrv2jB?3+UayF#B0U>=k8T#B#p%6-_Y5}LLmtNPr>kZJ8bbo3 zVLkp2yjpR@!pg(ZL*ZH|GeVM@AR)p!_o`j!WX-5aj}Z1Du|>!a$~DaQW$OEmD{^mC zj!xbkB?ZQwTn_0{@C|R2UrHHBAvGRKuaGQz6w$CF&JrM7YRzZq z@tA5nhEId~97S%Pk?KU3lWBmfz1@PrqwjZwa%E(#%wsKeV9X;@!0g8T6JJ!My*cVh zlk(CXC{+g1Sj^TR)Z;&Bg>QpnrF(%q#({$m6uG^J8!G~=yM0e<@|zqH{n0RDz3dUb*enrtH|f3TEQ1 zEoK!Ik%+NcD23E@fhwIM_Omp|G8S}6#liE^oyqqO9tj(l+4l@0*|Xj1>+ih|JvR6; z$jy4WY@g>c5K?VH!X__oh84ejCYz^xsqMR;y=n5ulr!@s+e;(3xUFo3TJf^?6y=X= z`KpRSXPdMc+q5cT+7rTt?CMsAlh`=Ld_MgcFP-#4($z@@ y>m=1mF&*yISR7A=e=iYTGB(Z93Pf=b@cxLO?M0)qAPp%D8np+arA0VIg!~C?rt4w= delta 50659 zcmZsgLv$s8wr#_TZQHhOJE=H1v7JABRJR@qqY7e4%m$6vwI8VOsnmnh@*j;GK8U`WuW zV)K1JTTR2u7%ipasES3ZIycb3fZ+=F-K@s^dYT%U=t7dj5@od!!N4+voynlBMu#_b za?G>aj$)AN` zQGhJ|UFy*@&^KTryl@`{@Y$gUyQAV+1|w`9!~Et5fWZ18Kyo~&2M^s z9S@l{{&UnoLIw85KLdq&$jsHOhw#q|hpk|&E}d>lXTY>ou+6(4G}O>TT(pxzwJ9!A zceC7Ct*J5&{aOTnjxxFI)R%sxCjb^h;R=ZcvV+Qr8Zd93JgbsVKSnvsU7*Md~X=owz})7_w(TAJVL?0~M`f1gl?Ajy-A;Px}-V>;fU zSkm__W6()M2VlFfg6B(21)E`WIA`8E+h+3DvR)WJ%jDV4Y`H5JCAVH&3{{}6m z&|7;u`QD$Pm}>9Ch~SnS@vn53pAf@RNuh=4zWp9PCYVy@l$6^qWVJsDm&Cw8wWhM2 zA-P=(oT~ONQ3gS8m$@(+1Q8dC!A^o*?TSz~O@Iu({T;s}L`cxmhhyS!-E4a|?HJT>=4fhs#JcY+CMrAhtGK`cg`3X(K;%n1l%{C zo4{}KBAQ=Yud$l6VUI1wSk+nthcJ|@H>DQN@w8e8TkuIRoX&}_9wGEtMPRmA%9mT5 z+cVPEsLE9tZH&vv37LXR4z5Rv>H0@nGIS9&xrphs;MR<9rs9g0wIWFtVC>P#zVpJm z7EWacw?sV|Php%%_VF36WSKI5aM&`URe&~<=^YM~ZVJ=TGGtl;Y@!nTHV=<%EqF$O z%-9dKS9SXx9^y)z<_{*1Tg_-|zuV!Q)0#1vB=OoXF=CV1CiyMI1H(eMATZkIilP;i z_=|aliASkv)XE=Akvpi*Kuek1%g4R6jLlU-!%-B9%|L3fnLuH1UBi%_ETAr(zwMg|M zZZNIGIy!qkfCu`>xxFUlo`OsPSlW34U}l9hhIk!U-FwzU7eUr+gI>|(DlAv>%|gD# zC0Z4n?d)v+_B>?{*Gxp096lOW5NJ*z8~Y52TFM!bl}*k`1_L7&h^VvVx~T-Uyoin} z1GP=tl`>{65B1!z(Z6a5ri)iLAF#Y+eYi0)%0X2IT5?d%Zd^2Q2;u5Qc(?lg~F@o3awrxj2Itmv0@)+Q>b(54sG2h0qLQi>a*HO0BkW2zIAKIQf0xoqG< z!&euD>N3yrYaf|Xss1LdR*}IY3KOjADBBpz5c%V%w~+D@(2Bl>%tZRxW&f4~|J)&~ z8JUS+YmqrpPHi60UGq<*8OS;x1%~qOj{*DLnm$+hIB~rCZ>nnKbN~MG*!BBO8E8`S zwS2Dk#vEh(=-Bm}Uz5shzv}(KD^ZkO8^d5E_Ah(seyiB+KxoUkX{{08vH|N=^*rm* ztA5@_nsJJL+|H)LlC#_mWpEIRy{iGr5VLW;TTudd!?p3g!9}yN5U}uu!W@5O&6dhq z8Ds&A?ZS3C9aqOSBa5syuKA+Spw*3Qjj4_n6Yn5)qhLF6oxZ&MFmvQ21Cm2>hH{Sfty2zAMyM+C(VGxlc1Y;hOp_B4w=TIP^?o9xmTD>k0Nqb^u zfrrXY;M7m6KRpQC9M}OS&#HpL9TX)sQIGpcE()eCLRGep5yZ%K%}ULh>yIL01;B=+ z=Ns`YF{B+cfx!O6&~AXH5}!2j`(KO#LH}6>8Arox(tKAs%FYQ>q=C?hok4kUiA5=F zVGyy=vMZg<5VJCK<5dR>Et#iv|Ga*<=R{lZ&8qcd*Y(L_ciKH2arWCz`|;1+V`R-C z7$C?5DIInn0P0_?v;T#`$0y?|^>J8Qf!)}kZVTf<-;DCyNmEJsF_D}hP@=~?p36@Y z9jyt)K+fJxNM8yJ84QJ#dj$CN}bw(mE``SPlUE?G^WNaJGIAJf0CH}k( ziapYfn4GO&9t+xrCYr`B8nYl3qTI8d(T0QD!H86uBe(CF6jt_x3tac`RyNQGboEpw zL2y6L04~@w3-0EnBjaL3N+y+KW#DN@?WbkgZVn;HWOYa@s)a4T z&doZUCCVN{QM@50P=dwMPL6C!cHcUWYp{|Fo_g}JsGu?m<;heApz%36Hs<5Vvg-*y>2U`)VC%g6o_r zvjKhP1;I`Dn@bp^72K((rQ>*StBm za;v@TM>D(tRecmRF3ypYk9eS~t2z1suru$}a%%6h$cPCY(%P8rE7>jH(hy2SnL17QE;QIkonApynLB!HmmBOkJ{uCsao9T=%gxEAW;Y-mdLh7;1S&g4uaJ$kn^Iwu$nk@B2Vvz#c^7^zUmIT zms&)Yz37d6?UZ9Z;A9t&Q27PO&U-kidDi}MYn#$Zi~o6`oS%HFRgpp{6%G!=3Xp2A zMB?w>WCNjGU>MfRh}gWr-6Zz_-Zm8lv*~R11cJY~Z*uTm&TbvGuD(*ff7IqxBpawb ztZV99sMmC^t3tS@VG4F*M0%^9zfo7>X-KQg-2^v%zg)EP ziij8Lj1&>fdkGb#%4p&3R^&IfjnV)(_$te6wJ6G6gXo*f)i|TuhH|HY$kaMML3flN z{3nYs4j&UKHgSyUUS{H7%91Zf1`tj;_^J}@KJT5|iQbyf?0S)ccrMI5sm=HWe_rC9 z;WaKu?uBVY&L!I#InY;_ZG14mf=Q>g0sihdBWz;+$`YUsv66kmQ86DA^MqJKg!?%G z@ewM6Nc57wIkrT(T>ONA66le-x+WM8SB4t5#T57#%WRfT+zZijn90(UO1BmwWD2AxbC~p` z(N$tgsb&l6$1m{qnS-Ul799u&p|;rr3fV&nIU_MS0}6@(F~Arjo1l6X8PwmO5Vq$p zyj_)leXIhq3ccCEzO|tSK0q`iQ2(u;?O+eTiXexOs`#kBx*yZJWVR_)xu$VwYe2>@B%9`4(dX0z)O3r*O9_E{Lb=h=b%QN2ro#X?T_=2oWK zAPXuvi(j^EMJAUS-X{zj9URCM#wK<0mWk4Uu1$BGAcCr~!)8dQej>uFfdn^8#=Vmb zH?mGtyje77Qy`&PI7L?_O)l4*7CFZ}2nxa8Z^%TT>;XoYq7zd?pXP{X^^0bccRv=_ zLx5Zzl8#vTd3s2g62n(=HW6F!Fb=uhecD9;>E`!Qio=LD}F-Am@q3xglGBp zFso2xpjQw(Z5@vcKSd}pcLW6!^JO4ID6oJT@{j-eb}Z%g^mvub8bB0Mj%ry!d*>zy zAqDi+p$y z5sdr*n>+-0!{VFo+pJwk%(;+C{t^l4k%qKT=X1xi&%u)|aB5l8P_@^s-4jtZ-nwSU zbq{7qVtb8B?&moK#UEcQ2w8voh926@M}SwEQ}%u9P!d{lqt1aaDzdtdLSS-qEe zYaN^o4K2ES4~z9uxN=NMYOI9i8Z|5}qJdV4;=fI(3ww0>Xw$A4>HI;I&OXOlH`3fN zS%D(OSDiI!S@@RD3@26JuR60|i;cnr!&FxKX;b_hr2SmwNpD-0M1p53AkpL)oaVxm zRJ_WDdgGRUo(;-A-$-v$d!Vs~p?8Z$4I4l6AdQM?vFK-^?~qbyiPW~%{#E^yHo&ky zo$^{{;{a{ZgZ9I45OCGGzNyM99MZI>4{dN_M98R6S8vS6%TN6iu{}s`JYCT8 z6Urc=_rK*H=rdCu+Ru!0_FLN<1~p%UMusU`o3>$Gu9nj;43cJiHPx5+l${zcJDz*0 zB|ZPXY2jlE`Y|*ZnZVke6l8#REIMw5Klu%?fN* zj(Fshkl6}riLVEc;&f@L(^FT5gp2&%3zz)IJ6U>rdK`&7#D7uYW)xQgQtmMD#X zxW&MQV};4$$k~I{UQg-LEVmWf^lbh*r*auxk>EV#MIxKdu z9fNI*b4J6^BO>D$P++g#`xB_;g81}hSEtCU5}KgldtMgTT7E-OckAsYt_$>IZL?Cp z4Z0DVJ&kvv^^Vp#(`c$Ze}BehrE675m7#EK$j?G4J>DUalP0L_?YQCg`X!?rT-z^P zFu_Sb8#R#A+QWgi*l?xqFi~dRk@VBH$q;N?jNQFJP4YKHIG}>nl#)+ImyAa1F4!R* z-vnjg8^0Uf$sVZ)6Q)A13j{#|iCg`j3fH;Cbfm);#|FCB4JcEkGnwon?1)c|3NqLawI>tD#lwq@&LeLu^}O!;{$ju(~qqT5Q#aLI&N}EwCUm@pPJC z?4h#2eC>6t3Sd^|w%_N!4L9Vy9m1Q#Fbw#~(;#8%?p~%fRV*x|Vk<(o!a+VUQc2Xa zVGcK#j*5`R8cqd<@M$uH`bv;=a;T1W&*p>8ib zC=m_Qz)bhSxlV>u!2|)zMB(uxr&U%Rs4j98OvoTkerq4< zTsgICcuK|Z_>;rFzz&2beeUWB$*|uJh15&Hh4{U{Wgms-;WWG{G%pZkn0Ed&;du$) z$?`o&q(BOmh&R`RO(<{A26VDg(Ont_a?Gf!{vN>q^ZNnSX&*d}^d}8}LiL==A#2>4 z*MUdlVvgW_^CTv&!vi=QN-ViwBB(b8#$)Frmqnqw_5Ga}8&Uf7cQR23iiS{|AN{=o z-g1_o#)5WB2P21D!AiX8n7$l9JaKvGmA1dkzkqOwASWnys2=|qz->&#GF7`>*~(Pf z>qvHfX&E^=+lP1yfetI_E&I|DD?Z)natj^=yxbfAxkG{H?i7-U2tVgh;gPNYbHa21 z8%!spo9OvU>(y*7X`UCP3Jj)r%3y?+<=2!}Fy&VlT6KlQWZp%-_vuh55N+J%`NPZ1 z-VXdY54`l$)w77|E1GCgNZP>a!6Zt4i5xc&^nA7nr(uy-&ki?INNNX@iiJQYy>7I! zlatC~Z=J?l{l;O#%`^Yc7nJpPHHC$Z$T}wbA|l7X^aY3S>hRi4rB3W2WXT{FaYLSr zG_#K$#S$0E^x6kqu*r7$Wwg1*QQ0Dfpc&Z0aA<^mqb__dDPGrQxbl8eqyIQHe@^-5 zu(ylHHd`CF2mm%$=EnYhe-5}`K6BV>%7e5NMHQcHPuk;8O*p+yu zsZDai2jKJh8l24;3*OMS;DJ%qc2k7BK<`f;>kdF3UBGa}N$~0-`8O4y2FFBe!vOf9 z3U?dG8^Kf$>Y`urmebrJWG0Vm`D*B6fffTZDU2dRq~!Efaypkh=-4s?h2Qb_BiuvH zX0M-p!KR5)J&K%cuA3ns8%cg*R>1Q_>l&;#HULY5-BWq|c`T`IKORnU_UhF0sX^?f z2ul1YKtPilynadT7#tg)Cg!Z32pL#!f;kqf`WgPWl|P%nWmny$#vf|a33P|uWelU_ zHU}<^7S@BCzDPuZ!S+)B=?ltxb-D4zl*I1JGVR6&IPTxm=3hw*+CBju!!sVMjUJcG zj?@wqo(d?>zu6o5VUrbJU=NoiwA=tSBYD=I%vaDuqVYIYdi{n9{5ymM{{j?wU-aPBcsY`QA!K@F#7!gE zMeK{64>pl^&K3T?(3mu*`=@yy+hh>|ouda?)hA^*ez2|p3s+e$oeq5s^cY)Id zG>O2(<#@wt2IfNSXS5f-&VZ_Yq8iUzT?DvJ&>Fk!uF=lj8KJd+2vm>7DJjH$dCK0U z$qz-+IgaoBzlW$FaQ!5R-%0ei)ZomV9RI6#@Fo)R+MWds2eRc;B_KWyD)DV;WVDYd z8cs~7N-jtSjHyhM%(*N+yoBg`Q1v7Ud3cLYgpnb3V%tC;XP%c0e@K?ciAi_}^qC}+ zU4kL;XeLpx0ImW=U#z{k*c`L=n(nM6lhG4eNi=GvpC=9DEAQ3tO)ejVXa+|by)=`+ ziMmyXx^F+<=S>V8<2N$08I%IBJwR~`&diEd-)E$h%iHxeG@04b*-o8a9JhruOq&CT zm&fyMl>=fp`4Z?NSqK6k+atWW>)CXYW986enUTpJ-0FP`Q{!g5scT}1nqkzTkrqx! zGfwxC>iw+@1{}HX`Y|Vm=oAFpGZX>HvnQE%BAkE-6-o??S6mQoMS%UAJ2_V^qIiF_ z#sr#;HB(ib9H#2w*?pP*DqNhD_Po5w(PFA5N8>$5Umz4g02V@G6q@*++vi| z8kCx>;t7sMHQ3E*jwlML{?Ds1ONKS&@|&Bc-xsCQUk2ng9fhz>(F-S;+04ZNzahO*YdNau!X9mV zEzgYkx{n%VJ&1_txYxQD+isoh)ATZ>&tS3sNQK!jzYF`v0>E%O@D>p$*aV%ohuAcU z=WM4sEQ1H>!YK?A@+g7MN*{SBP(tct4#VxYj{lU5geFa`%JfD{4|2MuFRTH+U-nDN zdt-p6-#@^ryuRFW-m#cH+u;@!-AtGjm0a}`S>&FOu`p-XD1DVP)GCk?AymX5m~x}Y zDz7*qsK%>sO}mh>NJbDSrKn_;DV|r_M-J`0gV+QrBXEpIjz^W622S_I*tKmoV)xnF z@va1I>x2REWf=>B3PvJ0O1Mf>7K=jpFIyxM3x&OBoOr^b+{ZWL;hg6 zlV_Q2FX~mp(7QK1YgGSr%BMB@?xF+tyf=7hE>1S~X zPMP_}3)R&%t)gw~@h^&l%%H_g3^ql>ZS5kB!&!DJ>BkDbwNjFf=6Bf;72v-us zQTWTr_SFE+$^xo`6B!o`Bzo4+Di`YS>EzuW@-#<9@Ut|*2IA>3!9Us5KynC#?dNCi zazp?Tgk1==nZW5{6VkX2&DHU5H~6DdjlaUdSDlUT=17&%->?T>V+EiLl}^kKy;rsFer}X0riT% zHp2bsTp}>2i+TvgW6^W}x`UX}*>}LHrpxn~;!CwN;~FcFq5VUpG|h}~iG-Jb(s*wM zl28hVZc$joGc6ppQU~_(3WOH-L;gjU=c_sxki!8Ih~Q2Mt)Fo(etnOabyGecAja?< zx&3(F(empH7%aBJFn)9!7=xEUbqkg}!K#khWx8cRT0=w6k)-4*!$G(c@Om|S=otj7 z$6%k05n(>y&)ManbqOQ#;`Cgd9&}Me*ei|81?MMpreWA9R@ zw@g55k_#c9jU}3}ZlOYHgfGgVq*k{dWSj@6M|+(9F^j1h#8}x+9QB-c$gbYU?3PyZ zQcw#SaXMbey_M!9g6Y9uyNVf^t)2cA8#>p?9)wZg?wgG~TJV&`3i7~ccv@xK2Afnd z3b9O#CFbSj-6`x47GDZBt#}tu1|1sD4+1Y7sfL`h^r4VcMov82FT;g-5R-y)Bj*G( z|9yqgfm8O2>oCfNYXPM)4{6Y~&qr!deGwU?#ZmTS)y>bW%xsVIEj2)@HTq5em5xbo zuD__-iP=z2$s~x7sFb;On(+f6>P#58*4_$Qgd1~;%;;`GQ(mS-%mo0;5DmQdm&L|WY`n2Fz>vXV;&=2_E78h=aj=*7 zg7HX|*p9btNq;G)(hqsDI|o;sjW+!7G#z;2Zc$|be*b9WLhM>?csB!bt%25eb)VU& z&omT>;P0S)m3U)HcT)y|yQ5R@Rgxa8r=0Bwx1D<*3bbd|(1*#neJ-X($q2y65&I^> zKf%@XTx_dR*-$i2l>-R(y?i-M9Oe9wN_O|!y z#)mO%%&pU9R(rh-+{;-Cj4Z$n-Ws7-Z*14pq&-R6VPH(3KD^49#@{;Hq4|9TE$`x= z)&lS3T@!iK$^f1Ci2y#lKN_o3x0RHhFrX-jPcufc=}tT}`)k1FT>~IRImPTy#EPAP zyzT8bdN%NjlJ4)l*aJ%tA^sT6Av*gdZ;|<)wA@QieLR+3#?n+2Ez?VuF9L?M%<7+D`BFc32_N(B4yK{mJM>Y7(A$!k6*}F~FQMLVE$rd3 z{&%%6Zs^p|;x^!V)#ym+8WxYR9@low?3e7gjede>*VJiw$42;E?4g?e^(Mr=F%#)_ zS&y2vrB5#^5jbw&dOKB^phO@-JB@0SZ;Onjl@3!@r@ffMX4jJqn{tmjmLR81ovwBF z(Ae@Dz0-GVum>*OAA78IKaG%oV?xL8oV~!x)P0Ur!Z~2$UrJ_N*z>fGvt#Fv@tJ2T za}9`WCTn$0K;&Gw>!Tiz&*Ll9cf}(AO*C@jUBe_?*7d=fIY<0Mo4^u>lU1`rTSfR6 z>;<9!_`sJUWEr?EOW!?S4F0LcC;gyB{tCXjk^SU4B`m=%k@5D8Ad|0Im<(L0ZQ6}i zujfJE?G*5rY|wxp$a1eN{M#fn*>5ZHBkRRFqi~7Ey*r#Ii$h*wR|43)H3C={z1F2m;pnq;yI|)dWfhCyky~YPbW$f8v80Z+f@rIfdpgK` zd-sVs*OroRZZ>Z|jTB1aC!W6K+{QmyU|Hn(Sn2O)H0WSrX@#gqS{=esak#+7os7ID zMY-HkE+01v=E{lQ8KK~s8N3`;MD$qk8HFa=j;ZF3l@31Ohj=L147hSuvc3R48!CNGLi*WXu9SChOyVTf7Mi&93e5YqEL{R0-%EoL*j==58ivvW-)x2Ay!5nJjvGLXM+)%-8t9ntoxf5Dx5#taj)T^3)lt^#!;dd4o5r zYN9u^gd+I;Zci2Ay=D(egs_YK#a$ix&%h1bFz3v@boy8Uq9kzZQvLY3~*jtft= zg+|=zMtaFT7?PV?L~@?hRp(;>>fUlS+nX-t<@-bH9tEN8Vxr2`Wx)Eg9O#&3!N;(U9&HIM`G(wqpV7A&ME?OH5%gdOVsLe@68?w+5pASMQ$hg z0E*7e6T+rcw8i}tBV4T`!TDrZ;3Zi;hwQy|hAwk=xq2hGR-m|ljybM9Y7aNiEI8_y zLSJod+wujk@1^*b6luVULJJ-VGxIwq8WUJV{P=isAp+b@Sd-cpdVjM0@p}MXE)KlS zjq~DWboDRMmO{a)==^y5&HV1ESYo-KJ(L{_2$9c}R;qA+zvS#smQ%U$@4r}>_bK%{ zTXB}>;drSboM22lhvB2=oP`KLwE-%`k}!Ab7;;LtY*k8}e*^?{pgpo65&C4|%mZ$J zSX$(1Kg!2Wc3H;H?#CJTdPT8BNyo}!e=NO87(B0&f~1YwOa~_e@DN79oQn*`T~)ye zWY+)Y37JZY_+8{PwP7P%ZVmu$8Uu08m=>+tvF*1bM#9x>Sb|!*=V~Q@#Kxw)2*R6^ z!z4xL$y|ODZ*J$H#fY=eh3H$Exj}2*+&l$YjIC}?%Zb6DhUl3xRhb?`=t6ycLSciB z_yoD^VWG4BdS5(#Gb~`i5mK4CqWCF*3;m0-kHZw@EUG{S;#9qiQzJxzsg?9wovkyx zDP;H8tNNNc)>P_&9&!{Q3ay0T1~Xy!FK99C(2HqVj^VQ2HUPD7`kl-+Q_~tPm^W%J z&248hsc-*LJY)fZc|S=4qP9sA7uR#DYUV-GCak(=YDoa5qZ%PXIpN=MlJGOozu3xE z24&<7n9E#6c5H_p85Q_wmeiV&MgA2F7u*qu2 ztyWJ?A-piJe~ZU|IcN#@rKKt>G;)tc%BI?>9M$1ToXf3al09^mXY=M;-rLm?C?@w^ zJq^?($1ODw{IU*h9Bq$@%C29v?ZmQo3ru!bUp}f^5paF&b~Ur2Tdg*4gWjqUufCx3 z+@wLT(U+}rOU|l+R}Tt`_)&;81uIph#5j>)#wi_nE&m3o?f8sKRb7s1wo6MhYYcj$ z^0N$!@N8Fmrn&LciL|co`tY!4<~R}Ux|cj!M;I?yF)b{+E3j6%nlI57a~Z+Ou+f1e z>pcqI4t5l8xTD$*F8CDosQd}V@bF^^khXd1f*9#}_B{!}Had-+Rg1p05OO1!D(##} zD-w)KP~43GxY9NQdV8!XYq&8?S*6^V(6>^rRa*m}-vQSu34!KHB5EbhL0{!65qq6> zQ9pfPx*x)N}sDOZF6uRKE_aO3cq z(gg}R7xEB5GR79DCP(>{3rDBe3Vz5=RKGQ=b|>nLQzzy$qvN!^-JeW?ICpq3OdVhB zS-=Y^%Cs_sKzUvs zuB2b>gje}Qv9iltaE9J5csY5(PX4eHEX^1Bs`v811?ebfdu0ymgv!yYTGVlawh>Qm zc`u$Tqjc^E(1o>QyA_NXVp(UI6xF)rJ~Pd0UKw&n$ge7=rzfiIaQKZSS#o+2h$0|NQtn^eic7y(-771y!7s(8>ze>d}8x@3ZDBx8p@NN8Hk_bu`0TB~vDERGT_XPN=3 z*-falJgU|Ow|D9*dZoxZIdEB0E8MiNF`J%Lp>3>3zFpzMZa6}uSO!hJafMJ-5U!Eo ztU{-s(JdqS1bU(F9a%d3OMh{V;QGM>vpLDs?Ent2g~{$|)u0-%U4E7v{XBAg!Dl0< z-=!NCY=lzn_}g~H3JRWp!$q=df%wFZp^VYc=;cdwyCn3-Ok_8Wxx>{d@+&+2nna(= zs%#|Dmfp>4{y!qpGRgcG-(UFz5~U0Y0QZm1%r>@=xz#AznuEJ@Om3hMEFuBWp=0ZQ zg}GIvcIul(_}izI0Y z_NJcNS0xfk+0-yeiX}97i{_=TwMN=ymjDME_Cix?&T#Ex>7{v-UcVXO)XfLmg`tIX zO@&TB5B{t2=`zc!L;e!xU9cO7_sGp*_X+(jh`8Ckd+hDCbMkR_OdA**o%RcgZv*K7 z1ok}8eh>mRA05EF-ctk;UTD|y``U$CdRl~a(H5ZBtafwp>*_qy%qyLp;KgIrArz-) zAQELgKwM;ItHwe2Pac5BZID0zOV%q+=p_sE*@l8cg3Nwtj}%lUo(F>u-HT9M4yQdv#TC9`*0eNoU8)VPR|HgZMIKIj z2k+a_-|brFpOHS%u5$+RT{ky5yH@4c>;FT8fxo0B>fKcIyQiljqF8*1zvC5>@6y+< zyRhrNlgCJg`DtSg?+TTbwivy!0bq#6T(Tqfo(az3_Fy0uza8Nf%VV=A%!YF8&-5Mh zXT*y0KD^KEjVz@7;CH{(?ccU_Bu@@x=#QoiZKQR%*}54h>^=Y?;qCZQ-3RrYmVZ*S-l94GO+{=|b0g(j>%4cq0?wx-6 z4rSoFW+2uHJ9W5vSxn~T>L(T1RqkBEba#m0OhX|4~ zSm_a2VVUI3>@8d^iCK7<+5d|LNgu2TKx%sT`-?xUNmAS9r5WY`q77cbHN>*#r36&% z8}gstT~%}nZKkDy#USWJ9r|82wk3*mon!NN`vO+L+GNq+4CydT-`B-I?f*gEx9Oo5WlIANqpc6I} zlf)RDWx!ZboRK(^G@)Z4`5_L&s3oXKURW=LFX6w&SR~)|Fj`^5S>e-|rbt$h##R&t zUJHIUV`L-8gM}&B>2WXcOHy@|rB3uG%6@D-T2&Wmk^={K83!ZOOElbQiD=yb+Q0&O z5P9ZENa>}Xt9v1s<~N8SBYr3?RrzqaV5kvW zu&Y|=Z$twWqm@1DlmN%2J&D`$#cXz;&2=fbF%%!vM8NojcvV5z{er~qZ?yHXi?i`) z#p$!MiSyxTgAA&+ndK`lAZzV;h38AP*F&yJKT~hpO7HTNIulxt-o>#bQ;dP&#c>Zt z)wL57$MsLw*ACf6PI5nTI6Q%gDjKbreDusT+bj~&z8N)ACL9RE%UuggPAhI zOVxe1I4|R45bD;omm-5+A1(Cmp`n`4O@o={yenwNdNV12GsG>axc}G_Xd*DE7(SL z>W5RxcGu?ys_QpW*CzPML{SEp0cGXS^2Y2^PiX8aRMtynn!iO@4-FsN(H{XMeWoIZ z<<=wvql}v@aI#JUVAibakYSY=yu(B4vr}j9ieRnHcC$COG688{#OaLJJZD#`ZyAZL zHTOA3bN`Pvm!mP%M*Y7}n?ADb-Hx_R$6t&lGkk2ky}3Dbp+!a3uK%9ZOe7tczHKWP zrY8QZL|e4wn;KA5Ep(l@J9G6|+v}#T^m;A&wDlrnlu}XHDg3*+A>MEuS6TIIjr)I17At;r67<3$ZU^ z!sNvH5%v)F@Gst9cL4e_GuYC^W~doN2OmHwOrsD$A>hU9UlNF4x2|@-t9=J_oTgESAJ=6-#U$Ll#nv$1*N|7Itdi`tPjZ0K6eE5deS;fmH zWvP;H^h<~xMv^5SjP@gx`g-J11As9SmiCWt1Gg?!vij@*(z?yMdeMoaCH{gjHMk_h zWH#?e>wNV-F2nIf@kpAfxa?=#Z%x*DhrXYHyQ-04U^v}m&;9ny%sZlpg9b7i+AkC| z@h%DdllpRH|CDjB{Ap^kC{qb*JXo`wP(h3d*_W0Uv(|_(tq%Ag5T?jOQk5{PG*M`B zw|Xc_O?=HPLLTB~7sez72rl$V*h=K;15)j<;Hz@^)OLkziblpEqG_{6n2CzXW|2dK4sej4 zl-q+2AlFsn`rrzN_w$iaTd2JeYGa|jq%d)W3!Loqd7&u~xJ9JZHIeGUv2~S25h4$U zfCkh}QBzswIWi{imklmBG}=kF=aPI_jOfylZ#CYdrR3hfZi~JW5zU+YoIvQ1nINrI z?3!(C`i@97092Ez2cQo|o(1X*mYlmDtFi{$83LOGrrs}lGgV!vk78<8i81P#TS02) zK3NM$FpuuB3PNP?>7qCzIVqNbBdW_OK$w5~&v=qcq?gLS2pT6LK%)sUn7pq($1xD$ zFr#20RJDgZ#0w!y-Kz7V`VXGPh})9o6PVuxDgfh^igHwUEw(Bn=TywPmkF@iwz_^q zp&t~AD^U$#`gjb@y=KV&go7^_W%xgr z8317o%gT~~f(FjQ&5>4+14;v&(bjd?l*ILYt=l6*P+#mY#5@z*ptOX$!raE55mUo% z)p9?qL?*CmJ3_%XTGW;IMCTpJsA!qAs_icZ> z_RyKGe^C>Oa4LOUyY`{xJ`{%yyYK$veLpqQ7M7|i5j|+OgfcUh`fqvYIM_*Is_nW` z=M%-Q+T3qJ^Oh#bFC`V&m)E-3z9z`%oB4TL(vLy3vOGB#t1C=V5PGdkoFiZd8XHY- zl*~N|cg?*(t9^I5r>oGM#Av%T?4$t=$cW9d+zQ@o&7y>l;~E)8rc~c*oe)=t7R?zo z3+!mW#I$n!x;)7=FSM@Tyc4W#^4g|I*qcm=@&akt7BY@T3HboB^pkC?*|JjEInQ3N zHP3Dq@4Xu(5o|VpQ`t7o#Vz(Ku(=^)2O`gS7$3TxPSemgI0ydpMco16b!54@H2jx>b`eH6X1ig7jUwhk+BihH3-;5 zhR~?yn!(m{Ysv%r{k<{zlE@>a?Hk}&094lN$N}YX?j<_2!poR$bBOt@CzDdU_(PSp zlPD#zK`HthaRarFMkzeQoqjCUgZwB}vA^FV4uVWl=p?&T?|YDcKUwy#gMKiAi;*G} zU)IG^q=@B*3*NpLd0ph?RZ&G;Ve-vRuEs#Wrh|L9xg`O~Ktc+*S4{@j^w#l_>+#Y2 zfs#c>!?&^#84k)E_dUp)q!fr z0bN-YQIrF!l(Jx?OQ{_IR?P;G};E^UAJLTBEL=yfYAJ z4RMQ$IW2&+_5<@6uNWR&?>Hmdct+&1DtXCUJmBsR={zF%CLzJE)qJ|LSEsbrBwDV1 zO?o6IR;OtCeq442zJ_L^<98Q;cjO_*X)c5VXe=vy{z4K6s|MAXivHcXn2EngNA6N1h(3Q8ms`)i)P1np+m^n}^(y^~%zu z(4+Ia@PT9wj46S{P)`8AARvL^-JYDBYAfQjMJ?nd#PoEV$(_Jot4SLJ_uW+x*ljAB zY6uLW-#b?5F_^}UE}>7r31c*8Zyqe@baBuKwUu~vWr0hpctGmAt2*c3!9SMNYY)k^ z)LOJ&;B*3XJ~*wq?kqV?GTmG(*C=VZ;Y2;Z?2JWNgX$h^!xr<(ojMR6PEYSDtUjg+ zLt5&5cLO^|sf|0Jw(0<+%+@f6-nWWD9zgUdZz*dCJI7hdOMJTPS`Wu{;sF4Q6K;KuHy}(iPO05qhJE{h+KeQq5ZOJ>O zPpJ9MXoQAp`Z(8=?fZ!;*_fu&j6*5XREJc9%=FIlBGPkSPCCNjhnI$L<)WDHq9)Q} z>qTE*S>*Re*y@{+6QH9~gd9m>5SU2J{`%}CxH;s8MiYC(+jY-?bAsSB?oZwpLoc+l za5{w>b5JVUtI->w=BM^thhw+F@hB3=^jUG{7JFIuRGQp$ie#I{LN}M;|Ln+wd<0Aq8{9Aq@FiPqu=gRg49*EH5Iemnm z#0n$PJ%%9}ZH32c{m1%F=~pJPBto!QQ(7=lRa+XdQ~TaAR|h~62th0=fjWQN!P>zo zCv(GX?Xsi|O0?O>R4t<5zWZSlFP209@+dXaD_}aE@+n%;< z+s3qgXZObL!^U4x5mm1hkrA1v@|=@P{O>G4B1tQ$y;BBCLXjfce(Sx3SfAy6EvMh; zEiWSC@hm95MUw@yX6uU!(bpDVzwGk@|LTOQ z*%cSut``d>d36kaufv_RjK(cfwY?@J9wV+N#bz7nS6-Q4+?_pecB~y*Q}m+?AqhYC zPSx31f4ry6C(muPceeTI9suLUo?oUdQXJ-<{02KIgnvIC{okB&XDOnZN%M}HCU`ZExTyZ&Y1CyrdX`|Xct7EIk|^M=2~Ny5xEAhnq5qfr2Z zPoMmxqfoA(u=~E`75Eaftgy+3_|Q21ldM1a59c-+vjUC<=2?$Vn*b?(DQ(^w^Yaq` zJvzbthh0xUIo`5AO?Xu&&e`4vn?qqm0Me9q#yU~P-=3wt`@0;+oO*~$PL(Zp1FP(v z-X&%u1deHDTo+1%^YldSCVoa@)i-GZgSSBjX`xob5;_bkGquum7ijvns$=$DAN?&} zKlw|YmAiOQ@x9}NbAXiwkce>Tl>mNbc1U6E1|}8 z%z3%7zg2bO8o_*3l!lhE(t_!Wu3qN=Ou#lw$?p{JKNLgD!)_P{6Hd$1hv-y}h6HsM zw6Y|3Ehd;_z~;wt-lhi?>iyo1RnF}F(O(fM<@WTM!YT%t7khexw7+{7 zt;7nBp!x#q0y44uj)Tj`Ym!_zX|TbAeEs!JE77%+6ch7)I%JY5ykK4LRqQrxdu(D6T7TUV9s?BXsi_Urw z8c>v0&#crNj?P!r8^O zI@=BF&=Na4s8+ui9hX@*22Joo7Tv(ce`7_aG45Rd9F$;xF?CIAWYJNfwjh`zWNTEB*cPq1$JTpv1KvG>5mt%;I5;@X%l&{F9E-D{yd+|wn z&!q?rVF8LiV^s;pR!(G(k6|f$4H~JpQE<{^gQJeEI?@@;ljJJ=Vj4zgp<>+-W_#RZ@wyWJHEh9O7AMshZ zmm38s#t|{J9L;FstEcYpdJ8bEP-9(|G>7bra43fq$o^J|D{rUy5svp{1r(RI5y)Jm zk^wfgX^t=<#)q)2G}r|yTVv_3C|evwa?4sE(%6>ygXUl+gUVMKzdz&F56+b-^_1ct zQ$6YRa|4wt|M-#$S-Vv26i`W)vtXBdt;Whaf>AGwR7wgOM!3xo~Acx0?h;$#aWOZ^?(%F11zqw}XhuJeJPXLz$D9v}Xie zL*jiWs*8L2E%s6W%H@<~I~&-!oO1^=-&-znD3?cELPIIyHEY@?$u4Z!Up{0V;g}S6 zQs9ct7bLxn%%g?FqfrPYtx30^7r@;1{($<0xyJ|YLhMRs&sy-;@kiks-F9~32RNT; z5g>wy$e_w*X;%!5Q<+^|A0sPya;c`eyP8wT`c+F$Tlro-A0nC0uha!Df_SlE`*LaZ z6Qfk(nr6{@8( zZ+C%73ey#<$u>tI58PgejkJzGb7YF3XKOw1ZDqvo{OV4!i&!-DsS8zWbD6rx-{@aU z9`k2qBXJ*~=dT6px-oeQtN@K5x((#(6Dv&08^JsTH6k(*RSR02xe&fEvpDnIY@cux zKS|uDEw@`PyboK^ulJrtg1@Pej?ECLIJ%Uj)fA&t!Z>BG4wg3Dz_u)!o<-bUyu1aj zvG;q-Yxt~0-fyaw?6=lo%_|F|8; z5z>oceZ3f{Dq|z=y}+I~fMj%n)O7z%;GUKcMPyzKpIg`r_;dKY7w}jvX2>E+Xlm>J z7z9H?0C&@w1Szhmfe7%Uyu&1USPvppJ?*gN)8HhyjdkXg=m|1HKo{I>u%W4XAchp? z!Lf|haY{9Q;Uk`Qr_gjmTL3#`y1}0AZUEhUB3(#skSy1OwCvIl$_!m(OP7a+~msG4051l{}lTM39kjgDbfzu0~ zm-uk>gOgo&zvUF;gJw$3!3f!k7gPg#`BL|z_VTja{}g5VCu+Ge-~S~_dLR$u3FC2T z#4b8Vu5sT@SjkspfPj~EpK0!-Vz`8~V3}+p? zduVJ!027yQrw)m=h!jU97t8z5ac;cBC@)rT1 zP*wNa@oRtcCGxQpB^qU%5M*|jNb~n z?ECS)2dXUNk!O5dTC*VM%4M86BKF3$nW=-KA;$d^=lvc(ed(kV63i9_y)CH&UTi8! zg`S+s%opF<{`Y`-I;e&Q%2M6D+|Z9FIYe_`&#spP`D_`iHJURJ>`YI%v;|Q98_KjY!x>*wl!Q2z7>>kU-NjXK$t^(+pr~5->f95Ew;$Y(k0pVI6yV1+>+*s1 zEDLrsl51&zLXEU|6=e}i(634&zdXlYzTl{@adXnTRfGBcT|YW!I4cat?s9+lG@OSi ze#%LLEE!1&^~7VuAy87!|MrCO{{a}hF(en)>9Wi3a)M@;z}koFiHgWafirK$I7zX40cSRf?S+Lp94y(KbxGo*QNOBf0R-*2GQT~Y<3Jj!;%Zh;`{*g@BQGurxEf6qcAMFvgAf+Hh@Cj)A4Ufk zXT^qPLPc#*tOx5C(3JkghVOku^t^^Q4P;a}PGuCIPFls`jNNQ3o_IPcL@^mn0T(H= z?`)xfG1kE$IQdCTlS>bM7z4`eihFE6G}Q*&u`gd~?385_2!Hh5D|h1+z>7v#KyFpB zBLgg=N)ca`0A0xf7s@~~E?B||@PuB(7WGO@FJZOt=g%{USHDQ=$ju&lO5$Xh5{zl( zFuhkz%ksI|yQZF=C~qKZ7f%nIW;)ce90aX7cx)Zp$^rvG4p)%ec9PUPvbg&X} zL|60af&H?fo&u{)>oiS9{91|^kZ}V0^1%;W+#dFy@5x2U7mW;Ub+wXt_5v7MO3rYB z!k1dW`M&Q9`Q5*u<0UR7p%_`D4U~6~rg~XxQ*KWm=<#L_VV&N za&$GhvtXnNw)O$}%u$<6E#4~vQyHxV@@nL6|3C=LX`OH;hYtuB&!%5 z7>yX9nM1v$gRW7-YsbM}`aI;+ar1Zn`q%a)HL7Gl{_~X?DPL@DyREd5-<_O+hn9q%DdIdZ?*?Das87-8=vpcgXN;!1oXNsM3{Ak&u!*Wp2U zPzW)77cR4ymTuz=Sl^acNkG+v9zYsiRAqhZkJd3~+&lP!ZBO@qKxdyFkr=a}=1rGE zE@N1FSy_po{RrU7H)6-0O|LR-hyW*WmT5joT?q< zgbj%-{Zb1+a{r6;yTT3;#kzcunnGFI<9;(I-XkFc#3H8)WSYN|rp-<}rOr*vO5EoV zT|^!32pg-K=M22;R6i(7FNL1PJ*#fJrKb%s@incjx06Cmi&t=642p?ahWsEd15n{6 zR@y;k(%fnQ1v4MU%Fr3nGtewE{`zGHi`rJ@1gi?jX%HP%!*F>=VzOM-w%HedzJ*U8 zw$q0^y|6E1}f?YSFIN#W>unyXEhl~wr`jQwc68Q__q{>@&uj6RAZ-erZpMvk`g#d>cU+bt#XO#;pp3^ZQ~To)FP3*~ky;!g%>^;~GB zjSb94zLf`Z?_cDjTcYtNDlc^GpwA6;mVHO_4*|iGp7Yftz%=!(rZU>9D<-zU8bqPB z$`U9(L7FnhcR%#_eQpd`9|)n7c|XO&iaKRyh*P9Cu#NP|{Wvnc2kRlp`v_0}ipUI> zG&IWjh*p7?3QT)1+xZkbzOD&ZAV0@Jaq~=UHwX)eJLtZI@2J$-wTUTitoq zZa_V1#9LK=EHAF_S!~wc?KJ($o>k`kEi~a+3=+MW4Ueb-9mjEwp({X27Us7o5{~ti zXb&bm(6wPDyX@SJeA0O?t8~r1cJi49?my*+twjs4`2v5+;4$yP zA;{u#Y%9UsT9Npsx>u>_WdW2yfSKep`u_s16eABl;bJ?(A}m>LkG zDr29`h}3hc;qWLO6?G4*p;TOIg`h@QF;P=Pg3+x*XV! z?is6Ab|a#ynx7vmro|!7RTj-<4HJm(dnP_$^ob@Mc5gpqooc zv-}A>UG*V$7Kb;`n<%{49?b0h6VJA|RBTOSI&XBzBM>M#c4QNhIS_&x*MD->5cV7HRT}iw4A=nM>`4;qN;&W;M=MZ5^nV{G+Ro5ff2V0b>f;8`0u9o{_h7h_;X{9;|n@%1($ z)@7oehPeZ09${Yo*~d2)?0yXPAelevBJ>v5Hi?EQH6Z$m4$&MrF1`h1_LdLyrx9Yx z^1#Z#O)zF~_D3gqNuAu+rvTjcs2XqPQ`x#nh;OyFO{I{wfIG*7qq%72wO`%83s(() zWS&Hsl;=14MA7%bMkN9Eimwodj50ab@QUj zr(rlOLH5Vn3~+C6*ZYY?9)s|Z&jsC$I&2(MFqMG=hoD^_ru+Fpkh43g6GhML@btoA zLC_z2`_y3L)7A-rC~bl2R_3aSlas^kSq(r}msk4$02cFmKjik;6?GsQQy`|4o%@PZanu@j(FMrH`Zc)AxnwA5xV^+GLigAn$9D)J3(aPpZ8D6w*`fz1-lQ zX%AN`;BK1hVD0W}m748cH%fWQadenN00pEjv`1mN>gIQZ9$KSfZ;I+L`=nTMit=I+YD(tmuHK2Z#qYrGJ0huB z386K6Z{q@yekO<&lRv0w`Av}zBma!WL_z8{0g#PGur(!^UVAX#JwnR$2CDvS4^ivC z<@Yq!4tmAH_=kA!ujIb~WIe(W%kp;a%+gKo=r}IO&Qh}{U-XkIG+F$A9eWXl1qI>K zx#t=SR{NqPP1FRY%{36ig(dY!y8@$$5oFcYR8y`lg`x4-8AvrA7T9YKNvslMC`BKu z0BSL4;J~;(5*KoJmljE3ST9|CfQEQzBtmvW!}$_LH9blt;If(8DRniyKI6z7*PN2d z4d$!lu7jSM)+N`he~^0Gj!2N4 zx+pl9drA+*Y2LvOhAhc?^+V${0fziGI5+&omq zi@%dmu5(UrKlYa20c!?7-!mSO zH%W-0&KdSa_dBq`&JXo1Ae@Nsuh*ndydrl?h7in3bS$`37bL<#gIMXr;Y(cL;$oks zD;ht1lnBmaplfQ3u^~O6a3;eu$(00MF%ycn1d-G2dAYn%=s=qU`%Qrp)Eb^M1hmzz zcT!Xk&p=c(?G+)Vun^N=fO3%veo@Xo*g#67oOivpGTx2wJ44xBH&#$|&_0|5E0dP( z=Vi8vl(pxKFnr{jaaw|J3l#I?pT?;GH8VDx_WG$uC+5YdO)Z~<1nHQv0*uvsjFOrh z*7WZ`QVfDLGVYFcNcJ|J;K&qN9ilES(*%ySijv7uPVisH_YklVfLp_2Cvu7@rSPvP zNgf}vRxi_XoX?V<-s_>L2Ul>MT{QL5=?2u&f*a9Ixvg+#)h&?0uD189)JS|_JL>{& z`4TxE6kX_qozd~K`MR6COW%@Z3vgPnK8Oc;P|ff-r9Df_-MnxOf|)=Xq_kf|C?M@b zA`M~bL!>U>CP7$p00+;n6+#zpie!zjDVO$okG0_nW$(hDtrc`u6|sUMR07uR9PsKx zHxQ7hVrms7_Ca!J(xG=~j{<}~Ul_W+8b*pSO+@79WG3CX_#)6=4MSKpG&8ORvOn=3 z2#ct{+_0>okwV>O>;`j(UB4qAKF`!m;swv=_*uPYdY^+D{wb60FnT#^W1=O1A)Y*7 zJCUcaAp(D_SNBJ0)}?^^DVjJrNS>bA=2xJSz)ej>x{=IHEC>-|!GR+OXttj}%Iv1{ z>oRF8iz~w&_)p<#s4r$ z@T*|_lqq7_&yQPYB3A^AzPM^xTzfZ~Zx^L1(!C8R7&OZ__~Yk0pcA>_2P+^BGPtt& z*xY86H0hhG1&8hNnj%bOK$?}R^#iT6V zV^trVvpoc!G1lvTK25hpNOP4Lab7;{by}uCx!Oc#*Hr~`i+&HuL1YhaicfoW`D`&> z+#Ki*&^Wc-2zb*_tUvuSi@@dA`;0A=KmwDJ1-}fb-oOSn%OQxB?c*T8_YnD&Vu?ds z&H6NX0NUw0GQ2#KZfHU`M7AqJ=L8qW*hJCo>=^S(&-dUGOXiEeaZZ6K zf91PKj}C&2iqQv=nQjH7K~m;VHQ3}Mbf0qv==#LUpqf=pBu|L+SWC=ju4@-}nXE*d zGWABa_kZ#w;m6?%O`GUU*fEaGL2t42Fo$u&tD!}4184JdBpOeIUde2%yljuwuG9)M1lvPImwHVs(yI^YN7eo{iDo3HbKr2R zzD`MOsa*AC!@B5(Ut_?Qnt>)25gh3&qz7rc!5&?-j2U$MhQ}I;bc-FRl z7{xj=^G@JttI>(pSHO7tCqXq-T-0+jst2EGy%XU%k>ot_Ip|4>0q{cB3W6q)0LN)> zNUUJ4AEnN(<{!2*Lh(S?zo~wua6hQjHlJOkV4#`0ovF*1vK%-rPJ1Fye)m{0SJ;fy z%ePFinSx<#uwTDO`z+M-pO8-iBe%iV3RK=L%5WfD9x`luUDT?_@mrjc?R#!Y4~PJn zDDp>&3oQR>GV@psV0B%_AZd(q=3m^t^KH10H5V`iWrZU9iN4JWtE+=%RSP}{fqaF} zDzI70d1YvTNuBvm)g)(=lsOd`@INuf16osCcwK7?Yj zQkpel>_X|fq6kv?GV>U5O5VMvfs`J`_hS~_O&j|pV*8AM;s$Y#t*r1uQln~w0i3vq zA_*1V`}7&74NaaRl}NwY%rWRU>UiPA017f=Uj5B*ql>|4*zag@U~btxxL6JgW5+|* z+q;dh=l~`eqJ9Wo(kLduqUnT~`{E^i1YPdO0c&&APHnnukvKy|NcQn|N-ab7(?6R{ zD~BY;orWQRsLmN0-RFGx=mIJTcXf}yMog{l@eQu=9SSyh!EvOUVh&iZ)X;g(YfT7E z7K8fW4@tg{aO_4V_U)>MBSEb6nIX+0vU_9R$jqzb#$2!&_nHcF4Uh~Z#h{r{;jSJl z>k(rBH0<_B`rqVtxO`;j_oRwF=>j8t9V|;hfsbbZJt895$|Qt%a4+G;e5@w2(PJqL zOl$>4^mdWD@R50E_&IVVFwKeNj&dS_V<>`r-wGH6j&-b98?jbJQdnhToz?(#@mc~^ zPKxP{{5mR!qi|UE8IQ#NfMHE8iZPI>6JaLP*{DYI2A2*K_SizKnb@pEsztc#CAE~u z(nJ-&prNohq^zB#cqz5gIV=94h$B4dRGX?7<@-*Ng!jeuX_I*Q=!0k1hKl_RqWaVK zEyY8e_k~m!rwztOX6l>1Z<&61*$1o2m!HBPyHc74gXSf)bOmJ*1TrZJdXdyxv}P|_ z0zQTWeTWRrL(%iS$tQp!PVGFnQGeL)0R*KuLdR5PQoHzD*S z?P2_)I7f!U7CRwPx!Cr z@}TAN0hccS`SfA;2I$DV0!hVX>n0<+bvHQzS>9PHVYIhw4~oOVt^(aso!8zFu=@ku zICSZF(ZFU$$H|j>oD0S1IWX^%g-L@x!&4q1S;4b%1=B3?+n-i-n$7O7#4PINozA%g zeHC^6i{a!myMM!9uEYG~71CEZ?z#aG-iCm|`Oo*zq^|GKZ+6#d!62^|i!ythvsA^p zTt3VT+XqXs9s8=ws&S>JvfRKWvmR{}@OqvUr}bQh(&@(Ef$wL8)BEE`QXf*PY_V%w z$_2lBGHK^D=AKsFmO)a}Qy4>9W@n~`%}pWb(3ECj8Be9WjJE26(ikA}h_JEOgZwif6(EbfR$R!0GVwd<=7-)FQTID%^P*-h2hatmIg)We#k zfpDLufnXV<*+8oE8qUSud@%Cfu!(E8K^(N11)3%5?1bd6{kM&CP7(FC<4!;BeFSoE zM<2dC_+w$x^ZDv&_5rj=Dtrk2t&v}|z^9$vle;+1RYKdWbo3z|LlTM(XSFO!p>X(t zgCV`H7#JoGAF%w?xEJ?D60SZ^9@4nV_Dcc=y?eJ=hszf>ZyF`B^6I0fkWL%9mE$f> zYxJwj{ndPmWl6`CTIHzag9n3Ple@iNZ!V3QatMBQWmV&K(|~s)9=?yaW2WQ`9Vu;n+=>)IXQNgh%VYKa z+R^89$v{Rmqm?S)QY$%S@Mcq}SmpVwP<#>5phBG$S=GQo>#228P-p{-Tmxy`{@V7x zM2)D8W_;Pe8vtvoSnOo5-^lF5=?DE}&+o|x^csvL(BMKr?A9pR2>!>E!W~J$ zOmQH}Z^iuc1nh!`{lPt4_q=1+PN ze>R(zonXHfu@3Voziv?bJ~A~s35H6&AsY%fDmW{p*2m(0eU>x)5>Pd#OS*SGWFPS* zi+LtCj0)$SOJ?H$%FQ}Qg^uM3>&KZU11JQwMNX#%*RKd=btz04xY0NIqBXu5g`E?z zhcGNw_~?}#__|U*Lt-@u^o4iD{wqbGZ031MHS; zngwf5F$|2PM*~khY^S|~@DHq#cH^kx*m&X6MWsynM9!#4xV5#c*?W47qAJ*UA9mh< zftkQ$Ttn6j=e-WXt@A{vZ7D#lpog`| zT+{W|qr&$&V@vV=wyP^^oA&F6<-{6f@Tn|QG6$E-rZ*DY%GK-M#R#-t*zvKVk}fCluxPCL!{alnnLedUuvsC$eOjM;RxF~aBo_E&YJFkpY1w`(QC`I zjd&}SA0f&{+v&J7HUhtN4Y-Q z7Cgg>u?V5OgnYv0+IaY38A{uIb<6+ER2$kE3sE@8-(Go`88nfu1DJ#98xq$u`(Gm= zs=}a(FV;dOjdBk-Bl8eYIg$Zw;mUF0U$S@Lb>(XD>|NOCOqi_3xqRF^A zz;n-!B_QV}zot>xDSkKJoq|(nHRqy1HxNe4p$D zX>j1!OQ22)$>{p$-)CL=M?Hgd^v$`Z==PLaPhf;~*om#5<7EFfRc$bm*vIVsx1O_s ze_3?}4OTiEoYvndQbvsk&t|qo&Q*Thv=saI+U*ULN0gla9%+5p5PTM0~WmcewFdgF3d zhwZwW<&mQhya4Ywwh6XWDon`}_Uxt_M{OH{x1U>uA4kx~QnN;Hf}RZ@%dU>Q2ho~} zV`9V)CZoJw+fBJb!6K4HSqt;I5>Z0+a)~>_P|KUMQTsHuFoLCiC+0sj!vt92yPch0 z7m_+96lM_oE`S`Vk4IoEin%amrn+?PmsZ?x79;y*mS>jLpXfPH9WRj4pIHCQ+$GB! z^K`kejj%il5I*WZAkSc!UiLz>%F->DhV@yxBj(Ypxonf?2S+x`^qpge$46-PxxAjw zgI#F=Po_K)6D#wi<)atWpF1fY9?`1xBMT~@)lVt-MF8Qzq5x~N`e2+IFOp|>HnVyh z713E{YtO8>!-8S%@I;$5?n}E;H@qe~$IF_Rx}ZUy3nhvmjtU_H;I>x z*>b6)nmNn&g_cVfZ5Wp>`~oIGJM=hDRqt}X%6ZGT7cXY>c6A22b-MtdKNZH!{{a$m zaW>6AEHMK!{eyuRY2D<&@OVs|T>pdrScn+^=SsxH@n87R(3}F0-Dawot+PrOsp9}e zAJf$Z=I;K_``sPK-5vI(U)W)F?}$svu+_P|taqv9T+37%{pLbP z&5Z6!uH-DC5}#ZInjR68fgTYly#)>iro+Q63Di&I=bs$KCOAHi--lp$cxY~VY<~Ev zdFT5IJXGCZyN3uc@b(W)Lxt*tc!dPbKRB>B2WkGPkK*C>?9kNF4*1~%0_p_uM*!l0 zq~K8DvDTo8=jt1rAI31ec=`cKbY(O)0}BVemeZ@ArW1+=5>q-sBvsFbrO1;UJ{ z85_nonfYW02nuQ88Uwb0Z~o|Ghve+wJ!9d09pgw3pfZMSTI+yfEK5;kS-^q zk)^N#StVZJST!EtB%%PZX<1^!KOqvr(^zZxR~3P;fu4bY_zN&M0c8e!2e7-dfP(Tz z6Uw|GZp6LT^sE1HK(Gidq7S_WnB1J0nA<+vQvt`)136o3u<%G|v>`6VW%sKS`8OBw zj1BjH{|W#A4E45UZ3PM82m=75&~6RvAE(8akaH5pxQ(8T=PKJ%*&*bi-EVFMk`>CNHIlXhNI@RNec!*VHbDEcA< z%sS}jMq;X13LHplO6N3D)nmb-1nImt!(G!CN21ZIP(KaW(V%_HunDG z1iqp3Z$c=*Wd-63m%k>lD2i|HMxdtAa1Rg`FN#kqkUaEmptDk|ypl`gjBZ_@f!+sV z@j|=yT}m>3&h`znrZ3?MkUkpdQwv%{-u2$nto%4%0eX7BUz$knj6ZpS->avps{uBI zv4nX)EzF;Y>Qay_63*6;lZgAia71&%p8)$$dsZeU2?c*d)J=&a*(t{ z1L{9Ftdq;oS>z^Eq1WJ3H2|xUte#f*WvD}u7d}>8MZi7SsnaJe}=(?>71;9v(kY@;Ohi9dm zfm^62)6qm8GMejL^ny4HBbB!VsI*^OmJ~?8;YRnJT#r-=cJx>dSvo6^X=;psn(owtwu+6>{erfv zJ*Dy(stj(%GgDbY*~ZIjeqC0@tvP9BcIv~|8TcM2aXj!I)b78s{VEO_YCjz zvMwCbC6>8QfczITm=N3bJSkbA&95CeLTZB7_0lF{CUq38(joU+sw{E{NkXqI$Ojj@ zf*W+QixLGf!;TVPgaSyree?caMFi?vL;N{(qVOt<%}@Buc-A~wRoF2OuCzAviDJIfP=8A&2;3&I>#I>uV@SkDfQnA zSNWktm2OMbkd%m|rX^zjA@K-dNEGHnAT$=zJu9K%TQ!isBYzc@FqftpnCBd}DNRih zOxCSr)bnHX2QA@&OkCymrcuC{|GGm=cOi{>S1Fe8<{xJ^@446C?fN^IAlIe&iRO7D zt+DvOYZTJw9{*+k}t%Dt?53@71Jc&uZCS}16t5_t98*4oY=8{|A+ z=(qBa%i~cdIKJ;^#RJ#a?NNhwV7&_@_S@|jKfnXMuljQ)wQ<<|;oLAs(YVW+G2SiN z+w^I_i!#(I@2OP3O@5-FB277F-sR+}fdm15yHHePRC0!Kht0<~hM=HguIU*a?~0o3 z1Oe^*hJHT-cPu5&x@`I+NphJ@8O2KL6LymWd48o37+TyWMfHhK=wTwNtVbe!Qn>Mf z8*n>&Ek~__vWD$Eyl0S33a8BL+0Td> zR1!pEs*Kc|(;ub!BuOha;lj%t(HanKdbdO=fWYOE0uy!SLV*j<&AjL%`*K5F|kMS>X_jS;RuBh*<96lD!F5!<4Vr%(%BV4xDN!VcX3k;<2gzA?DJDWU@J_WB)6Y%kQMJ%n5|yD3*$!9&zv9m&45CG+eimasWQX z<{fRWS<`f=Lje3O#?Xq?~{OpXclhYr`{A^SB7I4CgPe=5egb_U^_} z2i_%P_njo*(jCWnKSOXgvztFX6IJHQxgc1nR@rAZn_>EVyNWtwARG>K!_z~Uk5~CK z;MVC7g#|MrW?l=)x+i_}h@m``ZUD^imwf-VP*&)qK3@BI-NpVpw!_WZaZN2Tm>Kz= zn-K%~+JvWUv;&a%C`GwIL>LIr6hCiS9hHgA{YTr=UA_pJr18CMQ4T3*RJ2*X{Zg9)R3x3n#nL zr%B@Fkn4ov`P_i=fAl4_tBt9onfKvhSKbwlf_3?+*%tyn$%vWWj8%GcCF|^+Gcsz5 zV=dpty@s-b6VqDtsap}{qBg>yjpRSq;-PG*7dztkO4Q&5fwvs!bO_5F7Wl_g{X~^7 zV@_smdcAj#A=5Y{#|%A=VK9^hX8T+i5>Y z_mwWwEBw%-5wgDu6$Lo2cB2=Xc}WgxPQ*J%c02?%>G&jM z7s~wNu&j>nA7-O)paAeB#vJe}j+rjm4)<#|Z{2qBD6aBsl1+jFV|WQclo&(F)%Jr% zrARKtv?Tcc)dj%A22U|A3m&4A7xVbFd0sE;I9A45UDF%5id^o7>yR+2_3q>Ij-O5P z(5u8l7@;L@zB32yy`dhNatUW*njCU=nQA4Lgj+;Y>s|?UKcFN7OxY!d1EQ%>ygKX9 z0I-o>1&CuG6?_VOExcGmPSB@tKKM1WyW{9R;I;oJ2iG36%@yR>E8XHZ$Mz{*YmcNf zAPS~Mk3oBP9_v&KWlZe88u2&aFN1ifi{Aupg*G;%>ROKrJ#HflnmK~OpA)}SloJ?1 z1ylFx0wn?VDL|m8_HA|H*DJxTx2%KI@7GPg9V^@qoLR z!V80axbNkdXmeJ>qwYr+9U{}~+vtiM5Zf&2$+0IWSiqOeJ?u=qtnMe?-Xu>Jq%)6> z<|A#%_5geuc?9a%Ifo;ni$O^xz?)bD6)GMv^YBzd^Au1)gcALGyc(Iy495>K^`E0S@o0QX!dFjNtJ64s&}1nt zI0C5t&{?sRp8zau4^NGIVjmB=kRmD>S8(J19{`9zcfTI7e{X?8*$S@GlT%bB7zs>M zJ>){0d~qqm@EjHL+Q8u?E$^A;fY8_h%ks4?QDXc`&tK6QhCq@A*t=N@TqS4 z+__L0$%rBm!mycAvg_A*|wc-T|^~Xj^=cphN-c%5|1vZ zFQOrgNxGDwf4Vlg;!r_!*7j(HaunCAR}e@wH4(S!oA^dIKht1{(R!5)0BxMxTkABV zmr&hDYr*|g-Bb<{@#zi*PIwb$m%Gsp8_4KkDDZ)Y%|C-kqCAFf^f9OOi+T?(onHkR zq`qt+G{VVTN|>b3Por|4u584M=pAhhTQF`zB)tj@e`k0&1u5yVD4DMMqy(4zqy~KQ z*H>UUbBZN}j;}I-@uXD6-rX~k<+V8QKanI#OZ8?l9JSv=($Bv#V$w#w|7rsz!M|nZ zBAs-(I(-RoOjGu=%gd&n1D_DMrcuVA+x8eV>gT#YD|G;9RK2_TiYFx@qJU0WM6wsL zE5~mtf3`}_(ex?9ukL(Fq>gBhAO`AHl?k_^jz3$4ce|mxUG`^5UQ)brk-R*7&h_O6 zj+1iWl0z={50?2B##fM}VPxzc<6n-uET&(76s#D~R)&!jU({6S_AqB-dMFniC>Ym} z$xMas#J|Pb(B9xr$%sd4_oYO_-ejqGnca_j?~fh9pdI7#*7cJ@76KdjsXvsG#%K9wHX1 ze`=nBf4v+oocYtU0g7k5_7$#)$ew%UoXxmn%qU9kx%)8oV4KD5Q$z~tPQj#sC6+rd z;0?F=l3t;eFgtQcw+(sr5YGSU7QX)2ZHo_d0`FbBpB-Gt;7@^E{c^ zGAA*3qahHzgEHE6hTHLW)_mNDfA`OTQJdKMBDS^Ea3XJ3_})a~Y9;E6o(7NEHJTV) z=vm}p(;${bn^7eIN&2LpmvoYpMf|lJ?KFRc()Hoz-$An@Q%**t`g@1Hcs33nDjaLB zEu^?(vPL&5l^+B}7=|Xn8^eq($toAY)eLjb?o9WVe0~vJinu5|tu}HAe?&JV(V5Up z{l^W7vWc(Q7U6WkX6RZ=DE)*;IWY z;I{`VRV?)n9f>Na^KKNlD4Ng~j3A6=nYIWg^jQf)ArvN_I~gUPB_snVF7TJ$8q#;Z zM#guf9t!G4QCHT!_Svt$f7q;^h*hY51%FDrbV3qT3vQ4khT)0FyeGZ{IFa}h*?+x%s{jh6mH?4RK3~7@x0fO(-jv{4Wxrw zbjwcRx!{AKm95cGDd+Q>LwX1)`iq}qx!)>oD$>~A?U7Pli9Q|=eS^2CA{uVroA8&dvqB-(Yqf?o&6P$x>^5~5dtqogZF6> zjph|Dbx&BLRdW-5X!x=iAOjmCgW*|CO6akfon% z+N2>NHx^33w=9HGH@w8Z50$X1%CL@@+XY=JOI5<#1nhXl5}A8ajJzR)xclP9uP>HG)A5d<;9d zo|{j=$Z1>^e->1B>B#rUZdELf6%h~^S=nU62ZdK_Ju?t?_9a+{xn|ZPpJC(7{uV!n z8fcNdE|(og=J01fu#2XQ809#q+~>!qUNAwa&*{Tpy5{e2Nx^v|#A7^m7iS-ef#fi? zjEGXH>)?IsCRKAFaenr0OYBfWOJu_nYM^ZAt$EHke{~WvQEsfG&V6XS*@`UxONA{j zBLECmTRAnTciEbzQlKAHA`-Q?D;UYo&oHMU{gq~R_H1C-l8^BFmqgi9Dk0EK6)43r zOX}gN(9u~R9WcB}Mhp~TXB{}ukoBqlVKvNKbwgOu?la7SP$@lZ!whrC|KigSI3G*P z7pdDEfB#4Dy+Lo0L0Yi}g{UsDxFbacfEuK@Mzd3*s!K3@i&DWvj3gNZ%K$nvY zRkz1~VLh-`f37dsA>w>L9cSA1lM0q`sAw1?k-U84^1+(vv@HXS+T}~ZpgLtA-{g`T zwSSX+M95zWK{L+fR$@@K#furBj`pUFo>Cgvf9o##0sfwo;)X=fNau_iA8!T9c#XkV zvt?Bh5Y)g6@p)*+qC1Jty>}RynD4#s7-{Io`KHXv8!Wlh4g9S)sqZZF@jQ2L{*@noN<(3aVIpOuV2fEd{uj_j0~b&BEOMyx>5d3N?Jl z;~AYclbrW7?Tg5Sud!Pf;j}l-q|0;*!kcLcE`AFHH~Zg&q?2HaMatoW_h$}w)R+pv z%#M;I)7OU3=G*9;_$nTn9>lOuzX)RFLLSOL)k#kIliHhTu65&*t4i?L%LC(5yApY=%m- zk(0db%O=;o_^BXM)KV6Pv4G$8Ql6uovV+#yn#iL7HV^lnn1K9xo|dP~&1vST;PsSw zcqMvx9LwNW5?AD8e6B$ydiEK=f2=oc!4vr91oZTBoE_5(K&5ykT8N^7DT(STg|7^!k=VTCy+ub{kp5UD#(}W*uCv>I&G=Ve>4e8OV2gI zE4Vkw5sYWDp9Zui2bB&E(V5`o{gGwMfc(ejHN;z3whQo*w&6#zlQ4!!M?$EXYsj^`m;^be+=kS+~m|-QdD0S z4=iid9V+)@ZH^cM9T=DUcVG8ZmSx#3UtET|7pp%XMv~tbx+yYYbleC=Y7}FC*HFo2 z^I)+;m7a23$u$^Z?DP{l zvw+*jdd`CeG5GFPw678w2C$(vp3nD_;I8Lq04ig|_bju*bd6ldiHE3OsC&%IP@Z{l zfw#}fEJI!A4&}{O2^(^CpJSU#0E2{3*o=gtj`$w@8OxvVe<*3x2~<)apO~tKEwlrA z&YwDWG_($f`gb!>v0#*7tcGUn`U$af8-lO!NP3W<5Vjy!6I7 zi}+x4Qaj$9iv7FhZG%6Ck-emH;nD<+W4dS(=uUfdRW7`nTPRJ?2UWPMAhiQcy zK)~1k&fu!Paw;cag3u~yHLzan8>0;y^7qGPY~J+2%EuL=f$d+(+DQh0*|q3a54yQc z_w6789MVqRivD1c{6Ui1;krP#DYm%7lAMupC9(fOomow?Z{I8QcV!6an*BM2R7|(5 zjLIWaf3PXAi3dw6c_~)uwFypCEXa@00sS=MYPC=~%56UFEJ>RLa{7nC(h$e5n}sBf zrzutqRQ?R$NEY=9!JV03bKz%@(M{xx$i9w|#YVj7IMQMJ#Ck5gddPB=Z7Ycr5QY^6 zKU1)0nTcA83V~-EYHjZ5G~w;*mE-ZLs-`tce@gAh22aK6{o!lTji?^`Ud<{M6dg4W z{DDCB*q!}Ny}s#nu@6r)Czg&Vi=t%^_9_pbeRPqJHnJYV)Z`*(VMK@8Q(}{9kTZhl zgk3JfexJ*$I0lYDk>-jiZ%|8JM##tI?sdMJhMM9GF1Bwq8b@Z5TwxGB|APDBUdr$| ze`jlmgEz#x8}-?v@$cHEMcnlL%rK2j6>eaiFB9eOgvd)1gA*{+RgyEeTq+eW^TUa+ z#7ing!|D4iUsn*rtvCCUw(%YEg5WC)y>j|>>{08W)if3-(FFUL0FjhkJD>#+jg@eSqqJ6`z_y#pL( z@kUzpDo}QXRyCJ(w%-Cf!VYclE%To4>|~uv+{hTg+ec|@%Oq;=>!JZpL$cu1TCkOT zkZPHub4X!f)C)#n?R-Bn>d}nj3qy5JFb|)x$Zg0YI|D7S8WTmjG>#C*s3!I{e<3Hy z8>a$LJ*>sW^~3CvTL}8zTA(}8Q!utt&C`3AxwD7~vkr9*vh4D!Tg3yN^{^%Ekf(^% zC>r+QWL^VZh2OXVK}}#Li2p@?gW;`{o(!V7Fkl|M~mI8VFQn!$Y;A z%awm~Tys4q9_0TnVoRFI3N`Rne^A_2=Zhi5&nI;C*kc#mQt@>!&6>nY_+^Va-Xt}& zU4T?tbiITUOl>rPYIL8acxn{Gf}yXBR6?mDWXgb;|bZDEx+1f&X?o7=G0e*l=w91U(R z3jL)a5~$nJ5yBrrE~+!HKiiR0MPQUWFU)u0_)2k`$Jv53$YtX?@uT!mL6t1qyl>}3 zW_#fW$X^0iNyRQq8iu=p1v-V%uQCU!^jn~rW~W^5>=LJHMcRV_iVP~}FNkv$;)U}A zr?Vu0_a#T(qANMtGyH}ve^ee;!UJ3r%+gSxFBvxqqne*hX|9c}qp#e(DcbUSx34(7 z-nN-wVA$!ci!-bG=(u+aIa-w6ML$aXD&MuuNbQ>n1-wnC9yr*hCk$&xV=ypzBg|u% z8AF^3sRo+PZ*H;ndaEd2tQSc^^l$f{Xmz|yD37R>!#YfgEb?|`e?b#Ov;<;zN};F( zO0k--pyrbK$FGvSRlWGU`#s<~u&G8X-RJ$rcB)xnLwx;ba7#gMre2ylS16&`bS5Dy z6xLPk%W5WQeOoX9`TiU?JNGJq*cR&HOzi%oBk>u)cdZMz{awbo?dD8tXmI*_OhGv5 zxb76RJe}F_&)J6ie^@<=fZi9Bas={gwuwpkxT4>Mc#1HGr^(iS%gU!5l*bvzNf5_x z0w)3Ht*M;mbaj+Ls9H15cLnl#?t_7SQ;~+Dx54#!=)NASt8agvQfaLs$#@w*|3SYE z?bHoDBns)V79&35fftvoOg6K1US7|L4E+TA;{m#GmI5q)e_V81u z20onP88+D`f0)K#Y-2vgzTxoh>SZ-cyERX(OZ(Jp>9RFnRz{YeXv=%3xd+!!C#gN# z%;6;Up~H`FfH~%GGFM_6uaI+8(s%9KTW~TC+6$b5H~dXD#e&%OoMcps9b5bH6qj^h zeJ#^FC78Q7RS7y`{3c16avw3m7lg=geMYYO2tB*Fe*lypbQ17QpK7jH#KQz9PS_oS&jCg9kWHCkwJg;EmJ1$+G@((eVjf5wwOhuZdO)CZ*}JZ$(4$N<&Pot@0= z)H%Yj^l`5n&D!n?i_@&WUS~$hYR!G>``H+1wv<4<1B8@&JhNYM>&C1{Ai!dwD5aa# z8D3+)ogBpW_#)aQc?M}gqs7uM*fdir1m+a!I+4)h-hH5*A*voMf>^2`O?a@_lQO3g zf26KrV+ZiICTfs_($~m&f~Dq7*@A{>RvkIuyA{<2%(gG-gY?%OsV>^J+pYP0DQ6xw zj3>LxACrh}sqdcg#%)pysODJo;}D@`_D(SInLscza}WkHnA1Dat?}QKI7rlPXCXBp zBzIx0?{D>5JdC`CsD{svRAi$aQ}I}Ye<6ju{D_4IH7kvS{gOP>;RuPJeD(-)zXr#{ zYmQ3zRTxoiEG>l7wVH=8URqb*K>XP7?|uI3e{;0u z$Dl4au!GU$vTqlP9MaLMHuQ+=Iub-8GYp4~=1^8F1qp@_@x17#Xh#_?uAu1WukuCZ zD+z67GV3J1<&3a|PX?Kk1P$6jhc`y~oYr3j#)j>>jenOqANJQuinM4I6rXH33YQwn z)&9wVQwJD0@cS9#D1^*1#Ywwxkdm8qq zIQzlcg$nD9IA%ZR8aaq^jondaE#&i-o_y|Y8{Mgr3i@64g4k=KX?+k1&Wuymoccjv zDHB9s=^AD8KAcpyY*J(kw@UnOFX(AQAsG;(1Xm23wNU!(dxM&5Hjr6$f1oiVElWVlkIoU7 zrx3|%GcT)H+Mz>inY$5U=TuN1D`9FI}sbZ!U)AKCFk@^P*0biK2E1-;r+ zMkqC`hezrLL;RKa9>2y+ie6g2QbM75FCZbvFQ1#VlAO%F`CetrB)Q0F_h&BL=rBDB ziV?@YgEY#_laA2+f6sxBTC<~k)89@a{K_`6RVVMN#H<{)P3$l%Nn@HcK*p_B_p-3e z-L72+4+c-1o-1~c5_%4^p`k|Wylk(qyhrYnD7{dm>35Rkx2##HhEg1!iETO*pKh=C zC$bUmfL8h)RIV?XU#fswjR?)DkUl3x#X7!)%4viRo<%oZ6XAdV3@d&V7GV};&k>>ezTFazrb z@yY6Z18RK@BTC{To02~t_LTc}-L&G_zTJ!i&GaUF&@R7?9n!|rbk}u6nIafvCK?o6 z8>t+Fs;++ue=x+UO&`Lr(fwIN#su}ef1PArf+`NiJ~<(P!wOKC!abac^9Sl3F+4od zYE4fu!JFZt258Gh55mRooKPf7(wY*e4iXYEO};1TrhmPPGiF zOZ`2)&T?i0bz_MBq=tbnu81^&O!KNoSvZhCpn&U8HGsZj`lFC=nXQR8s0;e~E{U?D zL+0nrc#_QGVwlHshH-`Kb=<|cDDd6>&?Y*`2OMy)Wi4-GGb1oM+?u?K2HSQ-i|8f$ za`>sUfA%X{Sd?;25>ZFqOJR?2y{eOgKY8(Pe-hGK9Vo}kLo%-{P|#+!V#Hqrv$tB} zri}RTxMBmcW$58|=@PbWegq7HA;(xM=`e(Y_sK2vkD=Mai6i7LTdWu44E0)Bh{YbB zUqe497EB|9%VM`qUWAVA#l?5r!)RDKPrJUce=q_32*m8>51<({@58HN%=+fo)wf;w znE4lQkxMCkTDN!KuHOK8POFgjhLpw?k!pNA&Fh4-G_Z@* zA^`qahleHD>}#a%=JxSj36g7z4`$AO_RgH-As~nKg?`c|o7wIfcnemzMsAZj>mZ&T zf2jTeG1z@yVyEh!Gx%V5vzSq+J*AAGDF*F`>Ax>2V%)gnR)2RYhTTFY6MH|pc zsPb9bZ(>8>&(rb{YJFcS&e;EQt{`u}OnjStDpcj16h2>jog|CICsyx&*zzzD`JEk*KLAy$`;&lh2vcCM zY<%q0bh5DI?JC+K_K(I=INXw%Ei@T{l5R}}?>9OwFi#a2S7wF;fcpNrSaTdt;{B>U4=vtBw<+jbs#(Ne=EBOakKqM zRfBpn%x%7(^DXcl`+S81D0#SULMD8%@V<4}x;Hp@x6Gngl;pfuGfnfM0#m{nmC7R7 z(ZiNlK3i-d=-0Ja{bcqF#WeVJ&L1EnG4Qfruf#*1p*)@SDY;thI+mGY(5Uf-_M1?p zDaxZ2n9!*>OdxwmT|}k1e{$om{V!-Im0>DIN!7m7N;$}Gxo3z+ZkETRr?*QfGR2N3 zp9Q=Fv|||3_3Q|h7bxBav(ni;T?$4fv0P#+w6(<|_Yz6maQX@318o-5NJ@9`WZC+b zZVLvjU1P%_>Rbu<(!b1u+&)dDJ zr0`!;7ef18eRGyFf65m$6F7o>n^D+2Ptj*}S5*5!&2T_K@bJ?(%zBI8RVGnpLR5*C6VysiK;*z*X!p>EkY&{ zowUNv=YvvOMFnfQgEWo`>EGRNy}4OPk)=`IX+tXR2@jRP3s%=5OamRy14FI}gMrbr8^KU?@~JMZVliy7`H;#MW;z3|Ugu!N zRswM8QRLA$SkNc8{*ve1gnfmP2N6;NQX(U*75oX(y%rvjMtJW|s<=Kh5i?;8#NzZ=+?BI> z156|nfAWe*nIemyzozI?%|wVE@Ve&w93nu#(#q1%!XP+o924r{kF7!r4i|`Vt_iO9 zB`*u+(xemT^g0w3>U$uI_%m>3HeTtCW>J%aDTp0F_r4k;+4d5v8hcwmMp7Z$E*Rp= z-v?&`8`7io+r^Y~q8aEB7va|4ybaB5|6l_oe~2V}rVd74;Rr_BWr})htPfRg{&~_>Y9XLOfy2ROc z6JDYw3%{s7t@vl<)UGd9{xJ9(lNHv0v3Vpp#MnX~JnA)^{7I`7-8=z_Bc`l#!ALD5 zf35)yg)TQDRER0INZU*(9^!mfDk7R{bA+U}dxGx3lKd|0<^G;3=W(NqKMLo?Y!9Yz z4d-iX01?YBX+h1qV@JKhxs>T5kHz)Opfhkg;*LaK8PmO+;&DiwMqzd$iRCsCv#yz8V09$H<{0| z&amP9-Yn%iWV=6Wv-$QDtG+e9ZH8RUjVXgAAG?_vVuQ!qZQXmiqRTPlnLHe_#1n{W zCcHLt9U!TbzXVQA!G12vTK;vPH_!3csKe)x@nQZ+N3o*NDf9M#Bk=c~6z}71e+eby zcxlfz*wNHWL~(FgpxV?!FAXh9drvX0(f}Gn*WZhAM;08xsyb<;+RudBWq+i zO7}*6n5dKuS!N$IikeM*Xh68gN0QgZUX2G{&qs}oJ&)KH3#UP5)p=S7q5wTuUIc-8;;~P9Sr8; zDj#*umZyH*iCPdY_Wbcl9116nG!8E4@-2K&`qkavsmT8OH&#Q;7^{6V<{V3_A9Joe zhPzKcfv8+I+*XhlRRfLWCqrHoKawY@a(sSvvLIjgMX7FxfmW+If2A(RF)ix{iiK6% zK-UIq{JGx-igH%tJ{*SyLreB8Veb$>5-MJ76G?a6i;wW^h1Fg$x4?#xKPk)1@#vfE z04q+3e8-#~=U7m?Uypt^>Kdf-egT#LMt!!_?6^6wwB{dKQ#bx5jGfy#l-yR^w|HMx zm?sB6KY+d10TITbf2j~E?ksC}k0UycMuy=?Jxglu5jku4T=Ta8yvur63l}GUZXmX@ zc|&!SeqmBe1~WQ7M(Bp+gn%pC2>5x0-@i;0ZA{xT^#F&$WIenafiHr-)N~mq`}+79 zk2E@dCTC+P^8Jf5dNa`)vv;nNi)UslnuYY+k#t*7=)C>(e|9mgG-RfIjC)trcU;&_ za0gK0(|(MJcBj<%ceid}w(Tsvy}o+yU>X)@WIhw~&fBXK8Sh&N{fN%9oAsc2ap*h- z&rO9pdo&U+VvdY1DnQVc317sIn<*EUiu_8&sj9m5Mj%+2*p9uQ8Hz%&~ff8x7^ysZE3faoo?u?T9he0RPuZh+D9pB@UrmXw*Rw0e@$N>rr0OQFWN z@7W%La$zt!BoJ$i)rO-82U}36Ogy-uz)%ro0$XKwdWOQ})$j0EMfmp)vqA%}NX)%o zP?sJTYWWzy_e2aX_;$#4_kRz+;YI2%zOE}lCZ2Y!e;AiIv%PzoOGRiBRvLt2Ps+V| z!NOCaV(p?(*s*|s2>J5x9Wm9=Ym^pM>q+OKuQ@MVkv|od0NR3x)U5{*Euc(vWrz6z za(c7|W0Ij@R*9ho%e|(C%6D1>QiKHYDskHovwtODqKT)GC6|+hKFjb&6G^N=@5V*7 zZR)7`e;DULtqD8&<%vVM)a%A_!V?bivpaKBZT@QWmu(u|207cneC;|fRKQVj2aGN| zK;PgZJ@Oq^RM`rBqxNub&ON->QK^ullRE#Uq84gBljtxsP%Gu+6{%ISDwaQcchp5o zbDQU@gvO+To`O1FvUMX{*tpV@hq(v^JkSFme<{7=;Sjf&fvUCA5-zQlks7{MAQ_JD zXo@osC#&qzKAMr!ih=gg!|NLIPv5#hs9lg}SUMjB;%S*_VC8oUPR>#4AT?bX==QU3b zo%oto+42@aHLc=l$|XiQuDc9iuH3qYe}8QV?M}(^TTID96h;WMuh&4Sj#chIt=yWJ zh~Mlm+@a&4R1}fuOZd`%E%X^n#*vMyBn;wpQG>2Un&_4AI~|6PzuVL7Dwk`Noj2=R z(})4v6pFW`Nq){)ivCiJ_fG_;#$@ceHH?pzD2eMe()F57v2$!6OWl8v9k)1;1jYH{?=ocwfD z{Vth4>Bx2~2GQ86G;CuMX0T7YAAGNOUd@B5DdD=^b)&pBJP`7*EJ(E%7#wnoOKZtc0I4Rv?sZkf4^!LY~P@t8HTBH$Z~Or{iS3InEFkfRziAm&EmFE zhIwu=_Dp_ZG()}L#gH%mm>Cc2CRDDmc%F=`K714HlVtO>sl^%M8)2rjMt3$x112;r zHzq_k?hCkNb=Q#>61)&e2HD0hu*Dt`6SQFG*~n<(e~T!&8-&35{s`{wf8d-UOxzb3 z&jy2Vghr4nlBU6XFrdcjst~iu0(2wVH@Sw zU1d_c`JC8twJ*s^oJ=k5I!%-&&!rFtMsitNi)Ycp=!r?G+;Rdc(vt~-qxtBSR_B6a zFJjDRI8+tdya7vt$9e<3^A`R3|8#`G#^4N5R`O$PBWvUmX`3j0{vF#G&@9jYD-TYGP-Iq%;_?}@xc}ZS(3-;=Hd7=nj{8v zEZA3F{8pyVK!u9=T8bSL_h`fA)REJWs`XH6)dO zW)bFMQTzs+W?TX3C#cK&eGPZBJgc*VMwm$>@=?D@YOjfxhhI@rTdGGW2~;3hbzIay z8uiUKCn7C`2u;So5|&LyVYNbrt@w0v+|w{WgkxRti$iS?r*$K)ejN-Az9Yk3w%#zn zuqg>pM^M}r8?Y?>9NjVUs>z_McJH)zdopcE zrfUa|BZk@`5JYnCpbz+4c0R?E7`{w!&G-Z*`0O@!wDws=e{|j###$NaF@De~VOBh_ z4hRxxnlb2AsY)Gqz$=lUA2!oLwZMP4h=M0V!|BPVjtE1f-KWwX%pRVUffVI@2HNIn z2(&4fO_IqR-<2mH6|pQd6tGe4*Zh@3!S+qK*~F}2>oMAyYr`bijcHxbTx=S~R1@D4 z{jmb$k+;kuf9t!85vc%=GFX2)ZhSb!Ujaq;?wU88>31~Wk5C@Is2E0hLwud_$h4q! zRA!#?{+p?a^NeG(n?`A*b9n;NnK>zI($XbFgPTm;A_Xl=pbwR3<`G{kD-G2^%a#`U zMkfEN#S+TNOGe7vhx(FNXzq+B-3_z)P5=W<0G4)ke+(19z9neE!SdL$;wqr=Rur5s z%2{Od*hLeo)<12=NMS#@XB17k3ag*Jl}3g)C(}H`;6w+#oEr>nHol|yRID$@#8Uzj zC3D=PwS_)xSR~7}tM%YeKLtTb6UPd-<-Nn(|hkl8`f1N3J`PfJ<9YF}_5=M%=&0*FKvLr|L$dg;G2uZdh$z^|=7qiMThQEOc8izi*GZmDb3r4Hv$Xu#8liccAM8BdcDEyRx`$dZuYOd$d_Q7H?pT zf5f+J73Gbbn_Tqgo=8^)8mPK^B-+Qb43Y*~sDZ0{8LzWWsy@LTk_%lDF-FUt=dn8O zzJ(pksZW=m*K_(qLc~EHjuSl-%#V9ip>yKG4z4}K)eHY9J-9aoZqa|2R^A|cqR~r? zT+Z6UHhb>;sxR_+kPH^6*@F+KfNo|*e_o##icy>pO3?u0iU0fEbG5?qN<%~|cMVIpV9`kx7VUF874j<(&>o4$8Z15e_UDG0pvD_>&uV+0!x`})#u_48;#qm$59PST2 zS&mo!v52^lASAf1=yJ2;JbOG8ht4Z}wl)I9<#!~QaF zxOPL4QfR0LHIWvH@V$5&e-5L)7vyCXj3lN%8Z(0jPMPh0he~Dj$m6PW{Eq++0`UDE z&Q|{@uX}sZqY#X>J2a^{(g3Dt3OLjAf2PcrNJLych_Y?5a4%_u+ZTwSc ztK{{S!|;J+=y>rWmj0nEez)2glaO%j##LJd?|z=#@`g?EnJo-Ye-eS!oD~@gMg03& z7Sr!mdH-29Vi|O}ND$jOW%% z5HvEbT1j#90rUpdsk=TEO^SA~b(oYSc-|(LuwSD`i~^sE+dR3|K)3(`<@&% z__{IFvsze!o>YaiizzOwE`e6dyQ{H)(^EcXa1-MZax)T4e>5SmF={{%#zo9f{#fIa z!~@Da`$Tg#Y${(fuRaLtUe$@DiL`th;=J2#<0ZX)c#!&+1S`aCJyju+)y=xcJ;k)a z6!QVLGMl(7lWx_E+nEEsIL)u<4@tp+5IBJ~(dI#&&w~;PbDV|IILq*louHeKIT{gp z`bedVAhwBCIJ)yGn3Kt6}QxC0g*BRHIvcv6SsMt0W1drHffye$PO^#K&O`uG7|1DEIc0b94S`~ejM0Wz1!{{esqFgP(Y zG&nIZl~4j32rxJ?Gc-6cFqLxxoC7m3Fq54!8yYq<3NJ=!a&vSbH8eB|FHB`_XLM*F zGB-6alhLLqmu~?A3x7v)C^MS7RJFBLxsY&60!bji77wy5935oKNHQe+`t8=p^62J` z**bNK6p~sq-Cut_-P5Cl2LbVj@Hi1%!&MUF<5d&p83s2#VLUKIFpn^$B;0Vq0-@kW z63!)zVVZEM0=V%BH=Y`CpAjBNMYtcJUIsdRBD4oOe9&bK=zkDkGLRB(B$1547$Jz{ zKFl(TNU89ZN2KO33+zb~@DUS?$iN7~K!sw`fI^=r!AqD#DNhjw_LN3FN)u&#zznmL zuK@xWRRL#2OSl@JXb*mb8No=+JW#;lstu9wiVGiLz%|fB!Z-=K1&otgfKx;(01kGw z204du8svag8-K$_K#BHCP;d==0>c6YJ`m#pIsu*<#()V>VFcI};Gj{!u>cFkloCTs z;30UJ&OAO6A|O83KpUX(B?C0TzOR66Avy7lhFMY&KQK5(k^tEf5Qcyw2~v|lXq;sT z1P9mvF9Rimk&poivdUxW*I z^Xc^c(T7h@kMF{)h_a)b@ll%0U_cVib0Y1?qoeem{557;lQ9P$89EYZ@nu90^J%m! zzFFczNF{$lD?(a^oG8tAq^L+D9gj;j85p3PSYe^(ix5D*Z2qgm##B9 zr*|}_30=@7O=-G}=!(LeIGxdq<}{D*X+ev-EQ)CHGo@?#gWl7J1MBT+3=lcQ-6L0{ zKmU9bizg?S*B?(D7O&DpxE!L9RWw2>wrTX5G=ByS8ub8;z8GZjsOIqn@c5d(0WL2} zHs8^!iqQ}B6SA5E@;Ltnq)ygJ5*0PK({!;2f#F$Ngj2)hfJz~X6eAu#d5+z00 z^ib{N;p@-0pWh!1czAikcDN=3D7;Xcjh6ot*Ctsw{T3Bv&P3nWVKR_I$vSTmVD=*5 z!`achcLM}Gzb~R?9;eG88paUXvA~oQ9QPsVL|Hcz!Xaav%PBV>FcW(htCH*tLp4Om)xs6xF6)V3idJ~W^ZYUo9Y@SOv~ zzvL1^Jw&8!d$A3*4XJI2%LaGTr&b+nNv_j~pH)rVP&0lDhd}7aKmR6qgvp@l;NhUH zs^MmNoKiWt4Ol_#V4b`Ppa|fvD0u}oM zeN?N`1}WPhwYx;M8-IMSi&E~7a`0P5ds%kqQ*NM*6X<|FBKNu4AM5Y5NNs{UC4jp% zObdr#)dj8h2R;0Oq0MkN_NI|b&Jqp0$53qcNBcYdSexQb0mE+`wI9BlX|fC2-yihR z(aG(Hi>EJvjAfp}c_jQ5%b`t7wb2DlmOTd^@373efPZ5XyMKLkeDUJA4Y;DY2eau^ z+2NJ(7|fz)GkY7(qZ~Tjbd6{C5jBQw|mEdRBa+1YUz8_I_b z5u1rIbihPctA7XD=Zfdrhs|>q{lMQRvT=W)A>avnO}4#~T#59YzhVj8p}#iqu%NjMaRL zCg0rkR`fV1YKDc}F_SweWlz9GO}Frd)o_>YJ~X_hn}6$GHFjnX-Mpro@1olUAl*Hv z##XXjxwv6lwrtgGvnJcVV~O>+$7-^f9G>WM&3m|JHP_7R(^5|CGhdUdcjcsOy}{51 zSjiCgcCE)c7_8q?slBoJ;TIApWlv7h>G-;U_Td2R+4}ng5A+3e<rZ55?&;zeAvK($7HY2$ZaOH>wgjVO@Ys??Ngl(VkfpqzK* zKFUQ`9-v&dooFFz&DiA#k|nxiaU@-JN#{tq>XOb;kLuBbq}zR>DM$WPu)`02(4Mf< z4dh*Sc}Mf2YaXqOZuC%z>?*<7$!_d0bhiEvxqqMzS`&7;fDxD7h-1KQHFL!L8Anj2 zM~dH~QX$MX`(rSE9nTpb*|kJNY;k*Jes2I|CA0I(Z;s1 z>3@#v0IT0|1ZP@`1qy?P5RHkZ1g178mh)PJfIr!R=vsG14xvPER0|Gps5hq8lNwUV z3G0!UWuixp0S`KIfqJ+Zz-`%Wj_zW2--C6*daQtTp?c)Nn&_gEh-$OJG~}RPu^u_- zSE}Ph3t4+g$CVaoVEmZDhXO+`}*D?>oQv z?a%K;qPqO2pD6Ci>;KQzeJ)lG)cO}@GBuvQnukfL-XxYwKRB~0Rl(R4*z65gh&EI( zRxkt#2Ic3M00j*d3>1R6^gZ*^@_{@fD9=S9+Q!Ae#m&{g$=TG&$<)%q%*fK&(8SQh z*~rw{&B@iw$;eKDu##AAcvIWLX!^qUz=3wSXA}%%eA62?V?}2Uaox@!O;5U)XTNcB3QIvzFoMzYw_V=(@T#t59xoH-R;bg zTd(|fgS^!Ph7u?7B@3jh7KrmX$;&j=Ni-Zb;BZgi=sRRkFVie2(P}8sE-d$USA=iD zoEFXZYx}Qy_AO7iRjsg-3JIiKS)*PJWf!yvvlTx_+sjQ(NK_fwC*(mI}9aJO1I zskHg=*^ZgtZ|St;$Q#d}!&SH6=R-=7BEQWZ8Q^}MtwO67NSPfLyTN6;fj4U*->XFH zHw|+yFzik+f79re0X$LQ0*~$n{-~d9Jzh!nB?lN^wCGtdwJ*Hu6gKaFv*y1u?(3!b z4k=1B2ud_9HsBF1kYUpmx%Nx@5&lH`lPC)JknqEm zqPH3{wqA64)m_i)=HUBh8Ec`H@R`g67uPLHQD2#MuH^TKKP%QYsm{@Q$pU$gP?fcO z+=t`;D#ymW->+G}d7&J4@Z^6DmKPNKD`mSr3LaKybL45}i1X?EllpRE??DR#)vk+v z_dowu)3K>~b#+Oryne;p@J&VEm6v}1n~`?;_a3hqwtt>nwb?wAYyGp?wv~@VFTJ_> z{~puk=by3`-dw#TJTq;*_Z~0v>feTO_P@3wgX`+8gm1/examples/acados\_matlab\_octave}. The source code of the \acados{} \matlab{} interface is found in: \code{/interfaces/acados\_matlab\_octave} and should serve as a more extensive, complete and up-to-date documentation about the possibilities. -% + +\paragraph{Abbreviations.} +Some of the following restrictions may apply to matrices in the formulation: +\begin{center} + \begin{tabular}{ll} + \textbf{DIAG} & diagonal\\ + \textbf{SPUM} & horizontal slice of a permuted unit matrix\\ + \textbf{SPUME} & like \textbf{SPUM}, but with empty rows intertwined + \end{tabular} +\end{center} + + \section{Dynamics}\label{sec:dynamics} % The system dynamics term is used to connect state trajectories from adjacent shooting nodes by means of equality constraints. @@ -173,11 +182,11 @@ \section{Dynamics}\label{sec:dynamics} The system dynamics equation~\eqref{eq:dynamics} is replaced with a discrete-time dynamic system. The dynamics can be formulated in different ways in \acados: As implicit equations in continuous time~\eqref{eq:dynamics:implicit}, or as explicit equations in continuous time~\eqref{eq:dynamics:explicit} or directly as discrete-time dynamics \eqref{eq:dynamics:discrete}. -This section and table~\ref{tab:dynamics} summarizes the options. +This section and Table~\ref{tab:dynamics} summarize these options. % \subsection{Implicit Dynamics}\label{sec:dynamics:implicit} % -The most general way to provide a continuous time ODE in \acados\ is to define the function $ f\ind{impl}: \mathbb{R}^{\nx}\times\mathbb{R}^{\nx}\times\mathbb{R}^{\nuu}\times\mathbb{R}^{\nz}\times\mathbb{R}^{\np} \rightarrow \mathbb{R}^{\nx+\nz}$ which is fully implicit DAE formulation describing the system as: +The most general way to provide a continuous-time ODE in \acados\ is to define the function $ f\ind{impl}: \mathbb{R}^{\nx}\times\mathbb{R}^{\nx}\times\mathbb{R}^{\nuu}\times\mathbb{R}^{\nz}\times\mathbb{R}^{\np} \rightarrow \mathbb{R}^{\nx+\nz}$ which is fully implicit DAE formulation describing the system as: \begin{equation} f\ind{impl}(x, \dot{x}, u, z, p) = 0.\label{eq:dynamics:implicit} \end{equation} @@ -219,7 +228,7 @@ \section{Cost}\label{sec:cost} \end{itemize} to define which one is used set \code{cost\_type} for $l$, \code{cost\_type\_e} for $m$. -Setting the slack penalties in equation~\eqref{eq:cost} is done in the same way for all cost modules, see table~\ref{tab:cost:slack} for an overview. +Setting the slack penalties in equation~\eqref{eq:cost} is done in the same way for all cost modules, see Table~\ref{tab:cost:slack} for an overview. Slack penalties for the initial node can be set through the appropriate fields \code{cost\_xx\_0}. % @@ -250,7 +259,9 @@ \section{Cost}\label{sec:cost} Note that the dimensions of the slack variables $s\Lower(t)$, $s\Lower\terminal(t)$, $s\upper(t)$ and $s\upper\terminal(t)$ are determined by \acados{} from the associated matrices ($Z\Lower$, $Z\upper$, $J\ind{sh}$, $J\ind{sg}$, $J\ind{sbu}$, $J\ind{sbx}$ etc.). -Note that all cost terms, except for the terminal one, are weighted with the corresponding time step. If the time steps are $\Delta t_0,\dots, \Delta t_N$, the total cost is given by $c_\text{total} = \Delta t_0 \cdot c_0(x_0, u_0, p_0, z_0) + \dots + \Delta t_{N-1} \cdot c_{N-1}(x_0, u_0, p_0, z_0) + c_N(x_N, p_N)$. This means the Lagrange cost term is given in continuous time, which allows for a seamless OCP discretization with a nonuniform time grid. +Note that all cost terms, except for the terminal one, are weighted with the corresponding time step. +If the time steps are $\Delta t_0,\dots, \Delta t_{N-1}$, the total cost is given by $c_\text{total} = \Delta t_0 \cdot l(x_0, u_0, p_0, z_0) + \dots + \Delta t_{N-1} \cdot l(x_{N-1}, u_{N-1}, p_{N-1}, z_{N-1}) + m(x_N, p_N)$. +This means the Lagrange cost term is given in continuous time and then integrated using the explicit Euler method, which allows for a seamless OCP discretization with a nonuniform time grid. % \subsection{Cost module: \code{auto}}\label{sec:cost:auto} % @@ -275,7 +286,7 @@ \subsection{Cost module: \code{auto}}\label{sec:cost:auto} \subsection{Cost module: \code{external}}\label{sec:cost:external} % Set \code{cost\_type} to \code{ext\_cost}. % TODO: rename to 'external'?! -See table~\ref{tab:cost:external} for the available options. +See Table~\ref{tab:cost:external} for the available options. \begin{table}[ht!] \centering \caption{Cost module \code{external} options} \label{tab:cost:external} @@ -295,17 +306,19 @@ \subsection{Cost module: \code{linear least squares}}\label{sec:cost:linear_ls} \begin{align} l(x, u, z) &= \frac{1}{2} \norm{ \underbrace{V_x\, x + V_u\, u + V_z\, z}_{\displaystyle y} - y\ind{ref}}_W^2 \label{eq:cost:linear_ls:l} \end{align} -where matrices $ V_x \in \mathbb{R}^{n_y \times n_x}$, $V_u \in \mathbb{R}^{n_y \times n_u}$ are $V_z \in \mathbb{R}^{n_y \times n_z}$ map $x$, $u$ and $z$ onto $y$, respectively and $W \in \mathbb{R}^{n_y \times n_y}$ is the weighing matrix. The vector $y\ind{ref} \in \mathbb{R}^{n_y}$ is the reference. +where matrices $ V_x \in \mathbb{R}^{n_y \times n_x}$, $V_u \in \mathbb{R}^{n_y \times n_u}$ are $V_z \in \mathbb{R}^{n_y \times n_z}$ map $x$, $u$ and $z$ onto $y$, respectively and $W \in \mathbb{R}^{n_y \times n_y}$ is the weighting matrix. +The vector $y\ind{ref} \in \mathbb{R}^{n_y}$ is the reference. Similarly, the Mayer cost term has the form \begin{align} m(x, u, z) &= \frac{1}{2} \norm{ \underbrace{V_x\terminal x}_{\displaystyle y\terminal} - y\ind{ref}\terminal}_{W\terminal}^2 \label{eq:cost:linear_ls:m} \end{align} -where matrix $ V\terminal_x \in \mathbb{R}^{n_{y\terminal} \times n_x}$ maps $x$ onto $y\terminal$ and $W\terminal \in \mathbb{R}^{n_{y\terminal} \times n_{y\terminal}}$ is the weighing matrix. The vector $y\terminal_\textrm{ref} \in \mathbb{R}^{n_{y\terminal}}$ is the reference. +where matrix $ V\terminal_x \in \mathbb{R}^{n_{y\terminal} \times n_x}$ maps $x$ onto $y\terminal$ and $W\terminal \in \mathbb{R}^{n_{y\terminal} \times n_{y\terminal}}$ is the weighting matrix. +The vector $y\terminal_\textrm{ref} \in \mathbb{R}^{n_{y\terminal}}$ is the reference. Additionally, a different cost for the initial node can be set using the same form as \eqref{eq:cost:linear_ls:l} and the appropriate fields \code{cost\_(...)\_0}. -See table~\ref{tab:cost:linear_ls} for the available options of this cost module. +See Table~\ref{tab:cost:linear_ls} for the available options of this cost module. % \begin{table}[ht!] \centering @@ -337,7 +350,7 @@ \subsection{Cost module: \code{nonlinear least squares}}\label{sec:cost:nonlinea The \code{nonlinear least squares} cost function has the same basic form as eqns.~(\ref{eq:cost:linear_ls:l}~-~\ref{eq:cost:linear_ls:m}) of the \code{linear least squares} cost module. The only difference is that $ y $ and $ y\terminal $ are defined by means of \casadi{} expressions, instead of via matrices $ V_x $, $ V_u $, $ V_z $ and $ V_x\terminal $. The same note about the initial node applies to this cost module as well. % -See table~\ref{tab:cost:nonlinear_ls} for the available options of this cost module. +See Table~\ref{tab:cost:nonlinear_ls} for the available options of this cost module. % \begin{table}[ht!] \centering @@ -368,7 +381,7 @@ \section{Constraints}\label{sec:constraints} Additionally, bounds on $u$ and general linear constraints are also enforced on the initial node by default. On the other hand, bounds on $x$ and nonlinear constraints are fully split and have to be explicitly stated with \code{\_0} correspondence to be enforced on the initial node. -%The constraint type can be set using the identifier \str{constr\_type} and \str{constr\_type\_e} for the path constraints and terminal constraints, respectively. The string identifier options are found in table~\ref{tab:constr_type}. The default setting is \str{bgh}. +%The constraint type can be set using the identifier \str{constr\_type} and \str{constr\_type\_e} for the path constraints and terminal constraints, respectively. The string identifier options are found in Table~\ref{tab:constr_type}. The default setting is \str{bgh}. %\begin{table}[ht!] %\centering %\caption{Constraint type string identifier}\label{tab:constr_type} @@ -386,13 +399,14 @@ \section{Constraints}\label{sec:constraints} % \subsection{Initial State}\label{sec:constraints:initial} % -Note: An initial state is not required. +Note: An initial state constraint is not required. For example, for moving horizon estimation (MHE) problems it should not be set. -Two possibilities exist to define the initial states equation~\eqref{eq:constraints:initial}: a simple syntax and an extended syntax. +Two possibilities exist to define the initial state constraint~\eqref{eq:constraints:initial}: a simple syntax and an extended syntax. -\paragraph{Simple syntax} -defines the full initial state $x(0)=\bar{x}_0$. The options are found in table~\ref{tab:constraints:simplesyntax}. +\paragraph{Simple syntax.} +Via the simple syntax the full initial state is defined, $x(0)=\bar{x}_0$. +The corresponding options are found in Table~\ref{tab:constraints:simplesyntax}. \begin{table}[ht!] \centering \caption{Simple syntax for setting the initial state} \label{tab:constraints:simplesyntax} @@ -404,9 +418,9 @@ \subsection{Initial State}\label{sec:constraints:initial} \end{tabular} \end{table} % -\paragraph{Extended syntax} -allows to define upper and lower bounds on a subset of states. -The options for the extended syntax are found in table~\ref{tab:constraints:extendedsyntax}. +\paragraph{Extended syntax.} +The extended syntax allows to define upper and lower bounds on a subset of states. +The options for the extended syntax are found in Table~\ref{tab:constraints:extendedsyntax}. \begin{table}[ht!] \centering \caption{Extended syntax for setting the initial state} \label{tab:constraints:extendedsyntax} @@ -503,13 +517,13 @@ \subsection{Terminal Constraints}\label{sec:constraints:terminal} % % \section{External links}\label{sec:external_links} % % outdated and removed -% A table sheet with additional info is found here:\newline +% A Table sheet with additional info is found here:\newline % \url{https://docs.google.com/spreadsheets/d/1rVRycLnCyaWJLwnV47u30Vokp7vRu68og3OhlDbSjDU/edit?usp=sharing} % \section{Model}\label{sec:model} % A model instance is created using \code{ocp\_model = acados\_ocp\_model()}. It contains all model definitions for simulation and for usage in the OCP solver. -See table~\ref{tab:model:options} for the available options. +See Table~\ref{tab:model:options} for the available options. Furthermore, see \code{ocp\_model.model\_struct} or \href{https://github.com/acados/acados/blob/master/interfaces/acados_matlab_octave/acados_ocp_model.m}{\code{acados\_ocp\_model.m}} to see what other fields can be set via direct access. % \begin{table} @@ -528,7 +542,7 @@ \section{Model}\label{sec:model} \code{sym\_z} & \casadi{} expr. & algebraic state $z$ in implicit dynamics eq.~\eqref{eq:dynamics} & \optional, only with IRK \\ \code{sym\_p} & \casadi{} expr. & parameters $p$ of the problem formulation in sec.~\ref{sec:problem} & \optional \\ \multicolumn{4}{c}{$\vdots$}\\ - \multicolumn{4}{c}{Additionally, options from tables \ref{tab:dynamics}, \ref{tab:cost:slack}, \ref{tab:cost:auto}, \ref{tab:cost:external}, \ref{tab:cost:linear_ls}, \ref{tab:cost:nonlinear_ls}, %\ref{tab:constr_type}, + \multicolumn{4}{c}{Additionally, options from Tables \ref{tab:dynamics}, \ref{tab:cost:slack}, \ref{tab:cost:auto}, \ref{tab:cost:external}, \ref{tab:cost:linear_ls}, \ref{tab:cost:nonlinear_ls}, %\ref{tab:constr_type}, \ref{tab:constraints:simplesyntax}, \ref{tab:constraints:extendedsyntax}, \ref{tab:constraints:path} and \ref{tab:constraints:terminal}, apply here.}\\ \multicolumn{4}{c}{$\vdots$}\\ \bottomrule @@ -591,7 +605,7 @@ \section{Solver \& Options}\label{sec:solver} \midrule \multicolumn{4}{l}{\emph{QP solver}} \\ - \code{qp\_solver} & string & $\longrightarrow$ & Defines the quadratic programming solver and condensing strategy. See table~\ref{tab:solver_options:qp_solver_option}\\ + \code{qp\_solver} & string & $\longrightarrow$ & Defines the quadratic programming solver and condensing strategy. See Table~\ref{tab:solver_options:qp_solver_option}\\ \code{qp\_solver\_iter\_max} & int & $50$ & maximum number of iterations per QP solver call\\ \code{qp\_solver\_cond\_N} & int & $N$ & new horizon after partial condensing, set to \code{param\_scheme\_N} by default\\ @@ -608,7 +622,7 @@ \section{Solver \& Options}\label{sec:solver} \midrule \multicolumn{4}{l}{\emph{Hessian approximation}} \\ {\code{nlp\_solver\_\-exact\_hessian}} & string & \str{false} & use exact hessian calculation: (\str{})in (\str{true}, \str{false}), use exact \\ - \code{regularize\_method} & string & $\longrightarrow$ & Defines the hessian regularization method. See table~\ref{tab:solver_options:regularize_method}\\ + \code{regularize\_method} & string & $\longrightarrow$ & Defines the hessian regularization method. See Table~\ref{tab:solver_options:regularize_method}\\ \code{levenberg\_marquardt} & double & $0.0$ & in case of a singular hessian, setting this $>0$ can help convergence \\ \code{exact\_hess\_dyn} & int & $1$ & in ($0$, $1$), compute and use hessian in dynamics, only if \str{nlp\_\-solver\_\-exact\_\-hessian} = \str{true} \\ \code{exact\_hess\_cost} & int & $1$ & in ($0$, $1$), only if \str{nlp\_solver\_exact\_hessian} = \str{true} \\ From b7f75874757e238b8696f1e44d73548369161741 Mon Sep 17 00:00:00 2001 From: Josip Kir Hromatko <36133788+josipkh@users.noreply.github.com> Date: Mon, 15 Jul 2024 10:48:27 +0200 Subject: [PATCH 08/14] Fix small typo in Makefile (#1152) --- Makefile | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/Makefile b/Makefile index 17654e10b4..7fc19ed416 100644 --- a/Makefile +++ b/Makefile @@ -137,13 +137,13 @@ endif ifeq ($(ACADOS_WITH_QORE), 1) STATIC_DEPS += qore_static CLEAN_DEPS += qore_clean -LINK_FLAG_QPDUNES = -lqore +LINK_FLAG_QORE = -lqore endif ifeq ($(ACADOS_WITH_OSQP), 1) STATIC_DEPS += osqp_static SHARED_DEPS += osqp_shared CLEAN_DEPS += osqp_clean -LINK_FLAG_QPDUNES = -losqp +LINK_FLAG_OSQP = -losqp endif ifeq ($(ACADOS_WITH_OPENMP), 1) From 72d148cf37dfaed1cc29829b7792988e5f034f9c Mon Sep 17 00:00:00 2001 From: Jonathan Frey Date: Mon, 15 Jul 2024 15:23:58 +0200 Subject: [PATCH 09/14] Visualize cost-to-go in MOCP example (#1153) --- .../mocp_transition_example/main.py | 78 ++++++++++++++++--- .../acados_template/acados_model.py | 2 +- 2 files changed, 70 insertions(+), 10 deletions(-) diff --git a/examples/acados_python/mocp_transition_example/main.py b/examples/acados_python/mocp_transition_example/main.py index d524550ccd..91c619fe32 100644 --- a/examples/acados_python/mocp_transition_example/main.py +++ b/examples/acados_python/mocp_transition_example/main.py @@ -40,7 +40,7 @@ X0 = np.array([2.0, 0.0]) PENALTY_X = 1e0 T_HORIZON = 1.0 -N_HORIZON = 20 +N_HORIZON = 25 L2_COST_V = 1e-1 L2_COST_P = 1e0 @@ -171,9 +171,7 @@ def formulate_single_integrator_ocp() -> AcadosOcp: return ocp -def main_multiphase_ocp(): - - N_list = [10, 1, 15] +def create_multiphase_ocp_solver(N_list, t_horizon_1, name=None): ocp = AcadosMultiphaseOcp(N_list=N_list) phase_0 = formulate_double_integrator_ocp() @@ -199,11 +197,18 @@ def main_multiphase_ocp(): # the time step for the transition stage is set to 1 to correct for the scaling of the stage cost with the time step ocp.solver_options.tf = T_HORIZON + 1.0 - T_HORIZON_1 = 0.4 * T_HORIZON - T_HORIZON_2 = T_HORIZON - T_HORIZON_1 - ocp.solver_options.time_steps = np.array(N_list[0] * [T_HORIZON_1/N_list[0]] + [1.0] + N_list[2] * [T_HORIZON_2/N_list[2]] ) + t_horizon_2 = T_HORIZON - t_horizon_1 + ocp.solver_options.time_steps = np.array(N_list[0] * [t_horizon_1/N_list[0]] + [1.0] + N_list[2] * [t_horizon_2/N_list[2]] ) + if name is not None: + ocp.name = name acados_ocp_solver = AcadosOcpSolver(ocp, verbose=False) + return acados_ocp_solver, ocp + + +def main_multiphase_ocp(): + N_list = [10, 1, 15] + acados_ocp_solver, ocp = create_multiphase_ocp_solver(N_list, 0.4*T_HORIZON) acados_ocp_solver.solve_for_x0(X0) n_phases = len(N_list) @@ -222,7 +227,7 @@ def main_multiphase_ocp(): # plot solution t_grid_2_plot = t_grid_phases[2] - 1.0 - fig, ax = plt.subplots(3, 1, sharex=True, figsize=(9, 5.2)) + fig, ax = plt.subplots(3, 1, sharex=True, figsize=(7, 5.2)) p_traj_0 = [x[0] for x in x_traj_phases[0]] ax[0].plot(t_grid_phases[0], p_traj_0, color='C0', label='phase 1') @@ -286,7 +291,62 @@ def main_standard_ocp(): ax[-1].set_xlabel('$t$ [s]') +def cost_to_go_experiment(): + solver_list = [] + solver_labels = [] + + ocp = formulate_double_integrator_ocp() + ocp.solver_options.tf = T_HORIZON + ocp.solver_options.nlp_solver_type = 'SQP' + + standard_ocp_solver = AcadosOcpSolver(ocp, verbose=False) + solver_list.append(standard_ocp_solver) + solver_labels.append('standard OCP') + + N_list = [15, 1, 10] + t_horizon_1 = 0.6 * T_HORIZON + mocp_solver, ocp = create_multiphase_ocp_solver(N_list, t_horizon_1, name='mocp2') + solver_list.append(mocp_solver) + solver_labels.append(f'MOCP $N_1={N_list[0]}$ $T_1={t_horizon_1}$') + + N_list = [10, 1, 15] + t_horizon_1 = 0.4 * T_HORIZON + mocp_solver, ocp = create_multiphase_ocp_solver(N_list, t_horizon_1, name='mocp') + solver_list.append(mocp_solver) + solver_labels.append(f'MOCP $N_1={N_list[0]}$ $T_1={t_horizon_1}$') + + N_list = [5, 1, 20] + t_horizon_1 = 0.2 * T_HORIZON + mocp_solver, ocp = create_multiphase_ocp_solver(N_list, t_horizon_1, name='mocp1') + solver_list.append(mocp_solver) + solver_labels.append(f'MOCP $N_1={N_list[0]}$ $T_1={t_horizon_1}$') + + n_plot_points = 100 + p0_vals = np.linspace(0, 20.0, n_plot_points) + cost_vals = np.zeros((len(solver_list), n_plot_points)) + for j, p0 in enumerate(p0_vals): + x0 = np.array([p0, 0.]) + + for i, solver in enumerate(solver_list): + solver.solve_for_x0(x0) + cost_vals[i, j] = solver.get_cost() + + # plot cost values + fig, ax = plt.subplots(1, 1, figsize=(6, 5.2)) + linestyles = ['-', '-.', '-.', '-.'] + for i, label in enumerate(solver_labels): + ax.plot(p0_vals, cost_vals[i, :], label=label, color=f'C{i+2}', linestyle=linestyles[i]) + ax.set_xlabel('$p_0$') + ax.set_ylabel('cost-to-go $V([p_0, 0])$') + ax.grid() + ax.set_xlim([p0_vals[0], p0_vals[-1]]) + ax.legend() + ax.set_ylim([-10, 300]) + plt.savefig('cost_to_go.pdf', bbox_inches="tight", transparent=True, pad_inches=0.05) + + if __name__ == "__main__": main_multiphase_ocp() main_standard_ocp() - plt.show() \ No newline at end of file + # cost_to_go_experiment() + plt.show() diff --git a/interfaces/acados_template/acados_template/acados_model.py b/interfaces/acados_template/acados_template/acados_model.py index d8f0d93766..010d9ff06b 100644 --- a/interfaces/acados_template/acados_template/acados_model.py +++ b/interfaces/acados_template/acados_template/acados_model.py @@ -329,7 +329,7 @@ def substitute(self, var: Union[ca.SX, ca.MX], expr_new: Union[ca.SX, ca.MX]) -> def augment_model_with_polynomial_control(self, degree: int) -> None: print("Deprecation warning: augment_model_with_polynomial_control() is deprecated and has been renamed to reformulate_with_polynomial_control().") - self.reformulate_with_polynomial_control() + self.reformulate_with_polynomial_control(degree=degree) def reformulate_with_polynomial_control(self, degree: int) -> None: """ From 06ece8cad4e1ebc3ea475b92b4f7733057fdeeb1 Mon Sep 17 00:00:00 2001 From: Jonathan Frey Date: Mon, 15 Jul 2024 15:25:20 +0200 Subject: [PATCH 10/14] Add `reset` function in MEX OCP solver interface (#1156) --- .../test/test_ocp_simple_dae.m | 1 + interfaces/acados_matlab_octave/acados_ocp.m | 3 + .../render_acados_templates.m | 5 ++ .../matlab_templates/acados_mex_reset.in.c | 56 +++++++++++++++++++ .../matlab_templates/make_mex.in.m | 1 + .../matlab_templates/mex_solver.in.m | 4 ++ 6 files changed, 70 insertions(+) create mode 100644 interfaces/acados_template/acados_template/c_templates_tera/matlab_templates/acados_mex_reset.in.c diff --git a/examples/acados_matlab_octave/test/test_ocp_simple_dae.m b/examples/acados_matlab_octave/test/test_ocp_simple_dae.m index e093aa77b8..1bd0f0076b 100644 --- a/examples/acados_matlab_octave/test/test_ocp_simple_dae.m +++ b/examples/acados_matlab_octave/test/test_ocp_simple_dae.m @@ -194,6 +194,7 @@ %% acados ocp ocp = acados_ocp(ocp_model, ocp_opts); +ocp.reset(); ocp.solve(); stat = ocp.get('stat'); diff --git a/interfaces/acados_matlab_octave/acados_ocp.m b/interfaces/acados_matlab_octave/acados_ocp.m index 75660e3ad6..38374e9033 100644 --- a/interfaces/acados_matlab_octave/acados_ocp.m +++ b/interfaces/acados_matlab_octave/acados_ocp.m @@ -261,6 +261,9 @@ function print(obj, varargin) obj.t_ocp.print(varargin{:}); end + function reset(obj) + obj.t_ocp.reset(); + end % function delete(obj) % Use default implementation. diff --git a/interfaces/acados_matlab_octave/acados_template_mex/+acados_template_mex/render_acados_templates.m b/interfaces/acados_matlab_octave/acados_template_mex/+acados_template_mex/render_acados_templates.m index 2e26308bcc..ddd6ec7c2e 100644 --- a/interfaces/acados_matlab_octave/acados_template_mex/+acados_template_mex/render_acados_templates.m +++ b/interfaces/acados_matlab_octave/acados_template_mex/+acados_template_mex/render_acados_templates.m @@ -97,6 +97,11 @@ function render_acados_templates(acados_ocp_nlp_json_file) out_file = ['acados_mex_set_', model_name, '.c']; render_file( json_fullfile, matlab_template_dir, template_file, out_file, t_renderer_location ) + % MEX reset + template_file = 'acados_mex_reset.in.c'; + out_file = ['acados_mex_reset_', model_name, '.c']; + render_file( json_fullfile, matlab_template_dir, template_file, out_file, t_renderer_location ) + % MEX class template_file = 'mex_solver.in.m'; out_file = [ model_name, '_mex_solver.m']; diff --git a/interfaces/acados_template/acados_template/c_templates_tera/matlab_templates/acados_mex_reset.in.c b/interfaces/acados_template/acados_template/c_templates_tera/matlab_templates/acados_mex_reset.in.c new file mode 100644 index 0000000000..428f822b3a --- /dev/null +++ b/interfaces/acados_template/acados_template/c_templates_tera/matlab_templates/acados_mex_reset.in.c @@ -0,0 +1,56 @@ +/* + * Copyright (c) The acados authors. + * + * This file is part of acados. + * + * The 2-Clause BSD License + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions are met: + * + * 1. Redistributions of source code must retain the above copyright notice, + * this list of conditions and the following disclaimer. + * + * 2. Redistributions in binary form must reproduce the above copyright notice, + * this list of conditions and the following disclaimer in the documentation + * and/or other materials provided with the distribution. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" + * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE + * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE + * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE + * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR + * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF + * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS + * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN + * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) + * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE.; + */ + +// system +#include +#include +#include +// acados +#include "acados_solver_{{ model.name }}.h" + +// mex +#include "mex.h" + + + +void mexFunction(int nlhs, mxArray *plhs[], int nrhs, const mxArray *prhs[]) +{ + // C_ocp + long long *ptr; + const mxArray *C_ocp = prhs[0]; + + // capsule + ptr = (long long *) mxGetData( mxGetField( C_ocp, 0, "capsule" ) ); + {{ model.name }}_solver_capsule *capsule = ({{ model.name }}_solver_capsule *) ptr[0]; + + // reset + {{ model.name }}_acados_reset(capsule, 1); + +} diff --git a/interfaces/acados_template/acados_template/c_templates_tera/matlab_templates/make_mex.in.m b/interfaces/acados_template/acados_template/c_templates_tera/matlab_templates/make_mex.in.m index 9949ac3ea3..e9eed3349c 100644 --- a/interfaces/acados_template/acados_template/c_templates_tera/matlab_templates/make_mex.in.m +++ b/interfaces/acados_template/acados_template/c_templates_tera/matlab_templates/make_mex.in.m @@ -74,6 +74,7 @@ 'acados_mex_free_{{ model.name }}' ... 'acados_mex_solve_{{ model.name }}' ... 'acados_mex_set_{{ model.name }}' ... + 'acados_mex_reset_{{ model.name }}' ... }; mex_files = cell(length(mex_names), 1); diff --git a/interfaces/acados_template/acados_template/c_templates_tera/matlab_templates/mex_solver.in.m b/interfaces/acados_template/acados_template/c_templates_tera/matlab_templates/mex_solver.in.m index 23a7235d19..326a753122 100644 --- a/interfaces/acados_template/acados_template/c_templates_tera/matlab_templates/mex_solver.in.m +++ b/interfaces/acados_template/acados_template/c_templates_tera/matlab_templates/mex_solver.in.m @@ -217,6 +217,10 @@ function eval_param_sens(obj, field, stage, index) end end + function [] = reset(obj) + acados_mex_reset_{{ model.name }}(obj.C_ocp); + end + % print function print(varargin) From 0d03b85709136e077df3a704163fd1e55fc09192 Mon Sep 17 00:00:00 2001 From: Jonathan Frey Date: Mon, 15 Jul 2024 15:52:22 +0200 Subject: [PATCH 11/14] Fix QP status issue (#1155) This PR addresses an issue which caused the SQP solver to always return status 4, if it was returned once. This was introduced in https://github.com/acados/acados/pull/1057 Added a test to check that the OCP solver can recover from such a situation. --- acados/ocp_nlp/ocp_nlp_sqp.c | 15 +-- examples/acados_python/tests/reset_test.py | 104 ++++++++++-------- .../acados_template/acados_ocp_solver.py | 11 +- 3 files changed, 75 insertions(+), 55 deletions(-) diff --git a/acados/ocp_nlp/ocp_nlp_sqp.c b/acados/ocp_nlp/ocp_nlp_sqp.c index 42bab2e9a7..15596c559d 100644 --- a/acados/ocp_nlp/ocp_nlp_sqp.c +++ b/acados/ocp_nlp/ocp_nlp_sqp.c @@ -689,6 +689,7 @@ int ocp_nlp_sqp(void *config_, void *dims_, void *nlp_in_, void *nlp_out_, int qp_status = 0; int qp_iter = 0; mem->alpha = 0.0; + mem->status = ACADOS_SUCCESS; #if defined(ACADOS_WITH_OPENMP) // backup number of threads @@ -896,15 +897,15 @@ int ocp_nlp_sqp(void *config_, void *dims_, void *nlp_in_, void *nlp_out_, if (nlp_opts->globalization_use_SOC && nlp_opts->globalization == MERIT_BACKTRACKING) { do_line_search = ocp_nlp_soc_line_search(config, dims, nlp_in, nlp_out, opts, mem, work, sqp_iter); - } - if (mem->status == ACADOS_QP_FAILURE) - { + if (mem->status == ACADOS_QP_FAILURE) + { #if defined(ACADOS_WITH_OPENMP) - // restore number of threads - omp_set_num_threads(num_threads_bkp); + // restore number of threads + omp_set_num_threads(num_threads_bkp); #endif - mem->time_tot = acados_toc(&timer0); - return mem->status; + mem->time_tot = acados_toc(&timer0); + return mem->status; + } } if (do_line_search) diff --git a/examples/acados_python/tests/reset_test.py b/examples/acados_python/tests/reset_test.py index f8f2520889..0a3f5b09b3 100644 --- a/examples/acados_python/tests/reset_test.py +++ b/examples/acados_python/tests/reset_test.py @@ -38,10 +38,18 @@ from utils import plot_pendulum from casadi import vertcat +RESET_SCENARIOS = ["NaNs", "infeasible_QP"] def main(cost_type='NONLINEAR_LS', hessian_approximation='EXACT', ext_cost_use_num_hess=0, - integrator_type='ERK'): + integrator_type='ERK', reset_scenarios=RESET_SCENARIOS): print(f"using: cost_type {cost_type}, integrator_type {integrator_type}") + + for reset_scenario in reset_scenarios: + if reset_scenario not in RESET_SCENARIOS: + raise Exception(f"Unknown reset_scenario: {reset_scenario}. Possible values are {RESET_SCENARIOS}") + if len(reset_scenarios) == 0: + raise Exception("No reset scenarios given") + # create ocp object to formulate the OCP ocp = AcadosOcp() @@ -130,54 +138,64 @@ def main(cost_type='NONLINEAR_LS', hessian_approximation='EXACT', ext_cost_use_n ocp_solver = AcadosOcpSolver(ocp, json_file = 'acados_ocp.json') - # set NaNs as input to test reset() -> NOT RECOMMENDED!!! # ocp_solver.options_set('print_level', 2) - for i in range(N): - ocp_solver.set(i, 'x', np.nan * np.ones((nx,))) - ocp_solver.set(i, 'u', np.nan * np.ones((nu,))) - status = ocp_solver.solve() - ocp_solver.print_statistics() # encapsulates: stat = ocp_solver.get_stats("statistics") - if status == 0: - raise Exception(f'acados returned status {status}, although NaNs were given.') - else: - print(f'acados returned status {status}, which is expected, since NaNs were given.') - - # RESET - ocp_solver.reset() - for i in range(N): - ocp_solver.set(i, 'x', x0) - - if cost_type == 'EXTERNAL': - # NOTE: hessian is wrt [u,x] - if ext_cost_use_num_hess: + for reset_scenario in RESET_SCENARIOS: + if reset_scenario == "NaNs": + # set NaNs as input to test reset() -> NOT RECOMMENDED!!! for i in range(N): - ocp_solver.cost_set(i, "ext_cost_num_hess", np.diag([0.04, 4000, 4000, 0.04, 0.04, ])) - ocp_solver.cost_set(N, "ext_cost_num_hess", np.diag([4000, 4000, 0.04, 0.04, ])) - - simX = np.zeros((N+1, nx)) - simU = np.zeros((N, nu)) - - status = ocp_solver.solve() - - ocp_solver.print_statistics() - if status != 0: - raise Exception(f'acados returned status {status} for cost_type {cost_type}\n' - f'integrator_type = {integrator_type}.') - - # get solution - for i in range(N): - simX[i,:] = ocp_solver.get(i, "x") - simU[i,:] = ocp_solver.get(i, "u") - simX[N,:] = ocp_solver.get(N, "x") - + ocp_solver.set(i, 'x', np.nan * np.ones((nx,))) + ocp_solver.set(i, 'u', np.nan * np.ones((nu,))) + expected_status = 1 + elif reset_scenario == "infeasible_QP": + # set bounds such that QP is infeasible + ocp_solver.constraints_set(0, 'lbu', 1) + ocp_solver.constraints_set(0, 'ubu', -1) + expected_status = 4 + + status = ocp_solver.solve() + ocp_solver.print_statistics() # encapsulates: stat = ocp_solver.get_stats("statistics") + if status != expected_status: + raise Exception(f'acados returned status {status}, although formulation is subject to {reset_scenario}.') + else: + print(f'acados returned status {status}, which is expected, since formulation is subject to {reset_scenario}.') + + # RESET + ocp_solver.reset() + if reset_scenario == "infeasible_QP": + ocp_solver.constraints_set(0, 'lbu', -Fmax) + ocp_solver.constraints_set(0, 'ubu', Fmax) + + if cost_type == 'EXTERNAL': + # NOTE: hessian is wrt [u,x] + if ext_cost_use_num_hess: + for i in range(N): + ocp_solver.cost_set(i, "ext_cost_num_hess", np.diag([0.04, 4000, 4000, 0.04, 0.04, ])) + ocp_solver.cost_set(N, "ext_cost_num_hess", np.diag([4000, 4000, 0.04, 0.04, ])) + + simX = np.zeros((N+1, nx)) + simU = np.zeros((N, nu)) + + status = ocp_solver.solve() + + ocp_solver.print_statistics() + if status != 0: + raise Exception(f'acados returned status {status} for cost_type {cost_type}\n' + f'integrator_type = {integrator_type} after testing reset with {reset_scenario}.') + + # get solution + for i in range(N): + simX[i,:] = ocp_solver.get(i, "x") + simU[i,:] = ocp_solver.get(i, "u") + simX[N,:] = ocp_solver.get(N, "x") if __name__ == '__main__': - # for integrator_type in ['ERK', 'IRK']: - # ['LIFTED_IRK'] for integrator_type in ['GNSF', 'ERK', 'IRK']: for cost_type in ['EXTERNAL', 'LS', 'NONLINEAR_LS']: - # for cost_type in ['EXTERNAL', 'LS', 'NONLINEAR_LS']: hessian_approximation = 'GAUSS_NEWTON' # 'GAUSS_NEWTON, EXACT ext_cost_use_num_hess = 1 main(cost_type=cost_type, hessian_approximation=hessian_approximation, - ext_cost_use_num_hess=ext_cost_use_num_hess, integrator_type=integrator_type) + ext_cost_use_num_hess=ext_cost_use_num_hess, integrator_type=integrator_type, + reset_scenarios=RESET_SCENARIOS) + + # main(cost_type='EXTERNAL', hessian_approximation='GAUSS_NEWTON', + # ext_cost_use_num_hess=0, integrator_type="ERK", reset_scenarios=["infeasible_QP"]) diff --git a/interfaces/acados_template/acados_template/acados_ocp_solver.py b/interfaces/acados_template/acados_template/acados_ocp_solver.py index 92a452e065..bad8c8f844 100644 --- a/interfaces/acados_template/acados_template/acados_ocp_solver.py +++ b/interfaces/acados_template/acados_template/acados_ocp_solver.py @@ -947,11 +947,12 @@ def get_status(self) -> int: Returns the status of the last solver call. Status codes: - 0 - Success - 1 - Failure - 2 - Maximum number of iterations reached - 3 - Minimum step size reached - 4 - QP solver failed + 0 - Success (ACADOS_SUCCESS) + 1 - NaN detected (ACADOS_NAN_DETECTED) + 2 - Maximum number of iterations reached (ACADOS_MAXITER) + 3 - Minimum step size reached (ACADOS_MINSTEP) + 4 - QP solver failed (ACADOS_QP_FAILURE) + 5 - Solver created (ACADOS_READY) See `return_values` in https://github.com/acados/acados/blob/master/acados/utils/types.h """ From f8df76981b5b06e1215beb5a65439973cdb445fc Mon Sep 17 00:00:00 2001 From: Katrin Baumgaertner Date: Tue, 16 Jul 2024 17:05:33 +0200 Subject: [PATCH 12/14] Cmake for multi-phase OCP solver (#1157) This PR adds the cmake build systems for the multi-phase OCP (MOCP) solver in preparation for MOCP solvers in MATLAB. --- .../mocp_transition_example/main.py | 17 +- .../acados_template/acados_multiphase_ocp.py | 3 +- .../c_templates_tera/CMakeLists.in.txt | 2 +- .../c_templates_tera/Makefile.in | 2 +- .../c_templates_tera/multi_CMakeLists.in.txt | 367 ++++++++++++++++++ .../c_templates_tera/multi_Makefile.in | 2 +- 6 files changed, 382 insertions(+), 11 deletions(-) create mode 100644 interfaces/acados_template/acados_template/c_templates_tera/multi_CMakeLists.in.txt diff --git a/examples/acados_python/mocp_transition_example/main.py b/examples/acados_python/mocp_transition_example/main.py index 91c619fe32..fff88e7d31 100644 --- a/examples/acados_python/mocp_transition_example/main.py +++ b/examples/acados_python/mocp_transition_example/main.py @@ -32,7 +32,7 @@ import numpy as np import casadi as ca -from acados_template import AcadosModel, AcadosOcp, AcadosMultiphaseOcp, AcadosOcpSolver, casadi_length, is_empty, latexify_plot +from acados_template import AcadosModel, AcadosOcp, AcadosMultiphaseOcp, AcadosOcpSolver, casadi_length, latexify_plot, ocp_get_default_cmake_builder import matplotlib.pyplot as plt latexify_plot() @@ -171,7 +171,7 @@ def formulate_single_integrator_ocp() -> AcadosOcp: return ocp -def create_multiphase_ocp_solver(N_list, t_horizon_1, name=None): +def create_multiphase_ocp_solver(N_list, t_horizon_1, name=None, use_cmake=False): ocp = AcadosMultiphaseOcp(N_list=N_list) phase_0 = formulate_double_integrator_ocp() @@ -202,14 +202,17 @@ def create_multiphase_ocp_solver(N_list, t_horizon_1, name=None): if name is not None: ocp.name = name - acados_ocp_solver = AcadosOcpSolver(ocp, verbose=False) + + cmake_builder = ocp_get_default_cmake_builder() if use_cmake else None + acados_ocp_solver = AcadosOcpSolver(ocp, verbose=False, cmake_builder=cmake_builder) return acados_ocp_solver, ocp -def main_multiphase_ocp(): +def main_multiphase_ocp(use_cmake=False): N_list = [10, 1, 15] - acados_ocp_solver, ocp = create_multiphase_ocp_solver(N_list, 0.4*T_HORIZON) + acados_ocp_solver, ocp = create_multiphase_ocp_solver(N_list, 0.4*T_HORIZON, use_cmake=use_cmake) acados_ocp_solver.solve_for_x0(X0) + acados_ocp_solver.print_statistics() n_phases = len(N_list) @@ -346,7 +349,9 @@ def cost_to_go_experiment(): if __name__ == "__main__": - main_multiphase_ocp() + + for use_cmake in [False, True]: + main_multiphase_ocp(use_cmake) main_standard_ocp() # cost_to_go_experiment() plt.show() diff --git a/interfaces/acados_template/acados_template/acados_multiphase_ocp.py b/interfaces/acados_template/acados_template/acados_multiphase_ocp.py index a20f4cefed..af7c12b56f 100644 --- a/interfaces/acados_template/acados_template/acados_multiphase_ocp.py +++ b/interfaces/acados_template/acados_template/acados_multiphase_ocp.py @@ -341,8 +341,7 @@ def __get_template_list(self, cmake_builder=None) -> list: template_list.append(('acados_multi_solver.in.c', f'acados_solver_{name}.c')) # template_list.append(('acados_solver.in.pxd', f'acados_solver.pxd')) if cmake_builder is not None: - raise NotImplementedError('CMake not yet supported for multiphase OCPs.') - template_list.append(('CMakeLists.in.txt', 'CMakeLists.txt')) + template_list.append(('multi_CMakeLists.in.txt', 'CMakeLists.txt')) else: template_list.append(('multi_Makefile.in', 'Makefile')) diff --git a/interfaces/acados_template/acados_template/c_templates_tera/CMakeLists.in.txt b/interfaces/acados_template/acados_template/c_templates_tera/CMakeLists.in.txt index bf0bb83401..64f1a063cd 100644 --- a/interfaces/acados_template/acados_template/c_templates_tera/CMakeLists.in.txt +++ b/interfaces/acados_template/acados_template/c_templates_tera/CMakeLists.in.txt @@ -334,7 +334,7 @@ if(${BUILD_ACADOS_SOLVER_LIB} OR ${BUILD_ACADOS_OCP_SOLVER_LIB} OR ${BUILD_EXAMP {% if solver_options.with_value_sens_wrt_params %} {{ model.name }}_cost/{{ model.name }}_cost_ext_cost_e_grad_p.c {% endif %} - {%- elif cost.cost_source_ext_cost_e != cost.cost_source_ext_cost_0 %} + {%- else %} {{ model.name }}_cost/{{ cost.cost_source_ext_cost_e }} {%- endif %} {%- endif %} diff --git a/interfaces/acados_template/acados_template/c_templates_tera/Makefile.in b/interfaces/acados_template/acados_template/c_templates_tera/Makefile.in index 8108ed60d3..9bf97f8180 100644 --- a/interfaces/acados_template/acados_template/c_templates_tera/Makefile.in +++ b/interfaces/acados_template/acados_template/c_templates_tera/Makefile.in @@ -294,7 +294,7 @@ OCP_SRC+= {{ model.name }}_cost/{{ model.name }}_cost_ext_cost_e_hess_xu_p.c {% if solver_options.with_value_sens_wrt_params %} OCP_SRC+= {{ model.name }}_cost/{{ model.name }}_cost_ext_cost_e_grad_p.c {% endif %} - {%- elif cost.cost_source_ext_cost_e != cost.cost_source_ext_cost_0 %} + {%- else %} OCP_SRC+= {{ model.name }}_cost/{{ cost.cost_source_ext_cost_e }} {%- endif %} {%- endif %} diff --git a/interfaces/acados_template/acados_template/c_templates_tera/multi_CMakeLists.in.txt b/interfaces/acados_template/acados_template/c_templates_tera/multi_CMakeLists.in.txt new file mode 100644 index 0000000000..e1f6e8754d --- /dev/null +++ b/interfaces/acados_template/acados_template/c_templates_tera/multi_CMakeLists.in.txt @@ -0,0 +1,367 @@ +# +# Copyright (c) The acados authors. +# +# This file is part of acados. +# +# The 2-Clause BSD License +# +# Redistribution and use in source and binary forms, with or without +# modification, are permitted provided that the following conditions are met: +# +# 1. Redistributions of source code must retain the above copyright notice, +# this list of conditions and the following disclaimer. +# +# 2. Redistributions in binary form must reproduce the above copyright notice, +# this list of conditions and the following disclaimer in the documentation +# and/or other materials provided with the distribution. +# +# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" +# AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE +# IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE +# ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE +# LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR +# CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF +# SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS +# INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN +# CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) +# ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE +# POSSIBILITY OF SUCH DAMAGE.; +# + +{% set dims_0 = phases_dims | first %} +{% set cost_0 = cost | first %} +{% set constraints_0 = constraints | first %} +{% set model_0 = model | first %} + + +{% set cost_e = cost | last %} +{% set constraints_e = constraints | last %} +{% set dims_e = phases_dims | last %} +{% set model_e = model | last %} + + +{%- if solver_options.qp_solver %} + {%- set qp_solver = solver_options.qp_solver %} +{%- else %} + {%- set qp_solver = "FULL_CONDENSING_HPIPM" %} +{%- endif %} + +{%- if solver_options.hessian_approx %} + {%- set hessian_approx = solver_options.hessian_approx %} +{%- elif solver_options.sens_hess %} + {%- set hessian_approx = "EXACT" %} +{%- else %} + {%- set hessian_approx = "GAUSS_NEWTON" %} +{%- endif %} + + + +{%- if solver_options.model_external_shared_lib_dir %} + {%- set model_external_shared_lib_dir = solver_options.model_external_shared_lib_dir %} +{%- endif %} + +{%- if solver_options.model_external_shared_lib_name %} + {%- set model_external_shared_lib_name = solver_options.model_external_shared_lib_name %} +{%- endif %} + +{#- control operator #} +{%- if os and os == "pc" %} + {%- set control = "&" %} +{%- else %} + {%- set control = ";" %} +{%- endif %} + +{%- if acados_link_libs and os and os == "pc" %}{# acados linking libraries and flags #} + {%- set link_libs = acados_link_libs.qpoases ~ " " ~ acados_link_libs.hpmpc ~ " " ~ acados_link_libs.osqp ~ " " ~ acados_link_libs.daqp -%} + {%- set openmp_flag = acados_link_libs.openmp %} +{%- else %} + {%- set openmp_flag = " " %} + {%- if qp_solver == "FULL_CONDENSING_QPOASES" %} + {%- set link_libs = "-lqpOASES_e" %} + {%- elif qp_solver == "FULL_CONDENSING_DAQP" %} + {%- set link_libs = "-ldaqp" %} + {%- else %} + {%- set link_libs = "" %} + {%- endif %} +{%- endif %} + +cmake_minimum_required(VERSION 3.13) + +project({{ name }}) + +# build options. +option(BUILD_ACADOS_SOLVER_LIB "Should the solver library acados_solver_{{ name }} be build?" OFF) +option(BUILD_ACADOS_OCP_SOLVER_LIB "Should the OCP solver library acados_ocp_solver_{{ name }} be build?" OFF) +option(BUILD_EXAMPLE "Should the example main_{{ name }} be build?" OFF) + + + +if(CMAKE_CXX_COMPILER_ID MATCHES "GNU" AND CMAKE_SYSTEM_NAME MATCHES "Windows") + # MinGW: remove prefix and change suffix to match MSVC + # (such that Matlab mex recognizes the libraries) + set(CMAKE_SHARED_LIBRARY_PREFIX "") + set(CMAKE_IMPORT_LIBRARY_SUFFIX ".lib") + set(CMAKE_IMPORT_LIBRARY_PREFIX "") + set(CMAKE_STATIC_LIBRARY_SUFFIX ".lib") + set(CMAKE_STATIC_LIBRARY_PREFIX "") +endif() + + +if(CMAKE_CXX_COMPILER_ID MATCHES "MSVC") + set(CMAKE_RUNTIME_OUTPUT_DIRECTORY_RELEASE {{ code_export_directory | replace(from="\", to="/") }}) + set(CMAKE_ARCHIVE_OUTPUT_DIRECTORY_RELEASE {{ code_export_directory | replace(from="\", to="/") }}) + set(CMAKE_LIBRARY_OUTPUT_DIRECTORY_RELEASE {{ code_export_directory | replace(from="\", to="/") }}) +endif() + + +# object target names +set(MODEL_OBJ model_{{ name }}) +set(OCP_OBJ ocp_{{ name }}) + +# model +set(MODEL_SRC +{%- for jj in range(end=n_phases) %}{# phases loop !#} + {%- if model[jj].dyn_ext_fun_type == "casadi" %} +{%- if mocp_opts.integrator_type[jj] == "ERK" %} + {{ model[jj].name }}_model/{{ model[jj].name }}_expl_ode_fun.c + {{ model[jj].name }}_model/{{ model[jj].name }}_expl_vde_forw.c + {{ model[jj].name }}_model/{{ model[jj].name }}_expl_vde_adj.c + {%- if hessian_approx == "EXACT" %} + {{ model[jj].name }}_model/{{ model[jj].name }}_expl_ode_hess.c + {%- endif %} +{%- elif mocp_opts.integrator_type[jj] == "IRK" %} + {{ model[jj].name }}_model/{{ model[jj].name }}_impl_dae_fun.c + {{ model[jj].name }}_model/{{ model[jj].name }}_impl_dae_fun_jac_x_xdot_z.c + {{ model[jj].name }}_model/{{ model[jj].name }}_impl_dae_jac_x_xdot_u_z.c + {%- if hessian_approx == "EXACT" %} + {{ model[jj].name }}_model/{{ model[jj].name }}_impl_dae_hess.c + {%- endif %} +{%- elif mocp_opts.integrator_type[jj] == "LIFTED_IRK" %} + {{ model[jj].name }}_model/{{ model[jj].name }}_impl_dae_fun.c + {{ model[jj].name }}_model/{{ model[jj].name }}_impl_dae_fun_jac_x_xdot_u.c + {%- if hessian_approx == "EXACT" %} + {{ model[jj].name }}_model/{{ model[jj].name }}_impl_dae_hess.c + {%- endif %} +{%- elif mocp_opts.integrator_type[jj] == "GNSF" %} + {% if model[jj].gnsf.purely_linear != 1 %} + {{ model[jj].name }}_model/{{ model[jj].name }}_gnsf_phi_fun.c + {{ model[jj].name }}_model/{{ model[jj].name }}_gnsf_phi_fun_jac_y.c + {{ model[jj].name }}_model/{{ model[jj].name }}_gnsf_phi_jac_y_uhat.c + {%- if model[jj].gnsf.nontrivial_f_LO == 1 %} + {{ model[jj].name }}_model/{{ model[jj].name }}_gnsf_f_lo_fun_jac_x1k1uz.c + {%- endif %} + {%- endif %} + {{ model[jj].name }}_model/{{ model[jj].name }}_gnsf_get_matrices_fun.c +{%- elif mocp_opts.integrator_type[jj] == "DISCRETE" %} + {{ model[jj].name }}_model/{{ model[jj].name }}_dyn_disc_phi_fun.c + {{ model[jj].name }}_model/{{ model[jj].name }}_dyn_disc_phi_fun_jac.c + {%- if solver_options.with_solution_sens_wrt_params %} + {{ model[jj].name }}_model/{{ model[jj].name }}_dyn_disc_phi_jac_p_hess_xu_p.c + {%- endif %} + {%- if solver_options.with_value_sens_wrt_params %} + {{ model[jj].name }}_model/{{ model[jj].name }}_dyn_disc_phi_adj_p.c + {%- endif %} + {%- if hessian_approx == "EXACT" %} + {{ model[jj].name }}_model/{{ model[jj].name }}_dyn_disc_phi_fun_jac_hess.c + {%- endif %} +{%- endif -%} + {%- else %} + {{ model[jj].name }}_model/{{ model[jj].dyn_generic_source }} + {%- endif %} +{%- endfor %} +) +add_library(${MODEL_OBJ} OBJECT ${MODEL_SRC} ) + +# optimal control problem - mostly CasADi exports +if(${BUILD_ACADOS_SOLVER_LIB} OR ${BUILD_ACADOS_OCP_SOLVER_LIB} OR ${BUILD_EXAMPLE}) + set(OCP_SRC +{%- for jj in range(end=n_phases) %}{# phases loop !#} +{%- if constraints[jj].constr_type == "BGP" and phases_dims[jj].nphi > 0 %} + {{ model[jj].name }}_constraints/{{ model[jj].name }}_phi_constraint.c +{%- endif %} + +{%- if constraints[jj].constr_type == "BGH" and phases_dims[jj].nh > 0 %} + {{ model[jj].name }}_constraints/{{ model[jj].name }}_constr_h_fun_jac_uxt_zt.c + {{ model[jj].name }}_constraints/{{ model[jj].name }}_constr_h_fun.c + {%- if hessian_approx == "EXACT" %} + {{ model[jj].name }}_constraints/{{ model[jj].name }}_constr_h_fun_jac_uxt_zt_hess.c + {%- endif %} +{%- endif %} + +{%- if cost[jj].cost_type == "NONLINEAR_LS" %} + {{ model[jj].name }}_cost/{{ model[jj].name }}_cost_y_fun.c + {{ model[jj].name }}_cost/{{ model[jj].name }}_cost_y_fun_jac_ut_xt.c + {{ model[jj].name }}_cost/{{ model[jj].name }}_cost_y_hess.c +{%- elif cost[jj].cost_type == "CONVEX_OVER_NONLINEAR" %} + {{ model[jj].name }}_cost/{{ model[jj].name }}_conl_cost_fun.c + {{ model[jj].name }}_cost/{{ model[jj].name }}_conl_cost_fun_jac_hess.c +{%- elif cost[jj].cost_type == "EXTERNAL" %} + {%- if cost[jj].cost_ext_fun_type == "casadi" %} + {{ model[jj].name }}_cost/{{ model[jj].name }}_cost_ext_cost_fun.c + {{ model[jj].name }}_cost/{{ model[jj].name }}_cost_ext_cost_fun_jac.c + {{ model[jj].name }}_cost/{{ model[jj].name }}_cost_ext_cost_fun_jac_hess.c + {%- if solver_options.with_solution_sens_wrt_params %} + {{ model[jj].name }}_cost/{{ model[jj].name }}_cost_ext_cost_hess_xu_p.c + {%- endif %} + {%- if solver_options.with_value_sens_wrt_params %} + {{ model[jj].name }}_cost/{{ model[jj].name }}_cost_ext_cost_grad_p.c + {%- endif %} + {%- elif cost[jj].cost_source_ext_cost != cost[jj].cost_source_ext_cost_0 %} + {{ model[jj].name }}_cost/{{ cost[jj].cost_source_ext_cost }} + {%- endif %} +{%- endif %} +{%- endfor %} +{%- if constraints_0.constr_type_0 == "BGP" and dims_0.nphi_0 > 0 %} + {{ model_0.name }}_constraints/{{ model_0.name }}_phi_0_constraint.c +{%- endif %} +{%- if constraints_0.constr_type_0 == "BGH" and dims_0.nh_0 > 0 %} + {{ model_0.name }}_constraints/{{ model_0.name }}_constr_h_0_fun_jac_uxt_zt.c + {{ model_0.name }}_constraints/{{ model_0.name }}_constr_h_0_fun.c + {%- if hessian_approx == "EXACT" %} + {{ model_0.name }}_constraints/{{ model_0.name }}_constr_h_0_fun_jac_uxt_zt_hess.c + {%- endif %} +{%- endif %} + +{%- if constraints_e.constr_type_e == "BGP" and dims_e.nphi_e > 0 %} + {{ model_e.name }}_constraints/{{ model_e.name }}_phi_e_constraint.c +{%- endif %} +{%- if constraints_e.constr_type_e == "BGH" and dims_e.nh_e > 0 %} + {{ model_e.name }}_constraints/{{ model_e.name }}_constr_h_e_fun_jac_uxt_zt.c + {{ model_e.name }}_constraints/{{ model_e.name }}_constr_h_e_fun.c + {%- if hessian_approx == "EXACT" %} + {{ model_e.name }}_constraints/{{ model_e.name }}_constr_h_e_fun_jac_uxt_zt_hess.c + {%- endif %} +{%- endif %} + +{%- if cost_0.cost_type_0 == "NONLINEAR_LS" %} + {{ model_0.name }}_cost/{{ model_0.name }}_cost_y_0_fun.c + {{ model_0.name }}_cost/{{ model_0.name }}_cost_y_0_fun_jac_ut_xt.c + {{ model_0.name }}_cost/{{ model_0.name }}_cost_y_0_hess.c +{%- elif cost_0.cost_type_0 == "CONVEX_OVER_NONLINEAR" %} + {{ model_0.name }}_cost/{{ model_0.name }}_conl_cost_0_fun.c + {{ model_0.name }}_cost/{{ model_0.name }}_conl_cost_0_fun_jac_hess.c +{%- elif cost_0.cost_type_0 == "EXTERNAL" %} + {%- if cost.cost_ext_fun_type_0 == "casadi" %} + {{ model_0.name }}_cost/{{ model_0.name }}_cost_ext_cost_0_fun.c + {{ model_0.name }}_cost/{{ model_0.name }}_cost_ext_cost_0_fun_jac.c + {{ model_0.name }}_cost/{{ model_0.name }}_cost_ext_cost_0_fun_jac_hess.c + {%- if solver_options.with_solution_sens_wrt_params %} + {{ model_0.name }}_cost/{{ model_0.name }}_cost_ext_cost_0_hess_xu_p.c + {%- endif %} + {%- if solver_options.with_value_sens_wrt_params %} + {{ model_0.name }}_cost/{{ model_0.name }}_cost_ext_cost_0_grad_p.c + {%- endif %} + {%- else %} + {{ model_0.name }}_cost/{{ cost_0.cost_source_ext_cost_0 }} + {%- endif %} +{%- endif %} +{%- if cost_e.cost_type_e == "NONLINEAR_LS" %} + {{ model_e.name }}_cost/{{ model_e.name }}_cost_y_e_fun.c + {{ model_e.name }}_cost/{{ model_e.name }}_cost_y_e_fun_jac_ut_xt.c + {{ model_e.name }}_cost/{{ model_e.name }}_cost_y_e_hess.c +{%- elif cost_e.cost_type_e == "CONVEX_OVER_NONLINEAR" %} + {{ model_e.name }}_cost/{{ model_e.name }}_conl_cost_e_fun.c + {{ model_e.name }}_cost/{{ model_e.name }}_conl_cost_e_fun_jac_hess.c +{%- elif cost_e.cost_type_e == "EXTERNAL" %} + {%- if cost_e.cost_ext_fun_type_e == "casadi" %} + {{ model_e.name }}_cost/{{ model_e.name }}_cost_ext_cost_e_fun.c + {{ model_e.name }}_cost/{{ model_e.name }}_cost_ext_cost_e_fun_jac.c + {{ model_e.name }}_cost/{{ model_e.name }}_cost_ext_cost_e_fun_jac_hess.c + {%- if solver_options.with_solution_sens_wrt_params %} + {{ model_e.name }}_cost/{{ model_e.name }}_cost_ext_cost_e_hess_xu_p.c + {%- endif %} + {%- if solver_options.with_value_sens_wrt_params %} + {{ model_e.name }}_cost/{{ model_e.name }}_cost_ext_cost_e_grad_p.c + {%- endif %} + {%- else %} + {{ model_e.name }}_cost/{{ cost_e.cost_source_ext_cost_e }} + {%- endif %} +{%- endif %} + acados_solver_{{ name }}.c) + add_library(${OCP_OBJ} OBJECT ${OCP_SRC}) +endif() + + +# for target example +set(EX_SRC main_{{ model }}.c) +set(EX_EXE main_{{ model }}) + +{%- if model_external_shared_lib_dir and model_external_shared_lib_name %} +set(EXTERNAL_DIR {{ model_external_shared_lib_dir | replace(from="\", to="/") }}) +set(EXTERNAL_LIB {{ model_external_shared_lib_name }}) +{%- else %} +set(EXTERNAL_DIR) +set(EXTERNAL_LIB) +{%- endif %} + +# set some search paths for preprocessor and linker +set(ACADOS_INCLUDE_PATH {{ acados_include_path | replace(from="\", to="/") }} CACHE PATH "Define the path which contains the include directory for acados.") +set(ACADOS_LIB_PATH {{ acados_lib_path | replace(from="\", to="/") }} CACHE PATH "Define the path which contains the lib directory for acados.") + +# c-compiler flags for debugging +set(CMAKE_C_FLAGS_DEBUG "-O0 -ggdb") + +set(CMAKE_C_FLAGS "-fPIC -std=c99 {{ openmp_flag }} +{%- if qp_solver == "FULL_CONDENSING_QPOASES" -%} + -DACADOS_WITH_QPOASES +{%- endif -%} +{%- if qp_solver == "FULL_CONDENSING_DAQP" -%} + -DACADOS_WITH_DAQP +{%- endif -%} +{%- if qp_solver == "PARTIAL_CONDENSING_OSQP" -%} + -DACADOS_WITH_OSQP +{%- endif -%} +{%- if qp_solver == "PARTIAL_CONDENSING_QPDUNES" -%} + -DACADOS_WITH_QPDUNES +{%- endif -%} +") +#-fno-diagnostics-show-line-numbers -g + +include_directories( + ${ACADOS_INCLUDE_PATH} + ${ACADOS_INCLUDE_PATH}/acados + ${ACADOS_INCLUDE_PATH}/blasfeo/include + ${ACADOS_INCLUDE_PATH}/hpipm/include +{%- if qp_solver == "FULL_CONDENSING_QPOASES" %} + ${ACADOS_INCLUDE_PATH}/qpOASES_e/ +{%- endif %} +{%- if qp_solver == "FULL_CONDENSING_DAQP" %} + ${ACADOS_INCLUDE_PATH}/daqp/include +{%- endif %} +) + +# linker flags +link_directories(${ACADOS_LIB_PATH}) + +# link to libraries +if(UNIX) + link_libraries(acados hpipm blasfeo m {{ link_libs }}) +else() + link_libraries(acados hpipm blasfeo {{ link_libs }}) +endif() + +# the targets + +# ocp_shared_lib +if(${BUILD_ACADOS_OCP_SOLVER_LIB}) + set(LIB_ACADOS_OCP_SOLVER acados_ocp_solver_{{ name }}) + add_library(${LIB_ACADOS_OCP_SOLVER} SHARED $ $) + # Specify libraries or flags to use when linking a given target and/or its dependents. + target_link_libraries(${LIB_ACADOS_OCP_SOLVER} PRIVATE ${EXTERNAL_LIB}) + target_link_directories(${LIB_ACADOS_OCP_SOLVER} PRIVATE ${EXTERNAL_DIR}) + install(TARGETS ${LIB_ACADOS_OCP_SOLVER} DESTINATION ${CMAKE_INSTALL_PREFIX}) +endif(${BUILD_ACADOS_OCP_SOLVER_LIB}) + +# example +if(${BUILD_EXAMPLE}) + add_executable(${EX_EXE} ${EX_SRC} $ $ + ) + install(TARGETS ${EX_EXE} DESTINATION ${CMAKE_INSTALL_PREFIX}) +endif(${BUILD_EXAMPLE}) + + + +# unset options for clean cmake cache on subsequent cmake runs +unset(BUILD_ACADOS_SOLVER_LIB CACHE) +unset(BUILD_ACADOS_OCP_SOLVER_LIB CACHE) +unset(BUILD_EXAMPLE CACHE) \ No newline at end of file diff --git a/interfaces/acados_template/acados_template/c_templates_tera/multi_Makefile.in b/interfaces/acados_template/acados_template/c_templates_tera/multi_Makefile.in index b95031e83f..b6009b4948 100644 --- a/interfaces/acados_template/acados_template/c_templates_tera/multi_Makefile.in +++ b/interfaces/acados_template/acados_template/c_templates_tera/multi_Makefile.in @@ -244,7 +244,7 @@ OCP_SRC+= {{ model_e.name }}_cost/{{ model_e.name }}_cost_ext_cost_e_fun_jac_hes {% if solver_options.with_solution_sens_wrt_params %} OCP_SRC+= {{ model_e.name }}_cost/{{ model_e.name }}_cost_ext_cost_e_hess_xu_p.c {% endif %} - {%- elif cost.cost_source_ext_cost_e != cost.cost_source_ext_cost_0 %} + {%- else %} OCP_SRC+= {{ model_e.name }}_cost/{{ cost.cost_source_ext_cost_e }} {%- endif %} {%- endif %} From 2001da082e13ed811c708a663370d534d01488d4 Mon Sep 17 00:00:00 2001 From: Jonathan Frey Date: Wed, 17 Jul 2024 13:54:41 +0200 Subject: [PATCH 13/14] Simulink interface: add initialization functionalities and tests (#1158) - add input `pi_init` to initialize multipliers of equality constraints - add output `pi_all` - add input `ignore_inits` to ignore initialization inputs and switch to internal warm start - Test all initializations and combinations with `ignore_inits` and `reset_solver` in Simulink on Github actions --- .github/workflows/full_build.yml | 15 +- .../acados_matlab_octave/control_rates/main.m | 4 +- .../simulink_model_advanced_closed_loop.slx | Bin 33390 -> 35634 bytes .../test/create_ocp_qp_solver_formulation.m | 98 +++++++++ .../test/initialization_test_simulink.slx | Bin 0 -> 23459 bytes .../test/simulink_init_test.m | 175 ++++++++++++++++ .../test/simulink_qp_test.m | 186 ++++++++++++++++++ .../acados_matlab_octave/test/simulink_test.m | 35 +++- .../matlab_templates/acados_solver_sfun.in.c | 105 +++++++--- .../matlab_templates/make_sfun.in.m | 28 ++- .../simulink_default_opts.json | 3 + 11 files changed, 613 insertions(+), 36 deletions(-) create mode 100644 examples/acados_matlab_octave/test/create_ocp_qp_solver_formulation.m create mode 100644 examples/acados_matlab_octave/test/initialization_test_simulink.slx create mode 100644 examples/acados_matlab_octave/test/simulink_init_test.m create mode 100644 examples/acados_matlab_octave/test/simulink_qp_test.m diff --git a/.github/workflows/full_build.yml b/.github/workflows/full_build.yml index fa4da7b709..d962e2f6f8 100644 --- a/.github/workflows/full_build.yml +++ b/.github/workflows/full_build.yml @@ -248,12 +248,25 @@ jobs: working-directory: ${{runner.workspace}}/acados/build run: cmake $GITHUB_WORKSPACE -DCMAKE_BUILD_TYPE=$BUILD_TYPE -DACADOS_WITH_QPOASES=$ACADOS_WITH_QPOASES -DACADOS_WITH_DAQP=$ACADOS_WITH_DAQP -DACADOS_WITH_QPDUNES=$ACADOS_WITH_QPDUNES -DACADOS_WITH_OSQP=$ACADOS_WITH_OSQP -DACADOS_PYTHON=OFF -DACADOS_OCTAVE=OFF - - name: Run Simulink test + - name: Run Simulink closed-loop test uses: matlab-actions/run-command@v2 if: always() with: command: cd ${{runner.workspace}}/acados/examples/acados_matlab_octave/test; simulink_test + - name: Run Simulink initialization test + uses: matlab-actions/run-command@v2 + if: always() + with: + command: cd ${{runner.workspace}}/acados/examples/acados_matlab_octave/test; simulink_init_test + + - name: Run Simulink QP test + uses: matlab-actions/run-command@v2 + if: always() + with: + command: cd ${{runner.workspace}}/acados/examples/acados_matlab_octave/test; simulink_qp_test + + octave_test: needs: core_build runs-on: ubuntu-22.04 diff --git a/examples/acados_matlab_octave/control_rates/main.m b/examples/acados_matlab_octave/control_rates/main.m index 4c751a972c..5f96143163 100644 --- a/examples/acados_matlab_octave/control_rates/main.m +++ b/examples/acados_matlab_octave/control_rates/main.m @@ -143,8 +143,8 @@ ocp_model.set('cost_y_ref_e', y_ref_e); % constraint -ocp_model.set('dyn_type', dyn_type); -ocp_model.set('dyn_expr_f', model.expr_f_expl); +ocp_model.set('dyn_type', dyn_type); +ocp_model.set('dyn_expr_f', model.expr_f_expl); ocp_model.set('constr_x0', x0); % dynamic ocp_model.set('constr_type', constr_type); ocp_model.set('constr_Jbx', Jbx); diff --git a/examples/acados_matlab_octave/getting_started/simulink_model_advanced_closed_loop.slx b/examples/acados_matlab_octave/getting_started/simulink_model_advanced_closed_loop.slx index 87bbb44e8d457d5c4240275aac7f07f1484c8887..c187e5b418f2be667a8b3e9797c3dbba19f714d1 100644 GIT binary patch delta 34630 zcmY(KRZtkgnuQ^_ySux)6WrY$0>L4;Gq?tKcXxLUuEB%5yE`m*_hIWk^mNrcO`n;6 z>hJTNz6knOpZpC_k_7`t2LS&zyGVf^%>+{k0X}ESX*=04N0gs=wn#Vdxi>n6l$1&NYcE z=Ig#jxRU(y8sfiH@}G_pC*X>5fEB^lAE&>;0jy ziE|6P9dO{pG_MCMFs{ykWHQ$&?-S*AAr{qhG8Oe_qP^AS`&RWkxSl&GhH7d*2nV>4 zH21N~bKBFjst<*t0!YQaP{FILK$ocfvuN7K`H*5O$~j&L*oQ&Cr?i9emKN6mxJA5v zz$$O8{``o;T^l4fVJMN+BZ5rxvmrbb(SM`|{$KlkK;ww#OMCV&?cu((H*_?!abjZp z&$Vc7Q=y+39rDU6JO5bVlrxGYq%SJ{m$|cGZyulX=+ z971XoKbvb$p_m5*72^VfYi?iX=&&uLseqQBlyI7;%)@nj-m@p^groS8*hRHksk(Ib zVLRqB3NLzLE>5EyZN)zjv@#9#h`k9zuqq$nvH5;*YTdGEU!^gzWR@PAn`?qKy;f>= z9xRCfl2OFPUO|N^N%h8h4dg049RI3>TDaWR)yu*9a%=}*7YE}aa2sUTP$N(O^!u&!JJa_hX@Lk7Re>aun z2*(iDsU-9tbgsm0QT%z{4h2zrQ$oNbW{RHo4Z{|B^srXIE{+?%W{B}JPyP@qT9#QG zm$+>#3_OIC(v%4*%G>1FT9$0<$_%DgBN*AadTX`w-sk~=3qN7OZta1$Z-8M6QibO{ zv*toII58)5fT#FcpGF2-0&gJcpih~2qoeQdq+L7vWr$}Ibv?91Sg>vZIBx*o6Q`l7 z6aMmI32q>sJN!>-(6y<&gfn+u!M1J$aL<*UQo<<*s7XEA#AB?r7YPN+BQBq}g?yC1 zJJ-j3#&F#%i?A9b;K`t--|aR*+I|BI?QEBmC`Ks*E)zp66jB5zSa5olr05XR^&esq z5xPPC`)z=ScEu|u{D9#4mK)ZP3DFJ;OCVli)g}P~60VqF1ceWrce<#lD>pKEgTR2& z(8OV4#Hk%8i-rd{hvrJTxrO>c2ZTvQ`Xz=r2TFzeC9+F#QD@oPbv<^!c5`*JbOYTi z8${DA++#fEmt7A!P9G-KZ3sXqwHIg(BvG)4er$?pMXnO|>If1cV&@zW_cQzluRT@C zd6)=_&v#$u9eV&(Um_1%`Nl$;qot){HyhPz3T-FDYx69=B%JlGu&$$Sn*9` zGz$2%68=MJTxFFTQ_;|9lzChG8MBZOa9!8`$Z3CL;1Xg=UO%>VxC61}Cbhao`R3~A z-ToZ*d&lLLt0VTHAj{%HXcW(2)5!`PtF!frLV7ALHXfjr?1`xmVPRwA`}>0;G%da3Q=^xN-Uj2Xi316S-@@MF^f)uXyWhE@Jq@`DtKObX1e;~3b z<;4rfOp|vgJV{DQx)CCzuFsU$%3kufkJ%s%FG7k-qTOo0-+8?zV=^!>aNAKc0Uw#B zfA9=syFvly!T^+yhvg? z$fm>3X5W!%Dk5Ywl)S9e)Y@m{_&@$+g%kIu9#;TbOv+A)?o7?It!iPV57I$tcNa!y zDh=NGPHA+p$VJ*i^gGjC>QWA4{%mO}wYj80BL`Av)J6`X*^>p2niRXIkoaDFPtRv7 zt|b#EYf2%bHCZ1z7e}UVdNY54`=oVQon-XJ14eCh{3|X^!ZP5pdY;P6g-6->P6etN zl><0~@85ka{+8)SLh~7BG^kR6i{O%$*3RtXQQ>Hapl`Wlhy7;C%A#aH=yR;x|}z!uNoG;gxi&T_JMq{_L&uI>zmWlPAu$lUcEa)oW5v2Vql0y0qM2p879L zHb39`sv*PiPnyme(fx7D&X)#kIvwYf7fHa-u+9<-VNKjD=Wu8IROWQ(+TvX!{Irfg zxZ#$g*#+vdmlMjQq zA~#b!0@QnJjBmc}_qdgN^Ckv%%Znm}SKYd=o2D*s%4eF~ZWo!#OLzuT2uo#qkR2M!p|EessLs^(e@QH(hmuJ@b}1 zqU1ayVYyo(iH(BJE7~9Yy=Dq zz6?9Qr-<@uQwEZ{8ClL9kzw=qTC=8uN|y!tqi2F1@8%|XjVcd)W@ z-|9=}At0c(W$DiECkXa0C8~70$U;S}EY4k1=+{=Qdn7UW^3?(}F%=(A!)1?MUQe{N zw2g$;mwSdQ4CEajyep;l>zQ^3bvS6hqJ&~(7}x9q3#0te9zIwe2X40Cf};ZeO!QqF zUCr=jST&n?FYu_zQwMBB)Kl%$WB#4}?n{jejJM5{-K&h9#F7 z+9fNVGy28u%bI(Q7z zl@$e0nU2ohvqG?c9>bP5-721M^;=DN_v$yos+u1tdQIQsN@Psc)bhT6KNOK1rLC)t z-|zNSM2XVUV;?`)D@?swL-wINdh+%5|3>tB>cktc)zPJVGS)1Q{B01-BV98nn8|73 z-2BeGNuC_o@NI7+_SIOPfU2Xt;Yc^W0S&IVWkaP$zK>7q5;~1E3WJ2a!wvS_UZE(y z(Fx~><*~xW{S}EjPHS8NooD(+mRKM_M3fWJrrExh9C-HpvXIEf$0rmi|7)3s44rcP z_7;YQnwop*#lV1cfTXZ3u!U=Tw8@~0Bzbi-2nG(o(oHXlRdU^O>g>61SV@9|*11%Y zqfAh{fA{gaoj+7xCHh;v#;&{;{)kddnpce2Kwn-Y#`R`!uPwe%dmn zdt)5fmmHz?cKt!d`%z3u8F79f51%M~dW+c#V{DIDxyK?F_y#fG6gT@X-4P^_`U7Us zbvlwSaikuP3(^QID$ln2H&V!csezY=0i~+PvxXKTCWuN%{{6_|Z6eA)6g9n?@{s~_ z4GmHdAhR5vz0xX0T#6DCdG<9d|u7mS594Yn?Yz<-4-BnC=b#-RH2oAK|NJLYUfP21cb7`+ec?%BYSg73Kk3k!s=8btHY_S7!iwMTYhE1?b)d& zPVW5O+S)C$(welsU#l?+%H(@nIW{%W?Cy=d`KJ>!-U%DCh+We(2f$Pej~WE`-rtd# ziF$4@M2Gw%Cnp!gBz%UB6{Udxb7?8E2Z&|2plv^FQ|5E#MeS4Sc_XoRxp`@_Mx0SV zJX8fa?)S1dK~;b-PI{soe=K)JO2el{DMTI%NDFyQBIQY`h`k8tm5HYPoo516+00i* zx{VxJxXDv|muUb+5mcCE4owbx#&(?xaxOLO@r~2#bl(qm6+#J+e(7RL8km@NjtG(S zoo-gWUHvN<8K%U^yybm2a7-JZH15Ef7KQP^7RD$*JK5Vi-9OA98p@-dyGWct;lPEF z4RF~tG$oQ2@bI7kDKd-d0k#$`CRDGd9%}Z+4Ayw|ZW&(RaKxbKOBci@iy&7E zb8^Nfpk7`BlT#R8pr9@>5zI6+G+f{Py{LGWw6HcH=EY*Um`yx`Icouw`}(d=pGS#z z93NTP@nPeN_4qlN5OQ@(23z>Q)voE0YtY4HlR1MOnxDBLc%cv2(qwAQmu@9zcGhC~szAWp}`0 zCA5ccV$Yis-XN5-nC>u77j(4waR~ug~zIYqWz7nvW)k4J^c|-(;;V^cd^zsXQVtfF%~i0*XJJ^18C}Jk?!^H z$EM@PEj`wpUtR)i^$ln@S66-(u)+AyB>7&Djo%f-gM;gLI^g|?*5{pycienf z+1MnjOkVi|=4`1>_b%2uDhfo=+%9RQwBTgNC5w1tTFU^U@-hf*OpWeK+?AD;df({a zlcOUo7ye3vk2p7;KJ1wk80EWs_O0q)oRSU~AP0*Fr#0NksjeJFvcUm6!1Ycr(ceIS zpPQMJa&;x8*qP&Ne-6VR`_pL_4y4c^uW2=3Z6n@vCqg+Qp;mamQ*#EB}|4a#)I$h5Fs`)nhgV ztlqmKXB)o$F5TqGFI)w0%es-)4p+U^$_@b(f@C?9gaGvSu+i z3~&H?=*|>%v!?8l7ES|wK{3sINCT@1l$1W`M%zJ&^|*DJ@6Q50tnVOz0*%jiSvRFb zi6Y*xI()M$aFczH+3(R;ZXjeq252C>Ck49!`PyYuE#$r?>#TI-MDv5IAy&0FJO0SMtS;!l`6&23rO)UH6*wEGrepAjB9%*kT*S@ccoXEw*LkK*`@ zoKLf&(hnYN7Tnkp1}I>Q@edCk1?nu5-T@q1LucRAhq!wIrPADAuiT5Y@@_!_;qQ0< zQVDy}k5(A#UZ!&kd;fxY_!)r&u55WVA6n0%xCJIxtH>@RoLX!j zbn_RqK9h1REV@lZ)U^qnb4Xyfb;fG@a-Z~iGd_3N?>4&Ib?F#k<5 z3Why5JF7HFg7r<^Q3%VnGGOg!Tq7PByO6CZ&j-Dyf*61kv-tGV@P+?3_Hu<_D5$yC zMNzG?a8V^l;XujB>1|-Jv5v`r0+B^^WfSdMSP?)FS#aq)mre3W7XcC95Q=wUZ?5yPN1l$NMfDQ`$SDg_ZkRrb`1`Dmk_0RQ& z>C!z2I%JxOK8Te2*vqv%{?{WWoUYNRal+B9mv8eP zd^zfG^g$#@ZfRvzzpB3=VS@T(nR01>i96J=&Rne zvl$;8s<4^**ad)JMY(N@M79_EGUG$`52Nj07bk5v-Onk++pznfPe>|BNlBRPQ)rR4 zEbM5^J1oECoR%3(D2B`&neH}D`ECW{5h)Nm3JTg$iGC|vF+)IOOxrZWb>~{Q|3_Om z*xLGm%f%IL*Cr3=-X03nA`=iiVrG>;1<|Z;uFO$X?dh z9uHBno5NLGbgI1NLu0zr=ft4aR`x%hM92*jkLc)$9PA=5uM0OWzLl1t@($XCHm*5*>eKh|k|S2~(ms*)e> zMicJRaaZC?)>(naOEg|?-gp%ya7{JnT-@ZBdWg23AO1|*S*2a@lw@bmx4gTB=F?Xw zmxbzfqLP<&BSHE3-s;EAzFRTD9WYxa{0m!1?e)X?=-)`SN`!}oLT-QAli@0Gf@StR z-x{IRPJ9|@pux+B*(prCL5+7jUIPA6rF9W#8X9A`I&nbu@2Y4zrb8++vN=_Xvfpa= ziqdlMLi~3lT$LqI9B(>nOH`J|KYvQZK9`_(*lGLT2INimp~d|flxuk&D9I4-rUFky zamt~^Qd+aikdVypAq(N>k{EC6E{U+Wc|TsT9UQ^Y(nzeDpPy%^FUU)*Qd76$NX$6Z zQ_=b=L^mMgW_UrBGS*OUOreQ}MO3DuhT9oRehKMYEsTWK#_a=tt7}}m=pjp8sESOZ zB3%~USPhSp+>)R|>b!o~(J}`5!XqIBM6gK>SST5qFeN-Zyb-rvhovVH9i1yObXXO5 zc}(Hk(r? zR+a}8oU^Epq6YjrC!PaK^mABOi*Hjd_i!O4-C50@?o|MpWTG572NI&W4i4{ z^vcu()$*8>Gz6!vhHE(;T|&TdUW0L~JB!l9YiΜdiBIF=tb9o|?f{OKEQNe;rk2 z!X`nuYb0IAMZGJb7x#Wkf`UBT4%!Q_um}Kw8S>+r8KA(#+pkRfb}Hmd99CkDv;ppq zq~nY#auuR867J&Ru^h$}u26Don(0Q?<@3=mdlssLpOL;Yho`BMHT-N#^^ai<(Ce(` z#&BF7ni5+%4*6NQau22wAwK+U|B&uXKX^avr1#C>bq)7fC&v2{3qjx5RBU;5^%5Yg zMCX3+^zsk@7vd1Ie>tx*l1|y+?8V`M2=?m9P9P6Q;kqy1WgS8X5xOT}L)BW2o3_@# z_qqVb`(C#HRAOR74dZeeDGy3DXRST%qJ`Mv!R`fh+mvx@GelMcPrr`F;w#k=SE2;2 z230l-o$kS~os@SO&ercHQ)beES`EbTRIuOZ2xdGk+bT#0h_!xS(}r%m(iurZxZD16 z0Exbd`DLEczaHJC{VTz}rApKmM?o4+GR3WY?>DU%Cz&7Nt|CsdHl2Usc+)uupY^NjAAju%t7U z#IpsMnUy?$iMdSm1o2M<>MZAE|2`Y;Z0$%%fks}BY;DcW5o(GKvn??F_T$H>Q90e1 zGk!ee4ZHlq;_!O2PU&L4tSY1kF)S7Row>}X-NE8e`O3wz_w?aqDRIW*LcW@C{$LGXdoBZ+f2wsGkqC* ztmsBhs*%jLk%u?#%78IRTy8FL0Q^HP4aOY?8Z5k(W%Y=d%*c37C^~sjL8NEwz>QgsL%9+0ATUIlyYogmzBRc+Upj5hM#;>_H9Ro!`&gNeL?bt~BH8~R zk%xzLt^z)(PG?#1M|4%%B2Mn#^)Vq_5A-nncikmRD_BbE=A1at(1)U?1=IZFlag^K z$lNY!J1aSYY5={dd%J1xVXdj0=VM*Egj$B`=qlAv6fp~4J0{WB$&RVFUv%X){v?5K z2~2>+u;ZayRaIYXsdiK$tNLMV9VFJ!Pb`o!qt<>hq~G&YU{i$>+8Ch*_%h*9S6Iu1?FVohBn1GY=NaZWu6S=nZX&=piPxbUc-Ro6`j%ve!M#24CQbjRAEl zja^CtriiGfwcV*$!*2P z&AKjZ9=dN5E*Au`@JV;nKi#H!zndc#?`{P=dnTDO^JSJmt#?l>)$F=b{t8Y`N%4Z4 z$&HOlikSP8#E^ST=XMb*DK2iQ&a+Nzf*kpF<&OYPG{MS0p{WZ*kd#lk(0l5?)HE~WT|Gyd5yDgu}rB0Z{cR5pzrJ1 zRV90KC7~f9GY$@WQtpA)FkTO5)!Bqqo0Id^g9I@pXgPP*Crg_e>M-BK=b7H2%1RQQkZ{5|7h{osT{)cQ!;3I-L|%h4hvDmJ4kYQ#r>IXIF6tT^o9AJw4k zhFY;EEG#T2$%N9uhm8TCNzrg-7cTwl#dh7h0n%^HhCq|p6~7g1{v&yHSC$gD!1vn( zM%th;R4E7xP*YYd%K=4gty+{B7zlq~l8xnMl&gOd?C_+lj*eRXzxOOK8|v%9*En(f zx!r&FY)wv0$0&83aC8I$dsbgv+4Mhb5->0@9-cPkFZYMsd#*^Nt?Pj+oc)!cCnCoV zg~&l0otNQpQ|e!W`S#>N`JJ;HQL$%6wn=!cOJoR?MwNdR$p`U2+rLg9A0HiX?c(0C z6LLl(F0j-T6ch<=w=c;cD6y~{g>+XGJQVvQL#7r|VGgHG?Gg7tIfm&YR;3w_{!hw& zq7h7Pl?XBZm=T2@TGI&I^*)Y~(~*5MxMb_4-~RTrKeOTN1A?C51m}a8(?AYD!7vvo zaA>$-m~K(hy`$(EQFYsgg)W>?(9l%v1L!EH3UU?}NSaD7kbwf%7{cXfB0*U`-jBKW zungR?NKt$+7(Gy+g$hIDAGU-iL{X^b^FAD|gbh4e5c7*% z@cC3ob|I1H4nf6{gTWE2jQvEqTLn#%fg{g@It`su zN`|pco7le3yP?U9XpE-*^b5p8&YPg63a*p%qA>A5LXObJ%UQ2Id9F|c6!gxZ75?Rn zf%2!;u0`PE##7GG5xq8LWHBYO104`%>c>!4*zh#A(u6#Q^juy;8{n3YyNxt6@&uwf z6Z7)^%`8gfE0O}i!TWl0a=&FnYMK;`nw^3c=P!8*WFw9~QjDKgncHe})jbmH1isK0 z%3Fc~R=9YJG%G9XhC@h5a2|n{7dLerfxGKi7=TtcAyE)Bg9%2*7xtR=nf#CIlK!ln zurRLWb|t5P(kmaa_{=5cm_ShQXIy&1?88-U^J>6eBy#$fT_>!J!57$$UCKX6iUVR| z#?eF!B2=i?KR&*?xJ(1V6Ekn!$JXxQ$*FrC^|NL)`0_p`Sr^eE0>3IbNL-RCGmMwv z6Zj(I++GhM5&qHDrvYxMVL6F_am}(QN7L{?H1$(_Wg3pPuo3a}E@wPh!*O5b>Ie9} z`+Hy@;n7k#TtiN!5H#QBF*ZQ+N@L<_8}-M8mLtRcbBqNsqm%DQkqqT@99^M^bi3+DCZzGB>h zyo(wE4Q;L!6Qb-k#W}nyD=T?7PzbxUsEFb;5rZx{W_f1sc7qSx4^0&gE-xd)73S>8 zOY2&JS8Xwf$ze+-+P@| z!b*r|WwGxQKBe2fIU1%6dPRYHru^gmYdbn_?3$$k06K z1hqK`l1tj@On3B~x>H7k0ii4&U}ND>xU`D?H5BnxX{b1@)5^r^ibjM<;AIYUg#qnc z+u`#va z)U{{h+jmWWMCo3q-E{%AZ5^*Jm9xr*&-whM^o|h`I$5E2HGG>!*O!xt3_{FOfCc+1 zrf4xE#S4fCpW58$ZqY8#|9HGzQg$7qNL^p2Ffff6)+1OF+1uM+Hj*2Y#KxS$v#5m+t;xs(C+F znu;Qeg{_~OD$0_)PHA8fx8LjzBL!tb8Wx*{NpX3fA;R+Aoh#{iDi*i^ZY~|85s$Ol~XrBNg-}JCLuKE zkv?Rv+%XZq#jgVlkdlhP)#tT(R5@PhP0Z0O3Ir|~WQ*U{ zDqZ*X*7O%WEf`?c)SEo6^98liqlhFdad&gu4DZ;Q&lA9>nHNK7Obu%iY}K3)k_^u*iU;rWxR>*IGt zslkyjaU?|JK~dRVTv7dKlcI|4N0q0@Nyy+pZ1f3eC_s8>w!COjMZ`i4t&yYL8R@#y zvYl!8zXcp@I%R2_?9~Yv7BJpE;dfA+slR4F6Soeuhg68x4Z$_8uJ0MhjzZ73lUrMY9Z6S_`SidCBqkf?QXY_7e604`jz}zVDNe?hY5mG?F~%FLIY;4u%UtmQUgCI8e9 zZ*c&_rkExA;I9DHG0YmUdYWUn;Op!^_AwsLt*ZmB?c2C!b91%x@iR&2cxoRGrVu${ z6Uj{BEDjd7QP+g^cIxwo>T-ns6c-osB0*$fN@ojrg>ZxY)L3jL(3Vz!#Z8ZvcE)|L;k7kEnC zJ7N&PYs!j8QYQkuvv%hUxNTe57jRsJoTS#^wtvFZJ7B-wP-I1&SBY_LAKGdu%tx{- zbI;DscC5AfZms%RZghD)YF~|Qe1&u(U~y8R60?Py7}gOHI9#yhx&u2MAq5J)atl3m zzeQydY(8bFVqz1qn3TS9M4xp|A?VxQ<@$i(dqNDc(y$SC2W&G%v3|~jU4}PBCUaXo z{WA%Zy>-pU@2SQ@$4vVJYc;36qE+=ln~8D9ypK~ly5tZ;Td!I2Dph(Wdf^~AyK!XR zpM?{q5|JGGYN&lz_X18hlS{OA^$#uE#T%K3X05up%31q#e9Y{HzuY4@5ew2Pzi+&%n0+5jyCO{cWOGF69SU^0-~#lacdS{OOe-3s+;gjM+-Ppn_9o57n#f zB&bx*B~fQjd_G3QK|-1qw7{}UEyCyEL|@RXGzImN^E;@mW$wu*WmJ+rO9VHAjZ?%3PGtC_jIA=aSkxrC;{CLxiFp&@I-BhtvqQH8|_lo5D-AXW)Gms^pFAl zmx0l_q&YxG&hB1c;+z_>er8Ye zK-<#7*V5T*)zY7voJ!iL!~jIVgEXJw`1fPk-V{3Su~i&4h9&64>c%CdH@)R$ZiGgpff2yY zmEx#iR=THPYa<4{IKy2B?+j=7`+#E@c6-O&I*Kew>`B@DP6n{{CytL9O$~p0SmkXp zYc{F;TSEby-~!@t)F}QDi&vL*963NVHC~|4DEpYlr#kVfxdv>_9j%*7cYRq~sFhAH zP__5{j{Fc=t6h@gm3_-yn77q8$pb9x?DP1s-&b30*7t?|TitN7pQoZTt2s1HM)J{* zOOB4t$csv-A^-~qY|5b@(Sr+ne$z`OEpy=U?Z1RsAvj;mOqs18{&eQ1^|_!b)pLOx zp&gZ>2`6(W{KSfF2k7-C^^j_iha-4)j$yE7X4llavsp-Lk~K_~D(0q(zy47>kbfhK z<3pU@z71w450&a=5mXbPqf&mu@xZaw-}YnQ@WZbgg#tkTmexjJq$q0=xueb;vv+KJ zQT|R^3mIHT%XT99Amqft!g5KRIIZ?bQNHD4?~UA~sQIMa=I{AJ<5=z}mQjp)-h@Lc z2d%kbv3o)YDz}O?=Pk&pKWC z4CE{-_P}+^?d>v2d(;D03D#?U_~$BSQc$yNe!oZz*x@9$q7DgF=i1s@sLeGkjGOpO zuEQ5skPM_5RhJUVP?q(wvRX0KvzdR60HYyrNQ`+;6%sCoPV4F4xA@@1D2@=HbfM&q zPUjvG@NmR<%KulH^1O;?@Xf=+BPr+u%5?h&>X&aEpeY8u4;%T!BBN(xgQ#vQJYM2impm#t1DxpnsInNmk% zvG5e3Mk5Mu+Q^^rD}!;=UL=37lP3QG_tmko4PKaT|8=|6`gcz&wMCvO%e2WUt7ram z3HZ3HwnqBe`_kMSyd&?RfQ&+_QMY(o$MJwQaB@BJ_g4Q1ehh?CjsyiMa3mf35cENM zDtUEM4<7@KtoS&!WhsC}C*g1l^rg8Oflj&w^-+J__4Cq}uVp{(`nh(+lFRyQ?_=9| zfePoq49Bk*9%pp1#;_umUQM?52C^v94drh%3{^SeaVxI1@K>&p zyX4lxS*W=i)NFW<9E_fg6Ltz_e)I_`IlEDqdN?&VVGhlp3%AdB$>N z%qcSQ%6!HQnBMu=DBRCRL*-sF0VChUGP({}zBg0!@%wR!kHvhZgD>w~GVld4WiOk- zFzcquaXejev1R5fNsU!YfSGdWuA;*W8$@|?YKEssQpw>26_`s0Ts}uP+2#ddr=^?9zeI<+c|^ri)_Wu+hp;j;3uosL4-flJ5l1(I zx>KG`r11d@jQu3fos#a1EHH-xsuuVOf*B z@DkvuB)zI<({tRr9?q4B5csUXyMrU0<+HQeNwclwl@oUi)5dxMFZ14FW>%ZRb5KT3=5y%_=@n=-ehs>Kf@jO$~@jQ{kh=i-ir5QDPH6s{m z*G49kohxgpsvbO@Yks>YXq6i*?hZ^PA0`u%)JzBx5?1B}$>ks$NWszya;e|b&4!9m z6}&070?JM>mcjmj1!6@R%6D{e<@YjVN=%IzMd6uy@3v)0yMa;TFlf`CKmJIbB0EWwP?ldzSyt5>BYVYiyK#x1ikB7{m;7Mwa4?s z^}R+##wTOa@MnJZCMvfc#s1VTcY?2*`=J~$pR8>8xxmxd(dG?W=9tKTE&)DTAQ{8i z(j1GLwQhnmr^{lGTl+r0CQLoVdS8Xa#tf6L!M-Lq01H1cZq@$Zg!l zk(-HIYFY}AwxKZ@@!hViEe9U*F+H!Usw(p8(}Fz|b==C@@Y^lg!wJUz*_z%H&o2XJNt8jhAX()&{XcSNH{1 zdPN3@hN>kJ#!A3A-XJWMKV&C*U@*dSP>|75LRFq|{*GF}o+CDoiOuM}6XO>ARBduT zuWG#&A+Jhdul5Af7m z?9Btv%jv>3s+u=GS^mojzM$JG|4#Ohy6%z6MNCCSl~=8hmtW4?Rr_n52c_#=x6UU) zttX}8gIoBo1L4dg4-XG@hoquzw{Md2++T}&>aLPuv2r5mztXd^DDchZX0;%evEU-x zu9-cXLhS5wa`c1)VWBoQrVc|v4xIk@9c8M3@gp@&9Im*C=|Q>ghMmg*3uFey;QPJ!+_jeSj!9|CMP1o9^2Yl+WO@FOdH@H zm>;yDQ^@jIRNj+%TaT-^0N;z{sNO^zV*UVMT_0c~-*>_>-X;6&7Y~aC&xxJx5NC@%v6w zj0(EFQYA9W<`E@|bX~bRVWax(#KQTepfR#b5g8g&NL$4-wW3+0Sl@=eOA?eQPMLma zV8FD~k)EJ=jM!*OiwGBwjDDd`FoPLja461}oNf<12k4Hti=$;}?K#)c@gLrvHHYnH zPN%qD>VysZ;7J4?9Mt#DodXaL$Ef&kv^d*^bB{|9s`M7PEb&23udk)4C}tOe`Bww@ zqtq)oIF|Z_R}5jq?7rPdQ{=e~dW>>i5_Nn{2i5SC1zB{p&A z=ECS>&^EQm^KKIccZM#by8}RVc@5U4J`oi%7FJ9l2Dzxt8PBjOC^7lW5pggy=Ffxj zk0If;4N}qTVZ|I$d95tHd&7;<9`Ea~^CWusJPHdKQrVB*3v1U74!`^RQ_@mX*D&Wq z>DKC`r0MS0*N}mqYUO`|Lc`a39X}DSDvfzvbTZXRdk%c>|8BB)X*mOTAVITy+~1K$ zq&05Lv&=$wiHIN|2gha0iWV;6PeeFTlAP9CXDr-bGRig6*@up^0|J~uf!#h<*+pXM zch}*A>%JU%4eca&x%Y{UFaIBEGpvqe-(N)VZBk>AUO}jJWL4vy&e)cdSY^`2rkiwH z)vq6f+oanQJhZ0yd_p(h$qDq1%45HWza}MO98W*CNvlK*%&EM-Mc)Q}HehTS56ApM znz5meMQE>mfI~?O}UIhkVc1l_AWpGVPNH`0} zZLPd7`RV~ZE1&H|p)%vspUFI0wq%|IsSa$?Yb{f+O2-=l-Xk;%!^OpBDJv+k_i`#D zL!qN@RNzLvQee<3pLi9{_!!bY*8wvk@a8LYv_dZT_R8pqf_JR@^Z7 zeqRTaG&Lgn2x|ZUi9+l6%y*Iuqr=G(I3~6Hed5Hsja)bjEBj*?C+f-F%*-q!N!n%L z2kC1&Kt%8hsw}|yCYr}pF%Y@YNl274Gxh~1W^^e6S9dZgFMoa*58pSIlE-jfQCF7hIJPBTaj{8ysK)P;5%1HJ zaIE!|?>WpK>K{C)2`(G`#p^WIu9CS)8^kfC_lCls5GY?TK?e^K7q^+!^QV^jgi@MJ z?rmxbB|xNqds@LLb;c^5jcpV;43+7WDhVXeQc;q5i0SS5 z{Du`>{=Dwcu=9(j=H&_b$eQ=sa;#^%AGjh3%kOK0j#}vQ3U!SatN0=lEs#cNY6M+r4o`4thakD5e9~`@w@wXYoqa4s?>+I^>w%BApND8+1Y=B zuXC-#k_qOF7g5aYRNwc5Sh)XSB%dysqr&^dDzJo+ryVwK8-2ztiXz8jG3q`24^`h3 z97xn{ory8A?POwSVw)2u6HaVf9ox2T+qP|MVmo)fuj>AP-Ivu5{c!43uikxn@3q&~ z0RE0{+w{I^6z90V;IKG|iKN6N7+2xsXokoMLX#3SwnUFO{1%*0%!G3TdoF2eVuv9l zWI~$*ZxyzyW%lgJ8+^J)>_30^6w}t$c1Znqf6T^d@oWTq!C7I_#*+!l|1XVOL%ieA z6Tyg#e|~PalZ9AFIml4yzl`Y)@eC(C;3n!c-hCC+P4~GheHu45IEe1fKm&50-Tu}a z&*ScYXcOA(63j@JkSJ*fUHSnsDB`onf+7O>#j8xMjf>J`T9J+N`#HvGKzboBo6Q%G zSNi^nN@={)U+}J2*gXmpL=|$N}~dpwRpKeSiR|?l|FPw5k0ekQL(c z6XVW?fwwY7^yoN)g5q;q?%yh~xqt5{{Y%5yQrK+7{4uAT3q|*VG4-D2 zGE3VHgPadvd!Vkc{@FqmqaM*1hQ607qe^FGsz>A*@T2Pv8Jnt<*GetMqlY*1GcbG_(*|Ad!FDcKyT6}@^0c_l@%@f_ zC0kc1()X2bizw6>*Vg|%yKknjbH>E@KvBTDhqdX zh#BGfrYGFLZ)1-0@Bf<)wBpf?bTVt@rl8=qvK3_$AK!%->A0I5vddc*p4b=9%El)8 z_U--@)vHkf`bS?Gk^crF;k6*W{<^F@H7Doh&FwAD%Xyb7S3}rfX#xpK6pzmKF^jvS zV=x6QQO*51&+QHY0WvZkKtLTI%4!QnP~{{{u>bd4@XZ@m84Aq$n)P~m*N0|yOn-?mYypQ0!#z_(!Y7d_Fay2943 zCZ|(YXJeW9VxMPJg3DbK#q*@qY0Rl6yimoTeuIMpg$zIN;eu{mnkj-mQ>#{`{(d^t z92?+H3sIisLOu$q=<;JjVJ^37Ix-YjSUy#<)w!ASY7`@eRvw*q#LM49QU01+U3H`S z$xYtmRODh#eX&x!1++XroSw$gF)&;y8aJfC>S=~ORW-dwhyIp#67J7CJr!rPYJGWm z`XDDOC@3gfDpw^5Yj>_#NMRWy2{00%IlfJ9#fpErc>pXx_vZtYjTc> zDK%jHw*vu>Id7`VOJ5$t{*uGiu-J38GlyEB{N_Z#eN?|$2|($t42n~9>B{AhRURHg zz~$t#ubl#?m&IT<@_5r9M2jVNrmo(^ry%nY5)xYY{v9?t+9n$UU3F^SC!_VS7pn*|1nbPvxwXdcXR^w*EfPVg*oQ$Tj?w)F%Sn;@u zZ1-cAeYIrKd7w0EsAgc%Sa|@mt<7Qj3N4v7Cbe$%02(B3Ecn(#ajb77z6ZB zo@2#}=Wr{ym601|L}NJSNzfIY;uVe+BZIznJNQ1spXBYmCzb+IhK<%E>dnBPlMfnn}b1? z=_Gh777xSX>Ex*$DGCUx{-+?uQ&Bb~^SqG)jv~bfwl$v#dZd`W61O$waBzQjVcq?T ziLWOVyI;UU^ObQh%(|L)!S>#}DGty6yF(S=F3t&7?*$^ z;JY>7-w%^9G4{DM(Rtog#=jj{O+hI|Z^Q6VyA6%`Ue9gbuK0@&`Ay_)&ee3&LX;q3 zz(Yw0vFVv`5!cBrpM4QgDD*^`XyB@-8^ow>zL+daQ_TdVIUpMK$3esM9(wTQTX03a z>O+VkoSruC-KIiS1~%%sJFyw z#_S+~!vt{t*YjDX3R`|$DH1e#Gi6ncwwUgHc@~W<0Kd(CI(saGg^i!-P;!0+oTkEp zQdPq*b8~Wrdb#W}Z|k4N^hy`I-Q;M=V?shBKD~mUy`WfV*B}5|bJ?~^-S`}o*(JlD z#t=dK_kX2b4K->XPAvAg;fJPf;dr&Ofr0u7I$A7ixrj~Lisy$WC-s&^^Nrm2eUA(M zLR_1`j{XK;Txz?bOAPMM-rjG(dL-`H?d`D&p>0=;!Kk`!vl|yPbajl)`DC{GGXnk>VZYW8;mvtdrA2|7x<-T^1)eM(`ZO z{cPphEhgDgWXLI6+T}KI9uXFGspZg$O=@yFQWTjP?@F;oZsBlq;LCgP7& zO~BpNVaS2Kep#jnci9F;{zT>1p2yWe*~xy)I6H58dU|ZUC?Vel*j-Fj9PaR3*R=_i z&U{Yt*bEImg}tqX} zQV2469JgNwrN%1(U%dlK={l)SI!=wpq`E8#pb97IOyTk2x)2t8kj zZf<3aG^+Xjuv(3@Fqs;Wk#RMq;py{}mUwtKl`Kq4`8Hc!k?9*)?xkc&(zHzsyIjVE zWeO$9>$7$Y(uYBgMRh*~!ehqI{`Pua&}3%s9jIp~Mp!AMF%+dXN{%bKlB zbqiE^(&zUVbivFWMo7r`Is7pal7U9MG3A^+CyT=4+adFJwyv?cwarU9+sV<%*LG_a zrl#0gSN>uO*xGa|UDyu*lO7-AI>L*4IaU>jctC_V8Xk%ZC9q*fyo%SCu?f^ zk~FF(M8XlRt=EXvN-HY^H80O=Xm9j|vCZDqU*9c&@k(0OBX*OITH!(+;->1)Z3769 zfW|%j_3hdeVcWL_+#>!2P5U`Bpdv0cwN#dWi&dB=fLRf8103;j-(tbY2|Y35Y8!pn zD{3jAk>`bHr|0_ z9#^W&{(|!3a#&4G)7_&zeq7hr>=c@PoE|kcK(j@B{LS2Osp-O z-#lLQ(y3f}4d-~fT)3;A zL=p&;Kc(Pi0QdFX0e(Jv(|R&ik1}M|x(QcoO3(kKB)-`e!*_9>l6z|VxTxIcc^*iQ zM`eDHv~@Grjh~8Yp`uRv5hl7qDzMf}r)as~DtZ!&omTwhfYJ<#25P?}D`O(lhhz(T zwvKhzY7oD(@b?@m>h6!7tfz+`2)Pxa)zeHzf0EL0JMXnI3n1olk+T{U#NXOr16|it z?~iHY#Z5M->M>kQ35VJ3;=B`1l;~)=g&&3RXc>&RLeEKbN!xLLE@2O2fjB`_5SQN{ zY=}bddE$E1;$keX-AAbXj(Z6+-1XB0K6uGwy|H5*gsqUY=IxF2S6o!h-xNWl(A6#- zjwX*rPQ1ch4WQcS!`?k{+{0)lm0oG!0&0j1JWI?9IOW)yfQ$uUKpCss0P)QoqlBlm zvD*dV_x}69J_s*3fGE1G@=hbo`~1PSuH;L=r4qy!Bl6CpAjPQ=NHPAY)Z$$ShHF=z zOILZYb#S%vym+off#ZXpKbF6#b=X`9?F9+iiBY9d@3O{0&JpoPDqeKEZaomB zpiMJ45(748VI>cavZ!xhDyUFiI+Wt`W&(XA2y+5k=Tu;(v{YeBR}V%hORp5~C=Y`2 z=aOEc3Xr;g$*i8c+_F(vR&a$p`E zQ2*rU#!gWuq;uJa^oTOaW72_X4Kum}Pv-I-pG&MSR*g{UaxMGlyQik!#aQe^$se*j z-~dNBp82`6y+r371^H|?bMB~MZn!?p zJ_GjLjuB6Uk^Sq<&n{J7%)zd?4tZX~LKt3d}h>%{tQcZ7@D5T?Ni&ehcSaYhkH z&b2;ZJc$&af7-bJX=q(@e|~s3i)roWV`Q#r$M(-I&j7n`?YcI#y0a-WpDG<)0-gxg zgbUUo2653ob#lnfkp=^>r-V}xyggt0i~#FaHZ~^YTs0`K*tDxh(EWs+*3NV%(=C$C zukHs}jDP>nPlj~(Uk&+=gUZuB!``%PJd zs_P*V`_oJQ$)8L_8l&atPTk)VFcYfx@cs4c9_opZ2Z~;cEuzzYX8bZ_v8sYi_s_gxwgCD zDTvC_+}@B<>~gv4Sngsq_cV=VZ`j*yj`=2w*fw=-0B7rJ7OABEjvsL8`#D5%|H%ip zT>v%y(|0hWVlIS3!4mza;?H>FH{f!BQV+RrS-&Xwq7s(5DRsH0(8^M08sD#Wz6z>K z9t3&8@psS$%8acxLxBzx;cHLVwd@x`USxSJ{sjJASG~ciFN|{!wSRD6Y!C(dzOK*@ z2&7Pj3P|3^cgCpQGU8Z4i6zZ#llyk3m~7c?QDb&rwhCPC>-SA*=GL;|XJDeS-@F7F z<~-Fyzpb82$8C#;!=6foN94(bzNKAwz0NBIwMS{b6tfR&0p>npEmEpS2_;~dK)vDv zCLSYM!+>biQBGoq6HX+*>Dy~160C}^7qi#8qi_li2Frp|7{qnAQsvZ{3j{)MpX2#9 zOpCw{Eb`w2M|B9m^i?gK6F}5I@lo>CEuC9)pl?IFUb)|e5|I=nwf&VAYBL>MV0Yqw zw$!9wOJN|(9RISnrP-nk_^i`EK)&QCEazmYnN*3s3$u*4babjTnOZ5SrH%!5r;!uU zTI}snpC#nlS<-{HrS-1-#_kCoe1N!#F4~Wo@VA6+#G7I}?k&Vb05IpNY~dWgfeccQ zcwq)O3meoawzw*%1%|GHYnZS$4izOlGNur>(o>NyJr%JJ{lrWC<@9>~qSm{S5mVcI zO$p*@nn8foe_*d6Y`{!B^~?u7`cQg0Ezu$#%ye^Wd?M3gB?qI9S`!(3gq}*jo}p=I zPM>kj(?Ktq&@{-71W;+GS1qo#1`!^6yJ|vuo#ppt`4mMwQCyl<3joAK!*0ljf8z}Q zP!F9YLmf$1_CL~UqCWIVi)fQhxJ|u%Ucrq&byz;fG+dK-);t;Yi=rWgn5?S4fS~o^ zkYWiJU~n>{4e#(o3Au#sD-Wkb_x57gs089q+G0mPi6e^s0ARMem-OPJL>rgcC^1gu5=R{wW1wS;j~+2D3i9?x9s`oyCh=Vi;D{EV zK>eng)o>er16m1@THDvA$Wxfa?rLv(HkVUyl7wbT6<3EohY-|l$mx##Xkgvda?rLQ zNo&DOf57V_(QODMzH;5fy;^sC16b~QzLQTx&rlw*RYW76TODYpH-*<1Vbg@Ya9GMu zZrM*#rFy@p1Uoln_^oSpoTli4-zZX@3sW{Q6Df9Y1KG|{x60>bs7ikk9Hp<$iYm-7 z_X1gCaIbHsIddDGh4{^dr1L789A4k1%{sT+TV~J-%MmEt)e_y^pZdr}fIIT*qAXumTeLS-Fv)oRi$4o*0rd?yuPm41%y_}ZsGZaA8M;FI zY(m@p#fTjU{TJ+n}9i4UM0otk8?;*AJY9 zY>fg+GP45)3~eA2(hf>$lv0D~&6FGd7a{}Q%I!^ zz$JdIl{~4Kdy8``@YL{kqG5#?ZL+waDXh0dpQg~pO(!>Jp~iNFr0ZWuxNK;QqsHE& z6+u(^07e`ES2wGz-sfdo!lRS&TQY1L3DOd5R0-rB+c@l!`_7%#sSk57koErH8SrGB zIq=t$bO(kp>-g)rdh>rOfN{uU2iWn4We$Yks#Y(Y#3r*iXJUa46e@;<50kd6diC;vxzUa#ler0B zUtvbrHo&q12@^K${`#rlE5z$LW-a!qD@daXhLZ>wjj&XxIcP}OYv{eo{ z3+TQ`j|~*R?&`r@KQecEutFrR{R+h3Ab(&^wH8MwkIH!BA*4W7M1l9%O^Gj`6GGCO z7O+Rg>lI?_Vx_xElBV(|=$D9{?{zVJ)T`TRo|^L5+dxW*qCl)D%kqEXudn1}^T)oN zD0Qs-_5M9SY-}eKQ$AhM@yA3ifWPR@!qP0FwLT6@sTOs`yZwnj^Ao?{*EXbfanu@C zd+B#*bcBq5&{jtVDZdEslKh#;w@`MmjJWn05X^xrE%LWbd**{ti*)Od9r;1@Py$c5 zwC3h832TGdXd;~Ao2yRB8AhQEB_{V%)AAhokjg5?nAQZ##*lAzn z%5V2KumEa4>yyK~9-}BG%$B5$H@;I3KykMu2^-gYVVnVZZC zJ9wRRGt(u{C#`~}d(^7;z!2Xz7nmnIUwOwnuyHksd^`v<^x;Y69Ui9XAgf9g`U#?X zPHG6C0UFUN8J)xJX|jFn?Z&vo4%*_h%R{nf-iuB|H=y)N8xDZ_Vs=GUV#pyucCPGL z2HR0TSTQ8eEKaB~aj;AV6Dhu7BHGhH|253_t@$`;06GifgUt8>c#ezQdt;`=wXQkV z-@8C0U3cuz;H0Lyo{G|fb6|%GzU}F1>aPe+Ojp}EPm`N{(ci9EEm z=QI=)ClE0CE9rDM4CBBKtSO6J_z}9cPr7EgemsmqV0_|%5!&y8yTG4Q$t7^lyprpG&)}~F|I?OpZ(EO)4l_^F%4ur1?nfq(qtdR);%NCvxSiopW;<-j zx1}3h#)|)}g4qd0pTm3tDv zGLDeqU3!)<7Uc@LP>HH*`Tjyyji$G*hpOW5EZn}CIi-q|%@HtIM}8aPyj=K%wiLSQSB0Sp9-9sPI!Lwx@VTvt-wta)keHRy zWjaa&9M5b&YH106Ab=|~Co9P^k?4!DuE#9F_&Q}@#PIn{S#&p4VMCWfW|1r=a9Rqx zCvk?v_mq{0E=Bb27jdstj))9deL?@wR_I1@dxxE(32>4tx~d{G_7(ejy&t)=~*%jHB4>EFJm7?)Jj{pC1b8(9(0bfKOyPq z(&w=wGRMLw5S1n8Jj&=F!B63vA_0pJz6~|op(l~fYU;SW@iZ=r#EFQDh1P9t6x3Ydae0n;(|G5tu}h4gTsdJ!m5l|I#m8zCraJzUCS!UL zv$zUA@%r~gG4!-NqDuZWk}&s=*@QX3!QE>XEj!pc%%ULu>qXu%kWX2zh!G{r*#8vN zkqAZeMI01*7sAVveuzBKplQ%XH=aGksuz^r)!PV?qRdpZxj@aXenf9LdUses2z)v1 zYRR+tsGV(_e`SXUj8*gQqrtQ)+PbRnr7B{(wk9=lYgPz`a01sONe;h2jKdzF9Dp9q z{V9)IgD%cVMq#a(&lbCYZXd;B9Dx2VPLv=uU#Rm94Gf;Yx!};ZCtrT7*4pKC$ z_&gbPc6}wn4qK}lwryhzi!GNP=8KlvjZp%#{Oi30!a%nqUc}kac*S1KY_&-?OjrcPg zBJFQ}x&^j8zY$jl+hHY@jjWr+SaDGd(Yx8K7U8Crw9==VRAm2q@~a>C-&Uf~ z*B$Y~p?a7lM}#=uH&l^Q2^CMnDiyU;O~nKFTn2-n+U4p|M!!(6Jx3ZoE+l@DNL{Kw zVZTLFHcG&ANJQJVz<@f&{Eg&=-)kIxmdce@J=Gh>K;S9hKk(Ihv9@ba z_mz78JbPK&Q@0tr({PoJr?$YsS#|$6ZvS^W9#A!U!``orgE9VliNan;pA&Haq2|6oQ+5@rU};{zuz!U#WN z5pvH9-g{nPeF^ujk;qY$OLQL{w*;3L4jS){Sqt<~_)EuY3ZMscUBg zsWyu&c{*P}KDB=Ft?fPXNHUPxq3R|gi;s>de9B5oc1l~Tb`>JJOTtgvjp@O&7sDI5 zU>U&+@1KF~WI5(nAP27j63)56>yJy#wmdC5zy%b$+dNtC;hd=+n#;Jze!C% z^b-^I%Edbjrg>*muCO$Gu%z;QW|C3iOiFCa@DsehWU;@8XcRA>Jnw24q!On-6f@xX zXX?HRVaSa6VB^iOK`+A1j?1H->?z92g}DW<)Ecgqr=8w!t^ zb``+enJatJ2-C@)`y@MKiRvyt`M=MK;(o0^nYqq<(#4`n^R6?>wCU)rwDpB{=D$R| z`%o(zeh?K@5UCgr^{WcyFC$1EW!Xdg1A2Sg`5c2=`1-x*6-{3^zj&h@SExIBd!Y?2 zufmQX+|(h&3ZZtAxJgg~H=qF!9Kmt@WrZ{cNo<95dkiPEhNmy4TKQuApH-KUCzm|= z+5Y#{Fzfmf;uMixfKa)Bi(6R^>?*2~M_|ffP>XJ&QMEp?i4z<^-AL>Wnz`B)q;DMd z_`Y`kC!No7KG+n7%t(pw#GauY%Pv1gwzc}9e%PX^R>HnH5)fTeFNpjH2XD4_8ab_e zZLLYQBk@Hjno3(~w@V4lMeiP1*(N^57Gv2MlMl0#jjV@2ZUYGcI?3pb2C?GRFg`|{ z9PM8J^7+i)=N#x$?ruO{W~;k+>5#~%lGpHAJ|jSxC3&5UOf$kYHoO9n9V(BSooDw~ ze4?ymtRpAj&5m$fTEu}Rtbu=DTve{I={1kHV za&(}pd~uKx9g?Y%6XE0fLnZP2<3ZqGDdQk|4GJa#R%jl69((+5`i5Sj(-YG$&LBZ_ zW4*)*`niJ@tEtT&gA?kXvJQI=KN~#xChFVe1qdyN)@?WzTtxTrEV8Lj9mh z?kJ*omELeI?nz&-_$t;-7P@t!Wt}Fz{JI+nlzJX~)KOo*g9pe; zN%G|!gE=e*cwtH~;{O7p$vbq}^XQd+x-3p6^iI;T;*rbD2p1hNDs3o_s-EQDrTkW*e|_68f4Nu7(%;GxjrmQ*S|A*Q0rd9;36Vu7-Jw4#Xr2JX+@ zoCd9lB*V2~<&z2N@0Rk$KH5Nb#h5c9+?4XOXb7BgQX*@16%JTQbwX{FccLBOVag=$!1qZ~Tvd+*0jwKI`@>6A5 z`TH3a5|Y4;a*H}rBCaHk3{J+6XFixz3`C137-*U;F@2Z$`z( zXmya`Ff+lI^cpafu;C)Y7$DB$9=?S^Nlf4bQLXjh@VL4YFG-WbU32#>UiEoR_*~s~ zF3WSi=-WE09!g8ISr1_*viZD^70xwh@jsg4!~kBc9+^%MmpbFE+ftVFzfeta-99WFQ@H+KfCMBF)D zx2&v!mV-O#kN2_pm25}ngl@O+YqsKQgK1|o3bj)k=sjG)4WzcXDGy5{v;ZHKFPkRd zjZ3ppLPW4yO1$_Jj5F$e$2aK1KIjHMYj$WFEHe*h;6x6&^Xt^*m*@@vW z?M7mx+*#qf)E@}Lx*x=K*yhYYPgr6VIMV>lwgz%_9F6Qje`T!EYBBmje6K=M*u*$# zL)h=-)n8L<(-fxNvHC9LD&8ql7P9ITW^A-dXPiq&**bK5+93mke8cxa4z%6C1iD$0 zbcpu?-rt`B@LJh>YlHatmI;EnW_PVxVX=O10Vz%~ck67_b~JY?VbXe>-po+^S)j># zD&`$wG}^7d)JSEjh%Gt2vGrb_Gs@x71?kCI%XjTLg$lWJ+JmZ38dcr=?WZlA3wzJ(Lr!NaeXSYHsWH zM$q+mx^Bizx}Y`d{MLJyLbjD66q@lX(;>* z-y(9Hf95SrN((L~N+?TIFf(>ioG)HC{H*9=9Ll?)xHBL9p<*1$luJ?e7c=MnVe~Vg|q4bXQ5Rb}6m($exl!6YpB=u5C)Gay@uP!Wg>UztWYg&tfFL z5|#V+&B#+_i^Nw}D)}hDnnL7hLFA@P(z{?(xg31p*Wq&>d20vXyMmNzDI{zKJM3U$ zFRox*GR=fQrK+ilXBkXUSt1y3>aOHac^F8F7Dv>s{nihrY_h^RYqW~zuo6|blJ6=} zsHr(=63TNlOkR3sq`eJWsfVsHX5IC=e- zo}rs~D6?UDV$;15E%`BT2Z|vSo?&zI(37A<)y?uF2A|5|c}GasdAm{@;>P1fCgvC7 z|1Bddg|j8`C`M zY(FIA#v}ojU*9HXz1?n1Ik>5oioP?^>l_!_NfHLQcoIkzK;(o zX>M+6*r7Y!w&ZGtHvF_xm{$XA5G11JL*Xk=7Kc@4%4LpGPzJ^^FaTIiL z<;@O$v7G;fiwK-{T?En5?@?V_GnNFqkG_H~t$>+Tt94=AY>Q0=oz}&J>PD)+vqCL8e)+T`}#U(?$`j33>2cOu!Lgn=+Jiq;l>RwMW%IFqRr#)sIT}bzMGX)YACJ9*{B=Qid>do)?#cOZR^C%iVv`~ z+olamtvc-_qRq1HS{y%rOvA2r}vJyL)X21;40K3H9XzBYdHZ+eqFa3Gi9F2 zzu9P~g40W1sJMKrk|dS~n|AB9b#v&oot+i~D*Q?D4Umk9F-7JIiC$D*cSwQ^*Aw#W zgz*6oQ6tWle9dczqn~LjmWgSGZfp>}XOCT0rgDEYGU?8d{6C&#gPRB;T@ijR7(XE# zKF{M`WSrCg)y^5mL6ID)@9rAMnM*MeK{T&b)N?2uk>r|cCO<#sKYYrZV_st$pFQ+x zFy+1};JfDd;R7jg_t$I%W;{hCX^OLdan%Sw`fiIlbty@aK?X%rj}TU4WslEQlkY+A z3S!r-NDU7nUqOb1d0TMm^G|9RG(9dgAA?u(*PAT{PD-?I5%SL+Q`R@L+vu{bPHyb2SnG z>#Q2%M#yVO8j8}X#e`H(@DJvlySuE-E(w-vR6h=SyzU3T1?!*qk*i2keYaWqS*J~T_1=7Or+Do5&tzlm>YXK^#8E4ht(=FfmIqYqp zqEfbPrG6rj!|*-$Z`mG$Zc>su_u(`YY7s>+mh^sZ*GJcPeo29=JzeVkNDPA&4rw{x z7_}-q2NR67c%BN!9>%N~yVe#k_tLfVum}o?QcuDmuN{zX;YUv9RS{M%&#(a)U-$$f za%w$zfnXml(Ef3~Vw4e+o^Ht8NL3mP78x3;#KehEqSX^K8iZQ@PKCHf8#vc0MFM_W zQ^g?)mbw%T(xMXzg{2E0q`ws3he^y{E0pNVKw*R73Fpv#Gvt^c-n(1!aO?bY@NQuy ztL9B>Fl!>etH5tO!zU`h`Z55_xd{XDC*Lle#zF(M>VzBxa6xSxMv%hH-<~>VWSZn0 zi5RO4DWO=v&)0J0CnH^4S|6p*7ucgrVh{W(@Y@|!s#H^md>_|+#a@CAm}ILY-fiK< zdNYj?B|5%^OjC7Jmi()V9jCN~EaeCm=!L{q9~M#NF1^#PQq}oVI(-5baJ$WVR}CA= z;|}9q^E})VC3?2rGS>k~(I|OW?S=IPg7vO%mXyL@oeJ)+vx-NYrx-Z9cH+w1Xc5~f z54V-kxx#IUxQW?B_u}aW(SN=a3_Eu>{ff=}K{OK~`~~#*M6RnY1S21W9}FsBONiOr z@;fFXj88v0h@oc%37deTJ{_f64#_uj{H)nTSVp(ZvAk@`{pCNxv>Szu6RQ0G}kiP9^=Kp{ZqXG?IzKFboN0)I{^)tcO zn_Eljx}bwETSI5K3xE!;6XXby1NT#&{SKW;f;x{zGU1^!QyvH87Bv0&AU+G8k%H}H zP*HzB9w<)kdPaL+rWKc;f~_DDyC#;E6V?2>95JfR@TW7_kt;>o$O}|=1MBPE;zeX< zT|(c-Gp;))trCEdKnAV)xZ}{>jN!ra7QAJH|EBvZPHPq&^B#AEGZW+Qj9-=CRdr8H z2Og>kKUl2_f~qSJEph;2v)^E7N+jVt+6lY4d*BKBfLcG>=N(&$_t)1SID!y0;~7Z_dzZG3kwji%XHqezsb@Dw_9dPvp9Qng1T8Pge;<6DH{Nlj4mSIynV(?v81!r1OIY)Jz zYm!4W#Y50Mg@Kr9^-jh-z2R5bPainC9O$ZivF$Qo&r?8=XAN6eB;nUSqTd2^_{Kq2 zk&>#R$Pn&TnSK;p{K+dd!+u7-@2ss%?vI^8u!c39;kHWjTX=n?Ywh1MUX~bRVs;xU z5wp?1@Etaf&Y$A)i1g}C<1@?aW=4fAEO=zpZL75SG3^BbhSZz~#xB>&9+p!UVIObU zGYnq9Fk>c!`8|Fri?Rn!Gb+Mz%c2n%TO&PhW1YcMPrOCODIxdImSXe|HSndF@z z+qRV7$E9mj*5}~G(T8wMc2#@N-tq4GCV!>?gPHoL1_mmk8nG#=>8s2-1mVTODTOe` zf>h)X52y4)&-+@1(XS$$dN?)PwcsC0Iiz?VLN2V0c(vb%K4*rrGOQ6-XQtyJHc^a; zVV>bQiUK;&&{PxtMQO_>yBeG7iZ=BRS%%(v49A#y6|mM{53uMr-HzZ5li6n0T>sAB z3V7*yVLOv6>$P)#*E?t%$|2>VoYg%Al((C{5qPapPy0jI#~3D#SST0M^tO4AH7F_1 z51mj9y?}Veion38eFo8NtKrwB6$2>pSn%{17YI15iv84){xMj!g?t%@-@-I^z*p3QdDU(zxrQr2*ZPIO0Wc54Jt$|GBq&7TpAYN6tWVHE z*eEADm`X%rM)7%XULZqVy=6th@;ho+v9`=}FC zAigVjQp~~5@3u~ucof=(*PbZgIx<`&yR;<<$7)52e#IRuNc^!@c7Y%~j3$lb zNDl##_8G1MW%QATCj5C2RNP6pI+pU=rdz3=$`q3bLces<-ExA&O&{1 z9mNMaxhT$SI^uW9qF#a>rF(-8nS{wU&e7E$Q12J z_X?c*ARCW@YQDoxgNSX74?DH;q!5U|9MMC%n!?@rE0ju)WHlb2kGSgYCtMLcHNGoz8 z>`Q%I<5!Ks8PTtw?A|rn!;4Wh6Go_1jF&z7`mJotTAI;=z%A}dRM6@R=ghh30Awt~ zCDPlD1u_fQErb{n#}kL{uZ^snDOaVvK{=n4z0R4tS{<(Rq3}6OgDRac&apm^49GzI=S<+qys2GDj&-!n~QPFRxO38j%%y7yiN znwPpD!BK48<8fCjp(KG792*k|lmwi@9V4177RN#m!B^#t8s?-WZ4!ZXaU+jBvkO~3hn^?B!d_~9d2 zpLP0r0jA2`0fx90Bw!Y**)Y3wbqFa2Gr#OZ5jr~g0$ zHymzb+#zekX|J=(eboyO&{ETfaV?F+JpX}W8+w{cZ>F4d5xYk#mLXK=l&;{A-r71|UGNk#w%#0@P7at{w8@|$Z^%>0Gv zR0mmsL(7Lhi#j!Q_xWw5HoEDQS!A!H6`Q0}a6oGcYkgUW*}q0H35^tw%*k~C(*`jr z70`KxUR!q-b5s7^-T^IRuVUD|*@Utg9}q~}vJ{tb#+hY^Zx#PLpp zF%Q{!F&lIA8V2!N<|VSj)u&$M6XXe}+PE8wlP`8AIQIbI~oka1%rNkB6F)J`AIeJ{tU-&GdMz!S};MK#JTbEHEamVJt19*ip8>=56W*el&PcrT%TNynG`wW zSv2xIM^-(8ri5i#uXFKItctNKnHh~5(E2ZWf_D!>aU#&SSndTkPHig(4uIY~%^_CZ(9T=e zmJqH~z!+Cv8*28?_YtS59dkQYU3N8}R(WwU^XKgzQttvb9B&&CMj05u;GnZH$8o;o zsfo2d@sx#TR0hoARGsYH0lAS-E7|A0xHHvxn;%g7Q5e#6on`ux_926PvE?(ex{kiN zMP=ZGT#ZlY*jEEs`HRVKeW$8?DBFo82!S_?q}JA2`6UUq}Gl`c4J9Bcm|dQhHf{W-d(& zp|mo|Q~1QUr_yl)`{`3wthXqTt1ux5e2kE_UpvRy++R#l#$TuU`hQn)`TCrobg;IV zUn1fI?ZV7oe`>HDxdg!G58iO$49;Hs$Epd2laHYz0yqkPi8sm z&en?=ndv&+E3Z240f9lY7B!q)*i;R!+%-4}&WMSG2$IAJbRY-`)vT&gzoA6f-zQ@E zrWEI6F!(+_>@U8aeS7sGBFoe}q3l{z0k?s*#lv(naA+ip2n<4_p*jmoP>YWuDFNw2 z(5guXL+uJO#0DTWn6Z6gT&ns)&aUe^@qnH!!!IGfOE*OhJ*NOSirV_J_T!3McdX%n z8xV?CW6pSh0J6a#Q((n71|`5ADYeBest?)ba~@WxZ$;@rQRJ-GdmOCi!ixi%#g?!> z-zLoz4n#p!N!R60=r3*SRCZNs3Ib{6w})Dn{q<5+6c6Y|;eqev5T~`Ng2ZjXg#IsD zvt^nWLgzST9)cn#;PbmcuwUP;g(#dOs|w$){P16ZkKB?FM$7yHbiMe)+k==7PUp3{ z6mO1$yalfsGr8DCC(BQ$ernJAx#px*zUjkNY+0@Bnp+8>oBi;B7F1v3e|Fd85&OJL z>ak3V{6FbEixg{W>^I!KNSc}RlUmp@fjJd{%UYXiRsa69ICD-SA=ICzC3Ky&Kv=BC z>{cz$EA#i)e_fgRd7`?gV1~M>)vkbwRqskBDF4)NiT$;2KR?fnJOhLKz8$ZA)t9KR zF*-VT)$(nZvs&I<>72bZ`^BHr$-gRIXT;t9VIAvSY9{$^QN-Sp_Ds|DR`><4*`U@D z{b}uUs|QWTCLCt@BE`&Mmwx%}-i^W$^{zf=$_1_oX{!{8cyrW$dtGIH_f44X@@sEZ z`^(-nKAq5)7rpQIra68#Z+|kh+A}Gr>E9XGR{?y}puTI=aA)fIC; zdn=2We_zn6uMp(!=I3}YKkm}{u6d1H=bvu5nI-*wKHpsFsOHMwEWC|Ye=j;cc+kX{ z>`*h2$+kSE_QSKOld@T=Q|pf&J^20pn#%`vbl-in^18w4=SP0V@@OnoTg!X#zSK9* zm&?BHV&>|qRIfLgdqvq=g*9n0!-iLLzrW&k(SOM=K5adJhC}#$$I6et4t)}kW=MW< z)F`UfaANv*>HAHu7*_3L+sb+Qo271hNkUaL+djF4g+(hb{Y~68PkZzB`nhX2=hWNJ zxvwL1prd%AqR@5zkVfVgG5h|1sD1uv`TPg-PnUmqeEhq8sb5X@x~fO-FR;D6{`sZv za%6H zv|fs*Kb!U}^lmGq@U5;%V8V$Z(Df+(q^#A&|s&e72JYEK28Kz3juRB;4>^RqQ%Kga0 zW%d5YwuswHZ@bNPE@hFxnYO|Odlfn^C!FJwn7C70EGl_X*{ubtCS8ZO@KzMxa9why z{>SqCe+fn54Tr4W9GvE7Jhw6C09(&=F4^O24ojzOFb={0FcXAKURek-!^RHsW ze&JVruIevWPW}{_^>3ol9ighP^Ca{2V!kc+EBrE9X3q6Jul`(^dSTj|p3rLBxF-f( zi;5p`?$C(1JNp9g3YZ(O9*4g(xxaSpw14~&(J3$9)TiEA_D@?~tGVmK?s{YHb-L@k z)%5L}9?tK3kfIs1*n6VmwG;26LVuJT`oplfVX{!jYp4ANvo#uw)NDz* zaZ;r$=<0U2#cBKh@rt+ShF>-h@MdIUU=RVO2o4}tWSH3Z|E32p)C*Y{fNR+y0LW!v znEbU~L;6sC*b7S_*90ibjV#MhIoYDYg7Nm`!Ul7z7Zt7&yMVIFK$WT}sva;SO*q9D zrREgt!>64<>2Gp>gQU#m;NI10&Q zHXb7*w~Zz5Qu6mgMA@N%m^+V_HjN7g5{;o19^@Qa6gT7Xt&q+pv?)t{2A_-=D;}|d zg-+~Yx9ZbNu1s(7w&m<;O~*UPeipx*zTe&cgd4E)9p_QHIrq)NX{k%(kqdO0(#*5gc3z+#p+mICQ=_?576%3^ag9&O# zAbMdn=<;*xKfmg0b9F+oS^abMaH*#=43@6aWAK2mk;8ApoF|C_W000XB0Dk~qa%F6DFD`OrY;&cP%TB{E z5JmU-3d{S(Nk9mpB;5c~cL;?Km?lGF#V^?|ZT}t@L`zBdk#!;tH^aU@WbD`@Avd0@=d z9ZGPqHh-u>@~*7}AD*^l2I?MKWLc8jG5ecA%ZQKxmaLkBR^3Lf6>vdG1-3CKI z@WA{}78})ud~fi74(uFcgK~`4vmwx3&z#G@~SFc#?!DM&n!UE@Qg3OIyMHd$+MoB*e#i z?$^`P+nX%DRS_J(y4>hFq7gv>Xlc@1XLIztU4^$Oa9-$C6h^}wRp3yt;G;yAOd1Ot zYf7*_2N%>%+A&$q(cb%#VeI4{lyFf^=(@QxRtbM!mo~$tke?z0JSOA@EAS!}Uf{+s zEC)x_S*CKZEWd2g8l)0K0SdHtm_`);vMTpg30F__%`@7ARqiU>b_Vj>-+U)K*$?Nh^CH?xv}_$Ub45eW~Ou@zS)g(AV{QiF5>n6yyKX;5FoPVxKBOMG{~ zT_JxyCSwv38j{(TPFOr+llU#c7w0?AQ)w(W9}O~;U8q7hzplS{mqWU&_-46ogI&ny z@l+@OpKlV9I3&|8ov}D(Q*xHCH|Qf+IONUB@mWOM%LkzYx|QUQV?rnIEz(P)(-{9O zA0PbyP)h>@6aWAK2mk;8Apq5?fYQzY005Jn1~URcDYMcBx&eQ5%G^SzO8@|^Q~&@L z0001OWprU=VRT_HbZB*LVs2q+Y%XwaXY9OXTvc7yFT81#7739ql@t^tq)SCo1SBOz zx5QH_{DfEWMxieV+62d^#VFKe#U4?7h~UV~+8UImaSM zRat@PJk5C&3Ppc(_l~SO3Wc$aeB(>0%Y3TFD1#jPc$fB@h&&Y_$h%wLL)^W{WiHY_p*_^N) zug;&`cH1f)GUgdq_y6Q6&>_(1t%!+%BS$$*YaS3Mymf!%zn(yik!YkzTsS}7BlAw! zY0jH{w)r5BKcv|hgN%%<#M04@N>WxlkUvW!hGvl=WY z-|7_A_c4E9b|l0~%nHjYDEPKscNU(m5Wy@YG_<%C9Uc8UHIQD~)|Lk=u@w)lGx9oL zw~U#M4TnV`-1$(?u4acaoL(&0pvI#jg`e4x5-vj&6dKwz(-x(FVd3E5;3^M~tJFi; zne((475>|ZqeRs%tLy59O!^!V6%`dJCoh*x`pAD&xvuJ|Qjk?(B9}QwLeetT9J0}X z#~|cgaN|km9cf|qt;+DOrq!}Z+rc7X zVd3(#)1#h3Ly22javBj3FVjpWnSfuB3iQtz@vmOH_H^@|pC9UFKmao*CxLu=Pa}o8 z?l*r3n`3u7Z(S&lex)RPlz>M;WhIUG;kHyDF6)ryz5nM`FziF=AcGFPr!pOu?zDtGm3au9F``eq|~%*=N)BlI&nJyBl-RqatIR z7cX9*P?;*p-&z=aLn$~le{Hld>^YiE^#6Zxa%kFJ9W8p=%YHwOUyk;-0mLbUidS$r z(7?bT9F4}$TxN5;h?RK97_M>MZA}j)X<$H~p^_ZVrWo^hut49S;71jW4^O!Je4^W* zA(IFr80-E@aTf~ZH20$+Ln;3K?OOdRSNH861&67obD2y3F89^Id*|W)(GiwpJjs7{ zjEKi}*8U}(ot0s7G0)v?bvaoj69$pUm-=+FGeSNAeLDXm5m#icFn{h%67yU!z*t-8 zNv9Td&5P$`KE(RFEOvD#rQa&w|UotAHz?Bv2gxk+9L`a+p%@;b5?icOhmh z`0of82J$aYO-(Vz4o>djzd%*!5lfNUA8tQ|_c|~2-SwhH(R;4&waz+fb5X+AhE?2s zb0^wJQ6#|cd#?NC8@A6nZm)li?!9kmHRX4hrd&=YbaK3PO2mSc_(Ups37LzFi*}7i zNqbj&#ei%rQXlfSH=4*Nc%Gxj(8vneXzJ_J8F(zRZ7=n=rw&qFy!b0SGfDbrcXeDN zZW>vQKJ#-g{F<6%f4mofH=OL%oypnQ|ke(&C1Jbg161bI1Tpqr{?5*H=BpNx!W1STf4A&0RT!l zSv)K&>#D4roc>n%)_hmG_tEa3y*;;uvNyVdAU;S*WyT;Qkc|XBDkVlPE zGfz@g^>tZ0Bgtr)9m7E0Bdk}_&jAG7t7wypo^;Xs@DPs_KOqr6*?zDxQlj`XIj+Y- z_U_%FeQynoi?HhET}fdJ3l^yQFHd{ld##d49QzSn7ECE9Ag+I?s2D1DNY}OMw=B^v zw>K*8y3x(XarG*`(|qTS>!lf^-b|I2KffFKp8jNg`SK-lLq3-!4Vc!ZlS6%9_5(<( z3GY4qyT0a--D6wyD4)}VC#FxHu&}es6K>D_h`WKuTm1)f!uQO3du{x(KQ57@Rer8! ze&yU2K+rk(T3X^qPBG>u2m5v#KgOC4x&h1{_oV` zjjVRY>QE6@Lqh{`jrnA)xBF6d=9q?BJMxaKj?KNj7G1lV*+0txM3)0TeY$>2qt6im zKFeZL{!7d(EH(N8il0dSZy>e*a~_=V+ERKM80a}$!)t#~jTT)i$C3#k-1vS}6~%~O z?sf24rVt1yP_Ogonj<%^h}vZ`dirn#rXj@s(y8`~6&>a`Q1!+|HxIl30nQT;=pQE4 zrhWK;ZC881{&x++&kp93H;%Wu(q#gPZ3{w2Xprk%ASd^SYg|SMbn)5N))t>}6Mk$` zvA`uhW9)x#VV465sCa%26`3f}lT%QYNuZh@bA8 zcqO6B*YJS5`z^Iyj*oSN5p4QoTS44&Z-P;%8n+Ssp+ z33D0N(jM)tyDc8g&CjQ&q||?$-!{|9r#v~_X#_YxfBACLE>;E`){ylnZ_W0bj=c~{ zZfSpr=C((T;^Y+(5gLePhGN&#!dzXp+YOJe|5_O?Mp%o_YJh7DKnB=E4zvmXjT`Y^ zO7NG%?M45}N|A_xdp3B8goqRKEG<*CuRuO7mD_K;Jdm$lYJI8FdGSSF9#@tINA=-S zuF$hh)2PBr!j7ySyDLGUe=J)?~CTtdL0>wAt51Q7yC2keu7X>{``{^@*Wp4Kzu!a+IqK1@4%cKjxnIy zg`Xb@G&m@hmX?0a&*Rk?kofxgQisXI%z;VbDQ1DwfX(i+Bjl?FG6PXPJh3vVs=q*$ zSPO*oU8JIt;fZyUt-}&OTDehH2Vs9j7larY@ZP+6k&TT_$a9x#cYTtiM29H72mhmb z5W=mBu{=VKGx$@}(?u3N%rNZpfL8k_dy~i=08Jo$0Q`T0wu2;-mXpIdJ~^o=)$&%9 zlb2`a=l?ls_Jt-jHPzOa1Yw@f4~&eMpt@hj#^S*}(tFUb!dIj3Q4`{#Btd_by?*x& zKgFl4YGg#mp>7{27%=wh0snuVp>Z6s_p`gj zn@DJU337H^{20q;#;Oq>*d#3;4wZc6hZ1Itjb{oZ%sA7%+x_S-c9N(ygidkFYjgQM zdM&k@`LfN_zO7<-2EbLhXVDpjg2iDz zi|x>eyy`QCJlr3wJAE}Yr2Y2o+s6ytsrx&FhH4KVzG`i~Gc$iTmjgpt3`1@~w zr;rBxfR#c=MBt%*BnXr9@$pRwgRCHd@(z>t2mGAg-Nsn3R9qI@qZF{ppC`>+2Eq^^z;&RaB6rLLS>!MO;^qd@V$AbKV^P*)5?~XM_V9GGo$>xvZN|gH!}!F+0U(dtOr@2Sh&DGj zyHjQGKu$Usy2AxQlN+C%o?MT+ugVdP4h@xccD@O0MMi&3jh?9SWZ~f<2CFo65ET{W zusL%VzyTWvr=hEhiv5f6scQzaZ(u+zu+JnJ|^g7X=&-#uV4F>mkWXFg*U;Eq*7H=s;gCGj#bVE~jV)hake2)K3T8a_Fx%^qL7cpe7`Z|;w9!D;13pTor~Z)0MN zzrVf4?IDKOOh!g_;0MK_@$g~E{?5NL!~mhIT$AMXPoao9TblM}C|%{|2H_}vjhPvf zoLzspsrjCmR%@kFI+kI{#CY5f&kXE8O7G_Yao~`8;>6 z?P8@n9;ZBD0ex)C5H_rnZ%{+?uteT#qwpa<5its-*P~1N3-9VoCrPlwH@MU%^A4J; z7ta%3;%~|=asLjPGBPIMsrc|A1;kdk`t*Nr+5LE<<>1*7BW@*j$xMM64AWw=Rt%Sf zo=bf9>~!)>Mn{LH(sh-i;P8WbHVPFN7YD|=0mSRZxZ9)=Qi)5sh4$+;dsC1~%6m8m zpFc55T=oBI-y#-e)OVTmGFhl=!|4PM!T&FpKL|RNiTsnwrP)@yF;i2<)qlPcl&^o5 zj=oMvSXp(&DF`eNrioZ!JjkzTm);!&~rvns*} zOC-2JLm&_S3Inh`Yk_P2)C(7Gf?$7G0rk9IdsHy)#tjrL52hPY`tbsh6z6e3BLkzU z>FaZggLStmwv0?pX6Q^59ppHg0C)t#{r>&?>!hUc4<5`E;^Mb&)9y`p7BQNYc6-oqgul08ox(#I<#|_{VJ$h!~D~-hHU9b!(F6hWSFAb zkh1!_k0KvI9|i-I%Fdg_{8U~}eedH>wsuC3@1WP3V$cEH7eK%k6&0bw!kR%Nt;}-V z<)EIM;URPm(kZu3m1%zgH$e?t;(mHC-^`8Sdv@Z6jf)GRN1(5upmR{OxtE#jL^c;>ng%ax@J$lsI(IKa=Pex3E@PRu;R| zdiVw4{DDStv5S9RJz&i1H*YXsNn`jo_<BtmZDH=RqKD^sGW{YF^}zfySkGA(1~2y zpHPw~ye{Bvk~vQlAFK(I_K*v59v&i~l+8O6&gE-{5Yve; z0ug`+LZi`=4<9~ES6h?KkJij}DOX&xgw>tWrrD%Z#yNyB@!9{9%zIRf`~3OyuwDCA zP~+>CUQK^HrxIL{CEyC1Kby59Sx}-AR{W&Pc;w5|DZaM0Hqcl#o_n|`2M-;n;`E;1 zmL-5(_p5vNCfxGoLx^DZ=w#Q=an^YQQDkp!E($aG6#_2YWk7U{=W@PkOTnAqj z-}8GQayr@PFuSF2Rwr*7lZ!G$=z=ehF;G4b7WNk%Ziw`swkydflx@|jASjJ+$1BXq zEo#=-DD5&^WUmZiW7LlK0?F+^C~T?vPezTX*B@T5BU1^t5vw;+3!FGRZy!S{T7@n1qHr)1KNLq za|;=7S#}l)r4{}eM$yx+$ETk7p(R!FiA0)nzFx%zsO5%U6$zsHQ*mdj={XU+%a~)PU zNxa9(9c(r`O9d>4jHP7rqhy}jUZ=L7Pjm~G_@xj*PZTE4vbL@Z)GNN%_dvxVzFu<% znfBegK}zH~nz?eI;6Y5{MzygPET1lBCNpzzoHsKwE8qBbIWjsL2mF6~f~XrY2uOqR zk3TGKO8<51^%ggck9Jqfr^7{2eUm})9p(;=mzH_2d(_ZFn86z;SX*;}?(jL7r6Q!c ziH~ZE{9{=%l0GkmAhXdDd6e(OIux-k$3(7zG8z!epHUE-@`S-nQ}_nBlGYu9p0=iQoeLDrPY; zI+!*-2}#Sr);tCZJ`QB@6#$H7_~hLA^XLCSl|AlwFCfS%u{M8NRyZu~%)H4hUZGBV z)F-yi>w7>z$))W_W#HamzWf0AC;Hwi@+->d-Vwh;3`fA$(qZzNPoKIke;lO-!4S?M z5$?J=f|0e(NkT#r$cPWz1li)JlmAWW);Mb|yRh&j5Y_ku1TvryK&zoXss{nv>Q%dw zO@9k(taMp^%pZTpS|!l{GLO%8Oz8H(Ow|7IRu=}UOXBQysomtn%GJI3WZ#KivkN_l zVl(tPU~?8p9B*fxsO?Eaw(FWsH_wr?qq+HT{W02Oc>|?WQL2-f z1{xZy#Ba7T;75;-_csKcrt-lh4w{~wnM8=O7p(gLm4$y8V)+s#T^6!W`B3$GAn#Fc z7KzyP>!dKsEp<8BnX7@A`kB4L&Th=j8F#Y}+YL`&R9D~Tdh}V=>xajan16x{Jt+aQ za37!%*-S?cN0^wH5cTP?v-GOOYH;fGXnpUyfc7K*>}*u2cnru!P=xY@#kIRj_EC=S zu)+!lM{9rgrwG6Z1-GB~RJ5_-PV(M;R5&1M%A0KMXh(cBFrNA01Gd#bo|L>i?p#Ma z-mi$7MiM%am%zF}GN`O|g~8>WJNNI)f<}S(g;zMu8$(r#QxW!w091je`!)O|SD ztG&w*z!PQ>pBZP z(7b>9@}HK8-vd7L0Z!5WFJ2%V18$Z|@?;V#QTfS@lujz^p-&i&6|^FW#4i}@!G71B z9&&;dC4xkQ5i~r$&d9=o<>I2UYVz~HdI4Ona&pRmSwsA5sVcHeP*Uz^CwpR*F;!&) z%iTCvyp!@Svj#8w!*qok#JgJhH6Y zgI#+G&f20xXaC>;1BHo+X+QVl()~mcinF7-Gej_<_S0W|6%jFDk9y|J?PixhSOb4h zQdrGPCft%OsRC*kR0#&EzrTN|#EQz;#H2Zl>wRUs!=T;PilLkGvuDD!XQ!UD;$GT% zgc*=Gqh)pqz-R1A@3B!}i^=>|3kTBy=+VK!((|2($k9$=|6~FzaWFUGfCRWiVqiy* z1&D0}`NUhZ4U!e0<^o>504@0riW5pZ_A;dk&(UOtQo0&fdXi@}R6Ow@QrwHPd0WeYpa z5fani#*b=y`S$HaS`p_vv^P?FEV@4`Qi1En27LDM@fj+!W3a85rMwz_Z)JbD7|$P% z1ou}G#SS897Ir*h6T5O!QtD^tSvLhUQ1Ubg~@#DVrXekkplz+2v!*XF=IFK@!e+Ri5 zFucFPL_89j(`(})$ z!1u&4V6}+`6^Rqm-ay+#w^|6un9HF4l>SnKKc2%(E7|=xejNDI+Sb-kYBT!h$BnLX zZ~8;1_8#z%$8fps<(;hjd^up~BAZdcF{duEsrnxQx<@(vmJ80vmI;3oKo_VmC_IR% z=nwPaj@I42K8+3Ht@H@-uYZ0wMkXePfg8Ew_(}+caAc9gwEWw*Z-33j+kHFSSyp@S z!2jJl>ify!bg0LI@sSA$p^ybAQmsA$A|g4kuOOdIVV*7_W={yIucM$il#>Iq@?Sfr z6dR8FAQ}bMlF#?l3(0@xdWNm;2zs&LuV1BapYBhi7z-wSR)+Xs-DDLM5a+94uTyQeUIX zH!W1t&mzvh`f4sG7SjBaU8|2})9ekg^KS0wI#{}Iz%Sw8aTt=lHqZG<$UoEFt0=Q9 z_wn@c5ub51dV??u96`1d}hX!nh+No2ZxE5SA}+A_@@ICGRVRJrm-M*&^B?(#>6V9L93e{Crc8S#qodo*2%;jrer}=MjloEQ|Ez1 zm*?KBstqIbiyp9Zfn6>bo_V^8c>c zn~-sITegD|` z7IWG_)0*TNBsvNOyw89dl~O>WcIOU0h>*aY<-vb+-?LL{VaE?0Brb;a;yZKRCp&}G zw`^$!5RQ zlu~~H1^v3s6vR^__`vR3Z%iB4AqU0j@w|i#PwaH3==zsME5W$? z#=ail9d6PPA=@#Vo15nIxgZ!AK@6i_zk9b3wOngxGhXQe*L`>02op#Q^VdlFnD;Z* zDi**n+QVkI{+x$|&ddyt-BR3^`pzM?oMe9`7mw}{+m$OJhPRGWm1|eQet?SfdJf-3 zY7CW(_;9%?TeG_3&5$9jnrB<)ko7>mzmE^Ls6}15#19u(APoUtQb5TAcI|JpFz|V7 zTYzAZZa&ImT>Ka%6A_?dR{|$DJhKFlU-e8OEz148%i#eUW^8e)l20}85b7;D1BYI z8=f*mcwhC!#6NKF@70}!4H|gnxA`_whTs%dZw4!3fv_dzi2iQQg-bTvm8!OeXy^R= zk|X!%du+Q!ha9`PgQH)bk|R4mg!F&6huFLqkS$E8NHS{bt7})3^HrScURO<1?Lay{ zUh2z!2R_kbcV%&Ni~Me)%=6O*JcbnAGFw*$-(U3@)dzFh%gR16GuTW6Xd)qjI& z38<@+2msQJzK4^jj0c7ZP%T8C7vu>(K7PH}-WYORVgh8`ZCSDp8Wgj5m=J%`Uon;^ z71%x5=kOZ6_qN(GuN2CFg(4UDc=M z?7TeZa>mVYC>ImR80~Uds<+X~ElsQTHBwc39pTcjn5r||im zCDxkl+#4f0lZPOekVCh0g@~z)cw5KHHvRM-MkXdHLYrlg^;={1SO6$5-@m7c&>tnb zHP$^7z;d*=-U7z*I;1N~^6}#ocbi)i?&R_n5?iI|;*(K24mLW9-q zFD0)CsDj-*h{_(}_yKo%I**K`Ncms4|5Y!~jR~#{baZQbdn2GnN{_{#CUTXV!;X(@ zVlw0_syLm+gmDUx-C#arY;akO23_8J<5vnqrDSWn7A1MFT|Nb4dJh`RF*Yu)Z3{*xOg3lQkX@wF&UFq$@15xKo0XZu6bs;Ek)lF2_J96V52Y2pz#sSHcTIZ5 zd%dmO{jt74Qq*Dc;I9}Ve3B>3QlP((4O^USPy+{Yb-zI@`Ql!@MMR1MFe0+T9prE3s z`iyDcO!+VI7*wNy?x$W+8Q32jOoIMJM6&ncw!=Y%e#ZmdySE_J>yvd7s9)csIbos} z+n4Vu?uBPaxaaWtLNU2-G*k6dI6ZL)8Ozneq6L2wtYqi`@=7^boCuh6KFPD7NAttL z;1xEupu#ePs1lVEz;<+KsPoZ|z;@e}rVz9xu`uake1 zhI-D;Ilqrr0=9a9lrXWdAf1qop|>$H9&^k(ts|D#E&Hx+6y+*ZwVU!MPlnV-1GECV z3sp&F_ND@)LIHrTKrQJy<}Lr-igFus2;48f_tEk}GF4=u!_{t14vyDxaZmR)o^&O- zAQ+Fd;Uaqm?(RYWRYbnNzFd0c-R6I`2mQSl@~b{yBE-FYxRCz3eHLT@(om;$_$_-@ z(0T~z*i2Nu;>vq`xLimr=5h1wJvI^76-XOGgp4+4+Y#!SaTJD{LXPl(+gQZK=|d>F zH+Mh2rt;qExMh3kw&iu|eYbXEVw^*h2(f_R;PX`xD);U=A_EH;omg@fxk!IS6*8%d z7cAhFm-^+)7kRfCj_7*{Ry=Is*2;bF@n4|)8&I(PKuv(l2#M(AQ-XU$7&Y$3lkQwC z-oE~RkaH~Hnd;6?MF9$tMgXwy9!LDGA@ZTr7>UaBrCW;6cyY8KJ~A>g-adOb9Vg&j z!Z}|q4Qybm-*8#da0qy@)AfJ5F%a}v2shtft333>wER$@&$VsVQF(RyvlVWoi|T7e zd}H5igF-4TlF?dkQGg+?P9kgD0$WW@O3-63u06;=4)$!z2^~KoU2L}|y^4`e%wpWl zeqV!e-ihnwh2k;j>iPG`4(TVec1jfKptEhchc;NO>yPVEsGZc4el34PCN?%4MBi%W zX+KA!@o$4FK==b7$pO3<(&S`Y%gXHd4VIw?ru(<^aqe@MtoX0@&kHnj9d=h9#rx(F zX^}k0?VqZ@5_g}yb2u6nSkRgp6B85FcjmA1?=)`A{hI8|dB8JbZhW@cYhJSXZ7xUM zqAp9UYXu*BENJrSUH^all0txyhld#Wo;-enhWK;kazWKli+tbrJpC%lC!GmTcMp=p zJpb;HJ(iPo<{l*41|5KsOdrq6`)zIGSVtcqthVep_u~?mZfV}|eBn+)F?hPqpFdaE zo}cYszD|0;A1Gh3K3t3kbzgeq4!G48bwyO~B3X$IIs5%TK`wt>Lzq(eK{C&M4!55M z9uCkxB6*Lt?guED{ucJ`_A`EIY3Z>;1H0-CT%>(d${)94$9si>o<1Bjk6o-(Uyl8v z7BdM*FJcn<|MbQB!%7*ozGkw`$uscq5TWGOd0DkqNdV%9ilI!KONnRRGBJLQC;pb5 zytX!VT3Xs`@ZEnSBRbA2Lu8|+HjRj+`|yD^{@Ry&A1~ngV*ql=0MbOp#RaLQ%LnOu z!)p*6sr&Z{zcw}k7#i`%HJMr8xN##gCWhU1ARX9*KaMfBz2rR9<~O7)YKbcT*-pP!JfVMG-2H&;2bq=mN#Is+n3$Nf zzgUnVz3lhjUB>`N59va#m0~UQO7Pk>M29U56|o>&ieqDX8d_Q`e0*fc=`aBOb>{_D zS$X-X`sY}n58w;w%c*o-4W9HpqYDZO+6QS1qqefLihTR_rRQ2ji_PHOnR`6vwwIPH z0X*%WiZg#xoj-T3;a7wIIQ^WY_nvm9aw1BSa2te>$>PtCw!Z5bWA=?i3;nrN$Os@d z0B1-ioM6k%1nE(z;XK_k;?>bIs=bRSKjf_J%a@CZA}(K}IkiwI5Hk(rDz`z5xT6q5 z!(SQ~7l(Kj{!;VeODz!$Pf{M_{&r3|1Dv{g^{Rg#6sJNHx!STZk&_{x)j-~|xX;c- zo#mMFdIo)*4sNBR-+>I6StNT_+$N$v$L?B&G?AnK^RQK2{l$MjYz0W6Z2|lqj@U zX$^lWtV1w@Ol|oA$gWABqmH%d@d`6`vf+sIv7pv(Aav9;HO==nw90;vMY=&MwBnX^ zvRNh~y_N4=Fk&IrP0h_n3j7VD_3+d-CJ%&cZ?m7Qgqs+rQa#(*LRd@T{VKY3E03TY zkvN65haAX$8uG!JwkT!ZU(&Kkv#Kdhe=dJVe$l3~KiC;GEHZ7okY`v|+mqwUtzZ8N zeY-uIeGlnHv$$#e;~gIE@ygdU4v8A5w$EAFaYNh@tjl{`D%>N2`cy&_%< zMCg0El}yJIj7Fnrr&Uuf6XFKCsyLaF(J*f!TQ$TsQs~7^11M}}lBg2q0LahS5 zqN6$$@q?yOHgd9|KxJ92ppXz5aNK`9hP9y`@wXaH`2|Gevo(y5_cxF;m`E0dYE?Ee z{f?4RKQ+tp=yp3#l zAd;Rcn(0l-W!v)9;dw5~5Ijz%v}H(`-riodM~}`G4~GINu8forAl(&6m)(EN{Ct%& zG57rE3l$1-ayVbVey!HWEnyZ(B<7DJv@97J{n&l>FX0HJNWm*gFtW4DkJ+n>TMDg7s{i&0%z+0~95sC6@Wm z9+p9NnVOoWfQ6oJfib)c2rz%1{T|)1n;IAp;8A(s5ku=ljGKq&8(5-^sSw_&NCoVe6{|YlI z^4zn%A1~MuEpQH{Kq2S9C;yd|BB=UuhiOK9Ok}rFqEN2_Gevx1)Y3`M#)cbP z>eG?CgoMQY!9hh4GxO2g*x2dSvPlGmNXf~uQhegN9_DIFeN=yMczhjc@f`Z{lpN_| zS77k&Yo{P5`}H`bZmU!D-?2HvZFf>6>F9Xwoj33~Fe9Y7*}68(t5@##B-wi)jDl=9 z6DGPkQsNJ07tHW}d5^_Qo&10{(-#JXPpoJoBS0TDHa5~NF_cYYm&th_?Yb-!JDQSS zh!k~MpP)mU)%Sk|R3-kbR?H_AKMlG;O$f$u%RF1Q4@DKj#9Y-n>liO_X->BG)xYNx zl<_>CKD~xKX95T_L9ugZK+DkkmCa}=2FmAnLjf`P1_e;UADXf$9s^!(oa{|b13CvZ zJVu(VK&X&jyf~9{$SRfFFP*QMo|1w>*)RTNb2$I{KKp-`ql;|m`%(T9VZiF zZ^7tRdSx6B@bO5DkYgXPeUKz_va&C!k;n4rM;Ua$?$3DZFoRq)Gc!}=h;Hrb3cSxQ zN zRNsN-ZgHuO_WaIg-4|Ztor$7F*2AC8lMPF)FJUFN2HL+B{m+vd_?K_l%07Em0UDC| zicsH-!NZ5Iz>^JmA6Gcd)8;GigI}RN%p2Lv@yLHq)Xd!(`laG_u-VSL0mxu-dVGKm z4&HPXmhHm?1rF&=cgXFtHdaAQ#Y*w_;Qr65&f(tr`ZvqgL`ojLh1ClQyW?(?$QA-H z-;}K-6xra4jEa)dj;f2SDM=uv7#A0zk&)3_j-0x&iAjw3~lurcO zX+D4DR+{FAX72^vGFv$hkID|pRHUh)*gQ<}ypXl^<;}Bfz8$r#>PT%iMYryKaUanEL=69LXAw(f`qm+y z9t=YED5P^21P2)dLj*`Pq`d}MDJv^Wa?R1qFF|W-uqOUcFMidJ(?vC@X(6JUi4vo@gp5DM9SYYbJl0 zYA;B|zV}~*y7N7~V`F1O(kmD|7MQfTC}S@UyoVs7P%%9E9JbuTAWV>_-qsh8=0S09 z8gPAKyV1CQBofD@sMl}bvWm;g%9`?KY6XX&(MYFJ)B5P9ISY~h(4nw4gQBu>?cBzo zM`&x*3xEG2j~&aZh0(eE#klKLsd3rc^nM=`Op z<3jx?JbXxjxYMY%COWJjuTVwIn$l9r)6-M9S%DB8*@55PDE0>9q9Hxj3h3ybwdoxXF{G8`F96ZbD$5Fb>@2aB=21{me*KT62-d~+EY=M} zpVmuWNn@`$*&T(H@KYb&Z+QvutDM<*qwDtctMBNnYlP0smg)~5_6vVtc@BRzOX3Vb z7qq8J#8D7irM^{@+R6i>}n2SfA53-Au&hL9KV1=C1 z+Qt5M0oFpEO0Lj zXT8a%GmHE|)?obO?&GHSpbdRbD6nt|{gRUz04&a*KTjg$Z;XFJT~t7N0lL!_NbF)4 z)VS#{mO0HUBPVbI0uKr8|1~SgDkxOtNisXul~@f5(sa;MQhsB1-+b!1wV>SVgsVbTt2G%eL=Bv2itfI?o6Lrp zJr=Ly;?70i!vTNPo0&09fSl-9!ycOQZ6=Zt{ns$ha}5I9N)K{*p*NFc#<8OOM#_%4 z(|D!J1W(trJExMYY<|qn+)t4^y@yDs28L~30D7f4 z^17@k3o9$gT~ajyAd@@WUB0K}>`~{C2gWm$;#EPPAWcX|d+UMHsr6$OPRPNsVk{5R zRen9b1Cj;we;bYky45Lx*g2&6MQAAD|JUR}78wiJCz;!iEIJ}|F|n{V3VlxqUNABW z2~nf$7rK9$kUiWM247i#ZQvPXTM^m0-*nuOwTbV2ehN}&3gn)GgF_K*ePeJSQPgE@ z%*0M6m}Fun6Wf{CwrzHdiESqn+qP}nwzc`NwYy*K`_bK1@Aj+i*Hzv9?m73ILljgd zn;2Hi8QZ*We&4f8frn|TfLT_M7GICHgdGoO4kaPfpi@} zk z9&W}BIiL9OGnYH|j;lu@W{z!X$2+Pj(_`njdQ`6QQL!+o`)PIb@bryEBsX>i)ky9V zJ^NTan=x^KtesC%a_AkI1S_p}kf}U|3&p5;GTqoH=23~+s|oiWR)U(fSqh}pZ}G$2 zC1LeNz0trIMGopFd1X^R@@#bC$E#vZ79p`kj7i9Wci*yd&em*X_<9_Wd8%KgQXvH%`mwy~kG=zb>T?Dh zt<1~%9OWQ%gTng-zNi!t>5Wn-8X8#??w*_Duh>lZ4l$jG$L+>YoZ;qb_{859ozkGEZ+V%M`Wpz+azW9N^?Bm^j zQInrDAKVtU6qCnE%KqeJxaXi(_u-Pi|FX` zh&aa&iY3JA>^%BKYSll{T#t$#w3wNh6>T@?XAlqn2r}|cOFmj>Y}yxSGnn1jAi&2= zI*$^qK`S?!@+ZnKd7PMt{1XuzW(Z%xLm0<1)!>?ZPy3Z6Y?LvvI0bqdC%rAu937u) z&#R4~=bZ(k933|f_x8eF7d@Z4%$d|UFD#6glM4PRoNM>x={$pe(_;Rm(zV(O4!=Ln zw-HGR{&_bwGgEU?M8e;+$o8_4Rv8h&sRQd;d2>_plu5uP7s?$>$)r9b5qiUTvt5Qm z2jZ8!)nERYCr`!>YY1G)dA;13ZD|Y1e(U0g`8oL|ijc-F9GjGuHq^80EkeRd**~5c zaIq)+dN!G{&)?9>2pV9Hfq_x^!@yieoN{j2hOWq|Z(UYQS{fa69)&_a`lPOvN6ppM z^$1hDuK*^g^9v=CH%B^={6~8*EEcL{D;u3!TwJWdQvSaG6bXdK#C(6rvn9nxADz1S zez&XlzT_W64Yx|wuhle>lUE9^i<@g;0BuB|uUgcnKOdiD@tS$oM@vJO)MO)7Zj@1r z6#z+h{rkEIbgbFsaH8kHUbIGNeIL&o+v2nh1O@8FnrD@9eX|n?GmCx>q$?^cL&l`y z^YZYC^?bV876que^xBIFEEwqGVpb_9fl`vDLBw8v~u#-O0O80f<0IK_)i z^0Aqgh&0D9SQDZ9cFD4}$JwQW$}M_iii#!VZA88-Cn~kn;ulS|KuD-@rZXjhf6|E& zzlDQmX#O&meQ1<@*9#$xN zs=l$o@~wCmx*2uTYP8I_Q`G-d!?})9gKwPQjJn6+j(_c`qY?*()ockAx8tW4DD#jA$1xCyW1SJ8hEMd<*!aU&xWW1<8UqI;N>Ix`3( z(B%U+i_+=-Y|lG8Kd`|1@4B%hRo!r%&GxZCt)H5+fKac>x6hGxv+CE1^1P$MkIriF z=SO*f7P71}p7*O*ox}gqj&jESA++ZKs=hMn&O0gMRB9d#eDupPn{Y zU2}ReG)NoD#9hQ^bMS*Nw4>OK5yLGk2$Q{#0UBAc?GtHWceVZ>zF1(oP1Y_#Sl5&!7ky3ATM#EsB4duYJ&^?cPYO8XOLL|Lx(c=Be} z9AiyICmr|_oGIVm;8dj~O!|g^X548dG2di0z7bHE_pLl+((X4JRM+!$9d|yJj3>0m zt4V&%#YQZ)M-7Mk*SdAxp-!9axGpmE9-lVBp^C)@5-A{($5vl<4?%Ed{6v|}<<(dy zOfpd0*7eC+C~qc%vr^+9Fke@{dA->rr@!#W%-H;;pSY}`ATTcCJg}lGUZo4jnXl&`wyjizFPKmX$}s(!g{)ZjE@9u{sjb4NVSD;Iy^1YiIEg zA~`cvS3bQM|8Re}?%Xdbbj4yVm9)c9!>8#pV{>pSU^j5N+u2no{yPxX zWkrOAQO(9~LnykM-}Qd2nwcrLSE57Xrh9*SdOCf4y+7m3!wPVe#9FYob&!DyqN2wK zd7V%&9-B(`c0VqZ5pI+JNzg^gIZEn)g4>xsmPRzd`_@7Rz#DI_%QZdmcvvdU)3Rh? zW5)iRxJfTdbhD48#3Vly)&;eWbr$Kloqcij4#dZXPx;j8urq+Hf^Bo}heOtNz3^(g zJekTO4+5e~x$6%#L? zLDFgLFFCOTmOA7sQdhg2r&or?t@+|Az~G^cJ7z4#&M*bk%9hkSXiDE#T307mU+*C? z3}j>`HD1kKR)_9O4Lh2v#_-!0(6^=M{T!RM2EqrYCPz4HrH<6nIdL^_QiL^ zGnfud4(^NjVHpH?&r9}N4JZ3Q#!tB~gAt+IAmCvDIyiV*52Oebcu;c`7MJhyCuUWz zv6h8{8xLwQcHCJ2jhl-5L{nQgN4w0 z@K>XlS;fXpD2yW)LZyn%iuSjfgPT#hOF}^1@#cO}XOo|XRks#S^_{0y20W3zD+Ga> zb^`&pgRc5mLT$_p3oAY0rmO7>2oDUV@}UvbrDLI{w#1?5EOH-N^fZl+jb$8e%C>EM z^QNiFVh2wK?_Cfn2GhU^UVYa2e12Xo+35w-HTgwmk0T40oG#$!k6G$2;{iH`%*R>C z?f&L^lK$IbWo5}nY1~4W@fp%GB))C)^?eSQ%}wg;=t#`?(lgLgiAz?Ryv@z{wQ3VA zBHCHOYmnLU@^UJh9qd~$1oS?4$y1#U1_x_zY-FALdMVyN^uqI(!{~Nam*$ZW{dTLC zI0%M@F0d?ZpiX&j>0e*>y3gch@bmNY=zLK$G%Bqnz*W&fH#CwLz9{Z}%}4;Xxa^7ACXKyO6>&2Y`EMHwoiw26{1O5J*}5 zmYAp<-=M6o#udH-; zcgOiM@K`*YO=T11kXM%M6>jPoKH)-)^&2-gCYGt??VcPwoX~f^qw5mFCo2J6_3-rN zgmbG{-qWEO+hHzdW@aijbXE7f!V>B)X1>D1oxBMZ7Z+!(jnp6-&V)zuwaX@_G8gMr zKe9JJbozs4D+RhU-RXx@&t$QbB=8G9)uPxKGfgvf%_c!0GAq1kPt#FS|A!D+#X&^y(kECR9c;{p)VHP7Gw6QxCK3r&h_K^)pN>oG8p_8c=>(UH_H1^++`O6Y!8BhC?E4?wCLq(ZeTgO z&K8JfCO-5v@L)n2By!I`z_ww{l+1OT;s`jQjb(w=f`)}?Q&`MenH*}q^DDg7t=C`A zE2|q~N6PScjM;*zL%JR&Ukuic7h>9P>`*9=i>g&>%eV)@v@ixRQlB6 zWUAi$y{YY$(@uYv5`i`R(DZuw9*hPJju-5=|1_-0bfM*UrX@pV$y z63ybVX(J-tj?p?ktZ2#_#j89vrh&z@#tTSjUXK$KE#CJ#p12Uu7($&3`&-QXVOD;t z>+pvll$>gts|vGdi=4awEWg*|1rI>wjVzHIIYW@v6cMb|&=&svkmaxI1(iq&Lq%5i z7z|#^bb>6}4*EKmkYL}eDME@tZBe_qc^TP4g8BhWnQ7!*c;vP7o;U_+jh=*$>Df#X ze5iBI^aDvBPIym}E-dw49>P6}^(N^lU{I*dj>9`g`{6jN3)`KZyZyZ3aRB?1G5Tk8 zX-5xOVu&e|)+BGCrzxvRb^Asg(kp)L;-xdEl{k0bZV+$z;M$~l>eC;w1^TYdM)(8* z&myyD(6p7Ai)3F_0)E&iaMf(GUK&!oSMP5M>okQtE|&tFo}jpoAXB=#%XH@b3>Kom7^iLN3okFRBQLU^BC{Dp{G%J zvXujzJ3OsSND-P}iWInFuvDB;rt1-%9)%!4YA?lHo74LZQPImc8aOsLgdX`lzN zoH=~s5yD;lQA-4iPm~#Xc(|K)X7PP@$u5M=BUHa8b9MV~pGh4KZs$f6x9A8HdA3G( zlhiqM&DzZx?a<7hwkK9?c*ugbAqTv&#fDB({EBVD#xKY(eFgZT&IN5eayE7?GeLP? zsY{_ry=F3k*MOIZ^S64=dEo~y_);5M%59ZM>MF`esH<<|nTp4?=_``j8i)3`ZXE*C zU5!wi@3v;u7gp7!g|LIzf?Y!QUWt{^VWIV!1|60(nju-(If2wBG z`7+}+sU2w)lA2VXa`%pMUC%3qxq@`2#o~X-4SyIc^|uZW5Pb$sn|DN&B$*LJ1jx=mF;a8n5uhEm%w4_FpjH3BHx2R16d6NWi4K zVb4JZDG=hf>;~MQlf=Yul)*Oy+!BGyXHg_4jsyUnOwp?rUA5)VFty&B-X6q+zBJ!Y zt6R*m`U_;b9i-{xNIWsZ~`)1_7_x%cu^y|~{L1pX+JMa}% z0(;BCvOFBB1dX+~ug%!Rr-DUpi_-V*Df0%{H7R4XtB!T4w@%(>|FN?>nQW?Oe&E6> zhT$0%gjT~{q!_f@dY$t63(MtU%SPTEhrHWHVL!hB8jVOQA0NT(S_^tAq8h)4g(z;< zcqQm`Opw3wy$b=v)$Qx|N*q$&yvVh#j@A69ZklGI0kxC<)exf&>6M1EG&W)aY#ti$ z-3#IokBv1ygyKHSKF#A?*&B1|>_W1kO0_^%W4g0=q+tVsXO*z%ySb{L8CbWJbhoiD z^w9BB6Wm*aIY1TH1>PRZcyK=K?Z%rgl#-foqb%)9T^~)>uad**koDa$E+W-&r?uL` z!@aL*6^~X-HM~=4$lLkgu?ZEqMMVqvDHR^V4x5{j6-5$H!g6N($~lYUEy@}r@K66c zx`Di&FC@WAnh(F##uqdv=j$8zL_4H__k=2oWX9g?T*XH}uI=P?elf|yVo;hud@5D5 zSe)VOh)qw@ms5t%jfSXMPl8>CJsn}3bf*Qebn4;o8EPst91%(Z?*55{b z|4ciFaH%-=@3bfM0rm!SCRS3`S8?qjXEC>khnpITN$OFv0=n(6gyaUurFV*U2|P+c z5YD)<&cnJIF(04?Ta_7Hsq8UVD*RV@%bv@7zZfmoENab=VHC&Z7N)jiEhSE_#-jV< zpJ4E#*scNA_Ht909YJUYLsJ0!orNdjm)`5jN6ce3!SmV%VbEGv3^cC&F6VJ4oQD&- zv-b8|h_qE7D#);a0r-3P>eESPjC9ip6z_Y3c__8CWPq-@{d2Htt`(P94z2td(={8c z<1O8_2T3u_^Vt2gdzVj5|Fcx*R1JF<_}yEU6W-y)O2KPBHEBUQV>Up3J4fl@^9!NC znTnDxQlBY4?kUF7Lm~`saD{}y#9Y@1{Uk#?M?< zX{4uu?2aaX&QeU9K&hI%w)iJmkw0SDXqn@^;me-LmQZUaDi-*=h;r;VNXJD8sKLn{ z;j*inpHB6TXB}2$7ry~9^TD8hPKI;UeyPJ%1;E$Dh=f+VP8GvdoZB)a3fC>fp4#^^ zW4ZEWKPJR{>;aFJ7B;i1_P&GdHs4 zQG?zdW&gLKUSp;T7eUogg2t0c>U1$(h1YusC9Datb#1kS`gnZ=8R(Z2sg_*A{{uv+ zR!comZO!M|vDpzHbK6tE3#?_){-q7J-w1|P>S(bNilaXQG=X;C;kR_Rd<-~ai>u=~m8 z>|8L(svA4_IPp?!$seTEX6TlzwylYcfup$yJp{yn-f=)tYG`uu=7rK0KQ?5%u#SP_ zl(=#?At68h=p|PLqsGnunYz)z=^N->VXd1S>_CzIbb&;WjjyJum3`L|%>aX$NXe z=w&gRU*V4+C#kv9LR3Z6MJ?#eBnwq9A8-aDM^_={wjY|kEp^ns=@^rJJoj-dIy#nI zbVnU|zQ%x!uz(V~puT~Umz;s>eCk5PWE(rqYgim7T`II{V$Hfec!{=V@qQl8B3O0Q zx!AdYv84j8?F!_Low!9BIXJv|(!7?RdqWO)MWuaaPH6^oBF^vYOYx(D0Y-!c5ve$i zJ4fn@W5+_};^{ROb+$zkJ%TmLaXe`nh%rx0p*?`Y&TcuxogdfN#R;5ck2dFGln|w~ zIa9}1-M-r$MQTU6e?m=udGwmwj-be#&M02l12F~@KUFL%H02<)v#sj=pXOq6eZ{1s z^jZIRHK-q}M)_(r(mh3%HukV9yY+7r;sy@_6p8k{%Q=-W`BA-Cs4$wVtD*S#&ImX8 z6$F6vq4h|*QF(8VjWQVi>T2ydgNZwV_hr034yg~#@N49uNeDmn@|Othuqb$UnVUnxx`Iho1bytARjHXJ1PG67m2gXU3cw~ts=rAqXZbu5g1!iMJVAo9d*T$k@_y%9ANj}0 z$RJj-s6NQsz`fR=3c{%Q&AOL@?zR>f%w&t?u_#v!KU;O_OKX`z_xvrn8vb2I#ms{AjMC>wS9uw4;dC>avJ)g2;~FRc*^h0%Uf)DXT?@0W-!SBm zAU-HS3lc0%S>)%7k^DBWxYyW+D6X7LKp$cI>PZfvAf=q9dBXn}47J|QbqWf|v%_Q- zPWTBk^MuF(C)YF964_0SHjdwJX}zni74r{FpfnZ3c9-`_7x$am+9Zlqh)x-s%Mnd! zliiQnq)9PVC-&qUIZwn$NG5PDmW5Bkh8a2>c1&X*t}5~Mqzd`c=YSQ;iu-h*m&GF zWXB_Xos-3w1-js5W%8KT*se5fL*&VPi`92P$Rv39GE0sz-rtCnaDR8z7xeTi?>U;x10Ox4tkiA1yj3}_ zNdNlNE3*}jK3~(mVO*h4d4@l-BwX4C)EG8!y@(*_qra%xSIJ$W2b*yR3G{S|mUy7I z{e{%;&)U6@y%-Y3^48`iY|eB z!}SYdnfwL`d&5o(;wjoD1$%CF3lf?9HuZbIYwmLuhOMbYx<+xGa}fA{nA{!@TUavk zV@sNO>2v88ORyWKHygR{ioQ5#xMVP%ltx>2VP~vNHg$74I2BsPT#BUG9FmP@5YV*S zzTobDk1T26zO+~YZc)mfNXj@kZIsJGSiTz%8p5()+lMwfYXzC<`<-_a->B4w`SuGz z1{(W_g(}O`D$-1nXdgr1Tojg|LiLT!4L9HY=Iey>yQ$_Hw{KWn&gOAuQ51^#Bvvb& z_BTCq>qb?pLo$=)XMkmUfP>nL!~fU1B}=pl-kFCh5p;?R+$ExUshQGB_$J0@6WTW3sH>5WBUv#Fenb8u9+E_ z-EIusBKj~vZ?J{@yE>RGi{o*G3jvJ?soemP!yL=5Q^21!q7uDDu^+;MoH&BroA|>p zf|}0domQF zN!)Ge@NYy|*6sdM%9%S@XJ3586J|=H-MqrTN1;(a6>??!9wKR5&Df@_pl}uF&C_xu z3@f$k8sTil|0QZhB0!qpASlSw*(2RJErciZByyAWJDV z({5Z3048(ourss0Oz9)MfQq;^X4wLP5HoVDGptR)pVL0fBgLU^#%nIY2tloeQ}Fkc zt%rezmg`Jmnw4{FpfDK){E_piW3=>@;k2Vby^htmQZv18Y zPrH7Yk|^Bx`??i2lv0z3yccxVyKqhCQq*7Xxs>Ah8ydm25DS)1eyLKeKC$*Hh5OPI zwS8LSPm|3N`GYvOyA+{3Ema2shaX022Ej>w7)!CI}zzb`+eV5Zt2XbQ+K}O7hA(d6nIcW8s9??14 zClKP=`skqT*m0%(0Tt)7GutIan_PQ#VzR=2JtD(c`(iAEpeU94igltulGMb(0yd0XH3A8GFz9knqe_##EHcJGG-VRrdR#YzyIBrm65fNU3g zy!+`F;oA*4Zd3(n*!}iIFJt8o1!DIxx*clk3`L?gY~ktQq6{5{;i50(Bvm>zasV&o zbXB;;4emer`87czMDM9AXT*NY2P|0c2^FuFUn*Py5Mh})k zxrk$D9Jld@bJTWEUnh>+V*i80|lX@^ffE%)3hBVPxLf%<&I=@koO5R4}+>C?Wn z-n*m~MEy(_*(H(&$II^@z_EMgH88E}^Q-0aZz9DyLndw8Z`hQ2i^v)JVz5i}oMFZ@ z){`KzbnVGysr+t{Rp_qSx)3z7YNiy~t$3)}w9xA_5my|F2!?t70rel>V2sGQQX2v| z_+5{Fuiy1?a)EhYA<589!=qoP=HM6fLJ$`|)9aA^xYl-c-b2dh1srUaoT6u_nom*& zUGAtk^pf~4l({>$Vj#rpJg{~7n}~aRU8DyeQ_K8CdsLVrum8N=rLN*PDacAO(0Ke? zu0FnhTrDI>6Lsi9TN7;l4(Qb%?-Zt3%J3)uyk^#7SUCfl@&?(4@ITkudxJ@cA6d2C z8y#iNShac2D+7n`06)fTkcUWL`XE}}Cb;8y^R6WBhq670gsuyf+FcLtJ&d!x{{6LN zO)R!r1!=i%PM_xhl|7Id9)gH)m$>EqMsxD|D!FbQ+c|L45SH~PNK6nFi@J7>%nIF( z?va1Th(TO5EwVxbS?)s0tyB_QbdM}bohG4&UZkw8rs}X)K!9_(+*-D2_}yB&KCPX( zjpH7q5r`?6>$9;FxH4(STAyMtvtilV>PCo8xF54{$EdZf(ebqDcbqE5&w%wn$+&+k z_(7BhGeVbj#UZtSV4&EKuwloI6uM1UaucN*|9qxHQ+;Hj0ZYGyfG1`A;_PGb`$mc+ zDE(^g$kA8;pdc^GiQfD)qON^oDsKQgO*w6?Ru&9v60?X%h*6ERqX5f>0!x&Y0iR$V z))%46s%XclU7A3t>S9onv^JtcDwek6;v~u&?&UfjQ{aT}IUWulf3l?GdR!P`9O#W3 z`^ceF$)203RR5+^niW}DQM5*FBBgV=T@!UyrDik*ELhev*9aD`PKOlNtyj)c+P)XE zE)-xw>rMV*$q{xs<=FkFl#O38yd*al&vUhA9YzTHZ2=1m#AunYg<9ce?B;#Q!SfX2 zwEicdRH*GRX7Qc84;abM$neUa(s!UH#hqTNs<5exB6xQ`qeivQ+_*Yw?pKrmE=>KF zRA`pO7yn_HL{R_`5u$cqVnPqLDnh$~lN8t^?m#ona4n@uO=$KynoSP7m>Uyhrg*2+ zB(dn4*!1T$N?zaa=*2_WLaqfT3|{w@bF871Axz37*#F*wQ2wz5h9#`t+=bl=-|(iY zT6*`Cw4tH1pY*5SCIKJjo7sLj%QpCy@&6gZafjay< z_&ACL^z8e!0_m#+<1{!r>uQxCG^eDtH&t3o z;9jef%0sYcbZY$|)qSf$G_w6WkC)`|?Ec7D{#mhv#E8vEB-ghR+d})8GpKC4fX7FU z$3Swr20cj3-8C@|$nqWHrMH6i&Af)ocDcvn#nc^T!-FM)7_PTajSjKi%NM88hg_J= z$eyiV#M|U-JB!9c zZH#krz@L6T)y_YUPpyo*^BbQ|b*n}`;s9^uOx2(DxH6L}RZ9LhaVZ3C(V50N%9_^zwL%66EdO`jJ_cgrdI`U-V(5ug7pCs(nip_LNi#$q~z)!GxD|^^$ zpV>7U9>cB|$(i3{>cbw9AC^Le3xt`)S)KRYlli!zW&?aNqWkw2X&I^Z*}O7>p%{Mheg zn8J`dl$_c8^$RPe4-o8(IX>Zt@Dg^>N5Pq)U4pBhL-K-`oByvC*a2g3#~4 z+%O?Mnyd$5OVJP?gWBRbE$j&YMD=Xg>t-y$Cr(SWdU?Nr+unWDK26wD*zs%kIfXZY zJHAY+t?I7~#BeBr6>hb$_&D>Ap}9#>Ub?$Mbr!J7ml-KBq_Lk)4q(M;7j zf2H_3osA)9*}UXH`oT%k)YfVhw-~m( zdfy&P{EtyK?Ki;-+8P^WJMmqBLb*_Z6MsHSz{BB^1CR%uuwC`NvK^y4_o`had?@E{ zTqHnT&4|glmj0baLxr1`m0;QRY5vQO#%iBpPFF2xfNf@mL6u+f-^wU`!~^nGmfi=* zXLr_9vo!B+)|HDD{~bLVTHT}0^5@A=@$-(aiQrXMT}5$3<6A-f51bdeWx{(VVcqc; z|IF!Qbs)&h$zvdU(INmZc{0J}FSWIfRF3cP*ubm(v&)lS@;7#3)&r&@zwQiFWC zE`P5TLM4XE;M*gJW6+eYbn~bFowaZ$N&1@y2uASIe^cT{Qwj+ZOev_INGd*eLj!Fb z7M-jy7nSKfaDE|2-nV^!$xtZ;wvy^=@8=0?P-cE zGM+6voqb@16xJZRcIUWSSy%2)yR{d2YD_v{)yO3iNZ>C0(*IZ@0KuFAm+&VDM_Odiv}`u^%5nz8myYxKJ+^ zdfAHs{`RXn$1CGry?i~V41UYj{^wOwe}QBSV{>N?N+#m#*}u5<4F+_6N38aXjgB^K zZ4onq>W#WTF+!7y8czQV4Zv$3k!<&%5@AD2#&ti!EW7>ue$2}uq{xx1O)_yn1QY+;v=+OBYP< zDPEp7O_x;nZ-uX$o8FKa)W5jte2QEjJeuFQRMh#+tdnGlJYyi^hrB1+88w8_3I8gc ziqFVV@2_?(x0(Mw^zvEm)WN>XrUjxN;TEq655ev@*Bv>VHdXos$$TEhp`WNAg*G4j zH}QPfptnAup>>y__|`?Bvk{T_T2sJfs~Db;d-Vn<6`piDY06j$dkOf2;A8e}L$X>Z zZ}sj;V_Ml>uZ?*(&Vv7QJD5~Q*#6LU``h9v3wV#$YZ4ec*f8 zh{wEVGeX*a*!hKIxk}|N9Au?`EKbaPwos-S+;2RzeWHkn){J&VM6zI=N3EZnZ0lNcJq5W2OW6zZEOl$X#_1SL1HiRdZxLK z5SZ~Z4b+o+PWz8bgwxhQi^`36{n!Z)|IccZ{m-}i)kmm<^_0zyj_UKe`W}Q=d5c%C zjg=3vW%W?F_rZn-)>|nuyYZc^ogWyM7gg)ZEGqh5smz$T<_|y`Yn^R=u(nR(#l1^_ zo8Nfkoh&;u7J}W7nRnrdP}F<^9^!K_;qh}u0RPL({GZdlxU! zbt0brCSagV!UbpxqTJ@kIIct~M$peHt7?rK&y`;6a1%;1P0ofIivN_aWztME%Tel) z!B@(3vmw&Z;ry49Buc(qfl{7gR8X2h+0 zM7#)yI9KX)du#ZtUVNW74)Shx8q%(AHr_ym;p+?VNpFs*Z&sGJvv$Ze;dSnXg>d)~ z?2mRBxl*El^iJnRF0u^m1{zq)?9D7MDs+4}V*m`U6`W9lBgYO8wtvImc5|r?X4>CR zm_}WR9m}by!-;(f!Y{B{N;lR)~5Ny2Z&*zn{FVEQnYp%Pz7_fV5Y6nxMe|jr+gE5!jM7+n zMh_4JBy>jx;>gxSKjMScX*t>Ny<}tMgP1qCnt2!FJVqJZZ?`tMnm!c>@Ccl+5T50r zxg<0Xd-bS<%vUhdYs*!&L*e#t5;#D3vGAL5>ESaL^bWK9Nk6pZl}qq}V}#9K5F8(v zhcRDjWlxlCtNmWU`Ta8N8{?*gS{&17E+Dc%o1o-;j732H@c_ z(RI8Uc`3v;WMRAF$6$y3QHtFqG){Bkt+drItKJEpM-ivhVao@T@XMs?%* z+YvC9lm*H-^67U=U!?k<51GsL&S^8;8MI6ue`!yPJfsvdJLEID9q#_Juuf?j7_q2W z)smUsl`g2>fA^5vg;rW8D;HE81&Vq~Iuip?oahHe%KVj(oaRS<_E7F5S(M%=U3SJu zhM=laBu%+0v1GW)rm>94Gh1qOhRAAm?rDsN>cZlxr*9{!5^dwDoLmJJ)gvLQdvULE z4C#g`Az!IYVmgH4h-*OCl=~*u<P+Y34B ztma$jS6?_=Rdk@Uu`lAETr}R+#*2qma?Ta2LTdGe2%PGo?dz=lY z#VIXiWR~b*aoFAsi;?B6A)nxc5sL*^+GLz0x+sC1W;=fr^;k=M) zO_n2XqAm%_eF_HJw`BJoALHdjaFIgXnL{B%w)9|5M6$Y{tsp@MVsfA_JX5x?2DY@m z6DtY6dLC* z&#zqLkIpzB7N_L*eik=Pc;AZce3alKZ-oeeEygsz(9lpK=O(C8a_Y?pOu&yb=s7tj zLTuoPRuVA=(-TF}V?^e$%#!DN^1)r$*j9P#?bDe-G-bO&?tJ+lrr4@9{0PWjHqLZl zacn_kfK!aLMK3)<(B(UN_ap1Du4Qna5uqd60&ShaqOK(wOMUs)SA7WZrzUD9pB(!* z=B~rOfy)9tqpJZ$`p=B805LsYAhXk-w$g(rLvfSkG^25T`+o}qzU5fZ9AUX-Aq`T3 ze;Twezpbw@n`%j##`gE4U2U(^6C)0r{HEucjM^7s3u! z1{U`S_A|~iQzqr`{NyYw;fd9HMQiVA3zf^et=fQ)35dQb+{}tfl X9ryb87ZNN8EJ*m*y^jI^(fhvuqp(z_ diff --git a/examples/acados_matlab_octave/test/create_ocp_qp_solver_formulation.m b/examples/acados_matlab_octave/test/create_ocp_qp_solver_formulation.m new file mode 100644 index 0000000000..a64c9253f0 --- /dev/null +++ b/examples/acados_matlab_octave/test/create_ocp_qp_solver_formulation.m @@ -0,0 +1,98 @@ +function [ocp_model, ocp_opts, simulink_opts, x0] = create_ocp_qp_solver_formulation(N) +import casadi.* + +%% solver settings +T = 1; % [s] prediction horizon length +nlp_solver = 'sqp'; % sqp, sqp_rti +% integrator type +sim_method = 'erk'; % erk, irk, irk_gnsf + +nx = 3; % state size +nu = 3; % input size +ny = nx+nu; +ny_e = nx; + +x0 = ones(nx, 1); % initial state + +%% acados ocp model +ocp_model = acados_ocp_model(); + +sym_x = SX.sym('x', nx); +sym_u = SX.sym('u', nu); + + +ocp_model.set('name', 'trivial'); +ocp_model.set('T', T); % prediction horizon + +% symbolics +ocp_model.set('sym_x', sym_x); +ocp_model.set('sym_u', sym_u); + +% cost +cost_type = 'linear_ls'; +cost_type_e = 'linear_ls'; +Vx = zeros(ny,nx); Vx(1:nx,:) = eye(nx); % state-to-output matrix in lagrange term +Vu = zeros(ny,nu); Vu(nx+1:ny,:) = eye(nu); % input-to-output matrix in lagrange term +Vx_e = zeros(ny_e,nx); Vx_e(1:nx,:) = eye(nx); % state-to-output matrix in mayer term +W = eye(ny); +W_e = 5 * W(1:ny_e,1:ny_e); % cost weights in mayer term +y_ref = zeros(ny,1); % set intial references +y_ref_e = zeros(ny_e,1); + +% cost +ocp_model.set('cost_type', cost_type); +ocp_model.set('cost_type_e', cost_type_e); +ocp_model.set('cost_Vx', Vx); +ocp_model.set('cost_Vu', Vu); +ocp_model.set('cost_Vx_e', Vx_e); +ocp_model.set('cost_W', W); +ocp_model.set('cost_W_e', W_e); +ocp_model.set('cost_y_ref', y_ref); +ocp_model.set('cost_y_ref_e', y_ref_e); + +% dynamics +if (strcmp(sim_method, 'erk')) + ocp_model.set('dyn_type', 'explicit'); + ocp_model.set('dyn_expr_f', sym_u); +end + +% constraints +ocp_model.set('constr_x0', x0); % set the initial state + +%% acados ocp options +ocp_opts = acados_ocp_opts(); +ocp_opts.set('param_scheme_N', N); +ocp_opts.set('nlp_solver', nlp_solver); +ocp_opts.set('sim_method', sim_method); + + +%% Simulink opts +simulink_opts = get_acados_simulink_opts; + +% inputs +simulink_opts.inputs.y_ref = 0; +simulink_opts.inputs.y_ref_0 = 0; +simulink_opts.inputs.y_ref_e = 0; + +simulink_opts.inputs.cost_W = 0; +simulink_opts.inputs.cost_W_0 = 0; +simulink_opts.inputs.cost_W_e = 0; + +simulink_opts.inputs.x_init = 1; +simulink_opts.inputs.u_init = 1; +simulink_opts.inputs.pi_init = 1; + +simulink_opts.inputs.reset_solver = 1; +simulink_opts.inputs.ignore_inits = 1; + +% outputs +simulink_opts.outputs.u0 = 0; +simulink_opts.outputs.utraj = 1; +simulink_opts.outputs.xtraj = 1; +simulink_opts.outputs.pi_all = 1; + +simulink_opts.outputs.solver_status = 1; +simulink_opts.outputs.CPU_time = 0; +simulink_opts.outputs.sqp_iter = 1; +simulink_opts.outputs.x1 = 0; +end \ No newline at end of file diff --git a/examples/acados_matlab_octave/test/initialization_test_simulink.slx b/examples/acados_matlab_octave/test/initialization_test_simulink.slx new file mode 100644 index 0000000000000000000000000000000000000000..6882822e54a6bafb20d61c06844f2721325b70f6 GIT binary patch literal 23459 zcmaI7V{m3s*RK1-wr$(CZQFLzv7L@OosN?y=-9Sx+qUi9?>SZ9+3(&}=f_-Q)%tf| z_oy0cjya~X92ht{004mgw@3iL;=fm=K>z?3Z~y@9-xobGCr5V+M|UH2Z)XcP14b_g z`^Mx^#eQaViRVw)alK^j8ewRP%Mg(>NLm%aol$R@3ZJA)#lVD35_pY5%(1(}P2cH8 zv_kyKWO6unLu`ZD^Nw6_4z9)-2Z`!JsM;+&Bz_f?{)a{N(vY38j3!_n03f zE51Yg*UG`uaS{YvaW1f;_y*(jH#iL=jxl>FE(Ks`iQ&m2kzk@@QufA-VBRZLsy-6o zvY6$1vN@W!w@v05t1f8TbP$oqjrMuxL>6@hzc%tVto^7ex?@6|Vp|@Mg-zX?*&UDE zm=^S51;#ZPkWA-06#U~nuf*fJ&!*z~C)!#(M0Tn^!S%gBFx1le036`PGTf&gudOfB zYW@^Tih%M%p@Mfgfle`}SF!Z3%ORx}luNt_urI?t9~l>w9c`{7aO)(4kagY~gM|^7 zhgL{#!bl?9X9U@%S0i{RBIW-A-xsKP!t)P2`#gciD| z&nQKk!L+NFD-Q*G&5w;_US8Z`{8vDmv*vvL99J-U3GJNkb5B)`-UZ}}w*Z}3a$ z*d~Q=l=prrtz}k@Mv!^paqc0P_f@0polL`X4<{v4OK19NAp%R%#$D%Fw z|065%k23kc=w{>KVQ=GT$MpZAHnn#$vop6bv2rzW_)nVuKj%2_OEQ6N&VL63031LLY;<0WC4pGX0KO!Y-`dx1+W% zyhOk)VVQyk<&kI(eH~$fBa`pZVBJ8}~;8H?|^9g5rY9)f;$)F$}SNrkq|B+@VUJ}@C|HPC1gFx|rLojo4w6w8Ovv8Mj zv~>C(3Kj|Nj{VH=5}twKJ)K2r;1Vk0Q<}MUzXO7Z+3JjcqKZHM>Sih?mXtIMIldu` z547PBQm3$NsyT;Z9uQRe6&hZB|2|KLZ4*z`Y)J{Hg~~i!%jY+DmO(g*{}a2gMmtT9 z&M9ioN>=erKgz>xl%uuC3_&}~NT1k`FaoRM86KO@j8prbMdv1+i6yJ#)XGW=tns}< ztK(={6vGUmt$H3o^P)U4fKi`4RfCPJ383nRvx2fJ$`ollayXmh9GmD49tE?yhhoRKAk^=(vu>wb9($s2xjEmBE zK`?M4DJm@y*?XSZ$Fq}{w!wEKI7w+UX%m|66OwG4gq=k%%dboK>bRMi&$y@Koa&?5 zMiESgSj5!{2oG8UO2xXb-(LHP3`O-At)^&wBitGRS1?{93OkNK?lKq$W5DCi%?~fs&PByBqdL79MzA0ac|GgIj6F z2_ocKzb_Zl?*zS#PhMTUpnDWB&;p*O!D_3@6r1IcVy?6+sQ(6m%7)`z_7A|;zeV}~ z2SUQ@UtM;yadP}mx*Eg_poTDGL-;EGl0kw&{>lRUS;F)Q!tMfrOk$Qn?&vfvp44>O zrg!q>D4^2j!Zq0E&c_Z;DZ=wG+JC=9O~K}2a;LH^$QxpE#%@&TS)_~$FXw>M777sq zl3m*Jdv#|)ySM@<^#6ttahg$K$rOx`9+3MG!^GjdK2Eno`K#|x3P)9+uW+afTI(LN zn`fg#)zysElbdVg)V0uSlLY_1X5TsJE`izlZ?(nV9%`OM001{N0D$?wt97^ba4>Z= zv9V`#cC@<8uu@j@Z@;Vy0 z+DQ}{Su_v;@(WYg7FCvd)icKv$YwPa`MK-2YBk+4#f-W%ru*%>z5Li-cc&|+5PU^F zt^zJ{l8kIrjt$?V&qNQ=gUt}CF~e4ZU0Wk7Vk5d)#1L0gbMo|v6#1NnfP3Q;7@(X13X zFG$^X0Q6U$1a6|$gEU}KgcCgP>pA*c@V5I~Ji%`bO=~KPr@p2ITNYh3(NjM%XFT@R zG2YH)i*G1tgWAq>K4(mMcPGR}T6HBtJ>U`38x%nM}GX0j3A zb3E=R=WyrJxNb8RCZn!cpJ&F$$;^EQZ1|xgl8_AB-q+p-{(W<#pO6!=Ubg}{c6(TS^fpRnOh4B<|o}m zB2sJXSv%VN31Jy9EE10nznzlG%F6Qh_R=zyR7>F{W}>0s_h%c&Y;AqIx*FLV8Z4&N zJU0dStMpq@Gh`Vy%oD^a2!*`!dka!t5ZM+(2fNHnEGXg?FU}bl82;4MqYLTtO)cG6 z+WeI-d^=SQ!`mXj*vL9+uV?wr5_wzH)f1L1;Xq9PzbM}xbCQ0$^*0WBg~vCl)- zW+?Lf^$Qrn^TFS4u55UYWVGR5yO|Mi9#{z+lyvua-dH$G=VNL+ew#Z8G0~!L*x1~Z zlBEwVsK(tM(Pb}vW}~QvOZt|b?_eU3q7p=LPI6k_(~z^3jPToWn1T}y?(S0#^xrY(uwz4`N*Q&BEnEmTMv{E&l^AUfr>FD}ZZ#4~%&3GhA zg6hoj(7J^Q8Q1It2QES3*OHs4Bp3SNujUrNnDh(A{P{~wl&8M4z-;Jp3F|8-q;1G^ znKS@s!aLVxjuA+nd-$~(4N7KaX4*Hv*j$Id7)rM<$D5_Er6EfCNz@fp$T>4gPPiRf zM~Q&`YH@OOdV70IBU4-=#`f@)Thyj;Z@m2))Z4Jqx}_lzhcrMjca>`m!zVDe`gEB7 z@OXZjz?<)&CpxA6YTv$*5%;pkS`b@ZV;yopx z4XXWB9FFR(pql*u?jm}ZmST3Imd(*9jy^&qu8e6vBKuMm=QTAoQOCn-6W6+Bo6er1 zpai};YAV4;xy$9y)(=^f7Q_F5UOHAve5S+>flwrxq@h;+lav$_B)dmT$26^=)Lq}) zJnVX<|9y6bmaX|q&BDS$3W*RJ24Qh&E=E}nb=vFu>tOE2DmFUz9}@}qIp2le^ci+bJQ3Bx{ny!pv(KUM2iwFr z9wq1KtLjsSR^=*%<5jqXo9iOa+fEg_x{B#uD_d;rPr^sOqR+~Fd!T;8Xi;aV8Q!>= zH|df=3`)|)?!!fre888h>vZ7v*JkowXXjT`e2!pq*_gDUVNP8iBV(ad0zoDjQ30%R zJVSuz!3fI3ll(;FfcWUE*x&5z)^iZ%j6w73L++5nk&_er-pqP*N09dg+E;g#td-05 zi^J(U1@D>^3pH(Cn{(@%f zu=sWSXG52hD+yjylMz)t5b}&2q)~Z(76KlkOmiqmD7{(EC}qg|6{|Ml)s6i88xb(Z z!Z&|Y6qGG0r49QND-)AbB0|he1`v-XB3k@)Y7m%8*Bl=mYu)VhVxtDYWO8O|s&ev= z=6YikJb48To+3>f(xB>`uI`jf;CF;qKKIU6{>R6`fj?(-@v|@}C6Ua}=;&;7wT7mt zn1lr2kJ695_Iq}jF+C)H&Lp{qqshT^?E91WbmWZ~?Xhs(VW69rcVy>Ve0sqq<3aqJ z0Y>Dkt42NPXU}?b{X&wq_?vwB0BHNsCZkbjS%&kxO=3s4XcJz!tI(5iz`+&)7N=^7 z@g@TuQw~}aC=2Z-wd-X4kou2rgJWw*xdwQ!Nw*Rk28zPv84pLauFN~ZEEgA-O9uyB zL&HDBT4@>Wi$B0pQ-{g~*cZh_H~j<`kKD_kmx|Or_V|=y;!ACkvO7N~j^fq&I(k+d zb9V~m?mEqTISTq|8`C9w_rbt$jJg9biUdfUhBd>}Gt58x1G9oj_!&PJp9Qi&Wyfcj z9sT`3gBNT9{$9KCzGwh>&&p8cj~w28WD?XAxNW!Z^=8+(qp7+beYbAdISAfk+BSvQ zleLVTy6Rg|!D#E^fbYmez|23fU0F1&oV!X-h3du*l}^9;5VI)s^+iF)7=&0@ZWm*Y zm(c=BBe==P$hh`Gu6lZeN2PvR$K(sPK6>_+LYF5EJBkD~pB=~KuuzBFC`Q&9@aD{<- zYMxE{zGKzm!2C4$!%$J7EChz{D}XO@U~Xd?|K`UAc7{;PE&MfBAup>XvOE&?>sq(O z+jL1LJqj!s!Kh`r++XH4m{jMB7lU)`3f$4wDiuxu@+qk}^SQP!`fq(yC%dL1Fl=~A zVTY15lPVD5C(JA?TcYa7It})N3FXB5Pgw9VxQDN&4GM~I=O++q?J?aBKN&E1?(NJx z(DyAoX@&8^Fc`D>u0SD$o(5WiG6LT1&B;oKt|Hgv0GFEFF}KV8DkFg!VM=rd&N!zd z2FRueD68Aj-P?Q8Muv@Bf^4jSiIy7{0we6QZ6-Jvm{}Hi#3n7`&|k z)JSmr;}F~(YlqioWzgF_P385)szAVprNVakTD_>= zn*K;6LFI>*6jtAKycN|3{&O-OAz_o7^9%=T%=P8D8_-5*zr8&okGrD4%tR}HrI^X6 z>Ss*Mk>49R7CJh6X&J1CkhXbzUDBePCsXLU)z#7&R>nb^rqG{ZPjX`-Y4zoU1L{HO zjPqa^5t(G~iZqeUb1CEyaDVfY(8E58WusmRS2wo;Q?vT)j~kdZ+fLcCvbLrs9w<vIIN-_CkKP1H^oGA=$n6y28R z;l$rQb>@nJ-H62ag(d#}{)3zUHVh>ag@uKEVy`?rQk0xYybzzwe0Bcn)0o&X+-3yZ zDbJJ3+-Xh$&m@n9GrwnBRojOgzxQXp+0LX{xu%751H?)@sOQ6)9ki1 zW$u)a`LMKYafh-~ee<~e8G#}U&nDhb6%jF0H{z%CoVTPV75e7u6K3TUrxjaJeIfXr z-HBP0(?G7MtS^E{1{|lKI53^-Wpn^Q%C6W<-31pUrx^0Ny*>QQY+V1F=VMcT_sN$= zFN6$i;*?N2FCyf}G~+jPWTs0%=NrXOn!|n0Fk^$@{e7doBvLT@+6(lyiw+&C0lL!( zadjhE+_cb}2Iao=U{XZN!NM&9`V$~WZE;hk+M>C%+zV)r1I+`G)V>p^h&w&nTU&9+ z;og(tF&;_)Gs#+_eQ6@Dk52^hC)P<}kr`E0RY%ke-hU?uI}?9D&JG5<)!ff)sSbwa zGVjP1 zb&B_>b8bleOBO`IyzZJ?s}ESp7z=7IQ=8Y)hkGlz(hNBp<;IduZ;$8AN)DFzrTIvt zw%wZVgUbFA%_cTTO;B!QPX^z2e&G|Qlr&}&-D1DrvJA=tH!>TmH<@UHYbBT0XJMz( zkKsOdil05xz}NBdcx5lR9te&(@{K{_)dr1JS799GkY+>oMI9Yj8{C)~Rx*#S#Z!?* zB#m;~Q~yp5FoOrU?PV;Q6W5c8YDLb-u*gWX+F2FlT3)f^a;fDG?wAEMMeQoX zR=a}v8FPl9_wo`65lmb$9f`tK7>S-Sm6$ari+QI)d=B07&Q<_!TYQzn^%bG*w{xNQ zp>`sD#YYR7bkCi3<4L8S5f5F{mX~xg59fS?w0XyNo0jpCt2h$y_I5u!BYbF-%0W)4 zy?OJ1PBJiU632S8z~mf-kg;@PbTl26xtg+$aR)QfusgtiuH#_{FqsW2_4{04!&3+k zG9e+p?&_y*@sCK4iH8slOSSpA{fkM@SmJ|QJOXpLMNp~ovZ|sIbCW#4LaxKTTpMj_ zI$zQ(?*p|x;YtVM%n+T=#BP%-I=!?g1>ZH1~VhxAjd1wSItxw^)OCxBV)MeQJ2Sx0G( zaX?<`8fK#t0oe?DxIikwb#Bfa9swb^^n?-=xMOAa2i3bpOW2%T;aM#;U^V$+5lF z$2ZH?S|MOv^}>6<7sQ4vmhO~W(QU0wp#Cm`MlCFe#Sc1{` zY_b8?U&5?tB#oR@t8I4Ooj2<*8^ht)llfctE8nSQ{ov;Y8!eEQ9d{{UHpD<WhUTSFI>Ox`XvP*xHA2cRbDtOaw zY-D6(_ms7Qkn9r?qoJUM)H~41*sr6e@zGJzvZ!upskg3*k%Jd9!Z-nnz`($#2e#%a zJuWV8^#Jf|7mL4la;o5wU}*O~nj2GAP~X9lx_)3L)&Di=^R=EcISkR}p^y@RDIM6w<-Fn1#p%4Vt^~chfNrh~~QKrA{ za)0uax;kx+V{~#G(H-C3TEn&F8!zGY*ZVq3OD}(Pi?)mOm^G^+j`q-m+nsV!OS=Kq z876)A!jn6>P0RXq1yT1F{yT7Yn!im_snp~+le~i<7E%On<7d9f%&Cj0>`2RZa3UHn|m2jF&O9 zzgRq;F&+K)qp)6dCv8aCPfVij>ng~C{0Pi#(|RiwM;|SeKSV}3nWyJgy_%wXwUMwF zJj>6A6RY*Me?J>t>tvq9_hhbTWMo3R(w8adAjEHWiupA`>ND&;wjnOV2M4=Uir+vX zepK@zA|fi&3DgUr(idL2xLW17(BY1OwV0uKs)d>Th>w3jI~gbx!hD+T96ny+ywFNX zEuhkT2v5t;H6x~vi;exDL)-RjSAl~{{v)QXt+QFIdkPCLr1zPeq1JN|K*gxOAcN4l zPrG;A+O>Uj01maZBXFrT<@aKIZuSk4Dhmqb9T!^XG#mI)WKvQ?wo|R>H^cAt^6FHr z6o+D)Zr@Q=iV~AbNxB^=Km+3SM};E0!@c0 zzjQAzrmk+^dX}&RpMosN1SDrpY|v8}u)Dus|NAx)8qy|r!bLs{)pmhm+0dOrhIwgq zUr#67tFUkq@D~svoGuLWR<3n+M~qD)iJq~HC90t!YwB8ij)GST$fsCa*IVu(#>2(t zG&ON@Glga>ghPB^ZF|3ay+5{t4pCJt5+_yBQE))+sSPyEho1O`0E^IBo?(W%c#BC( z+Z~vCp)C1(ga1g!JYJ-B5vw5p=8h6S!~@;!YqTj(kkL}ZyMd;+dPhNo{PaF{l+R&H zg*cIg8s$1R{ungRXwb&q$WP9ERG_P(lE;K>_Wir%CE(45gThOAd+ouZtZ(UTbZpE= za$*lN1PrXSgM3wl_YjGIcc5>g;&exOhb$Wvm^fo!)x(j-IV%`>9JZA}=*yZgZH>yK&v4NsH4j1rvR0Fq7zP-jTz^AK=2wex*a8f@_ z0!fqu&(^4B-G<>E!p6XPr4bSe)F5{=by^ks?XjoU!tS$xx`P9n(-b0lGhg_NZM0fN zW=ZMB;-OJO;tUyRJkN2xHpCt61}!b`+faq1HhIEZpP#0zt3>eY$w(9;G)^r2^SKrnw=ZkyrG5Qu zibCEG?p^NE;?){QPf2H#OiHS&)(qPtxdnf73lAN2_0;tAS9HE5hzbP8`l8F}erZ4@NOe`vJodxFKom{D>S$>{@0#?v?l!Jn-Y$H&?GEZcy zw7*6b4beQh$hjYc>)1~MoNQmd4)l-=WAQ^59{<1;x$RI1md6?Ts4%?-echnJn;BPYRAm#Psd9vo9YQtI)0WKp(hEewp6Dbv2f~9#M|ek6 z@YSf0h^b=50*|>@*4KTj>|j|=gIq7(ewmS-BM;<$+W&+mNh7F)mg%pMCIS#3{I=F@ zjS@rtic4SqJZgH`{jN=2otJwp|%2rz++3Ua{FKSgl5vEE_ge(TI627#p zsH|)Rv$nDAip<9bzy{v#4VJ+(srrHTAmJj?pV+jYa0?se!!^<|FZ8TvgB-BsCa^q{ zs3oc}^q}J6;`X&X!{$ctcxl7DTZpsdz(Iw3r>AP|1E`9Tl6kmq7vJ-&)niK+IUZ)#J0LYZD^GIWHGOWoXggy zD%SN}`*PDs_kpG+1~f8v&(}~|ljr373`oSkd?YL(9{+Z{Z3%iLFJyggS$`V#eQ9#9 z8oO<*pYCj?)&zz*o%FBW`mE^Ilk)NLHCHaaCxW;VPaK_Mh&zJ>ZQYxiysofBI*AZT zvgZAE7Kyd2_3~^)w`uChiGW@gYh>PSY2kM1-mE^1H*4kK;3(${D&xWa;S|7k7OIR6 zgQvwMaS7!RF!1v!iw`q5CmX2bO}}iUjl{BQ((;hBiCmc&cwwU(04FI@|264TcTHw@ ze&s;+Nm>swMmJ_QA_K3U{VEf(Odqg*sU?=1*2=M)TQ_Kf^RJzOQ2?=~V|#BnB}GUI zeaU^;4!~ityxoz!NJ{nq^Y-uE)wS8vr7|A;ObwI=x5!EM7u4~7a;ZQ@91CLglX<#w zAJWRp%hM|b!TBgoP{sC8<&a4-_*8U7@(QcABbclJbaeOre&@#RgYB8mq7&-#H~}nT zH(>a1PQCryCL9e4ZrTlT4!&hg;7@6``sf9Nzb!QnUMm-ux;*qhzv(| z`V^mam_oCAS{Q8VEPZQhOJ0mbQ7BrfZZ={mlSoyGGAsJ*x4knC#Vpiy{J3f%Nqti6 z=|Hqk4|EbJ5-jsoT%UE}skLq>J~lT-`Xj>0MF7*k3j}6OAW~d1t60I#Cja{tN7XW> zud~qxHW$NJ1&94fN#W$tNd7bWjpOZicCww{q^+g3%-UmLgTZ4xxVyU>*hq?W)r5EW ztA;J&()`k1&HLtL;vb^w+wXI*WdgsUU%w-glQfe%pAOyl^uI^tKv zeU1oUU*8@+?I6TMBXzaN!Jim;6ZIfXL6~BF{W##+SRj#rLUZK5Jrq9#X^W>zM_QW$ziwKgFO=J ziTMrRN=NV8FOSg7MBWaU(rnj-tlGb)yQ8cto zKqa>xUjvmO*uba^O>R^iE5rpAgGGUMc8O9~eZ8*sg#@@D2+PPUy_2@ek_KPpT;+6G z&VXHi`*+shAuZf9EWfspUCZ(zoMBhl@Z2ZxnK0Yg@&yWc)eE^Q*dk@8pEF1Ua^t3L zl0&)TAfbAdZeH_mqv=nEvst`zk9G-eqfnHusYyHBoCSCsZQp&dyq)_E=ID6uO9HuS zG2M@a*Z%01k;_P|xEZh2%j*ufWRpGwft%m8{AIzc*_mfsCVonT1i3j_-ai>HbWjQ0 zyTU(d`lQiUo@PbP1@|=PA*+*|NWZL_+IY9kEVz4Ogy+(pECg+P2%X|r7pIjnsU^otF7Lx9FE3}zYM<+Gf4 zlUiY8@KHWO@bbkWS5A!LmeK_!s=~yiS*~9JIu;QSvp${TMB>RYS2(%BamA#+JvL$; zG<}7iHLF7`+FmQqoQu8X8j@1ymMcqoqh>pK9dfzbt4v~guO^2vJ=iC|MQVx2B-H=x6Fv&*-XVBY%J?eT-l)&qfYV{DjMha`i z$iiX_55)u8cPgL@wE**h3Op-uI8rPtI@qKR{|-H8j3+5=F$@mtD37U`vSI^54vJ*z zUK@xx1XgD9ZQhTV*`CdKAZ`xMc_?EGhL#L1_*n>Z4*=?t(I}?BHR|TEb%uxF+tS}@ zbYzRp4=&!My@d>Y(2Mrt=Q^&7Cdq}==-Z5k(Dv;KbXB<{d*pP{{jqJi>1PW*c$xx#y3uAch zz3k)iQoePkxfW_nUiiFUN%?L9y+NiMLzp9?a%E}JvT|<`lLxTH57C-)Hd?V7j^qxN z$aX((?Ghkrl5ita<@W*XS!PC&z)p-W!iSsYDZ%||k^mw97HxvP=CAOCK*xsyIsdk^ z@4vv8w_}aKQlS2sP{mtQfKO?HrWAC&XGQ7 zs{p8fUQ{KA?^+Wngf}6A6=*d5Ui>yI`|Y0a{f46_gFX{0HwHHRSC z9k(oYaBTlb-ys+;!xVhTXtpuOlt`D{Ewr2v{5>9!3p6}eBRF&l<@b>iYLoO%;buHJ zRv~H`X|4qNiL@n9AG^o^=kUed-u* z>xYV{3%L}4``cYG#xEsg%%#`bQXNPtNSV0jzFgtf=LJ`e{9;y&C&lMA^@aaAcOW!$$aJm!!6f;5VNM%KT zdZry%IX24U^ zp9;2l1$Rx-fkYC?sLY@n>JHTq6ee#p;5Z3Chq!$b*=_#at>Li+GG!(f^iW7z+1qIA~_4o>jlqo_x2q$EZiDY-+}5b=hZa^&d24>_P85k)Pc+liPpigaEsi^J|Fyt zH37p`jJMqWoH~$e#`ORXAUyreCf#{^$SS_cTp|$g0M?d?IM=e~{&}~>vS<9wmkzdPdjMb^8 zQY)Jn`647!72%du?={$(7@p)d73Vo-C-0Sz%)4oXUsMG}+ zzscKzd5X|Obz1Uipg-rL01rnLW@ucx{Z>o{I2l{Isa%Ks&_MF#v58&8@Gcsv!_DsI=c;?>Zrv~0I> z&va;=cTiM_V{a@Kl~-fYSbLqPJgtPkTP!y6_Yu3uyg47>FmWZ?4n!E)wVRC|tO4XJuRN*k6c`xw2Qjqi)dg_}l zZ0pk5$QOSgKi+2Xx%(YMddvV|F19vQq@FPw|0=k_S2ALXxCka+KH zMFE$oSQ!%&PCx?VKoYJi4|@!Fn5Qi<%U$86A$n9092RyS=LQ@tHR}jW&n5_E*67+8 zh4?%qSXg->F}RS83nU?v3y(@@%IhNkf;)KSIN6t&g0;`a&V=&y&Sv16*c6MMlAT9O z;Ri-U@~A2iK~RM#+Iz}gz-!WKQeHNF@bH6~T(bG&R#1BkCB(Cs5a6vQJ0HB{N#RjG z{S}_7{pexE6=4_Ne}~ZNe}QX35`1g=P-(K3-mJz!6SooG`|HMhIvjDnlAweKSRmw= zqHJj>l$UC8sBtftLdV@`wVYf5x@P0QTFv4WYp2Y>qOj<> z$H3M7-D8O<(V zQxKkL5oscZFZzd`Iu{Mzluco2J!GNSoNbrJkKBdMAkil7YtMtx^2ldv)H1Q33l;R8 z1;A*`odLnNep2$D6v^m;Mm^Fhvm}h>@x3}X^HaSvjYQNfWGKNJkEXkycw2i$Y-v{$ zmt%9V#XvXp*+tL8AxE__#84a^6`d`I1s^(dA%7iYSW>s$)x6H|mUP|D_4~AA?k|o9_bV zTibN3tqBO3qFuuaIk#J$td-W>15=x3)qO6=JAN`>1f<~adXOF%ykaA;#%a)j5()`X zmr=nj7l8N{71Sju7Wsu3YEq0svI%=Z$|(0=S~JLMx^oS53tO{bwPKuJt(ug1Xr+x0 zPgL4vUS6{56=0EAL!v=+vJ-A4xdVl~`#tDC45W^y#6erCCg0<;v%0{?R;Qczu-Jzk zxmK=AaArI{f{fAWG|hk_?do2zpKNyeNADPS#8e_{1GmKB=t>=RyThcoYI|0QoPT$w z`;EwW`Y}_d~6JClo^f|9FBTnkqBT&I~0b>xupm zFh1Z5i;ZJpFpGZF-#-_jT}u3LR&99fPglY$5ZrrfFQJ!=_$81vDX}kQB;Fgc+!0># zyTd4?TN(81%QG%zDc+DmMfbz%%(k&1wb2l=0A%f~)XVqB@c}0PD63f1ZXAp6uxPRTGj}%k?>gcVaw!|6fQypcsHP47e4U|l_DNPEC@9J*z zzGUf<<>#=gnwO4PN@k%4oL#L@eD)6xJ{PNAqQUr^P5P{Cci7kcw6ld1YH!JR)d*WR zg*xFVX}t^hi^{WyeG_}ZUaCTXSN)jY_ z@`-v5FC`8t2h@jvX-3z(`!KqEVp=>?9$${%;g4`jl@*DnOX~*Zu0`BXN}Mel>VsW) z<1_v?0x^B1F`$nnVf9N(wu9&uCqMxWZx|i$gabPoreq~G=Q|%_;F8&Hfnrzu6Q7=G z8Vq)bDBmuS3Dr6NMywO14D^YN3_iW!8z@`VVdcZmKlXI+mVF<4Aolj{_ zH^u@Dyx(5jY19^dmSkrUN87_kSB`0q&q2Sk4KVEGMAgx3=dHDHhTZ&CIboO0TD>GU zDVM@)twCUEtUtpGcK)#hIrQwXM?v=8haj)a>J{Ee66}oYMz~?n3r(V%Mil~+|9q1r zgdJdf{f1oO{_FC@i+g*2_qut-^e2t(62TqSe!4=L*DtB%Uel{f%d0q>8~@eEG<(C+lcR*Ws)`>C@pBO6CpN0(%PV_h%gxt0eW-!m zVkrf(u=u^x$gQJ{!qCG%cW~6!X(PKKDa-K>N_*dlewN{=C3F%8XQ+fly9C~*>!WP`I`reI z$J9z*!C6yiZCt)C&cdsCEbcq&Z6Kb_<()^ zCtGcJqk-Stv8`U`=)GH!f1IB7QttH-ZXLn+;V0kTuq1QnXq3~r-I>*9ImmZc(Us!O zsKXKnTU8--97ELrIt~TqlBuh!*ib5#C#%pVlCw?dR0mEpErZ5sqebg_a9!Daq7bp; zhruFy%eLtCwX}hD&q!reev_{-T@gwxII*suR+29PO!dJqSc79mO^A!cDBv*&OgQ#h zDmF+stCkgp6-(C$%@g{fBB9PR<2J>?^5=_SeZ{0UV%(OeO)oy`J|pFg+>!$8@8O0| z4hd6y{v%08%m|a~$k-~`c3ac6Eq~Uy4@d#5TtpYdQumrsjg%PSlk!F- z_bQVYa>PA+{NQWRPFFEgw`a+&T0414j;LtRc%djYf;iSSc8ySUe_6)*p&s*gdZ+iB zyVxRBU8tJTo_wrs=NG}aT#ILEhg}q>)o@O&+sxNbJjiQ}S;XSO_I>qB1F^RmVU`3Y{{(e=%HZcp0#LC96*dT|ny>H1#JG|oNyq0#SeX`MPHmR?gmrQ6$|JG+Lap_P^TiaRYzKU$aI7!)002*X_ro87T3 z_KCg6sne^c?pqz;a{OH!7b{yFWMumsigVVl*!p#BB9&A~Wgd(M1Q^0RZNnU?SUtORvp^CZ|g4&-rMP)&?z8$&t0=g0XsKR zo}}$(EoAY)mdv!%rgxTkwAp@0$c;%t?2x`qta_K-#By+JeGOA}TKntjZh09Ebr7GO z^z}@pP0p!g)lxq?3c=4$8aX~bTG*j`qqfv)rZ$3%VSba>w^T)ug>RYC9s_8 z72f>1=Vry@`HL?u-0`VpfwjYgY9V*N&}8&MgwYeG%_s|tvAf7+4ofT*5bv#7WHHUe z_hd@9-sbS$&%(?bRKbgJ(?Rw=8{OC(Kpbg6;PWhCg%ld zRFc%1H^=L}$8dxQC%VM(dE(D^)6sdygybY(M2n>odo=lGThI{C@7TYBH8kEC(P1%; z*Znp@M*D}7Gp7CX100Cb#v=Qwbp)Rt$~zTs8D$>&hJK!}Py3$kdfGJBWMpIE;eiEI zG$Sd+;LlUYUtjDe3hA3_E@DI!)5A%y;US@Vqc?XkhaeaB^hJ_26FT)#UpG^ATlj;% zxJ3BN8mq(=s%o<=$8<}`>aKbcaIfG3)e@M zNewyBIt~4ao#dbvbA;dlK>u^NljztxpT2EvTCZW7bhwBPUcUa`l*bcp;n7qh2LH6p zMW7pqy~DGip1H}FyszZc;9JL6=^3nOCryqs{q^=Qnx&u!lnlxSPZp9=opNud)BwMe zw>@RYt(WPgQo-i(F9&|V_3Y;YaET|Yi%qEL%}{lCkKwhfQbm}16u8@|(w&p=D<*iU z`B>uX+u@3~bh;YMQxkfsCXs_fYla-&`| z{o>;=E=B?pHiXnLfW10Mc@N{2z&twyqlzWXrY~&aR_U7rT6~L5xKF#F(Q^UVU!Q&o zT4G^QOsMtKSSoQR(Ns@hyX1RL8Nn8wF|1K-91bpS2lW6>N!TgUr{S}rp~%6nMz*(j zJ_kpFmjtkFv_=GZR9iyd>F|rJQXYM4OWAOHvqb3Dh0(sKiz>LNAMx}>=A7;(R)s^ zSEd+prar4~M%(C2>mCPyfEI|?rdU#~gmq)q0Vo}gHAh4*Q=JZfzGwcy(%5odthS8pI2# z&>P{XVAR&(VhAwLE2`k{xjT_n_}a%u56uJUQgG9k4M1Zm={ z<)SvtGBMyo1~De#?a*3BX`~oScNdQ(Uwjjs^zUd&$RHoVt+ojj<>6bHU;oact^R{Q zQzijW>$Wqd-3&4bK>F^0O1e&#(9hjWd)UoGjO?B&LVburEn0Mwna!&?kZA^^1qGtS z2hhm2C8rezfsX6Uiw00Kr!TA6f))clPeER?jkBGr9Pd!)1aw|vU6Jh_=4&{Wlav6C_ZK{L+06deSf@w4dJucTgbx6)|Z4|nJ ze*v91QjmL0E*)_J8mmzw-x!}3$2WcSOjoFajloqzBX{u|-PRETTJj;3Wokh@G)_B|!46hjiehn$8MQ%SNgowRA09A*(@8C|WsJTR^!7ZG5o4j}FfLLta=btu zoaILHkx+oh=o(HqP;a_`%B29GFxuJ?q>doU>9?3YIs$sjBKYx$t&dUpW5_&eiOny1_8fwz$&YfA^Wl z`_AztyGN`Y9>S@tkxrE1{Ll|G8s9ily>tyaO))|P2t=+0w3fBxXpN%KtW>r*BYbCI zbl9$ZwEDh!1lfnS(c!am=Jf{S2Cd3`t05GaG_mf8OnfPy1PGJGlM*#M?FtK^*k-vvd|nTwZHgiF zEsHpYS2(n?#KhB(j21)Fe98)W=bfsmACE`k@KF2{c&?ngUDg`q9D^d;%^92veS$Ob z#)f>mL1%z3Or_J^n)9?qpOLKBNtaVrOwx74HLY$@DIx$mSg7V!IV8z|Q&DlqVba+Q zxiuU>zWr<-@U{D5}}+jUW~Ex*FmqiiG7fewmqk!us%qz4-ymmNEg0QeTcK=+7( z*l2B{*D|IcJBwitPu5II)8uC<$OVan(?u=BtFg{WqA-GWsCCENe*6 zaexC73EH$(8X1*H+gD6esv0U}d1=I(hzBzG^o&+lWR*U~t^=kq&$Os3L@}t%aWKc= z^8CqYl_WILhM@p|Ww`JNzLbDjfsJ%9h%zW0x~)M@m`+DLoY{FVa_XBTzm2cpyGO_! zg8iZ+(qEC-n{%BX!(Ijr)f#0Fy*Vpk6RlMaqh=>$?OOP0SX5YHS$D>9_Vmxa;lQqd zt}_e9`0uc4EyGKPRBL_WlH5V~R7w-bNUCBZd_Y4)P8C zG!>#!v2mC@l=W)XK@O2Lf#unz7N!>GS4d_pY9ueS)u)?DRQ^7r9{1$cbdkBByiu&c zsp_wRC8Rn9tu%qySnfAcrFXnL;FCbpSJot4*M^eZpFo~q29G`U0nspy$mj@H?@UK4NOs$^?(N%tDist3~Tk)6CdD{sGzE2&)>>avC!6vPcL5;2M7S}IF0Q9&LW zXMbuX=}nlA4tp8@%(jA#2GM&upQln+gZrep6oN49xY4J(RoTTQY zuGZbzCOt%TVM8VidYz=%J&HV!K`B)pBliRESjmBGl^1Rm`O5m}W$a4q+u4bjy2OB( zTJKc4PoSrjOeh@FlUz^=zP_0jj+?_CHUC3tq2}9dIikiNNVE&QGhSp+xmBW`zPcG) z0ZgN|<)}qV)3&JL z)PCd@JA2HI6isT;iVmw(@^0$w)_OI+d#ZdrtZkd_A(JKdVW-gM zky9w!QP#9(RUY=Z1GfRXd&xCk1 zoO7P4nyfW;2f{e{-srIR2<0g&;ixA7da!Yz__iUDZyTzcf=nNTwi)1(v)@Nw${6C> z_|V$+T=JJI2zfzVLNYBG-Tb%;M)b zwbbII|3uPs|rc17c; zW-q1t3rEoN#X*#L!$df0S4xG0fiU2V5) z`n3VY&aW1I8ye$bZc!{FZP_aRo28LD21H-JQJ5Y0siU38#$IdI74!)&S3o?4`YOja&?+&(*}d2oxoSZp8X z4sad3hwdicRC11TmZNctpI}!VfmyEa`z)w&KoA@wK_y5RY76{gCg1!nrW~pkTM(q* zj%Xg!a`F;4j$*qD`fmEo&QM=4ERYQ!@+zEusesq0I#0fXzA&_MDemVSbyyGTVVF8Uj|jw~sc^ zm{^Y$&mprv$zS_trC4S{#WwJ#$r2gHc2d$iiMU}IN@)w}HMOZ$;OS1lQc9hcg ztfBFADOPKmMwnePSo*aoM?lZ;T6NR`$xN9f1_eRri^C0J-m`9(&1ETw{hOc@>_gn?HJ|8i5u|63?-5#IA;0+jqdNkd@^q2Ni#Un#EjzL*l6#dWdZG&jftULwLanS|ubvt^<8AjVQxlt8uan2*Wdpy8nwE7svy;U8 z$Oc@8Iy`Ft?`D1z>CX{5V+AW__6$O2Wl$3FP;=&_4;6|lY))WmE=qzZY*@PWZn06%#I-2tKk{40f2eJhyU*QSG0x93y~C4NeKtwYOrjQu`RO z+T4hh1UX(htD{Tk;uR@?W_q^-Xc!uJmLru)4OH55$fJZntRGKGBj^WdfB?BlNj~36 z#(RJwgG+fI-CRM!KHb=+W~XR((9CMx#jo$*2u+HNe8x6L zl_aJtr{H~o1j>AAZyC>fh6C;E?>>7C1;RF+#xwAD)Qyg6J!XWett-S(I3YL8+48wk6h8({qX>D$rd( zVgQA;KH(2=s(TgM3)p;u_L6dooX z!)q@T&+a11+4)3iw6e2HCGwqNC{lptzH+Xr#wYt?f|td%tF9jkugHJC^D|qlow)Up z*`7f%=5|{VK^4PX6A8uYL*SBj_*`7lzZ@I1ofb@3b%|*-_#cn$$H# zGR=$uwIVId#_DdDq5eV)h;s?Z$-2E%|Fo&F44uK-_|P*}x|dluv~5C8 z(1)0^mb$L&MLZGXieQo^p@=&qVZPEQfFajShd*Zt~w6NE%Q(;sdidin` zVWNXADVF+ZD58Bk5%!pL18I6BQjRM!AAlHVNhh1D971MLZ4pjfo#s7pJ=YvtU@4u3 z-`&@u!cn0iGjmrFiPNyMzRa#bk;Bfte)}kzF`)azfG;#ZVw%ZtcwEEAVfxK-{c?uE%WaM^F zg?45yl&^1}6Ihhl{qz%bvA4q7*d^dbf}O|#`~v|fQSgT{7$-lSPCL_d6)W*}l8Bz5 zF8bA}BCbAni!3tgX3Zklbmz=YOs(gY_OqE|C`kLdjm^lok#RHWq8YmrM;I23&{68X zP{xk?IbY0BuT3-?{*^E4dha%1SjrYID(A_t)oHJE=DdRsPAOvX9qlxV@{i4W@-O~d zb|e>GL4AV-iszwQUX>#YcdiX%wYQFM>*V2{j>&|`8;YqTV`n>G-gTd63}?L!@O!@4 z8B4WzKP_E4w!U7zft&|dFzSgM)HRF#_Mf{ZgZ>?D3Fnf|Ji%B1j zyN{EhWXSdMRHM(}{yyPbp$Jc>2kqY+DjeK{3hsB=;lae|Xk~3?Vyp0=poLhNn7#g^ z{4kTGrq(5n+q>@*VX;cY#M~prG>P_|dJfK=t3gVCelPh}id5{gL3Ml(?__>B`m=w z)7Vm1XW=uN2tuqgY+qBwj)ZC4=ji<;ShPZSFpicRnB#C8mp-8kSirqs;Yt1qww$CS zqqI)5IIrK-rwbkIsp8L&Y@0O?J~NyZL8j!$Wg@H#_tOS#X?a~Hb+-zH=J>Y2$8z55 zT-@JUx*$jKPD+OS1PQBGzFkLW{5y~p;lBnbR&!ScqhGg@xqehMw7 zL6WgIrjPi2?Y0|{Jyw!f2O(?{+jCvk8-d8Nl!@cY-@B9)l&j2y`f3>IP2v-qI<2}z zKl)AAQnzCUbtU)*U*`X>2!2Qz+(Y{Qcl?7e_%YzI>h_Pwe*-)pK7SG4J`Q|raQz+l z<6(w>HYEHPpX+1dV;$;m;u7NjA^uqg`_BgYmm>Bt^08#}H*)?#?fYMpqmMz4m6*Rl z9w>hS{gWW`G3v2Y@;A!=VblFNr^l$jDJCB?AFCVxVE%hJJgB7qWd2R$_?Ypyr{s_L zf3F162O;F234PpQ@)+~DaQPc^Bk~u_pZWV&8S^pZ@wxdM(xv@RkpC=#$DGH<*>8@s d&R;nHe7LDAAwT364i59-v3*#9G 1e-10 + disp('pi initialization in MEX failed') +end +if norm(utraj - u_traj_init) > 1e-10 + disp('u initialization in MEX failed') +end +if norm(xtraj - x_traj_init) > 1e-10 + disp('x initialization in MEX failed') +end + +status = ocp.get('status'); % 0 - success +ocp.print('stat') + +%% simulink test +cd c_generated_code +make_sfun; % ocp solver +cd ..; +n_sim = 3; + +%% Test Simulink example block +for itest = [1, 2, 3, 4] + if itest == 1 + % always reinitialize + reset_value = 0; + ignore_inits_value = 0; + elseif itest == 2 + % always reset + reset_value = 1; + ignore_inits_value = 0; + elseif itest == 3 + % dont reset and dont initialize + reset_value = 0; + ignore_inits_value = 1; + elseif itest == 4 + % always reset and initialize + reset_value = 1; + ignore_inits_value = 1; + end + + if (itest == 1 || itest == 2) + u_expected = u_traj_init; + x_expected = x_traj_init; + pi_expected = pi_init; + elseif (itest == 3) + u_expected = 0 * u_traj_init; + % Note: first solver call is initialized with x0 for whole horizon. + x_expected = repmat(x0, 1, N+1); + pi_expected = 0 * pi_init; + elseif (itest == 4) + u_expected = 0 * u_traj_init; + pi_expected = 0 * pi_init; + x_expected = 0 * x_traj_init; + end + + out_sim = sim('initialization_test_simulink', 'SaveOutput', 'on'); + fprintf('\nSuccessfully ran simulink block with reset_value %d ignore_inits_value %d.\n\n', reset_value, ignore_inits_value); + + % Evaluation + fprintf('\nTest results on SIMULINK simulation.\n') + + disp('checking KKT residual, should be zero just because not evaluated') + kkt_signal = out_sim.logsout.getElement('KKT_residual'); + if any(kkt_signal.Values.data > 1e-6) + disp('failed'); + quit(1); + end + + sqp_iter_signal = out_sim.logsout.getElement('sqp_iter'); + disp('checking SQP iter, we set max iter to 0, so expect 0.') + if any(sqp_iter_signal.Values.Data ~= 0) + disp('failed'); + quit(1); + end + + status_signal = out_sim.logsout.getElement('status'); + disp('checking status, should be 2 (max iter).') + if any(status_signal.Values.Data ~= 2) + disp('failed'); + quit(1); + end + + utraj_signal = out_sim.logsout.getElement('utraj'); + u_simulink = utraj_signal.Values.Data(1, :); + disp('checking u values.') + if any(abs(u_simulink(:) - u_expected(:)) > 1e-8) + disp('failed'); + quit(1); + end + + xtraj_signal = out_sim.logsout.getElement('xtraj'); + x_simulink = xtraj_signal.Values.Data(1, :); + disp('checking x values, should match initialization.') + if any(abs(x_simulink(:) - x_expected(:)) > 1e-8) + disp('failed'); + quit(1); + end + + pi_signal = out_sim.logsout.getElement('pi_all'); + pi_simulink = pi_signal.Values.Data(1, :); + disp('checking pi values, should match initialization.') + if any(abs(pi_simulink(:) - pi_expected(:)) > 1e-8) + disp('failed'); + quit(1); + end +end \ No newline at end of file diff --git a/examples/acados_matlab_octave/test/simulink_qp_test.m b/examples/acados_matlab_octave/test/simulink_qp_test.m new file mode 100644 index 0000000000..ee2c60faac --- /dev/null +++ b/examples/acados_matlab_octave/test/simulink_qp_test.m @@ -0,0 +1,186 @@ +% +% Copyright (c) The acados authors. +% +% This file is part of acados. +% +% The 2-Clause BSD License +% +% Redistribution and use in source and binary forms, with or without +% modification, are permitted provided that the following conditions are met: +% +% 1. Redistributions of source code must retain the above copyright notice, +% this list of conditions and the following disclaimer. +% +% 2. Redistributions in binary form must reproduce the above copyright notice, +% this list of conditions and the following disclaimer in the documentation +% and/or other materials provided with the distribution. +% +% THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" +% AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE +% IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE +% ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE +% LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR +% CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF +% SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS +% INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN +% CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) +% ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE +% POSSIBILITY OF SUCH DAMAGE.; + +% + +clear all; +check_acados_requirements() + +import casadi.* + +%% +N = 20; % number of discretization steps +nx = 3; +nu = 3; +[ocp_model, ocp_opts, simulink_opts, x0] = create_ocp_qp_solver_formulation(N); + + +%% create ocp solver +ocp = acados_ocp(ocp_model, ocp_opts, simulink_opts); + +% solver initial guess +x_traj_init = rand(nx, N+1); +u_traj_init = zeros(nu, N); +pi_init = rand(nx, N); + +%% call ocp solver +% update initial state +ocp.set('constr_x0', x0); + +% set trajectory initialization +ocp.set('init_x', x_traj_init); % states +ocp.set('init_u', u_traj_init); % inputs +ocp.set('init_pi', pi_init); % multipliers for dynamics equality constraints + +% solve +ocp.solve(); +% get solution +utraj = ocp.get('u'); +xtraj = ocp.get('x'); + +status = ocp.get('status'); % 0 - success +ocp.print('stat') + +%% simulink test +cd c_generated_code +make_sfun; % ocp solver +cd ..; + +n_sim = 3; + + +%% Test Simulink example block +for itest = [1, 2, 3] + if itest == 1 + % always reinitialize + reset_value = 0; + ignore_inits_value = 0; + elseif itest == 2 + % always reset and initialize + reset_value = 1; + ignore_inits_value = 0; + elseif itest == 3 + % always reset + reset_value = 1; + ignore_inits_value = 1; + end + out_sim = sim('initialization_test_simulink', 'SaveOutput', 'on'); + fprintf('\nSuccessfully ran simulink block with reset_value %d ignore_inits_value %d.\n\n', reset_value, ignore_inits_value); + + % Evaluation + fprintf('\nTest results on SIMULINK simulation.\n') + + disp('checking KKT residual') + kkt_signal = out_sim.logsout.getElement('KKT_residual'); + if any(kkt_signal.Values.data > 1e-6) + disp('failed'); + quit(1); + end + + sqp_iter_signal = out_sim.logsout.getElement('sqp_iter'); + sqp_iter_simulink = sqp_iter_signal.Values.Data; + disp('checking SQP iter, QP should take 1 SQP iter.') + if any(sqp_iter_simulink ~= 1) + disp('failed'); + quit(1); + end + + status_signal = out_sim.logsout.getElement('status'); + disp('checking status.') + if any(status_signal.Values.Data) + disp('failed'); + quit(1); + end + + utraj_signal = out_sim.logsout.getElement('utraj'); + u_simulink = utraj_signal.Values.Data(1, :); + disp('checking u values.') + if any(abs(u_simulink(:) - utraj(:)) > 1e-8) + disp('failed'); + quit(1); + end + + xtraj_signal = out_sim.logsout.getElement('xtraj'); + x_simulink = xtraj_signal.Values.Data(1, :); + disp('checking x values.') + if any(abs(x_simulink(:) - xtraj(:)) > 1e-8) + disp('failed'); + quit(1); + end +end +%% Run with different initialization +% always reset and ignore initializations +reset_value = 1; +ignore_inits_value = 1; +out_sim = sim('initialization_test_simulink', 'SaveOutput', 'on'); +disp('successfully ran simulink_model_advanced_closed_loop'); + +sqp_iter_signal = out_sim.logsout.getElement('sqp_iter'); +sqp_iter_simulink = sqp_iter_signal.Values.Data; +disp('checking SQP iter, QP should take 1 SQP iter.') +if any(sqp_iter_simulink ~= 1) + disp('failed'); + quit(1); +end + +status_signal = out_sim.logsout.getElement('status'); +disp('checking status.') +if any(status_signal.Values.Data) + disp('failed'); + quit(1); +end + +%% Run with different initialization +% dont reset and ignore initializations -> only in first instance an SQP +% iteration is needed +reset_value = 0; +ignore_inits_value = 1; +out_sim = sim('initialization_test_simulink', 'SaveOutput', 'on'); +disp('successfully ran simulink_model_advanced_closed_loop'); + +sqp_iter_signal = out_sim.logsout.getElement('sqp_iter'); +sqp_iter_simulink = sqp_iter_signal.Values.Data; +disp('checking SQP iter, got') +disp(sqp_iter_simulink) + +fprintf('should require one SQP iteration in first instance.\n') +if sqp_iter_simulink(1) ~= 1 + disp('failed'); +end +fprintf('should require 0 SQP iterations if initialized at solution.\n') +if any(sqp_iter_simulink(2:n_sim)) + disp('failed'); +end + +status_signal = out_sim.logsout.getElement('status'); +disp('checking status.') +if any(status_signal.Values.Data) + disp('failed'); + quit(1); +end diff --git a/examples/acados_matlab_octave/test/simulink_test.m b/examples/acados_matlab_octave/test/simulink_test.m index c6b5b485a8..e4848b3ea3 100644 --- a/examples/acados_matlab_octave/test/simulink_test.m +++ b/examples/acados_matlab_octave/test/simulink_test.m @@ -51,18 +51,49 @@ cd .. +%% reference +% uncomment to store % simulink_u_traj_ref = out_sim.logsout{1}.Values.Data % save('simulink_u_traj_ref.mat', 'simulink_u_traj_ref') load('simulink_u_traj_ref.mat') -err_vs_ref = norm(simulink_u_traj_ref - out_sim.logsout{1}.Values.Data); + +%% evaluate output +u_signal = out_sim.logsout.getElement('u'); +uvals = u_signal.Values.Data; + + +fprintf('\nTest results on SIMULINK simulation.\n') + +% compare u trajectory +err_vs_ref = norm(simulink_u_traj_ref - uvals); TOL = 1e-8; -disp(['Simulink: Norm of control traj. wrt. reference solution is: ',... +disp(['Norm of control traj. wrt. reference solution is: ',... num2str(err_vs_ref, '%e'), ' test TOL = ', num2str(TOL)]); if err_vs_ref > TOL quit(1) end +% sanity check on cost values +cost_signal = out_sim.logsout.getElement('cost_val'); +cost_vals = cost_signal.Values.Data; + +if ~issorted(cost_vals,'strictdescend') + disp('cost_values should be monotonically decreasing for this example.'); + quit(1) +else + disp('cost_values are monotonically decreasing.'); +end + +% sanity check on status values +status_signal = out_sim.logsout.getElement('ocp_solver_status'); +status_vals = status_signal.Values.Data; +if any(status_vals) + disp('OCP solver status should be always zero on this example'); + quit(1) +else + disp('OCP solver status is always zero.'); +end diff --git a/interfaces/acados_template/acados_template/c_templates_tera/matlab_templates/acados_solver_sfun.in.c b/interfaces/acados_template/acados_template/c_templates_tera/matlab_templates/acados_solver_sfun.in.c index 15ffd83d4c..84179dc0d4 100644 --- a/interfaces/acados_template/acados_template/c_templates_tera/matlab_templates/acados_solver_sfun.in.c +++ b/interfaces/acados_template/acados_template/c_templates_tera/matlab_templates/acados_solver_sfun.in.c @@ -144,12 +144,6 @@ static void mdlInitializeSizes (SimStruct *S) {%- if dims.nh_e > 0 and simulink_opts.inputs.uh_e -%} {#- uh_e #} {%- set n_inputs = n_inputs + 1 -%} {%- endif -%} - - {%- for key, val in simulink_opts.inputs -%} - {%- if val != 0 and val != 1 -%} - {{ throw(message = "simulink_opts.inputs must be 0 or 1, got val") }} - {%- endif -%} - {%- endfor -%} {%- if dims.ny_0 > 0 and simulink_opts.inputs.cost_W_0 %} {#- cost_W_0 #} {%- set n_inputs = n_inputs + 1 %} {%- endif -%} @@ -164,6 +158,10 @@ static void mdlInitializeSizes (SimStruct *S) {%- set n_inputs = n_inputs + 1 -%} {%- endif -%} + {%- if simulink_opts.inputs.ignore_inits -%} {#- ignore_inits #} + {%- set n_inputs = n_inputs + 1 -%} + {%- endif -%} + {%- if simulink_opts.inputs.x_init -%} {#- x_init #} {%- set n_inputs = n_inputs + 1 -%} {%- endif -%} @@ -172,6 +170,10 @@ static void mdlInitializeSizes (SimStruct *S) {%- set n_inputs = n_inputs + 1 -%} {%- endif -%} + {%- if simulink_opts.inputs.pi_init -%} {#- pi_init #} + {%- set n_inputs = n_inputs + 1 -%} + {%- endif -%} + {%- if simulink_opts.inputs.rti_phase -%} {#- rti_phase #} {%- set n_inputs = n_inputs + 1 -%} {%- endif -%} @@ -331,6 +333,12 @@ static void mdlInitializeSizes (SimStruct *S) ssSetInputPortVectorDimension(S, {{ i_input }}, 1); {%- endif -%} + {%- if simulink_opts.inputs.ignore_inits -%} {#- ignore_inits #} + {%- set i_input = i_input + 1 %} + // ignore_inits + ssSetInputPortVectorDimension(S, {{ i_input }}, 1); + {%- endif -%} + {%- if simulink_opts.inputs.x_init -%} {#- x_init #} {%- set i_input = i_input + 1 %} // x_init @@ -343,6 +351,13 @@ static void mdlInitializeSizes (SimStruct *S) ssSetInputPortVectorDimension(S, {{ i_input }}, {{ dims.nu * (dims.N) }}); {%- endif -%} + {%- if simulink_opts.inputs.pi_init -%} {#- pi_init #} + {%- set i_input = i_input + 1 %} + // pi_init + ssSetInputPortVectorDimension(S, {{ i_input }}, {{ dims.nx * (dims.N) }}); + {%- endif -%} + + {%- if simulink_opts.inputs.rti_phase -%} {#- rti_phase #} {%- set i_input = i_input + 1 %} // rti_phase @@ -371,6 +386,11 @@ static void mdlInitializeSizes (SimStruct *S) ssSetOutputPortVectorDimension(S, {{ i_output }}, {{ dims.nz * dims.N }} ); {%- endif %} + {%- if simulink_opts.outputs.pi_all == 1 %} + {%- set i_output = i_output + 1 %} + ssSetOutputPortVectorDimension(S, {{ i_output }}, {{ dims.nx * dims.N }} ); + {%- endif %} + {%- if simulink_opts.outputs.solver_status == 1 %} {%- set i_output = i_output + 1 %} ssSetOutputPortVectorDimension(S, {{ i_output }}, 1 ); @@ -480,7 +500,7 @@ static void mdlOutputs(SimStruct *S, int_T tid) int N = {{ model.name | upper }}_N; - {%- set buffer_sizes = [dims.nbx_0, dims.np, dims.nbx, dims.nbx_e, dims.nbu, dims.ng, dims.nh, dims.nh_0, dims.ng_e, dims.nh_e] -%} + {%- set buffer_sizes = [dims.nx, dims.nu, dims.nbx_0, dims.np, dims.nbx, dims.nbx_e, dims.nbu, dims.ng, dims.nh, dims.nh_0, dims.ng_e, dims.nh_e] -%} {%- if dims.ny_0 > 0 and simulink_opts.inputs.y_ref_0 %} {# y_ref_0 #} {%- set buffer_sizes = buffer_sizes | concat(with=(dims.ny_0)) %} @@ -770,29 +790,53 @@ static void mdlOutputs(SimStruct *S, int_T tid) } {%- endif %} - {%- if simulink_opts.inputs.x_init %} {#- x_init #} - // x_init + int ignore_inits = 0; + {%- if simulink_opts.inputs.ignore_inits %} {#- ignore_inits #} + // ignore_inits {%- set i_input = i_input + 1 %} in_sign = ssGetInputPortRealSignalPtrs(S, {{ i_input }}); - for (int ii = 0; ii < {{ dims.N + 1 }}; ii++) - { - for (int jj = 0; jj < {{ dims.nx }}; jj++) - buffer[jj] = (double)(*in_sign[(ii)*{{ dims.nx }}+jj]); - ocp_nlp_out_set(nlp_config, nlp_dims, nlp_out, ii, "x", (void *) buffer); - } + ignore_inits = (int)(*in_sign[0]); {%- endif %} + // ssPrintf("ignore_inits = %d\n", ignore_inits); - {%- if simulink_opts.inputs.u_init %} {#- u_init #} - // u_init - {%- set i_input = i_input + 1 %} - in_sign = ssGetInputPortRealSignalPtrs(S, {{ i_input }}); - for (int ii = 0; ii < N; ii++) + if (ignore_inits == 0) { - for (int jj = 0; jj < {{ dims.nu }}; jj++) - buffer[jj] = (double)(*in_sign[(ii)*{{ dims.nu }}+jj]); - ocp_nlp_out_set(nlp_config, nlp_dims, nlp_out, ii, "u", (void *) buffer); + {%- if simulink_opts.inputs.x_init %} {#- x_init #} + // x_init + {%- set i_input = i_input + 1 %} + in_sign = ssGetInputPortRealSignalPtrs(S, {{ i_input }}); + for (int ii = 0; ii < {{ dims.N + 1 }}; ii++) + { + for (int jj = 0; jj < {{ dims.nx }}; jj++) + buffer[jj] = (double)(*in_sign[(ii)*{{ dims.nx }}+jj]); + ocp_nlp_out_set(nlp_config, nlp_dims, nlp_out, ii, "x", (void *) buffer); + } + {%- endif %} + + {%- if simulink_opts.inputs.u_init %} {#- u_init #} + // u_init + {%- set i_input = i_input + 1 %} + in_sign = ssGetInputPortRealSignalPtrs(S, {{ i_input }}); + for (int ii = 0; ii < N; ii++) + { + for (int jj = 0; jj < {{ dims.nu }}; jj++) + buffer[jj] = (double)(*in_sign[(ii)*{{ dims.nu }}+jj]); + ocp_nlp_out_set(nlp_config, nlp_dims, nlp_out, ii, "u", (void *) buffer); + } + {%- endif %} + + {%- if simulink_opts.inputs.pi_init %} {#- pi_init #} + // pi_init + {%- set i_input = i_input + 1 %} + in_sign = ssGetInputPortRealSignalPtrs(S, {{ i_input }}); + for (int ii = 0; ii < N; ii++) + { + for (int jj = 0; jj < {{ dims.nx }}; jj++) + buffer[jj] = (double)(*in_sign[(ii)*{{ dims.nx }}+jj]); + ocp_nlp_out_set(nlp_config, nlp_dims, nlp_out, ii, "pi", (void *) buffer); + } + {%- endif %} } - {%- endif %} {%- if simulink_opts.inputs.rti_phase %} {#- rti_phase #} {%- set i_input = i_input + 1 %} @@ -803,7 +847,6 @@ static void mdlOutputs(SimStruct *S, int_T tid) ocp_nlp_solver_opts_set(nlp_config, capsule->nlp_opts, "rti_phase", &rti_phase); {%- endif %} - /* call solver */ {%- if custom_update_filename == "" and not simulink_opts.inputs.rti_phase %} int rti_phase = 0; @@ -853,7 +896,7 @@ static void mdlOutputs(SimStruct *S, int_T tid) /* set outputs */ // assign pointers to output signals - real_t *out_u0, *out_utraj, *out_xtraj, *out_ztraj, *out_status, *out_sqp_iter, *out_KKT_res, *out_KKT_residuals, *out_x1, *out_cpu_time, *out_cpu_time_sim, *out_cpu_time_qp, *out_cpu_time_lin, *out_cost_value; + real_t *out_u0, *out_utraj, *out_xtraj, *out_ztraj, *out_pi_all, *out_status, *out_sqp_iter, *out_KKT_res, *out_KKT_residuals, *out_x1, *out_cpu_time, *out_cpu_time_sim, *out_cpu_time_qp, *out_cpu_time_lin, *out_cost_value; int tmp_int; {%- set i_output = -1 -%}{# note here i_output is 0-based #} @@ -889,6 +932,16 @@ static void mdlOutputs(SimStruct *S, int_T tid) "z", (void *) (out_ztraj + ii * {{ dims.nz }})); {%- endif %} + {% if simulink_opts.outputs.pi_all == 1 %} + {%- set i_output = i_output + 1 %} + + out_pi_all = ssGetOutputPortRealSignal(S, {{ i_output }}); + for (int ii = 0; ii < N; ii++) + ocp_nlp_out_get(nlp_config, nlp_dims, nlp_out, ii, + "pi", (void *) (out_pi_all + ii * {{ dims.nx }})); + {%- endif %} + + {%- if simulink_opts.outputs.solver_status == 1 %} {%- set i_output = i_output + 1 %} out_status = ssGetOutputPortRealSignal(S, {{ i_output }}); diff --git a/interfaces/acados_template/acados_template/c_templates_tera/matlab_templates/make_sfun.in.m b/interfaces/acados_template/acados_template/c_templates_tera/matlab_templates/make_sfun.in.m index 877604cf02..7fba492238 100644 --- a/interfaces/acados_template/acados_template/c_templates_tera/matlab_templates/make_sfun.in.m +++ b/interfaces/acados_template/acados_template/c_templates_tera/matlab_templates/make_sfun.in.m @@ -222,7 +222,7 @@ {%- endif %} {%- if dims.ny_0 > 0 and simulink_opts.inputs.y_ref_0 %} -input_note = strcat(input_note, num2str(i_in), ') y_ref_0, size [{{ dims.ny_0 }}]\n '); +input_note = strcat(input_note, num2str(i_in), ') y_ref_0 - size [{{ dims.ny_0 }}]\n '); sfun_input_names = [sfun_input_names; 'y_ref_0 [{{ dims.ny_0 }}]']; i_in = i_in + 1; {%- endif %} @@ -235,7 +235,7 @@ {%- endif %} {%- if dims.ny_e > 0 and dims.N > 0 and simulink_opts.inputs.y_ref_e %} -input_note = strcat(input_note, num2str(i_in), ') y_ref_e, size [{{ dims.ny_e }}]\n '); +input_note = strcat(input_note, num2str(i_in), ') y_ref_e - size [{{ dims.ny_e }}]\n '); sfun_input_names = [sfun_input_names; 'y_ref_e [{{ dims.ny_e }}]']; i_in = i_in + 1; {%- endif %} @@ -337,23 +337,35 @@ {%- endif %} {%- if simulink_opts.inputs.reset_solver %} {#- reset_solver #} -input_note = strcat(input_note, num2str(i_in), ') reset_solver determines if iterate is set to all zeros before other initializations (x_init, u_init) are set and before solver is called, size [1]\n '); +input_note = strcat(input_note, num2str(i_in), ') reset_solver - determines if iterate is set to all zeros before other initializations (x_init, u_init, pi_init) are set and before solver is called, size [1]\n '); sfun_input_names = [sfun_input_names; 'reset_solver [1]']; i_in = i_in + 1; {%- endif %} +{%- if simulink_opts.inputs.ignore_inits %} {#- ignore_inits #} +input_note = strcat(input_note, num2str(i_in), ') ignore_inits - determines if initialization (x_init, u_init) are set (ignore_inits == 0) or ignored (otherwise), ignoring corresponds to internal warm start, size [1]\n '); +sfun_input_names = [sfun_input_names; 'ignore_inits [1]']; +i_in = i_in + 1; +{%- endif %} + {%- if simulink_opts.inputs.x_init %} {#- x_init #} -input_note = strcat(input_note, num2str(i_in), ') initialization of x for all shooting nodes, size [{{ dims.nx * (dims.N+1) }}]\n '); +input_note = strcat(input_note, num2str(i_in), ') x_init - initialization of x for all shooting nodes, size [{{ dims.nx * (dims.N+1) }}]\n '); sfun_input_names = [sfun_input_names; 'x_init [{{ dims.nx * (dims.N+1) }}]']; i_in = i_in + 1; {%- endif %} {%- if simulink_opts.inputs.u_init %} {#- u_init #} -input_note = strcat(input_note, num2str(i_in), ') initialization of u for shooting nodes 0 to N-1, size [{{ dims.nu * (dims.N) }}]\n '); +input_note = strcat(input_note, num2str(i_in), ') u_init - initialization of u for shooting nodes 0 to N-1, size [{{ dims.nu * (dims.N) }}]\n '); sfun_input_names = [sfun_input_names; 'u_init [{{ dims.nu * (dims.N) }}]']; i_in = i_in + 1; {%- endif %} +{%- if simulink_opts.inputs.pi_init %} {#- pi_init #} +input_note = strcat(input_note, num2str(i_in), ') pi_init - initialization of pi for shooting nodes 0 to N-1, size [{{ dims.nx * (dims.N) }}]\n '); +sfun_input_names = [sfun_input_names; 'pi_init [{{ dims.nx * (dims.N) }}]']; +i_in = i_in + 1; +{%- endif %} + {%- if simulink_opts.inputs.rti_phase %} {#- rti_phase #} input_note = strcat(input_note, num2str(i_in), ') rti_phase, size [1]\n '); sfun_input_names = [sfun_input_names; 'rti_phase [1]']; @@ -394,6 +406,12 @@ sfun_output_names = [sfun_output_names; 'ztraj [{{ dims.nz * dims.N }}]']; {%- endif %} +{%- if simulink_opts.outputs.pi_all == 1 %} +i_out = i_out + 1; +output_note = strcat(output_note, num2str(i_out), ') pi_all, equality Lagrange multipliers concatenated for nodes 0 to N-1, size [{{ dims.nx * dims.N }}]\n '); +sfun_output_names = [sfun_output_names; 'pi_all [{{ dims.nx * dims.N }}]']; +{%- endif %} + {%- if simulink_opts.outputs.solver_status == 1 %} i_out = i_out + 1; output_note = strcat(output_note, num2str(i_out), ') acados solver status (0 = SUCCESS)\n '); diff --git a/interfaces/acados_template/acados_template/simulink_default_opts.json b/interfaces/acados_template/acados_template/simulink_default_opts.json index 6526e050ff..0985daa760 100644 --- a/interfaces/acados_template/acados_template/simulink_default_opts.json +++ b/interfaces/acados_template/acados_template/simulink_default_opts.json @@ -4,6 +4,7 @@ "utraj": 0, "xtraj": 0, "ztraj": 0, + "pi_all": 0, "solver_status": 1, "cost_value": 0, "KKT_residual": 1, @@ -40,8 +41,10 @@ "cost_W": 0, "cost_W_e": 0, "reset_solver": 0, + "ignore_inits": 0, "x_init": 0, "u_init": 0, + "pi_init": 0, "rti_phase": 0 }, "samplingtime": "t0" From bf3574eaacb3f707a0e73660ba14a627b5a7b818 Mon Sep 17 00:00:00 2001 From: Katrin Baumgaertner Date: Wed, 17 Jul 2024 14:17:32 +0200 Subject: [PATCH 14/14] Python interface: default for `sim_method_num_stages` (#1159) BREAKING: change default for `sim_method_num_stages` to 4 in `AcadosSim` to be consistent with the default in `AcadosOcp` --- interfaces/acados_template/acados_template/acados_sim.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/interfaces/acados_template/acados_template/acados_sim.py b/interfaces/acados_template/acados_template/acados_sim.py index 81bdbb675f..16618baf05 100644 --- a/interfaces/acados_template/acados_template/acados_sim.py +++ b/interfaces/acados_template/acados_template/acados_sim.py @@ -44,7 +44,7 @@ def __init__(self): self.__collocation_type = 'GAUSS_LEGENDRE' self.__Tsim = None # ints - self.__sim_method_num_stages = 1 + self.__sim_method_num_stages = 4 self.__sim_method_num_steps = 1 self.__sim_method_newton_iter = 3 # doubles