From ad8811f17b19176bb1ac0194191ad1d0f12ba073 Mon Sep 17 00:00:00 2001 From: Moritz Schappler Date: Mon, 28 Dec 2020 09:58:31 +0100 Subject: [PATCH] Summary of the code from 2016 (updated dependencies) --- .gitignore | 20 + LICENSE.txt | 21 + README.MD | 68 + data/MPV_list.m | 123 + data/atlas5_arm_FT_payload_MPV.m | 52 + data/atlas5_arm_diff_MPV_wrt_PV2.m | 42 + data/atlas_arm_convert_PV2_MPV.m | 38 + data/atlas_arm_convert_par1_MPV.m | 139 + drc_paper_path_init.m | 13 + identification/load_experiment_data.m | 410 + paper/.gitignore | 1 + paper/atlas_iros_16.tex | 77 + .../Collision_Summary_Cinderblock.pdf | Bin 0 -> 157576 bytes .../ImpCtrl_E057_resultfigures_icra.m | 119 + ...mpCtrl_K300_wall_colldet_move_away_021.jpg | Bin 0 -> 143232 bytes ...Ctrl_K300_wall_nocolldet_collision_022.jpg | Bin 0 -> 145064 bytes .../CollDetCinderblock/image_source.md | 9 + paper/figures/CollDetStick/.gitignore | 1 + .../figures/CollDetStick/CollDetStickIROS.pdf | Bin 0 -> 208819 bytes .../CollDetStick/CollDetStick_Format.m | 140 + .../GOPR2201_ImpCtrlv5_E055_part4_t036.jpg | Bin 0 -> 206148 bytes ...01_ImpCtrlv5_E055_part4_t036_bearb.pdf_tex | 61 + ...PR2201_ImpCtrlv5_E055_part4_t036_bearb.svg | 511 + ..._ImpCtrlv5_E055_part4_t036_bearb_small.pdf | Bin 0 -> 186980 bytes ...R2201_ImpCtrlv5_E055_part4_t036_manual.txt | 12 + .../DisturbanceTorque/DistTorqueComp.pdf | Bin 0 -> 81631 bytes .../DisturbanceTorqueComp_Format.m | 105 + ...ExpEval_settings_ImpCtrlE061_R11_obscorr.m | 154 + .../ConstVel_AssemblyFigure_middle_plot.m | 121 + .../FrictionCharacteristics_left.pdf | Bin 0 -> 17009 bytes ...ictionCharacteristics_resultfigures_IROS.m | 156 + ...6_Joint4_ConstVel_Summary_medium_speed.pdf | Bin 0 -> 83887 bytes ...las5_plot_torque_ident_MPV_left_DRC_IROS.m | 178 + ...atlas5_plot_torque_ident_MPV_left_IROS.pdf | Bin 0 -> 84658 bytes .../rigid_flexible_joint_struktur.pdf | Bin 0 -> 1766 bytes .../rigid_flexible_joint_struktur.pdf_tex | 70 + .../rigid_flexible_joint_struktur.svg | 603 + .../ObserverFlowChart/observer_scheme.pdf | Bin 0 -> 65619 bytes .../ObsFeedthroughStiff_compare.pdf | Bin 0 -> 43319 bytes .../ObserverFeedthroughStiff_Format.m | 259 + .../ReactionScheme/reaction_scheme.pdf | Bin 0 -> 42113 bytes paper/ieeeconf.cls | 4593 ++++ paper/iros_references.bib | 354 + paper/sec_abstract_intro.tex | 101 + paper/sec_colldet.tex | 92 + paper/sec_compliance_obs.tex | 103 + paper/sec_ident.tex | 148 + paper/sec_model.tex | 281 + paper/sec_rest.tex | 29 + paper/simulations/EquivalentConstantError.m | 5 + paper/simulations/SimExp_MdlNoiseExtForce.pdf | Bin 0 -> 17180 bytes paper/simulations/SimExp_MesNoiseExtForce.pdf | Bin 0 -> 11708 bytes paper/simulations/SimExp_ObsExtForce.pdf | Bin 0 -> 111918 bytes ..._impctrl_sqrt_damping_test_extforce_comp.m | 242 + ...impctrl_sqrt_damping_test_extforce_noise.m | 334 + ...rl_sqrt_damping_test_extforce_noise_plot.m | 124 + paper/simulations/getNoiseLevel.m | 38 + plotting/atlas_plot_sl_compare.m | 147 + robot_model/atlas3_arm_fkine_num.m | 80 + robot_model/atlas3_arm_parameter_urdf.m | 141 + robot_model/atlas3_leg_convert_urdf_mdh.m | 65 + robot_model/atlas3_leg_fkine_num.m | 75 + robot_model/atlas3_leg_parameter_mdh.m | 65 + robot_model/atlas3_leg_parameter_urdf.m | 105 + robot_model/atlas3_torso_parameter_urdf.m | 79 + robot_model/atlas4_arm_fkine_num.m | 80 + robot_model/atlas4_arm_parameter_urdf.m | 148 + robot_model/atlas4_leg_convert_urdf_mdh.m | 65 + robot_model/atlas4_leg_fkine_num.m | 75 + robot_model/atlas4_leg_parameter_mdh.m | 65 + robot_model/atlas4_leg_parameter_urdf.m | 114 + robot_model/atlas4_torso_parameter_urdf.m | 79 + robot_model/atlas5_arm_convert_urdf_mdh.m | 105 + ...oriolisvec_fb_plin_minpar_sym_lag_varpar.m | 46 + ...isvec_fb_regressor_minpar_sym_lag_varpar.m | 1004 + ...m_e_kinetic_fb_reg_minpar_sym_lag_varpar.m | 179 + ...gy_kinetic_fb_plin_minpar_sym_lag_varpar.m | 41 + ...rgy_potential_plin_minpar_sym_lag_varpar.m | 43 + ...otential_regressor_minpar_sym_lag_varpar.m | 114 + robot_model/atlas5_arm_fkine.m | 40 + robot_model/atlas5_arm_fkine_num.m | 103 + ..._arm_gravload_plin_minpar_sym_lag_varpar.m | 45 + ...gravload_regressor_minpar_sym_lag_varpar.m | 113 + ...tia_plin_minpar_regressor_sym_lag_varpar.m | 569 + ...5_arm_inertia_plin_minpar_sym_lag_varpar.m | 52 + robot_model/atlas5_arm_jacobig.m | 28 + robot_model/atlas5_arm_jacobig_num.m | 82 + robot_model/atlas5_arm_parameter_mdh.m | 83 + robot_model/atlas5_arm_parameter_urdf.m | 119 + ...s5_simple_shapes_stf_plot_transformation.m | 73 + robot_model/atlas5_torso_parameter_urdf.m | 76 + robot_model/atlas_arm_convert_mdh_par1_par2.m | 55 + robot_model/atlas_arm_fkine.m | 46 + robot_model/atlas_arm_parameter_mdh.m | 46 + robot_model/atlas_arm_parameter_urdf.m | 40 + robot_model/atlas_calc_impctrl_output.m | 156 + robot_model/atlas_const.m | 354 + .../atlas_identification_experiment_test.m | 1324 + ...pctrl_sqrt_damping_test_settings_default.m | 157 + robot_model/atlas_leg_convert_par1_MPV.m | 112 + robot_model/atlas_leg_fkine.m | 47 + robot_model/atlas_leg_parameter_mdh.m | 43 + robot_model/atlas_plot_arm_link_stl.m | 109 + robot_model/atlas_plot_arm_stl.m | 34 + robot_model/atlas_plot_frames.m | 78 + robot_model/atlas_plot_leg_link_stl.m | 59 + robot_model/atlas_plot_leg_stl.m | 26 + robot_model/atlas_plot_robot.m | 86 + robot_model/atlas_plot_torso_link_stl.m | 53 + robot_model/atlas_plot_torso_stl.m | 24 + robot_model/atlas_torso_fkine.m | 68 + robot_model/atlas_torso_parameter_urdf.m | 37 + run_all_simulation_scripts.m | 18 + simulink/atlas_dynamic_library.mdl | 22619 ++++++++++++++++ simulink/atlas_impctrl_library.mdl | 14970 ++++++++++ .../atlas_joint_impctrl_sqrt_damping_test.mdl | 3894 +++ ...pctrl_sqrt_damping_test_settings_default.m | 157 + simulink/results/.gitignore | 1 + 118 files changed, 58858 insertions(+) create mode 100644 .gitignore create mode 100644 LICENSE.txt create mode 100644 README.MD create mode 100644 data/MPV_list.m create mode 100644 data/atlas5_arm_FT_payload_MPV.m create mode 100644 data/atlas5_arm_diff_MPV_wrt_PV2.m create mode 100644 data/atlas_arm_convert_PV2_MPV.m create mode 100644 data/atlas_arm_convert_par1_MPV.m create mode 100644 drc_paper_path_init.m create mode 100644 identification/load_experiment_data.m create mode 100644 paper/.gitignore create mode 100644 paper/atlas_iros_16.tex create mode 100644 paper/figures/CollDetCinderblock/Collision_Summary_Cinderblock.pdf create mode 100644 paper/figures/CollDetCinderblock/ImpCtrl_E057_resultfigures_icra.m create mode 100644 paper/figures/CollDetCinderblock/ImpCtrlv5_E057_R04_impCtrl_K300_wall_colldet_move_away_021.jpg create mode 100644 paper/figures/CollDetCinderblock/ImpCtrlv5_E057_R05_impCtrl_K300_wall_nocolldet_collision_022.jpg create mode 100644 paper/figures/CollDetCinderblock/image_source.md create mode 100644 paper/figures/CollDetStick/.gitignore create mode 100644 paper/figures/CollDetStick/CollDetStickIROS.pdf create mode 100644 paper/figures/CollDetStick/CollDetStick_Format.m create mode 100644 paper/figures/CollDetStick/GOPR2201_ImpCtrlv5_E055_part4_t036.jpg create mode 100644 paper/figures/CollDetStick/GOPR2201_ImpCtrlv5_E055_part4_t036_bearb.pdf_tex create mode 100644 paper/figures/CollDetStick/GOPR2201_ImpCtrlv5_E055_part4_t036_bearb.svg create mode 100644 paper/figures/CollDetStick/GOPR2201_ImpCtrlv5_E055_part4_t036_bearb_small.pdf create mode 100644 paper/figures/CollDetStick/GOPR2201_ImpCtrlv5_E055_part4_t036_manual.txt create mode 100644 paper/figures/DisturbanceTorque/DistTorqueComp.pdf create mode 100644 paper/figures/DisturbanceTorque/DisturbanceTorqueComp_Format.m create mode 100755 paper/figures/DisturbanceTorque/IdentExpEval_settings_ImpCtrlE061_R11_obscorr.m create mode 100644 paper/figures/Identification/ConstVel_AssemblyFigure_middle_plot.m create mode 100644 paper/figures/Identification/FrictionCharacteristics_left.pdf create mode 100644 paper/figures/Identification/FrictionCharacteristics_resultfigures_IROS.m create mode 100644 paper/figures/Identification/SI_E036_Joint4_ConstVel_Summary_medium_speed.pdf create mode 100644 paper/figures/Identification/atlas5_plot_torque_ident_MPV_left_DRC_IROS.m create mode 100644 paper/figures/Identification/atlas5_plot_torque_ident_MPV_left_IROS.pdf create mode 100644 paper/figures/MechErsatzBSB/rigid_flexible_joint_struktur.pdf create mode 100644 paper/figures/MechErsatzBSB/rigid_flexible_joint_struktur.pdf_tex create mode 100644 paper/figures/MechErsatzBSB/rigid_flexible_joint_struktur.svg create mode 100644 paper/figures/ObserverFlowChart/observer_scheme.pdf create mode 100644 paper/figures/ObserverStiff/ObsFeedthroughStiff_compare.pdf create mode 100644 paper/figures/ObserverStiff/ObserverFeedthroughStiff_Format.m create mode 100644 paper/figures/ReactionScheme/reaction_scheme.pdf create mode 100644 paper/ieeeconf.cls create mode 100644 paper/iros_references.bib create mode 100644 paper/sec_abstract_intro.tex create mode 100644 paper/sec_colldet.tex create mode 100644 paper/sec_compliance_obs.tex create mode 100644 paper/sec_ident.tex create mode 100644 paper/sec_model.tex create mode 100644 paper/sec_rest.tex create mode 100644 paper/simulations/EquivalentConstantError.m create mode 100644 paper/simulations/SimExp_MdlNoiseExtForce.pdf create mode 100644 paper/simulations/SimExp_MesNoiseExtForce.pdf create mode 100644 paper/simulations/SimExp_ObsExtForce.pdf create mode 100644 paper/simulations/atlas_joint_impctrl_sqrt_damping_test_extforce_comp.m create mode 100644 paper/simulations/atlas_joint_impctrl_sqrt_damping_test_extforce_noise.m create mode 100644 paper/simulations/atlas_joint_impctrl_sqrt_damping_test_extforce_noise_plot.m create mode 100644 paper/simulations/getNoiseLevel.m create mode 100644 plotting/atlas_plot_sl_compare.m create mode 100644 robot_model/atlas3_arm_fkine_num.m create mode 100644 robot_model/atlas3_arm_parameter_urdf.m create mode 100644 robot_model/atlas3_leg_convert_urdf_mdh.m create mode 100644 robot_model/atlas3_leg_fkine_num.m create mode 100644 robot_model/atlas3_leg_parameter_mdh.m create mode 100644 robot_model/atlas3_leg_parameter_urdf.m create mode 100644 robot_model/atlas3_torso_parameter_urdf.m create mode 100644 robot_model/atlas4_arm_fkine_num.m create mode 100644 robot_model/atlas4_arm_parameter_urdf.m create mode 100644 robot_model/atlas4_leg_convert_urdf_mdh.m create mode 100644 robot_model/atlas4_leg_fkine_num.m create mode 100644 robot_model/atlas4_leg_parameter_mdh.m create mode 100644 robot_model/atlas4_leg_parameter_urdf.m create mode 100644 robot_model/atlas4_torso_parameter_urdf.m create mode 100644 robot_model/atlas5_arm_convert_urdf_mdh.m create mode 100644 robot_model/atlas5_arm_coriolisvec_fb_plin_minpar_sym_lag_varpar.m create mode 100644 robot_model/atlas5_arm_coriolisvec_fb_regressor_minpar_sym_lag_varpar.m create mode 100755 robot_model/atlas5_arm_e_kinetic_fb_reg_minpar_sym_lag_varpar.m create mode 100755 robot_model/atlas5_arm_energy_kinetic_fb_plin_minpar_sym_lag_varpar.m create mode 100755 robot_model/atlas5_arm_energy_potential_plin_minpar_sym_lag_varpar.m create mode 100755 robot_model/atlas5_arm_energy_potential_regressor_minpar_sym_lag_varpar.m create mode 100755 robot_model/atlas5_arm_fkine.m create mode 100644 robot_model/atlas5_arm_fkine_num.m create mode 100755 robot_model/atlas5_arm_gravload_plin_minpar_sym_lag_varpar.m create mode 100755 robot_model/atlas5_arm_gravload_regressor_minpar_sym_lag_varpar.m create mode 100644 robot_model/atlas5_arm_inertia_plin_minpar_regressor_sym_lag_varpar.m create mode 100644 robot_model/atlas5_arm_inertia_plin_minpar_sym_lag_varpar.m create mode 100755 robot_model/atlas5_arm_jacobig.m create mode 100755 robot_model/atlas5_arm_jacobig_num.m create mode 100644 robot_model/atlas5_arm_parameter_mdh.m create mode 100644 robot_model/atlas5_arm_parameter_urdf.m create mode 100644 robot_model/atlas5_simple_shapes_stf_plot_transformation.m create mode 100644 robot_model/atlas5_torso_parameter_urdf.m create mode 100644 robot_model/atlas_arm_convert_mdh_par1_par2.m create mode 100644 robot_model/atlas_arm_fkine.m create mode 100644 robot_model/atlas_arm_parameter_mdh.m create mode 100644 robot_model/atlas_arm_parameter_urdf.m create mode 100644 robot_model/atlas_calc_impctrl_output.m create mode 100644 robot_model/atlas_const.m create mode 100644 robot_model/atlas_identification_experiment_test.m create mode 100644 robot_model/atlas_joint_impctrl_sqrt_damping_test_settings_default.m create mode 100644 robot_model/atlas_leg_convert_par1_MPV.m create mode 100644 robot_model/atlas_leg_fkine.m create mode 100644 robot_model/atlas_leg_parameter_mdh.m create mode 100644 robot_model/atlas_plot_arm_link_stl.m create mode 100644 robot_model/atlas_plot_arm_stl.m create mode 100644 robot_model/atlas_plot_frames.m create mode 100644 robot_model/atlas_plot_leg_link_stl.m create mode 100644 robot_model/atlas_plot_leg_stl.m create mode 100644 robot_model/atlas_plot_robot.m create mode 100644 robot_model/atlas_plot_torso_link_stl.m create mode 100644 robot_model/atlas_plot_torso_stl.m create mode 100644 robot_model/atlas_torso_fkine.m create mode 100644 robot_model/atlas_torso_parameter_urdf.m create mode 100644 run_all_simulation_scripts.m create mode 100644 simulink/atlas_dynamic_library.mdl create mode 100644 simulink/atlas_impctrl_library.mdl create mode 100644 simulink/atlas_joint_impctrl_sqrt_damping_test.mdl create mode 100644 simulink/atlas_joint_impctrl_sqrt_damping_test_settings_default.m create mode 100644 simulink/results/.gitignore diff --git a/.gitignore b/.gitignore new file mode 100644 index 0000000..d8f4d79 --- /dev/null +++ b/.gitignore @@ -0,0 +1,20 @@ +*.aux +*.bbl +*.blg +*.log +*.synctex.gz +*~ +*.bak +*.asv +*.ps +*.dvi +*.orig +*.nav +*.out +*.snm +*.toc +*.soc +slprj +*.mdl.r* +*.autosave +*.slxc diff --git a/LICENSE.txt b/LICENSE.txt new file mode 100644 index 0000000..0677443 --- /dev/null +++ b/LICENSE.txt @@ -0,0 +1,21 @@ +MIT License + +Copyright (c) 2020 Institut für Regelungstechnik, Leibniz Universität Hannover + +Permission is hereby granted, free of charge, to any person obtaining a copy +of this software and associated documentation files (the "Software"), to deal +in the Software without restriction, including without limitation the rights +to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +copies of the Software, and to permit persons to whom the Software is +furnished to do so, subject to the following conditions: + +The above copyright notice and this permission notice shall be included in all +copies or substantial portions of the Software. + +THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +SOFTWARE. diff --git a/README.MD b/README.MD new file mode 100644 index 0000000..b3146fb --- /dev/null +++ b/README.MD @@ -0,0 +1,68 @@ +# Soft Robotics for the Hydraulic Atlas Arms: Joint Impedance Control with Collision Detection and Disturbance Compensation + +Authors: +Jonathan Vorndamme, Moritz Schappler, Alexander Tödtheide, and Sami Haddadin + +This repository provides supplemental material to the following publication at the IEEE ICRA 2017 conference: + +```bib + +@InProceedings{VorndammeSchToeHad2016, + author = {Jonathan Vorndamme and Moritz Schappler and Alexander Tödtheide and Sami Haddadin}, + booktitle = {2016 {IEEE}/{RSJ} International Conference on Intelligent Robots and Systems ({IROS})}, + title = {Soft Robotics for the Hydraulic {A}tlas Arms: Joint Impedance Control with Collision Detection and Disturbance Compensation}, + doi = {10.1109/iros.2016.7759517}, + year = {2016}, +} +``` + +## Abstract + +Soft robotics methods such as impedance control and reflexive collision handling have proven to be a valuable tool to robots acting in partially unknown and potentially unstructured environments. Mainly, the schemes were developed with focus on classical electromechanically driven, torque controlled robots. There, joint friction, mostly coming from high gearing, is typically decoupled from link-side control via suitable rigid or elastic joint torque feedback. Extending and applying these algorithms to stiff hydraulically actuated robots poses problems regarding the strong influence of friction on joint torque estimation from pressure sensing, i.e. link-side friction is typically significantly higher than in electromechanical soft robots. In order to improve the performance of such systems, we apply state-of-the-art fault detection and estimation methods together with observer-based disturbance compensation control to the humanoid robot Atlas. With this it is possible to achieve higher tracking accuracy despite facing significant modeling errors. Compliant end-effector behavior can also be ensured by including an additional force/torque sensor into the generalized momentum-based disturbance observer algorithm from De Luca et al. + +## Contents + +This repository contains Matlab scripts and Latex code to reproduce the simulative results of the paper. + +### Dependencies + +The path initialization script `drc_paper_path_init.m` has to be run in Matlab. + +The following repositories have to be downloaded and their respective `...path_init.m` has to be run: + +* https://github.com/SchapplM/robotics-dep-ext +* https://github.com/SchapplM/robotics-toolbox +* https://github.com/SchapplM/matlab_toolbox +* https://github.com/SchapplM/robotics-dep-geometry + +Some Matlab functions have to be compiled using the Mex compiler. This is done with `atlas_collhdl_mex_all.m`. A Mex compiler has to be installed and configured within Matlab. + +### Scripts for Simulation of the Controller + +The following scripts can be found in the directory `paper/simulations`. + +* Fig. 12 is created by `atlas_joint_impctrl_sqrt_damping_test_extforce_comp.m`. This calls the simulink model `simulink/atlas_joint_impctrl_sqrt_damping_test.mdl`, which also contains links to the implementation of the impedance controller. +* To be able to create Fig. 13 and 14, first run `atlas_joint_impctrl_sqrt_damping_test_extforce_noise.m`. This takes a while. +* The figures 13 and 14 are then created with `atlas_joint_impctrl_sqrt_damping_test_extforce_noise_plot.m`. + +### Scripts for Processing of Measurement Data + +The following scripts in the directory `paper/figures` process data recorded during the experiments, which is not part of this repository. + +* Fig. 4: `Identification/FrictionCharacteristics_resultfigures_IROS.m` +* Fig. 5: `Identification/ConstVel_AssemblyFigure_middle_plot.m` +* Fig. 6: `Identification/atlas5_plot_torque_ident_MPV_left_DRC_IROS.m` +* Fig. 8: `CollDetCinderblock/ImpCtrl_E057_resultfigures_icra.m` +* Fig. 10: `CollDetStick/CollDetStick_Format.m` +* Fig. 11: `ObserverStiff/ObserverFeedthroughStiff_Format.m` + +### Implementation of the Impedance Controller + +The impedance controller from Equ. 2 and the disturbance observer from Equ. 4-6 is implemented in the simulink library `atlas_impctrl_library.mdl` in the directory `simulink`. The dynamics of the robot are stored in the library `atlas_dynamic_library.mdl`. +The simulink blocks in the library can be obtained best by opening `atlas_joint_impctrl_sqrt_damping_test.mdl` and then following the library links. + + A more general version of the impedance controller and the test script for Fig. 12 is stored in the [robotics toolbox in the directory examples_tests/impedance_controller](https://github.com/SchapplM/robotics-toolbox/tree/master/examples_tests/impedance_controller). The simulink implementation is generalized within the library [lib_joint_impctrl.mdl in the toolbox directory controllers](https://github.com/SchapplM/robotics-toolbox/tree/master/controllers). This allows an easier implementation for other robots. + +### Kinematics and Dynamics Model + +The files with kinematics and dynamics functions in `robot_model` are generated by a [dynamics model generation toolbox](https://github.com/SchapplM/robsynth-modelgen/) based on Maple. The input files for creating the required models atlas5arm, atlas4leg and atlas5wbody are stored in the [directory robot_codegen_definitions/examples of the toolbox](https://github.com/SchapplM/robsynth-modelgen/tree/master/robot_codegen_definitions/examples). diff --git a/data/MPV_list.m b/data/MPV_list.m new file mode 100644 index 0000000..90e301d --- /dev/null +++ b/data/MPV_list.m @@ -0,0 +1,123 @@ +% Hard coded list of identified and tested base parameter vectors (MPV) +% +% Output: +% MPV_Liste +% List of identified or calculated MPVs +% Fields: +% name +% Unique name as in [1] +% lr +% left=true, right=false +% MPV +% base parameter vector +% Friction +% Friction koefficients (coulomb/viscous) +% ident +% true if parameters come from identification, false if from drcsim +% additional_info +% description +% Source: +% [1] https://external.torcrobotics.com/redmine-drc/projects/drc/wiki/List_of_System_Identification_Results + +% Moritz Schappler, schappler@irt.uni-hannover.de, 2015-06 +% (c) Institut für Regelungstechnik, Universität Hannover + +function MPV_Liste = MPV_list() + +MPV_Liste = struct('Name', [], 'lr', [], 'MPV', [], 'ident', [], 'Friction', [], 'additional_info', {}); +MPV_Liste(1).Name = 'Left_Arm_MPV_001'; +MPV_Liste(1).lr = true; +MPV_Liste(1).MPV = [0.1573871065, -1.5595029000, 0.0000000000, 0.7859850378, 0.0448462400, 0.0000000000, 0.0000000000, 0.7949079018, 0.1791520000, -2.8028900000, 0.0042486140, 0.0000000000, 0.0000000000, 0.0000000000, 0.0091505215, 0.0718428000, 0.0000000000, 0.4781205055, -0.0146219341, 0.0000000000, 0.0000000000, 0.4816696410, -0.0488130000, -1.5876150000, 0.0918000000, 0.0000000000, 0.0000000000, 0.0000000000, 0.0948000000, 0.0000000000, -0.4240000000, 0.0204450000, 0.0000000000, 0.0000000000, 0.0000000000, 0.0244450000, 0.0000000000, 0.1855000000, 0.0000980000, 0.0000000000, 0.0000000000, 0.0000000000, 0.0063680000, 0.0000000000, 0.0318000000]'; +MPV_Liste(1).ident = false; + +MPV_Liste(2).Name = 'Right_Arm_MPV_001'; +MPV_Liste(2).lr = false; +MPV_Liste(2).MPV = [0.1573871065, 1.5595029000, 0.0000000000, 0.9507095978, -0.0518932800, 0.0000000000, 0.0000000000, 0.9596324618, 0.1791520000, 3.2433300000, 0.0042488092, 0.0000000000, 0.0000000000, 0.0000000000, 0.0091507168, 0.0718428000, 0.0000000000, 0.4781203102, 0.0146251094, 0.0000000000, 0.0000000000, 0.4816698363, -0.0488236000, 1.5876150000, 0.0918000000, 0.0000000000, 0.0000000000, 0.0000000000, 0.0948000000, 0.0000000000, -0.4240000000, 0.0204450000, 0.0000000000, 0.0000000000, 0.0000000000, 0.0244450000, 0.0000000000, -0.1855000000, 0.0000980000, 0.0000000000, 0.0000000000, 0.0000000000, 0.0063680000, 0.0000000000, -0.0318000000]'; +MPV_Liste(2).ident = false; + +MPV_Liste(length(MPV_Liste)+1).Name = 'Left_Arm_MPV_002'; +MPV_Liste(length(MPV_Liste) ).lr = true; +MPV_Liste(length(MPV_Liste) ).MPV = [0.76548134176328086475, 2.18579532371411033864, -3.36679020219315816576, 0.36570945929635051419, 0.06608140056466821344, 0.08703601222236768964, 0.01335995346019671660, 0.95089897869440120903, -0.26970649558347592478, -2.81892435599024926418, -0.03820618012581489947, 0.00681925538585450002, 0.04636309883851623403, -0.04642438144604121852, 0.04868499211377804586, 0.05931714107610924769, -0.10597597978878517400, 0.22010084420300898844, 0.02837399040227467362, -0.00423553073840591751, -0.01437966021789946307, 0.24811687708054733226, 0.04234643072573841122, -0.90025729415270228095, -0.00495306442733004382, 0.03184168034963766325, 0.02054908037286609299, -0.00243787503652728027, 0.02263923829643003927, -0.03132287032197611509, 0.00082180820216224727, 0.01127094051557824515, -0.01706075121794684360, -0.01307998776117153157, 0.03260419512895625094, 0.00166716905898238454, 0.03538516556760971238, -0.04241550412335153702, 0.00717867388240493384, -0.01082530682058349160, 0.01899495959933841446, 0.01740687266806503763, 0.02472459586141461871, 0.01247281703553209699, -0.01045265287992424609]'; +MPV_Liste(length(MPV_Liste) ).Friction =[]; +MPV_Liste(length(MPV_Liste) ).ident =true; +MPV_Liste(length(MPV_Liste) ).additional_info = {}; + +MPV_Liste(length(MPV_Liste)+1).Name = 'Left_Arm_MPV_003'; +MPV_Liste(length(MPV_Liste) ).lr = true; +MPV_Liste(length(MPV_Liste) ).MPV = [0.15436687558901718287, -1.79001699728903895803, 0.30983917908757691029, 1.24637502870675609401, -0.10820084924366554779, 0.00785994900132328499, 0.18358336527316104769, 1.27459695794607141828, -0.42285872571384763852, -3.44562711124992304690, -0.10495456788994080022, 0.10890083632644231848, 0.03538745883526583230, 0.00636513269808429948, -0.13704943655502493938, -0.12309124153899400622, 0.06180971565110134763, 0.26009070303100539912, -0.08678918389394592314, -0.02522801708759258091, 0.01916413331656796268, 0.29079466436111167660, 0.03903009384060714820, -1.26434325338835384933, 0.14991819078149351552, -0.08215246067327044988, 0.00357905320150150646, 0.02692025785318218067, 0.16008790690168647752, 0.15765743192046441368, -0.11613132417786538320, -0.04321613861548635749, -0.00309719153537051138, 0.07195760364857979596, 0.02499312922903758685, 0.03665121525567988092, 0.10333210964408531818, -0.31217237385807206085, -0.02899008880494072585, 0.01070712148771495523, 0.03981404801325769127, -0.00904265051274576181, -0.10178500431115558578, 0.00132297908715041379, 0.31110382503834060897]'; +MPV_Liste(length(MPV_Liste) ).Friction =[]; +MPV_Liste(length(MPV_Liste) ).ident =true; +MPV_Liste(length(MPV_Liste) ).additional_info = {}; + +MPV_Liste(length(MPV_Liste)+1).Name = 'Left_Arm_MPV_004'; +MPV_Liste(length(MPV_Liste) ).lr = true; +MPV_Liste(length(MPV_Liste) ).MPV = [0.33393074746729478619, 0.49168264078906454007, -0.57221507078970168525, 0.82327045149314936889, -0.08418816468869724789, -0.13430148925623175415, 0.11486642418011108746, 1.06363747322025226083, -0.57584896999723444999, -3.53144978241003082431, -0.40707763938598551245, -0.01085789356312704540, 0.09928160558900700483, -0.02659211725480692054, -0.10344321475518375442, 0.09181197634210225278, 0.04142935241922292983, 0.29482150004546642252, -0.08280242970439875838, 0.06062576971226957961, 0.04570616457733767124, 0.08446571782632668335, -0.02520039950329647921, -1.27341704533674771049, 0.20055221930778924233, 0.01853447013009582034, 0.01225421978262815695, 0.05179387581220479958, 0.22001467062863616642, -0.12976354531130390724, -0.05394019153867368049, -0.10034622082370425744, 0.03388951709722081568, 0.01762486241647511637, -0.01140460680125916434, 0.22042329864439155762, 0.16662207709952214785, -0.23715064432276203310, 0.01539908392181162967, 0.00055782813150621012, 0.06046483074290523452, -0.02690483767828424910, 0.03682403744281181890, 0.05001496162528824840, -0.06152253204488489918]'; +MPV_Liste(length(MPV_Liste) ).Friction = [1.18299176326868060727, 2.14588859012265764648, 2.06829633818479186047, 3.01748110617867215666, -0.02704179148459615045, 0.91573120628035986623, 0.08058582011596240879, 1.48031686050016797473, 2.92184185279183950001, 6.53155898566343040557, 5.00257897004997964530, 1.67057544092897569676, 0.01557262634338507819, -0.27032147417743540574]'; +MPV_Liste(length(MPV_Liste) ).ident =true; +MPV_Liste(length(MPV_Liste) ).additional_info = {}; + +MPV_Liste(length(MPV_Liste)+1).Name = 'Right_Arm_MPV_002'; +MPV_Liste(length(MPV_Liste) ).lr = false; +MPV_Liste(length(MPV_Liste) ).MPV = [0.42134348471511529066, -16.23026693110771390138, -23.36695698059924097834, 0.92207471578907274079, 0.48571811273489245986, 0.14329552123467678704, -0.03817461619820469026, 1.02500379777448080709, -1.05704969525885839055, 3.60857509639060358708, -0.04636527654728531816, -0.01176704058168475189, -0.12629020393054965488, -0.02030838429537643389, 0.27258640564685909791, -0.02918252512304901972, -0.00094093262345408850, -0.08371383280467957488, 0.11682081290503826265, 0.10288382824394387560, -0.11954366757750831129, -0.12390060609871730857, -0.17887153454899754057, 1.50209361980077726884, 0.22490756357577876279, 0.02879753093785196102, -0.01489701165628885306, 0.07500784243600927548, -0.27824595273857766209, 0.07763883590612156993, -0.01892392810455879870, 0.03224065720185817496, -0.03186865017330495209, 0.08373153525935926600, 0.10970848781700641428, 0.48210903837929847127, 0.16810833412808501297, 0.16594023041669270224, 0.04249104640423352619, -0.04695738353846781038, -0.03633040646273997393, -0.02004118196562151843, 0.30394816786724060398, -0.17855625388902371387, -0.14060832107883616815]'; +MPV_Liste(length(MPV_Liste) ).Friction =[]; +MPV_Liste(length(MPV_Liste) ).ident =true; +MPV_Liste(length(MPV_Liste) ).additional_info = {}; + +MPV_Liste(length(MPV_Liste)+1).Name = 'Right_Arm_MPV_003'; +MPV_Liste(length(MPV_Liste) ).lr = false; +MPV_Liste(length(MPV_Liste) ).MPV = [-0.06397965518616706426, -9.52688942151654316604, -36.98868260321970780069, 0.86487085403325680844, 0.11504623077856082625, -0.08313162761295336822, 0.00413363243117902211, 1.02838283970518440391, -1.53296503384768478817, 3.25370379622049954449, -0.01584591185359230867, -0.02655075740129327413, -0.00074154392311962826, 0.11197065232891185993, -0.33114619201000838888, -0.16855472557503967113, -0.44660725764374759050, 0.31038042401991605690, 0.04082016456675067323, -0.02983460990933904655, 0.08185630030854806893, 0.16879834209737015760, 0.13204941152845139918, 1.29387160081679697399, 0.39492240719297205809, -0.01992939510595776592, 0.02546700503387202066, -0.00991975202008979137, 0.38940136393954610794, 0.07337548852500354324, 0.08476583064572047743, -0.18669642232000499549, -0.00091355345345075850, -0.05173544288127391449, -0.06261723285910181236, 0.16809212399538883687, -0.06428726581931240580, 0.24318684381672436845, 0.04661438914238174441, 0.03925865841878396073, -0.00496274444159157564, 0.07861764340326352074, -0.21399989459288729088, 0.21113243300162112814, -0.02639790999401218571]'; +MPV_Liste(length(MPV_Liste) ).Friction =[3.61749506639503071170, 3.83982288303048502343, 6.28385761019903554825, 5.73245274341846844379, 5.81961761348425099527, 1.00527371109305119212, 0.11027915337759580661, 0.40168714794518145528, 2.48804277559938080699, 5.15724924874063184177, 7.76537839504549598502, -9.17456512663697587584, -0.53307087108855344404, -1.39797729436355266941]'; +MPV_Liste(length(MPV_Liste) ).ident =true; +MPV_Liste(length(MPV_Liste) ).additional_info = {}; + +MPV_Liste(length(MPV_Liste)+1).Name = 'Right_Arm_MPV_004'; +MPV_Liste(length(MPV_Liste) ).lr = false; +MPV_Liste(length(MPV_Liste) ).MPV = [0.39287250477001284255, -12.54370357855884599019, -35.01345761454054894557, 0.64163115970224426921, 0.47286316508774295375, 0.08343037692690663532, -0.00570249871463831062, 0.98669847850249348120, -0.98164402875668665960, 3.57314945067820355362, -0.04289803304907951337, 0.03929710556882153039, -0.13163856310010371709, -0.01111616530801225536, 0.20585219189256356853, 0.00596413801347008346, -0.01622521820684819094, -0.14925463815771269904, 0.09683043751708038382, 0.08975280355411398292, -0.06993981653503519857, -0.18940237490948957921, -0.02922481813766847347, 1.33696052368277173983, 0.21500814191347533688, 0.03606394660374128563, 0.01627661970159693591, 0.07344159537996731990, -0.30591584309367625405, -0.00052887762055183114, -0.08427204774360709527, 0.05695846649959473984, -0.04623189412992154135, 0.05460992783416721702, 0.06956614010490985711, 0.45832367118003397577, 0.08044369389062833164, 0.23076859772703198215, 0.06443878588169359156, -0.05402057946270356209, -0.06870428986741816679, -0.01907403610527726168, 0.27454912924809449226, -0.00177915263824457350, -0.12143076077160484816]'; +MPV_Liste(length(MPV_Liste) ).Friction = [2.93075082634048644792, 2.13290176964670186166, 2.28502342751290710154, 5.48389978960351509585, 0.58999142764465672961, 1.25158156563887401624, 0.61832368270332316307, 0.81728514297995591420, 3.53874972078109673035, 5.78615532358833828397, 5.73811654850812313811, -1.21852772600630854249, -0.52305525236760830321, -0.79606020015439304949]'; +MPV_Liste(length(MPV_Liste) ).ident =true; +MPV_Liste(length(MPV_Liste) ).additional_info = {}; + +MPV_Liste(length(MPV_Liste)+1).Name = 'Left_Arm_MPV_005'; +MPV_Liste(length(MPV_Liste) ).lr = true; +MPV_Liste(length(MPV_Liste) ).MPV = [0.1971953692, -1.6769170000, 0.0000000000, 0.7212042630, -0.0426361632, 0.0000000000, 0.0000000000, 0.7302032614, -0.1815312000, -2.6647602000, 0.0041857726, 0.0000000000, 0.0000000000, 0.0000000000, 0.0089439106, 0.0640292400, 0.0000000000, 0.2325545978, -0.0083453240, 0.0000000000, 0.0000000000, 0.2358342810, -0.0341847570, -0.9061155270, 0.0040014567, -0.0000001376, 0.0000761180, 0.0000308586, 0.0070021357, 0.0009175260, 0.0004821300, 0.0099451335, 0.0000265644, -0.0000001796, 0.0000027705, 0.0139485768, 0.0010562400, -0.0639376010, 0.0018100147, -0.0000000019, -0.0000009528, -0.0000076225, 0.0044600152, 0.0000116780, 0.0000934240]'; +MPV_Liste(length(MPV_Liste) ).Friction =[]; +MPV_Liste(length(MPV_Liste) ).ident =false; +MPV_Liste(length(MPV_Liste) ).additional_info = {'from URDF'}; + +MPV_Liste(length(MPV_Liste)+1).Name = 'Right_Arm_MPV_005'; +MPV_Liste(length(MPV_Liste) ).lr = false; +MPV_Liste(length(MPV_Liste) ).MPV = [0.1971953692, 1.6769170000, 0.0000000000, 0.7212042630, 0.0426361632, 0.0000000000, 0.0000000000, 0.7302032614, -0.1815312000, 2.6647602000, 0.0041857726, 0.0000000000, 0.0000000000, 0.0000000000, 0.0089439106, 0.0640292400, 0.0000000000, 0.2325545978, 0.0083453240, 0.0000000000, 0.0000000000, 0.2358342810, -0.0341847570, 0.9061155270, 0.0040014567, -0.0000001376, -0.0000761180, -0.0000308586, 0.0070021357, 0.0009175260, 0.0004821300, 0.0099451335, -0.0000265644, -0.0000001796, -0.0000027705, 0.0139485768, 0.0010562400, 0.0639376010, 0.0018100147, -0.0000000019, 0.0000009528, 0.0000076225, 0.0044600152, 0.0000116780, 0.0000934240]'; +MPV_Liste(length(MPV_Liste) ).Friction =[]; +MPV_Liste(length(MPV_Liste) ).ident =false; +MPV_Liste(length(MPV_Liste) ).additional_info = {'from URDF'}; + +MPV_Liste(length(MPV_Liste)+1).Name = 'Left_Arm_MPV_006'; +MPV_Liste(length(MPV_Liste) ).lr = true; +MPV_Liste(length(MPV_Liste) ).MPV = [-6.31726457212190783963, 6.19186706562645294838, -4.52954483970101318135, 1.33300829296491851750, 0.16375090020275578917, -0.59883151603209883174, -0.94112815719782838553, -1.15453105617105378222, 0.77159519435230361495, -3.33909858694973671334, 0.44153639221386153935, -0.85836066306336467058, -0.80719008283833715289, 0.78044670330038068418, -0.13420847821931899957, 0.40642984377640284377, -0.40794259727986365016, -0.41072849445447279226, -0.01622795953721931084, -0.21995407256137042284, -0.75627820796665257141, 0.15157987497483305095, -0.59751341275161573563, -0.95720520736342940005, -0.33798370404876915130, -0.06721120366409800984, 0.43436894567278389045, 0.18728782725596215819, -0.34754568414455194736, 0.08034307221600793525, 0.03756232428400394646, 0.02670007067191093944, -0.28938625437625548065, 0.01732954904755147282, 0.25008577825316474774, -0.05579910078542373031, 0.03505411234175155599, -0.02197435680574784389, -0.05648758001688295588, 0.08663948273276075862, -0.32693153084000420305, 0.20097133788789273146, -0.22973526805495825265, 0.04604165520189010263, -0.04179653465772796561]'; +MPV_Liste(length(MPV_Liste) ).Friction = [1.19999999999999995559, 0.59999999999999997780, 1.60000000000000008882, 2.60000000000000008882, 0.55000000000000004441, 0.25000000000000000000, 0.20000000000000001110, 2.00000000000000000000, 6.90000000000000035527, 10.30000000000000071054, 6.00000000000000000000, 0.05000000000000000278, 0.04000000000000000083, 3.10000000000000008882]'; +MPV_Liste(length(MPV_Liste) ).ident =true; +MPV_Liste(length(MPV_Liste) ).additional_info = {'Generated in 2015.07.28-10:40:01_left_dyn_assume_frct_1-7, MPV_3_L.txt, joint friction experiments'}; + +MPV_Liste(length(MPV_Liste)+1).Name = 'Right_Arm_MPV_006'; +MPV_Liste(length(MPV_Liste) ).lr = false; +MPV_Liste(length(MPV_Liste) ).MPV = [-7.58142159477708243998, 0.02065865131884787181, -6.53207666479888171551, 2.25417596181722856841, -0.12276950448848626685, 0.30405767700691210820, -0.94730556322036396644, -2.40227390143230046249, 0.30663363224687567588, 3.65771490740324223268, -0.75849133393691869909, -0.70836201886722005572, 0.53685840834949460909, 0.41873875402391430578, -0.24591572383184262529, 0.81682466322523272773, -0.43527007594736560891, 0.44510775634630050934, -0.00563538173359354015, -0.55867669455646484789, 0.59844901758989410556, -0.23103907187214098307, -0.52136543507834787192, 0.80639702194366680299, 0.03022540309892494254, 0.35540201135893678686, -0.21728138389892981408, -0.02090324393437515901, -0.33485649106354808957, -0.01067059890697879231, -0.02041802140501606383, -0.04368624382510415821, 0.10990573783540509567, -0.19795599445355038792, -0.35287151304694602816, -0.08278116993594696049, 0.01511361621728222679, -0.02209512710809223568, -0.17107106378099468103, 0.19283024995536465762, 0.13558219332972154536, -0.11866747674316464878, 0.14067785768636209554, -0.00008349919210985161, -0.08359357598910950593]'; +MPV_Liste(length(MPV_Liste) ).Friction = [1.19999999999999995559, 0.59999999999999997780, 1.60000000000000008882, 2.60000000000000008882, 0.50000000000000000000, 0.22000000000000000111, 0.20000000000000001110, 1.60000000000000008882, 8.00000000000000000000, 6.70000000000000017764, 8.40000000000000035527, 1.30000000000000004441, 1.64999999999999991118, 1.80000000000000004441]'; +MPV_Liste(length(MPV_Liste) ).ident =true; +MPV_Liste(length(MPV_Liste) ).additional_info = {'Generated in 2015.07.28-10:42:32_right_dyn_assume_frct_1-7_shz_offset, MPV_3_R.txt, joint friction experiments'}; + + +% Ersetze in allen MPV die Einträge 2 und 3 (üblicherweise schlecht +% angeregt) durch Originialeinträge + +for il = 1:length(MPV_Liste) + if MPV_Liste(il).ident == false + % Kein Bedarf einer korrigierten Version für MPV aus drcsim-Daten + continue + end + nl = length(MPV_Liste); + MPV_Liste(nl+1).Name = [MPV_Liste(il).Name, '_korr']; + MPV_Liste(nl+1).MPV = MPV_Liste(il).MPV; + % TODO: Anpassung an links/rechts + MPV_Liste(nl+1).MPV(2:3) = MPV_Liste(1).MPV(2:3); + MPV_Liste(nl+1).lr = MPV_Liste(il).lr; +end diff --git a/data/atlas5_arm_FT_payload_MPV.m b/data/atlas5_arm_FT_payload_MPV.m new file mode 100644 index 0000000..d0b37e5 --- /dev/null +++ b/data/atlas5_arm_FT_payload_MPV.m @@ -0,0 +1,52 @@ +% Return MPV for payload behind F/T sensor +% +% Only use static parameters. Ignore inertia of the payload. +% Assume payload CoM data in hand frame (not: FT sensor frame). +% +% Input: +% m_pl +% mass of the payload +% r_pl_EE +% center of mass of the payload (in hand-frame) +% I_pl_EE +% inertia of the payload (in hand frame) +% order: XX, XY, XZ, YY, YZ, ZZ +% lr +% left/right flag +% Output: +% MPV_payload +% Testfunction: +% calibration/hand_force_torque_calibration_test + +% Moritz Schappler, schappler@irt.uni-hannover.de, 2015-04 +% (c) Institut für Regelungstechnik, Universität Hannover + + + +function MPV_payload = atlas5_arm_FT_payload_MPV(m_pl, r_pl_EE, I_pl_EE, lr) + +%% Init +assert(isa(m_pl,'double') && isreal(m_pl) && all(size(m_pl) == [1 1])); +assert(isa(r_pl_EE,'double') && isreal(r_pl_EE) && all(size(r_pl_EE) == [3 1])); +assert(isa(I_pl_EE,'double') && isreal(I_pl_EE) && all(size(I_pl_EE) == [6 1])); +assert(isa(lr,'logical') && all(size(lr) == [1 1])); +NJA = 7; + +%% Convert Payload data from sensor frame to hand frame +% TODO. +% Assume data in hand frame for now. + +%% convert payload data to whole arm PV2 data + +PV2 = zeros(NJA*10,1); +% Leave inertia at zero + +% set mass of the last link +PV2(end) = m_pl; +% First moment +PV2(end-3:end-1) = m_pl*r_pl_EE; +% Inertia +PV2(end-9:end-4) = I_pl_EE; + +%% convert to MPV +MPV_payload = atlas_arm_convert_PV2_MPV(PV2, lr,uint8(5)); diff --git a/data/atlas5_arm_diff_MPV_wrt_PV2.m b/data/atlas5_arm_diff_MPV_wrt_PV2.m new file mode 100644 index 0000000..fcb3da2 --- /dev/null +++ b/data/atlas5_arm_diff_MPV_wrt_PV2.m @@ -0,0 +1,42 @@ +% Return the Partial derivation of Minimum Parameter Vector with respect to +% Parameter Vector 2 (Atlas v5) +% This Matrix can be used to transform between PV2 and MPV + +% Moritz Schappler, schappler@irt.uni-hannover.de, 2015-04 +% (c) Institut für Regelungstechnik, Universität Hannover + +function dMPVdPV2 = atlas5_arm_diff_MPV_wrt_PV2(a_mdh, d_mdh) + +%% Init +d3 = d_mdh(3); +d5 = d_mdh(5); + +a2 = a_mdh(2); +a3 = a_mdh(3); +a4 = a_mdh(4); +a5 = a_mdh(5); + +%% Assembly of Matrix +% Generated with atlas_arm_sym_codegen_mdh_dynamics_regressor_minpar.mw +% Source: atlas5_arm_minparvec_diff_wrt_par2_mapleexport.m + +t32 = d3 ^ 2; +t35 = a3 ^ 2; +t38 = t32 - t35; +t37 = t32 + t35; +t36 = a2 ^ 2; +t34 = a4 ^ 2; +t33 = a5 ^ 2; +t31 = d5 ^ 2; +t30 = 2 * d3; +t29 = 2 * d5; +t28 = a3 * d3; +t27 = a5 * d5; +t26 = t35 + t36; +t25 = t33 - t34; +t24 = t33 + t34; +t23 = t31 - t33; +t22 = t31 + t33; +t21 = t34 + t38; +t20 = t34 + t37; +dMPVdPV2 = [0 0 0 0 0 1 0 0 0 0 0 0 0 1 0 0 0 0 0 t36 0 0 0 0 0 0 0 0 0 t26 0 0 0 0 0 0 0 0 0 t26 0 0 0 0 0 0 0 0 0 t26 0 0 0 0 0 0 0 0 0 t26 0 0 0 0 0 0 0 0 0 t26; 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 a2 0 0 0 0 0 0 0 0 0 a2 0 0 0 0 0 0 0 0 0 a2 0 0 0 0 0 0 0 0 0 a2 0 0 0 0 0 0 0 0 0 a2 0 0 0 0 0 0 0 0 0 a2; 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0; 0 0 0 0 0 0 0 0 0 0 1 0 0 -1 0 0 0 0 0 0 0 0 0 1 0 0 0 0 t30 t38 0 0 0 0 0 0 0 0 0 t21 0 0 0 0 0 0 0 0 0 t21 0 0 0 0 0 0 0 0 0 t21 0 0 0 0 0 0 0 0 0 t21; 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 a3 t28 0 0 0 0 0 0 0 0 0 t28 0 0 0 0 0 0 0 0 0 t28 0 0 0 0 0 0 0 0 0 t28 0 0 0 0 0 0 0 0 0 t28; 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0; 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0; 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 1 0 0 0 0 t30 t37 0 0 0 0 0 0 0 0 0 t20 0 0 0 0 0 0 0 0 0 t20 0 0 0 0 0 0 0 0 0 t20 0 0 0 0 0 0 0 0 0 t20; 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 a3 0 0 0 0 0 0 0 0 0 a3 0 0 0 0 0 0 0 0 0 a3 0 0 0 0 0 0 0 0 0 a3 0 0 0 0 0 0 0 0 0 a3; 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 -1 -d3 0 0 0 0 0 0 0 0 0 -d3 0 0 0 0 0 0 0 0 0 -d3 0 0 0 0 0 0 0 0 0 -d3 0 0 0 0 0 0 0 0 0 -d3; 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 -1 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 -t34 0 0 0 0 0 0 0 0 0 t25 0 0 0 0 0 0 0 0 0 t25 0 0 0 0 0 0 0 0 0 t25; 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 -a4 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0; 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0; 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0; 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 1 0 0 0 0 0 t34 0 0 0 0 0 0 0 0 0 t24 0 0 0 0 0 0 0 0 0 t24 0 0 0 0 0 0 0 0 0 t24; 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 a4 0 0 0 0 0 0 0 0 0 a4 0 0 0 0 0 0 0 0 0 a4 0 0 0 0 0 0 0 0 0 a4; 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0; 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 -1 0 0 0 0 0 0 0 0 0 1 0 0 0 0 t29 t23 0 0 0 0 0 0 0 0 0 t23 0 0 0 0 0 0 0 0 0 t23; 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 a5 t27 0 0 0 0 0 0 0 0 0 t27 0 0 0 0 0 0 0 0 0 t27; 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0; 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0; 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 1 0 0 0 0 t29 t22 0 0 0 0 0 0 0 0 0 t22 0 0 0 0 0 0 0 0 0 t22; 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 a5 0 0 0 0 0 0 0 0 0 a5 0 0 0 0 0 0 0 0 0 a5; 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 -1 -d5 0 0 0 0 0 0 0 0 0 -d5 0 0 0 0 0 0 0 0 0 -d5; 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 -1 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0; 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0; 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0; 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0; 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0; 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0; 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0; 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 -1 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0; 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0; 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0; 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0; 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 1 0 0 0 0 0 0; 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0; 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 -1 0; 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 -1 0 0 0 0 0 0; 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0; 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0; 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0 0; 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0 0; 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 0; 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0;]; \ No newline at end of file diff --git a/data/atlas_arm_convert_PV2_MPV.m b/data/atlas_arm_convert_PV2_MPV.m new file mode 100644 index 0000000..c8f7318 --- /dev/null +++ b/data/atlas_arm_convert_PV2_MPV.m @@ -0,0 +1,38 @@ +% Convert Parameter Vector 2 to Minimum Parameter Vector (MPV) +% +% This conversion is unique, since MPV is a linear combination of PV2 +% entries +% +% Input: +% PV2 +% Parameter Vector 2 +% lr [1x1 logical] +% true for left, false for right +% version +% Atlas Version +% +% Output: +% MPV +% Minimum Parameter Vector + +% Moritz Schappler, schappler@irt.uni-hannover.de, 2015-04 +% (c) Institut für Regelungstechnik, Universität Hannover + +function MPV = atlas_arm_convert_PV2_MPV(PV2, lr,version) + +%% Init +assert(isa(lr,'logical') && all(size(lr) == [1 1])); +assert(isa(version,'uint8') && all(size(version) == [1 1])); + +%% Load Default Values +% Standard-Werte +[a_mdh, d_mdh] = atlas_arm_parameter_mdh(lr, version); + +if version == 3 || version == 4 + dMPVdPV2 = atlas3_arm_diff_MPV_wrt_PV2(a_mdh, d_mdh); +elseif version == 5 + dMPVdPV2 = atlas5_arm_diff_MPV_wrt_PV2(a_mdh, d_mdh); +else + error('version %d not implemented yet', version); +end +MPV = dMPVdPV2*PV2; \ No newline at end of file diff --git a/data/atlas_arm_convert_par1_MPV.m b/data/atlas_arm_convert_par1_MPV.m new file mode 100644 index 0000000..01515c1 --- /dev/null +++ b/data/atlas_arm_convert_par1_MPV.m @@ -0,0 +1,139 @@ +% Return the minimum parameter vector + +% Moritz Schappler, schappler@irt.uni-hannover.de, 2015-02 +% (c) Institut für Regelungstechnik, Universität Hannover + +function MPV = atlas_arm_convert_par1_MPV(rSges_num_mdh, m_num_mdh, Iges_num_mdh, a_mdh, d_mdh, version) + +%% Init + +assert(isa(version,'uint8') && all(size(version) == [1 1]), ... + 'version number has to be [1x1] uint8'); +assert(isa(rSges_num_mdh,'double') && isreal(rSges_num_mdh) && all(size(rSges_num_mdh) <= [7,3]), ... + 'rSges_num_mdh has to be [Nx3] double'); +assert(isa(m_num_mdh,'double') && isreal(m_num_mdh) && all(size(m_num_mdh) <= [7 1]), ... + 'm_num_mdh has to be [1x1] double'); +assert(isa(Iges_num_mdh,'double') && isreal(Iges_num_mdh) && all(size(Iges_num_mdh) <= [7 6]), ... + 'Iges_num_mdh has to be [Nx6] double'); +assert(isa(a_mdh,'double') && isreal(a_mdh) && all(size(a_mdh) <= [7 1]), ... + 'a_mdh has to be [Nx1] double'); +assert(isa(d_mdh,'double') && isreal(d_mdh) && all(size(d_mdh) <= [7 1]), ... + 'd_mdh has to be [Nx1] double'); + + +d3 = d_mdh(3); +d5 = d_mdh(5); + +a2 = a_mdh(2); +a3 = a_mdh(3); +a4 = a_mdh(4); +a5 = a_mdh(5); +a6 = a_mdh(6); + +% Convert to Parameterset 2 +[mrSges_num_mdh, Ifges_num_mdh] = atlas_arm_convert_mdh_par1_par2(rSges_num_mdh, Iges_num_mdh, m_num_mdh); + + +% Mass +M1 = m_num_mdh(1); +M2 = m_num_mdh(2); +M3 = m_num_mdh(3); +M4 = m_num_mdh(4); +M5 = m_num_mdh(5); +M6 = m_num_mdh(6); + +% Erstes Moment +MX1 = mrSges_num_mdh(1,1); +MY1 = mrSges_num_mdh(1,2); +MZ1 = mrSges_num_mdh(1,3); +MX2 = mrSges_num_mdh(2,1); +MY2 = mrSges_num_mdh(2,2); +MZ2 = mrSges_num_mdh(2,3); +MX3 = mrSges_num_mdh(3,1); +MY3 = mrSges_num_mdh(3,2); +MZ3 = mrSges_num_mdh(3,3); +MX4 = mrSges_num_mdh(4,1); +MY4 = mrSges_num_mdh(4,2); +MZ4 = mrSges_num_mdh(4,3); +MX5 = mrSges_num_mdh(5,1); +MY5 = mrSges_num_mdh(5,2); +MZ5 = mrSges_num_mdh(5,3); +MX6 = mrSges_num_mdh(6,1); +MY6 = mrSges_num_mdh(6,2); +MZ6 = mrSges_num_mdh(6,3); + +% Inertia +XX1 = Ifges_num_mdh(1,1); +XY1 = Ifges_num_mdh(1,4); +XZ1 = Ifges_num_mdh(1,5); +YY1 = Ifges_num_mdh(1,2); +YZ1 = Ifges_num_mdh(1,6); +ZZ1 = Ifges_num_mdh(1,3); +XX2 = Ifges_num_mdh(2,1); +XY2 = Ifges_num_mdh(2,4); +XZ2 = Ifges_num_mdh(2,5); +YY2 = Ifges_num_mdh(2,2); +YZ2 = Ifges_num_mdh(2,6); +ZZ2 = Ifges_num_mdh(2,3); +XX3 = Ifges_num_mdh(3,1); +XY3 = Ifges_num_mdh(3,4); +XZ3 = Ifges_num_mdh(3,5); +YY3 = Ifges_num_mdh(3,2); +YZ3 = Ifges_num_mdh(3,6); +ZZ3 = Ifges_num_mdh(3,3); +XX4 = Ifges_num_mdh(4,1); +XY4 = Ifges_num_mdh(4,4); +XZ4 = Ifges_num_mdh(4,5); +YY4 = Ifges_num_mdh(4,2); +YZ4 = Ifges_num_mdh(4,6); +ZZ4 = Ifges_num_mdh(4,3); +XX5 = Ifges_num_mdh(5,1); +XY5 = Ifges_num_mdh(5,4); +XZ5 = Ifges_num_mdh(5,5); +YY5 = Ifges_num_mdh(5,2); +YZ5 = Ifges_num_mdh(5,6); +ZZ5 = Ifges_num_mdh(5,3); +XX6 = Ifges_num_mdh(6,1); +XY6 = Ifges_num_mdh(6,4); +XZ6 = Ifges_num_mdh(6,5); +YY6 = Ifges_num_mdh(6,2); +YZ6 = Ifges_num_mdh(6,6); +ZZ6 = Ifges_num_mdh(6,3); + +%% Parameter +if version == 3 || version == 4 + % Quelle: codeexport/atlas3_arm_minimal_parameter_vector.m + MPV = [ZZ1 + YY2 + (a3 ^ 2 * (M3 + M4 + M5 + M6)) + (a2 ^ 2 * (M2 + M3 + M4 + M5 + M6)); (a2 * (M2 + M3 + M4 + M5 + M6)) + MX1; MY1 + MZ2; (d3 ^ 2 * (M3 + M4 + M5 + M6)) + (2 * d3 * MZ3) + XX2 + YY3 + (a4 ^ 2 * (M4 + M5 + M6)) - YY2 - (a3 ^ 2 * (M3 + M4 + M5 + M6)); XY2 + (a3 * MZ3) + (a3 * d3 * (M3 + M4 + M5 + M6)); XZ2; YZ2; ZZ2 + YY3 + (a4 ^ 2 * (M4 + M5 + M6)) + (2 * d3 * MZ3) + ((a3 ^ 2 + d3 ^ 2) * (M3 + M4 + M5 + M6)); (a3 * (M3 + M4 + M5 + M6)) + MX2; MY2 - MZ3 - (d3 * (M3 + M4 + M5 + M6)); XX3 + YY4 + (a5 ^ 2 * (M5 + M6)) - YY3 - (a4 ^ 2 * (M4 + M5 + M6)); -(MZ4 * a4) + XY3; XZ3; YZ3; ZZ3 + YY4 + (a5 ^ 2 * (M5 + M6)) + (a4 ^ 2 * (M4 + M5 + M6)); (a4 * (M4 + M5 + M6)) + MX3; MY3 + MZ4; (d5 ^ 2 * (M5 + M6)) + (2 * d5 * MZ5) + XX4 + (a6 ^ 2 * M6) + YY5 - YY4 - (a5 ^ 2 * (M5 + M6)); XY4 + (a5 * MZ5) + (a5 * d5 * (M5 + M6)); XZ4; YZ4; ZZ4 + (a6 ^ 2 * M6) + YY5 + (2 * d5 * MZ5) + ((a5 ^ 2 + d5 ^ 2) * (M5 + M6)); (a5 * (M5 + M6)) + MX4; MY4 - MZ5 - (d5 * (M5 + M6)); -(a6 ^ 2 * M6) + XX5 - YY5 + YY6; -(MZ6 * a6) + XY5; XZ5; YZ5; (a6 ^ 2 * M6) + YY6 + ZZ5; (M6 * a6) + MX5; MY5 + MZ6; XX6 - YY6; XY6; XZ6; YZ6; ZZ6; MX6; MY6;]; +elseif version == 5 + + M7 = m_num_mdh(7); + MX7 = mrSges_num_mdh(7,1); + MY7 = mrSges_num_mdh(7,2); + MZ7 = mrSges_num_mdh(7,3); + XX7 = Ifges_num_mdh(7,1); + XY7 = Ifges_num_mdh(7,4); + XZ7 = Ifges_num_mdh(7,5); + YY7 = Ifges_num_mdh(7,2); + YZ7 = Ifges_num_mdh(7,6); + ZZ7 = Ifges_num_mdh(7,3); + + % Quelle: codeexport/atlas5_arm_minimal_parameter_vector_matlab.m + t6 = (M5 + M6 + M7); + t5 = M4 + t6; + t2 = (a4 ^ 2 * t5); + t19 = (-YY3 - t2); + t11 = (a5 ^ 2); + t18 = (t11 * t6 + YY4); + t17 = 2 * d5 * MZ5 + YY5; + t16 = 2 * d3 * MZ3 - t19; + t3 = (M3 + t5); + t15 = d3 * t3 + MZ3; + t14 = d5 * t6 + MZ5; + t13 = (a3 ^ 2); + t10 = d3 ^ 2; + t9 = d5 ^ 2; + t1 = M2 + t3; + MPV = [a2 ^ 2 * t1 + t13 * t3 + YY2 + ZZ1; a2 * t1 + MX1; MY1 + MZ2; XX2 - YY2 + (t10 - t13) * t3 + t16; t15 * a3 + XY2; XZ2; YZ2; ZZ2 + (t10 + t13) * t3 + t16; a3 * t3 + MX2; MY2 - t15; XX3 + t18 + t19; -MZ4 * a4 + XY3; XZ3; YZ3; ZZ3 + t2 + t18; a4 * t5 + MX3; MY3 + MZ4; t9 * t6 + XX4 + t17 - t18; t14 * a5 + XY4; XZ4; YZ4; ZZ4 + (t9 + t11) * t6 + t17; a5 * t6 + MX4; MY4 - t14; XX5 + YY6 - YY5; XY5; XZ5; YZ5; ZZ5 + YY6; MX5; MY5 + MZ6; XX6 + YY7 - YY6; XY6; XZ6; YZ6; ZZ6 + YY7; MX6; MY6 - MZ7; XX7 - YY7; XY7; XZ7; YZ7; ZZ7; MX7; MY7;]; +else + error('Version %d not implemented yet', version); +end \ No newline at end of file diff --git a/drc_paper_path_init.m b/drc_paper_path_init.m new file mode 100644 index 0000000..8b002d5 --- /dev/null +++ b/drc_paper_path_init.m @@ -0,0 +1,13 @@ +% Füge alle Unterordner der Beiträge zum Matlab-Pfad hinzu, damit die +% Skripte funktionieren. + +% Moritz Schappler, schappler@irt.uni-hannover.de, 2015-09 +% (c) Institut für Regelungstechnik, Universität Hannover + +paper_path = fileparts(which('drc_paper_path_init')); +addpath(paper_path); +addpath(fullfile(paper_path, 'data')); +addpath(fullfile(paper_path, 'identification')); +addpath(fullfile(paper_path, 'plotting')); +addpath(fullfile(paper_path, 'robot_model')); +addpath(fullfile(paper_path, 'simulink')); \ No newline at end of file diff --git a/identification/load_experiment_data.m b/identification/load_experiment_data.m new file mode 100644 index 0000000..68ad417 --- /dev/null +++ b/identification/load_experiment_data.m @@ -0,0 +1,410 @@ +% Extract Data for Experiment with given filename +% +% Input: +% matfilepath [string] +% Path to the experiment data. The mat file is converted from a bag file +% Indexes_To [Nx2 double] +% Indexes for the data to the robot, which is chosen for extraction +% Each row contains a start and end index +% Indexes_From_struct [Nx2 double] +% Indexes for the data from the robot, which is chosen for extraction +% Each row contains a start and end index +% +% Output: +% exp_struct +% Structure with experiment data +% .FromRobot +% Structure with measurement data from the robot +% .q Joint Positions +% .qD Joint Velocities +% .tau Joint Efforts +% .t Timestamps +% .ToRobot +% same values as in .FromRobot +% + +% Moritz Schappler, schappler@irt.uni-hannover.de, 2015-02 +% (c) Institut für Regelungstechnik, Universität Hannover + + +function [exp_struct, Load_struct] = load_experiment_data(matfilepath, Indexes_To, Indexes_From) + +% load mat file +Load_struct = load(fullfile(matfilepath)); + +% calculate acceleration + +Load_struct.FromRobot = filt_velocity_elec(Load_struct.FromRobot); +Load_struct.ToRobot = filt_velocity_elec(Load_struct.ToRobot); + + +Load_struct.FromRobot = calc_acceleration(Load_struct.FromRobot); +Load_struct.ToRobot = calc_acceleration(Load_struct.ToRobot); + +% Filter Velocity +Load_struct.FromRobot = calc_filt_velocity(Load_struct.FromRobot); + +% calculate electric motor torque +% status = 1; +% try +% if isfield(Load_struct.FromRobot,'i_el') == 1 && status == 1 +% for joint = 1:6; +% Load_struct.FromRobot = calc_torque_elec(Load_struct.FromRobot,Load_struct.ToRobot,joint,lr); +% end +% end +% catch +% warning('No electric motor currents available'); +% end + +% extend impedance controller settings to last timestamp +% change stored values for these structures: +settings_fields = {'ImpCtrlGains_left_arm', 'ImpCtrlGains_right_arm'}; +for i = 1:length(settings_fields) + if ~isfield(Load_struct.ToRobot, settings_fields{i}) + continue % old data does not contain this field + end + Strct = Load_struct.ToRobot.(settings_fields{i}); % temporary variable for changing + % get fields of structure + fields = fieldnames(Load_struct.ToRobot.ImpCtrlGains_left_arm); + for j = 1:numel(fields) + Tmp = Strct.(fields{j}); + % check if field is time dependant + if length(Tmp) ~= length(Strct.t) + continue + end + if strcmp(fields{j}, 't') + continue % do not change the times here + end + if ~(isa(Strct.(fields{j}), 'double') || isa(Strct.(fields{j}), 'logical')) + continue + end + % add last entry again + Strct.(fields{j}) = [Tmp;Tmp(end)]; + end + % add time stamp of last measured or commanded value + Strct.t = [Strct.t; max([Load_struct.FromRobot.t(end), Load_struct.ToRobot.t(end)])]; + % write changed structure back + Load_struct.ToRobot.(settings_fields{i}) = Strct; +end + +% convert force torque sensor measurements to hand frames +% https://external.torcrobotics.com/redmine-drc/issues/2588 +% rotate from sensor frame into hand frame +% assume rotation about z-axis +Load_struct.FromRobot.F_lH_raw = Load_struct.FromRobot.F_lH; +Load_struct.FromRobot.F_rH_raw = Load_struct.FromRobot.F_rH; + +% Load_struct.FromRobot.F_lH(:,[1,2,4,5]) = -Load_struct.FromRobot.F_lH(:,[1,2,4,5]); + +% if no indexes specified: return whole file +if nargin == 1 + exp_struct = Load_struct; + return +end + +% if indexes specified: Return only data in the intervals given by indexes +exp_struct.FromRobot = ExtractInterval(Load_struct.FromRobot, Indexes_From); +exp_struct.ToRobot = ExtractInterval(Load_struct.ToRobot, Indexes_To); + + +end + +function EditStruct = filt_velocity_elec(EditStruct) +% Return Acceleration. Calculate if needed +% TODO: Filter Acceleration with kinematic mode kalman filter + +global FilterElecVel +if isempty(FilterElecVel) + return +end +% Differentation by four different methods +% Filter first and derivate afterwards or derivate first and filter +% afterwards. Filters can be done by smoothing or butterworth filtering +if isfield(EditStruct, 'qD') + + tic + omega = FilterElecVel*2*pi; + step_time = 1e-3; + order = 2; + switch order + case 1 + constants = tf(omega,[1 omega]); + case 2 + constants = tf(omega^2,[1 2*1*omega omega^2]); + end + constants_z=c2d(constants,step_time); + [num_z,den_z]=tfdata(constants_z); + b_filt = num_z{1}; + d_filt = den_z{1}; + + + AS = atlas_const(uint8(5), true); + for i = [AS.JI_lArm((end-2):end),AS.JI_rArm((end-2):end)] + qD_filt = filtfilt(b_filt,d_filt,EditStruct.qD(:,i)); + EditStruct.qD(:,i) = qD_filt; + end +end +end + + +function EditStruct = calc_acceleration(EditStruct) +% Return Acceleration. Calculate if needed +% TODO: Filter Acceleration with kinematic mode kalman filter + +global FilterAcc +if isempty(FilterAcc) % TODO: Globale Variable besser abfangen. Standard-Einstellung ermöglichen, falls nicht gesetzt + FilterAcc = 20; +end +% Differentation by four different methods +% Filter first and derivate afterwards or derivate first and filter +% afterwards. Filters can be done by smoothing or butterworth filtering +if ~isfield(EditStruct, 'qDD') && isfield(EditStruct, 't') + + tic + omega = FilterAcc*2*pi; + step_time = 1e-3; + order = 2; + switch order + case 1 + constants = tf(omega,[1 omega]); + case 2 + constants = tf(omega^2,[1 2*1*omega omega^2]); + end + constants_z=c2d(constants,step_time); + [num_z,den_z]=tfdata(constants_z); + b_filt = num_z{1}; + d_filt = den_z{1}; + + dt = diff(EditStruct.t); + % remove dt=0-values (e.g. from Gazebo when two time stamps are equal) + dt(abs(dt)<1e-6) = 1e-6; + + filter_befAft = 1; % filtfilt-error-msg. Take this as default. + + switch filter_befAft + case 1 + % acceleration from numerical differentiation + QDD_1 = [zeros(1,size(EditStruct.qD,2)); diff(EditStruct.qD)./repmat(dt,1,size(EditStruct.qD,2))]; + % Filter Acceleration + for i = 1:size(QDD_1,2) + QDD_1_sm(:,i) = smooth(QDD_1(:,i), 2000); + end + QDD = QDD_1_sm; + case 2 + for i = 1:size(QDD_1,2) + QDD_1_tp(:,i) = filtfilt(b_filt,d_filt,QDD_1(:,i)); + end + QDD = QDD_1_tp; + case 3 + for i = 1:size(EditStruct.qD,2) + QD_2_sm(:,i) = smooth(EditStruct.qD(:,i), 3000); + end + + QDD_2_sm = [zeros(1,size(QD_2_sm,2)); diff(QD_2_sm)./repmat(dt,1,size(QD_2_sm,2))]; + QDD = QDD_2_sm; + case 4 + for i = 1:size(EditStruct.qD,2) + QD_2_tp(:,i) = filtfilt(b_filt,d_filt,EditStruct.qD(:,i)); + end + % acceleration from numerical differentiation + QDD_2_tp = [zeros(1,size(QD_2_tp,2)); diff(QD_2_tp)./repmat(dt,1,size(QD_2_tp,2))]; + QDD = QDD_2_tp; + end + + % old plotting information + % figure; plot(EditStruct.qD(:,17)); hold on; plot(QD_2_sm(:,17),'r'); hold on; plot(QD_2_tp(:,17),'g'); legend('speed_{orig}','speed_{sm}','speed_{tp}') + % figure; + % plot(QDD_1(:,17)); hold on; + % plot(QDD_1_sm(:,17),'m'); hold on; + % plot(QDD_1_tp(:,17),'k'); + % plot(QDD_2_sm(:,17),'r'); hold on; + % plot(QDD_2_tp(:,17),'g'); hold on; + % legend('direct','sm_{after}','tp_{after}','sm_{bef}','tp_{bef}') + % QDD = QDD_2_tp; + + if size(QDD,1) > 400 + QDD(1:100,:) = 0; + QDD(end-400:end,:) = 0; + end + EditStruct.qDD = QDD; +end + +end + +function EditStruct = calc_filt_velocity(EditStruct) +% Return Acceleration. Calculate if needed +% TODO: Filter Acceleration with kinematic mode kalman filter +QD = EditStruct.qD; +QD_filt = NaN(size(QD)); +% Filter Velocity +for i = 1:size(QD,2) + QD_filt(:,i) = smooth(QD(:,i), 100); +end +EditStruct.qD_filt = QD_filt; +end + +function OutStruct = ExtractInterval(EditStruct, Ind) + +% count number of rows +N = 0; +for j = 1:size(Ind,1) + N = N + Ind(j,2) - Ind(j,1) + 1; +end + +% Create structure with the same fields as the Input Structure +% The dimensions are already pre-assigned from the intervals above +fields = fieldnames(EditStruct); +OutStruct = struct('t', NaN(N,1)); +for fnr=1:numel(fields) + tmp = EditStruct.(fields{fnr}); + if size(tmp,1) == length(EditStruct.t) + OutStruct.(fields{fnr}) = NaN(N,size(tmp,2)); + end +end + +% Loop Through all Intervals given in the Indexes Matrix +% Extract Data for given Interval +ii = 1; % starting index +time_last = 0; +for i = 1:size(Ind,1) + I1 = Ind(i,1); % Starting Index + I2 = Ind(i,2); % end Index + NN = I2-I1+1; % Number of entries + + % Loop over all fields and extract data, if field is a time series + for fnr=1:numel(fields) + tmp = EditStruct.(fields{fnr}); + if size(tmp,1) == length(EditStruct.t) + + if strcmp(fields{fnr},'t') == 1 + % avoid time to be discontinous + + difference = diff(tmp(I1:I2,:)); + difference(isnan(difference)) = []; + t_sample = mean(difference); + tmp_ = tmp(I1:I2,:) - tmp(I1); + OutStruct.(fields{fnr})(ii:ii+NN-1,:) = tmp_+time_last+t_sample; + time_last = tmp_(end)+time_last; + else + OutStruct.(fields{fnr})(ii:ii+NN-1,:) = tmp(I1:I2,:); + end + end + end + + % Return Interval + OutStruct.I(ii:ii+NN-1) = (I1:I2)'; + + ii = ii + NN; % Starting Index in output struct for next iteration +end +end + +% function FromRobot = calc_torque_elec(FromRobot,ToRobot,joint,lr) +% +% % This function requires an impedance controlled identification where +% % desired torques are given to the robot. Based on the desired torque, the +% % sign of the measured torque is determined. +% +% % Alexander Tödtheide, toedtheide@irt.uni-hannover.de, 2015-07 +% % (c) Institut für Regelungstechnik, Universität Hannover +% +% plotting = 0; +% +% % load atlas constants +% AS = atlas_const(uint8(5), lr); +% +% k_motor = AS.k_motor_elec; +% gear_ratio = AS.gear_ratio_elec; +% +% % iterate over +% % since there are two arms with three electric motors +% +% +% indices = [AS.JI_lArm(end-2:end),AS.JI_rArm(end-2:end)]; +% +% t_to = ToRobot.t; +% t_from = FromRobot.t; +% tau_est = k_motor*gear_ratio(joint)*FromRobot.i_el(:,indices(joint)); +% tau_des = ToRobot.tau(:,indices(joint)); +% +% Intervals_des = (tau_des > 0); +% +% %% find time intervals where the indices changes +% k = 2; +% % start first interval edge with zero +% t_switch(1) = 0; +% first_interval_sign = 3; +% for i = 2:size(tau_des,1) +% % towards positive +% if tau_des(i-1) < 0 && tau_des(i) > 0 +% t_switch(k) = t_to(i); +% k = k + 1; +% +% % determine sign of first interval to known sign of other intervals +% if first_interval_sign == 3 +% first_interval_sign = -1; % first interval is negative +% end +% end +% +% % determine sign of first interval to known sign of other intervals +% if tau_des(i-1) > 0 && tau_des(i) < 0 +% t_switch(k) = t_to(i); +% k = k + 1; +% if first_interval_sign == 3 +% first_interval_sign = 1; % first interval is positive +% end +% end +% end +% % finish final interval edge with the last time value +% t_switch(k) = t_to(end); +% +% % determine start/stop and sign of intervals +% intervals_infos = zeros(length(t_switch)-1,3); +% for i = 1:length(t_switch)-1 +% intervals_infos(i,1) = t_switch(i); +% intervals_infos(i,2) = t_switch(i+1); +% % create alternating function by cosinus +% intervals_infos(i,3) = round(cos((i-1)*pi)*first_interval_sign); +% end +% +% %% Apply signs to measurement +% k_last = 1; +% for i = 1:length(t_from) +% % find out interval +% for k = k_last:length(intervals_infos) +% if k < length(intervals_infos) +% if t_from(i) >= intervals_infos(k,1) && t_from(i) <= intervals_infos(k+1,1) +% sign = intervals_infos(k,3); +% k_last = k; +% break +% end +% else +% if t_from(i) >= intervals_infos(k,1) +% sign = intervals_infos(k,3); +% k_last = k; +% break +% end +% end +% end +% tau_est_corr(i,1) = tau_est(i,1)*sign; +% end +% +% %% determine final shift +% tau_est_corr_out = (tau_est_corr); +% FromRobot.tau(:,indices(joint)) = tau_est_corr_out; +% +% if plotting == 1 +% figure; +% subplot(3,1,1); +% plot(t_from,tau_est); xlabel('Time [s]'); ylabel('Torque [Nm]'); +% subplot(3,1,2); +% p1 = plot(t_from,tau_est); hold on; +% p2 = plot(t_to,tau_des); hold on; +% p3 = plot(t_to(Intervals_des),tau_des(Intervals_des)); hold on; xlabel('Time [s]'); ylabel('Torque '); +% p4 = plot(t_switch,zeros(length(t_switch),1),'or'); +% legend([p1,p2,p3,p4],{'k_{motor}*i_{gear}*I','t_{des}','Indexbased','Interval edges'}) +% subplot(3,1,3); +% p1 = plot(t_from, tau_est_corr_out); hold on; +% p2 = plot(t_to,tau_des); hold on; legend([p1, p2],'tau_{est}','tau_{des}'); xlabel('Time [s]'); ylabel('Torque '); +% end +% +% end diff --git a/paper/.gitignore b/paper/.gitignore new file mode 100644 index 0000000..3eeb9f6 --- /dev/null +++ b/paper/.gitignore @@ -0,0 +1 @@ +atlas_iros_16.pdf diff --git a/paper/atlas_iros_16.tex b/paper/atlas_iros_16.tex new file mode 100644 index 0000000..c4ab738 --- /dev/null +++ b/paper/atlas_iros_16.tex @@ -0,0 +1,77 @@ +%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%% +%2345678901234567890123456789012345678901234567890123456789012345678901234567890 +% 1 2 3 4 5 6 7 8 + +\documentclass[letterpaper, 10 pt, conference]{ieeeconf} % Comment this line out if you need a4paper + +%\documentclass[a4paper, 10pt, conference]{ieeeconf} % Use this line for a4 paper + +\IEEEoverridecommandlockouts % This command is only needed if + % you want to use the \thanks command + +\overrideIEEEmargins % Needed to meet printer requirements. +%\pdfminorversion=4 +% See the \addtolength command later in the file to balance the column lengths +% on the last page of the document + +% The following packages can be found on http:\\www.ctan.org +%\usepackage{graphics} % for pdf, bitmapped graphics files +\usepackage{graphicx} +\usepackage[font=footnotesize]{subcaption} +%\usepackage{epsfig} % for postscript graphics files +%\usepackage{mathptmx} % assumes new font selection scheme installed +%\usepackage{times} % assumes new font selection scheme installed +\usepackage{amsmath} % assumes amsmath package installed +\usepackage{bm} +\usepackage{amssymb} % assumes amsmath package installed +\usepackage[latin1]{inputenc} % for German characters +\usepackage{fixltx2e} +\captionsetup{font=footnotesize} +\usepackage{color} +\usepackage[countmax]{subfloat} +%\usepackage{color} +\usepackage{changes} + +% Symbole für Tabelle: grüner Haken und rotes Kreuz +\newcommand{\ok}{{\color{green}\checkmark}} +\newcommand{\no}{{\color{red}$\boldsymbol\times$}} +\newcommand{\SkipBeforeText}{\vspace*{-3ex}} % Platz nach figure und vor Text verringern +\newcommand{\SkipBeforePicture}{\vspace*{-2ex}} % Platz vor figure verringern +\newcommand{\BibBaselineStretch}{0.92} + + +\title{\LARGE \bf +Soft Robotics for the Hydraulic Atlas Arms: Joint Impedance Control with Collision Detection and Disturbance Compensation +} + +\author{Jonathan Vorndamme, Moritz Schappler, Alexander Tödtheide and Sami Haddadin$^{1}$% <-this % stops a space +\thanks{$^{1}$ All authors are with Institute of Automatic Control (IRT), Leibniz Universität Hannover, Appelstr. 11, 30167 Hannover, Germany. \newline Email: \texttt{}@irt.uni-hannover.de. +\newline +This work is part of a project that has received funding from the European Union's Horizon 2020 research and innovation programme under +grant agreement No 688857 (``SoftPro''). +\newline +The authors would like to thank the other members of Team ViGIR for supporting the robot experiments. +The robot experiments were supported in by the Defense Advanced Research Projects Agency (DARPA) under Air Force Research Laboratory (AFRL) contract FA8750-12-C-0337. +}. +} + +%\renewcommand{\baselinestretch}{1.045} +\begin{document} + +\maketitle +\thispagestyle{empty} +\pagestyle{empty} + +\input{sec_abstract_intro} + +\input{sec_model} + +\input{sec_ident} + +\input{sec_colldet} + +\input{sec_compliance_obs} + +\input{sec_rest} + +\end{document} diff --git a/paper/figures/CollDetCinderblock/Collision_Summary_Cinderblock.pdf b/paper/figures/CollDetCinderblock/Collision_Summary_Cinderblock.pdf new file mode 100644 index 0000000000000000000000000000000000000000..113bffd33b3f536a5f684e52f6e1874aa861dd1c GIT binary patch literal 157576 zcmV)dK&QVYP((&8F)lO;CCBWKq6#%2Fd%PYY6?6&FHB`_XLM*FHXtw{QZGhnY;(kJkg_fBdLF|M7h6Uw%BVz1q{)&;R(xyT9K^-_PqQKmV^EzkaOVzdd!4kEcrM z%-enHBA-u<(Z4-qMu{#U0!v5J|*PKQ%e8u*VnOe z-*H~~dlmdWJ9y!HB7eUi|Aw*3X%1`td&c^B>fbQd=TrZ>u|A*r*Nye@)W2b@kEi~u zi8pf6{9eZU)Ejv}^}YFhHpq{szBRwk2Kn*Sx90cRAm2~@**xCJ`>ESJ{`tp$|50*K z_^E&Wm)}4Cx4)f%VgHPue?!MFKmXzU|M|IJeeKfDbMv*w{Q0-vKmPJBfBoCPoM+Fg z`EY&p-lLvW{`PB5?U#AJLe{WE_PyL&N(tYaVi~m|vEB!RCGe5wV{QJ*3 zP7BTI80Rk~8`}e0{R4jgEO91~kro_(A1+VgX(!A>|Kqgee?0TgnS1gB|A_@ESjcLGeMpK93zg72J{#{zN+l65)eDM*%RsYGMF&X@pXpBfUfS;qYuSr6lM zW|r|FBawIw{%)C>)41ECCwjg!i|x442#Ewsd4>T#b4GkWk~W#`d{GH6CfrZe%rD8D zIvVrK$4_}#%yn8*BGaaHG3RN4EapL&&bBGfpR#ghysGo_WIF3~oUJTRBm2p>;#IQR z*J+J0h*Tn{>pq=G_Pe&)t14kWaav**ue)YfT^ zX>uU^(rJ!LhE;lin96Y4?$;mK>2>Qo&Z5Uj5$~NbW3cEh#2IUvTfrn!PurKdSQ-1Y zQWkx^LclKb6F99jRPDichE2Rw8T+)-wm(g?Pb=**aSI{4>zSSvwokT{Owan-ar%xv z)$)-zWAH9&1w@K1e2@^b!_QCf|8Eayc|E1k;ms)J1eZ0cB)5Rc4VH;wO!QCaQ!K?n;*s4a-gJubT0>SwI{B@3Oj*^HaySRF#z%witsEn}*JjBZNbUIOH@!6(8TFlY(N0qxnzVWm zvZos6;#=e7LX9`lr0vX$j|}+mTgyhi&z#91_Q&K0#N(h|IwN%R1eA4gILmN3S*$}^ zJQ{R9avEyaIKw7)kZ?KKEDw)aL&IsB^N^O|K`ydT9YjRmW;Z^pr7S;Fgv3@6O6K_R zm=&rVR_Wm};}$c4cy-U{`OW}=H803YKfL9spL0Br-85n5sN4^enJ(teLLK5Fwx;2< zALder1}E0mVJ@O;Q@!sXqHD~|G;tj2)B|Ib5hi+H9?o*@n9QOd&LXM?ZY5;Rs+9TGFj?~meK^Y{Yiwr|v%AOa z1orE8!YSZVHI4v>pJ4fi;V*v{*{nVq5DqyJFAFvBLr&IZCu!G1MlKC|_}0X7m6bcE z5RtB~0vs~3OtA~o*)KoB(Qt(gAaakT$)(RVYk2F|-27$we8!|qN%TUWpetK+n2(;#Ke(7)wk*n!cnhEq!D>|%WxhnGaserOnTUqYIFxp)u z@Jq}5d63hdh5xA=FKV`sZF4Js@$%Xz`}H^!qq~sVXUCx!)wyY8n%}YC2dO4pgQF)9 zQR>0&G7b?Dr5-PStiSn|9vN@GmAq{n+EI%7j}o5d)PvK{c$WFr;4E>7%9)GZ{&pfE zPVL$lhjx_t(F6fp!j(hKI6OrBd2tmu4(k{umRZf?u#RS8xtQ>2rqAbWI8X)V&qKiF z&;0g$^XHt2M^3l%W4IZo+g|?Mn9RpatTKd6tQlaOA!2HF%)U1czYu@ks=vc8L`F5s zo=NV_pJNHR{5dC%aVUrA79SXIV@`f~zKzK@&QSWuma&CIbHy;3ZCh%P8i#JIqA80; zXpec7CcbglMeWM($hQu=5U-l_6#x;hQZE{ZZ-_m+-L!6Fp3?BGVPd5zYaDiQ>2oPU zwnm@CC0053j>9g7EzU-9=!K`8T-b~*S5i(nTS#~klB?%CcKY7oAj|Vzmg_K% z**t(S=_W#b`@^9e;#xgdZ~(-oJ7@F(&&gJQ&Bg0Dj6-~Sa7{PhIf?zAY{wxSVp>z} zt%vFK&EILHRWD_A!FN(MRrD>|Q>6;sea}+a5w#tKuI&boWaY)CtFdvDxf%6GCPfVQo&OEI&Je*|R9Nuw> zGY8;Y=iuZy4)N$_l({?^ zaGsbr=bC-Mc_K!spB@(U_wvqfuI2_DCoW`8f@8He-C_kFZgS~XdZ&O~+WhdX@wTPX zndZ$ybpzLl-G776Y#Vbphugea^AOx5q4|{`Km28Gj|{<%_YFH8@35F|LXh9u)&8XAt9;@adE#(r`D&!KlY?t%Un9F_m?fGVK{Pf2nAgS1d@8m8Wx{zzntmFB_ z+dG!?!G!NbkK}+n;X1K73Dh@N%W3b@?5xZ4>r(Oj*-g^qW1mU3HB&4;GtFu{OOrF9 z2z8F%Go602ee#2uzE;yVCLD5nUW33r;__v?|Mds<`yl1zfp+t?V#|uZ%)@AweZDl( z;V;+mS@}%2WrLH&#NLQ~zM1Db&D-Rx1#%t5EXAQPGHu8Nhr*D#VRe>mriPds{8?Fr z@R(euZx&E? zD1q$jF6A@b_SCR74_)bZ*_5R^bVWpby!fSMduk~NMAWUTk~@|T>HxW5pKzH}Z#w}P z&+9Ug%* zn56{~aNy5Te~$gSTS!d!PU}OtnU7hTrpaG_V80XbDleUQ^H7@0+;U!;vznZ1p*0VK z5jppm16Rt>Gc@q*Z*tBt6t0w8_5|kJzO44S%*{Q>z?JfapaR(@sBB$_(!7~lK65zC zD4*^4a2UJ0ILyMm;)ND7yy^!H&u_!w;!eevx@ou^PxCMsF}KP2Z^8q!)Qmg7z3lST z{5RomaiQ2oS6q9t?H?xcTpB)v#Phkln1`I)brc7oLq$Z)JSM`!q5+VVwTC$N8K*cQ z9)!HC7EP>sikHE2&9|1Ey$4}A4-+BD#_E&Lgm~FOI7-67lH3FXd}b%G;h}U`7jUqI zo?#<6Or$4UIXUEnb(jd(QJ6ZipofW&W@EHnLde1}M)R2=kLDYhwpMU+dB!pe)2`c$ zZQd$ZGmz_`W)Fpv#mkB8HS6)Ltq@DXurt*zGKBO+&Vj;y-Pv9%2a31@zu;rZ z0(hHl!N=kyB@K1>NEzN2t3qTQ z>_H@Qh|A??=>}TxvouvAs~&z9cWW9IewO)J&v3I$4|+_vf8*P04AXtZd@T4`_Sa|D zJJ5hOJw!zWZL8}aSt|Hi>gSSw zt@1JnW-BHTCmge!ey0(F9q{myx3e^>eT_HaUPZ_y+-z}cnvZ#0S<8fMJLO}e zWwy_B!p>4rDInKbnnZK$=S|46#r^sNJ3a6an(=%YhT(1To?RvlXNy@H$JB#d|1ul% zhIg}n`TQ^s*9Q06)80~#=5VdJBM+v$O}i)kh=-_{c6)Y)YsIXLt?j7trKlDY> zBa_S$h-{j_+M8fAzi_LVV6)m|II4i&g%#7DQF+RMY!`{$F~EM^X%g7pp`V)b;Z$)M zv-UQeD)H$WIun#Anl~IaqSw9UoQ+@~Qqs*uv()>LlDDfnf$?^PK3&K)RN8yPiPF5U z!nf9kCzPMM(F)r2JX6G*p=Fft7+bH=G+$b(*x+C`?C6|pQ z5e8y5*7A2ZUp=LrHpZmh%}nQ*PfILd3Vl9QGk8GN-#aoF|T%$b!Om za^o7A@HF=lCD~({PivX8;VFsviNFcssEOofK*CvOg~8`>4Z*kCJ0h0`JzS!gFA5p& z-Q~$xmhafkMp%d3FJ%}uOF1z~QTBgQbEn)39HO@Kz zv}H#CXCvH?d2v&1?P6ZsNMHB9Q*P6k0@p|rlHn>Fu92p6*mMtZ5HIeWsP_h87b|DM z;TyRjB7A1ro{F&8@Qv7qmYcI1z7fwGm8FPxkO-|8k9m~*L_oH;RhgedF0MU=RCA`u zP@R3~M3ZHh%4wC=b5<8}&AIu`FfU$ol<&hPh69~*0kGj2al2)QglA-`-Eu;T{U%YY z`e+0J&&d9a&5x&;L}@2Do@!z&A80(y7F9S55EJ7Z?&B~H@ug z`UCrYkoo3T*+~Mv5j!uRC1l%iJBe(QWknAKd?R;z9TgpibW|5UiAfY}Y`CZ)WV`Tb z(kRu$Sm8KPn%#q)eKg=4QAf(Q68J*ZhD|O&BI`x8gN4Y+UCBJm&N4A>9O5G#SdEAZ z5w>#U#1QE((6_S90TES}*F7qBHdL(aw`Xa8J(^6Vy~7AthT1=<=M-{XoH-ao9VT2_ zLfYvm_ltUk2C+^54@zGJ@= z2_ia85q-+Mqml>5;T$Ae>3~RNi%$>DMghl27JMl77YGduH$j?eJYrjC-e#_cPb1C2 z^?U5b4C-ZvF6!WHEQp zI}o#zJBPya18$KlW<2Dk0k=q6FN$-sM8DwG4KHYTrv7H#~~(Z4-M$IS46S zcz!sIh!id(VS%6(C0C8g1#cY7lEoo@Hi0Ssb|z-v;Ao-;vx) z-3sSC2)5@`JB0`$>%Ww|HIqOIyK%g znVRh|Ti>&cgpkgUS47}{j8g~6@tm!gd+gt_-$2kx`JVDKUmgOZ8KI4XZn%S>kt)yn zn8NhcY7dY*cbSY#(cog%x2KV$)^I!OnUW^PK+4=SMCua>CfpFI&mpj|#kE0;VhA+A z*+9|h2bnY|BEXdJqCrCokAuLU%+Xd~3Ju7c!(AdAJG3oSo<{%wE`+bEW`9Rba`^ahlqVHzEJ;0!2Lr(?) zJ%RXp0vff(%!UpmmJyJXiq!>y#kz5j%0V(%^dQ`L$Af5Hl zn#Z4&tI_=WRyye_AfmV6ThEtjF~AIVvipOiLoKt@^is}O2T?pjc@7WBqT_r%jR|=I z7z$LMABRf?#p>N{_8|E!co+3nV`cR25&WG8G)A&O)*hfJ*P{mn}Ksq zBC=m3w@yU)iNWd_g&Z-Fop0SCC?+im0RR>>7A-myI((3vq7E`|I=Rz*5Cu{vk|rIV zObZ6WLSzysuN>Zn!XQ$lr4A;u^-^Q?46UsbVV2EL%9HMn%-~i!gUx#={Hj3Hr0K0` zEupU%q+6b()0rcE4Cl(v?;zJaKyDGAHE_}BdP)kaQQ>=KvCa_M32>x3|3lsn(qz!H zVrF$sdG!(jbE~soq_Mi@^p{F!ePwt&5vpR;smLI@mGBId1Po+#;jA8uK<8{CPMC3d zK$hMLTKFti*!?nOi2!>IfDod(!C;t36I(hX7Y5#gki65sfMPD~Af19S z^>u3nc@QiI5@-V2OHZ)%1K4^bly1)02dSEbOB<}5-ME}hcLx|(-Tfkq<~##ZGXTbw zfRK$AlP_(3Jl7eCsJh@#*|=Q+zP zWhmL16b#62>UdwV-$ZsNqBhwzo9}u*pN@b;NRFViROgp04o2H&L6?#JwHR=z1k6vP{o`umddT8N&@5W$2|zat1`7S~T(UiURJSWM^x;VT>RF zfw0a+a^g*qj6~)m8&~l)IFXWoa1KnQl7O7IIBmeK^n6RFsd|bU*z7Os4{<7n=c!jB z>LYW$Y(71*SUIP~J;g}QyIX7W^hG7P*~6weqt;O4X1ePkJKJ5Xs+U1?POs!7A0G-b*E}_x z$WA#GzIBo9V)9$NsIiaxR=stj#*S{ch^Ppt?JU$30|7#7>f9OE?0V}F>->hH`=!&3 z#$v&?=KMW8qG4I8{A>fZuv)>^ln;c@#G_J74-iTgb6oRb=Y{U8KFaD zk-~+?|6Jz@>B?b{;fA|WuKWtq+0%&gOqz$a;8eNT;;{1TLP%e85vRBGQYVEAZ388e zoFs;;kXvX6@k*^Sg8U%b+RHT?v#j{PT(g0cx93q8t=xw{NV#uuh6lnffmIyl-9!i! z5H|c)Rluv#h_Iyq2|dFZBG-ADikWk*Ju9a@o@BA|11D+Eu#Vby>^G2^JiS5LMqgXW z)7zutRf+7$XJq!8r=}C>dM3{gWyce1^}Q$?U8UO)`4+uH zZ8Fzk=A`e%t2`3SC+fD~yD^)WRR&HHL2+5V(LAtx!;V#IacQ6wGk89r7&!t>i z)Zudn=~+9Di^zpi)(%z+EY+B-9S2+G5-e-Sp;U>aLA^Pe3#C4oKTeSq!i19uy(w5a zJt~8~H4Dw>DA`;*u`afo%H*8h5KhLDPtNHrkKGX&Sr_$=sB_SK2ys{c`vRf+&6KPn zpzJKR_gdYSXKEMar_>B)>YJPlO6Me3TwoB$piHys&7gV!oGi|AGm_S-+NR94(%#As zzrN_=10rB0%WhSXc}X6@s9PQGNGo?M6IpsDl4P{Xn2Y3>qYGfd6nxB=WE!x^MWh*s z$#0XGh%#mNG+^v5TZ!{?xw46n(qg(VMO8sSZ&d$$=>@gooqB=!nW4OetkT_Kf>HIY z-kC2rH|I0M2rI^pI?SbT!~xM@5p?Dy!kP&>^N4bqj2y_DU`2pbIkHLo(7GgUX#7Y*_tD43@vV$~@C#@`1Pgmb;RI5s) zDu0n&E1yXKUSp=h!3{v#vo+1RjVIRl4lB8G7Y+!!S@!;X%lk~(%25V5aaj{}uqN8P z=?qpy)2YmC5X*=%s9Cs~x2K5~ktHNZQkp_2S#!Z}k=vt*ECMW5O9#{WxAY;hZZmuK zXQK*|X~7*~AnT@kpg;{|-E_MYkcZ4~_aYyk%*Ni$W?Rz~d=NG5wn?h+Oc()k2BMD# zIaP0(^Pmo!GjO^-5-4fRZjP53E&5P1!VD{(%1;+4zH$)4(?bZii|}--MARtyRNZ)2 zGyf(;+0z8vhdfabj2$XvamV|Lq2u)+%j)(~LN=E5rH$=Gl4W&oaX?5mc|=Cv5UFha zAXm)MXt%;N5Dhx`sEA914n7p4RUY*NjD))lIx09NY34?><5}Hf;=- z_cD?+YnXUJOg8H*<9mrP$R2Oe!2#*mB+fXf#FS@x`0&!x4P^C@&j3jX$_Rm60cBxo?D{|KoMOOylJDEgSr%Q8r_j0MxnVZPC zNKU)m(E-qsP2$zVmRMaDmD?WDu~|8Nx$WZgu$t~L5JJc-pe4&LpqUUVu|vJYFKIgO z_US?;Hd%Am8OTJEc6Bp!=*A}d=n6S5(2Y&@(WNR-AQRh!Xj*|&XY=bU)Yfd?J;&~$ z#y;+sW|HPUJ(@wkO{MgwH;I{R;@2M-dfyJUe;wFJB!sAEA$mluUE>#h5{YQ&K~##K zQ5K`A6xu)pum#BEjO$569W+u$h6sUl@8yTsln`a~*|b6}r1>Wqbl+mN(2N~Qf}I1J zvAup~1e&q6eWn8>)XZ5gP?6p03RQ@f0i&o(K{Ph&W!Uf8xwKA%^CFOB*`vx^1R2>) zU?^ekie%4Jc5tLOfvqw`*30llCKO{IA#ss3FkBd;5$fBEpkSYfUD`lQsJYUD9IRFw zoFbtH>(vH*4A6dUT3sl|5Md+G^rgwlX;terAY5+P_XIK6q+3mL76sz3P3yj)goC!K z4sn7U?4xzouIhPTvEM|JX4iG!E9BYrj(3Z3_vuxjaaJSCsCJ=4H};XML@fi_Y(L*F zguVtz1{PSX!8K`O1lO??Yq7%09rB>ehO%3iD3N4fmeDDYmZhhwX&~JXIrVkTK}$9( z4AD`{&aO0ZDNcslPr1&OwYGe7kGG_uE<1z_A%p(u?LlVCH}~A>buW3smo}Mz&_8Xj zGQ?%+x%9RZq-2MD*m^6p40s$*2r1c&8HrGk4G?wq~VQ&vVfzE(} zyCVWMS#7MSDj3L@P8^jgrtTpzVTHWxDbzWzTGH-+YMXFas^_t8Bnk#3!DhI zo4s)jDcRXSH~AqPo7>IHz6c1%R)rXJrISYqa)0-^2nZK^cHE4FmMp_9?5u-wY;HF% z9YiQlj%Bz-yLsLWwSO01;*9*B=<}87kcEfZtO|m%=URDR&~oWHZPB z(@!yyQ3g14xQWoo2M4d}hsT05Rz~IG$*4rwFa~u46H)z?$tZ)dHON6=b~9nUvl&n0 z#Tc|?2eZq~5J<^3mWU5frzgF%vL;4^%F3e80NS$CaWVWZ{D_SR>jgq=dZgU#9#AI{#dAgrLOg1Y9^8%6f{QL-?g0^hdii0>I zEt{Lq!(nR>lFfbjVb>FcWHXdt*s~5K4LR(2fV6Bj{mZBzEt_$O!*Od6lI^mA%G4CL zFsqwL+o~ITIe@TkBpqBJEt?z7)0?zVja9r72j7v$b+XRY$$I6!{CZp!yF z&4|HK5!J}|cvnmq(MuW>_M|O8koB$?Aqr}q%l6*%?A59B62JbyeiLEqcLWw>Wv7N` zb^1`~^VG!{1tPLd&yZk2M7F4D&x?ecHuD%=_FbAkLb1?uyI@dmBf#|}BxI{fI`zoD z=A8!imj)1ugr3q;C{U2?LLMPSaiH@)qe$o}8IDBKzEeASkd)1^*=b?|1=)-Po!*9k zf-I}XdwY%=kTZ5c?4%c9vBxG|qhgAX2 zQ<^=Agb*?s=*BX{dERd+#ChJ$ysyyddQgci>UwPbkcp-J?B<6|Y?81kEs+8V*s8fm zd2W-G8f|bIaoL*?MKI5yIP0uWGtmzgv6tFzK zx`qm@8M9i!P{8tBZk1C3%hMi3D7>=e-oEcyM9p?GTzNe<=4=YS^;wyj*Zuwch-!zr zD@j9hndTH}a8Ln|EyO7=a;l|_&=Hrh9JK#bU@~4wU@0znIkFo_vgPG<8Pr~vmX1sX zg7ti7hq~Pt2;B}6_WX2LDqZ~9j<1=Q|EXq#4B1xqcopcsPR%;xd(eOF^>gxq{%cXg zB2|L^>!S&7R3p28X`lPK1WUHv3RIqst)5$f%5yue+5Wk;-#BH$gS!w?dTyS)_(Iar!=`KN29 z3MrRNacF_?YZv0T+9gxm41)5jIbjVWq3m(MgchvH@=`kUlEO`3-HPFu3guUmXXPeT zGfO0Vgx%`15Y}4$|0S}6>Wqr;cK+G$)@-xLN?Ac#cfyz@dMP+5g4gmfN zQ7%zdsKGv8=5Qdc7^cuXg`455<|({8|L~KDQP8Kk@`69vsTzs?IjJuO-h9l65Q80F z6SG8ZiE&8+uB^6Y%jGicyONlCM2C>3H$k8dJK{?x>Nv8>uFWY|-n)a( z!9!+qc_^FnP1=<3x{fhFvt?cRi~xjOPh=H~UVxG-CVqVB0Maz8fCy~Ul1b%WRh+Hd zXSC4KAOX!b08OhvXu?h{9rc0^A5Cq%K>xMzw}zgz#J;-+%VjT~!?+*_YbRLKTcK7j zv6}*^SF-OSt_`WzM=m)HPwVqFk6AQ(L+Di%r^y9!ZTt+qD3EzAUL0S9+?$m~ zRf~K@z>*1zXN$+A`jV7b| zsNM>>AXNv^#nh@hHPjY#XjTn1rp)SHap=I3tJy~mAz0TGdE$zF4Xc`nkYOE=32E4& z<~<2`yTixfp$u!+HM0yPyk1i>P0me6;X*5RXnZRKh6stHiuU6vP+wl6WmBUjBwxFh zS*%S+zE=0oAR_qz3qB>X$LCZE71*hXhyFZhzIGvW)NI~QmSaINa93h1cJWSyF6bx_ zboHv)$%L$+NU2R-G1ey^fv}n;Smm!4HCfLo5O3|8r`d1!b#geKYF{VE%}(ui9o?1k zxa(-Hks;rD=P#wRw4Cs{I3S_<)cM(WBZosA1YKu*%sd71tzGjD2QLplgBOzof*Gnze5q!{j9p1)by*BMv ztjB$#KX=k zhoBQ^_J+0 zq_VHK#2b##eI4F#R5}b&hWEkQk+)>En;maiG*K@gThI9G@|G;gR23+}cCiwDYf6}9 zc_Rzju#e98bH{Ph-Ra-S(bF$%D(=Rs(1?M!e;GU4+@ZwPr`5MEccR9 zW!cj^7FxbQ7Pe_8U4~fRvzTs?%X=15{wkY-1*|Tnvn0&29O(yL*d~XFpXo1g!J-Yk zuMqm)Vl-1CtkN}ZbqyhMnk*mkhf-`;_0UxWrC3*(>eNn?xA|6R=cUr|v+Xlkq5u$& z9bcOcTqY`~s(owEV%d$n?J_}3uM(!qWO?TgO0l_WyrBqCifyuIQNru>wUl<5EJu1l zI(Ey&L|?+*-nFn~$)-qOdGECC50}Z(GxhH1L^rZEi>dy?+ZNuffmEz$Fc&#ciml#> zR>I!3@OeNW@nzn%%f#`%(1~^AgudfV3kT3ZCbqN>vH>8(K9~x0W0$5U767`jvweOk zuFu3%K4fCc`ubMC>uGL3#Pyj-g|9#)_O7RupQZJ*)(lXDt>v@aP=vLcz78YT*^niV z>onmNVFiM)L$sXr8P`8jxq|{dSg$H#8R43--L>5}>^Bg*Oq$qPP;{2hC_nRVOK}Yo z#Ty&ah)qO00)EN+8gC@7XMi&pG-A8gAAE*~_m~|fT)nSR)oi0$yv2++s&_g(wn8Pg zE2M@46I5a;cH_ARDzT4(Y@G6B_23!h$9o^%!iG+)x2md;xGOOZ4$z4uP4VeTAR&Y^ z4U}V-_S@*YfKIGe9z}@sTM(VYJU4HLIA}H)uE-p+Hk$NXM!2=ub25B}EbKWM;ilT8 z-!kmt54%o=Cw*wgZXxvTKs$DpFJ-^3lUq`_PE=A-b*RNY+F4X7dQ+T?w^1M+EMtgt@9(caFm%A7I4G2XwPWwe*dAAg6kLXMBmuCxZUqi)lAy^E zkbcW7H$Nc~=kOIEq0MBn6o|)eb!@e`Dg728tgTrcA*RM;=ZVE_;yO>7rXwKXzR%oD z?}~VzF|PB(3TW}+JQ@17cSX9EbaA~WcMh0w7n2%iuJ^?8u5rC5-erpAT@iD^uwOvQ zt|m(E14nV)Cl)S<>pyw!hrB6ryTe*qaoSSXfnwqe>DZ-yulBgSCvr!E?L84@|9VfP ze+VE1D05rNE$D{?n%3Cf@`oZU7uk=N3s8jB9=rO%w)~d9yR?I_llT`-Y**LE8RfVk}U9^_Dk( zd-G$s{zLLBQ+n_P>aT9Uxk9VYhc6`Gs*rna-fy2osz{hxbcNijec?I%SIE7ZSLD!A zpAX;1)VJPoN_`q}NYqd|+q+WEjv|%bFJ144{M?Cz=^cT$^P}_I#XA(LiwfaZGpeFw z#${Ax81ep1*ISZOF*&MFS=SNY^sRljq5MpE8)~zdRq@7Cm%Syjy@X^X*K+x>>H;1T z@#Db^R&P`2xNLo@wkg)bNhuM_yA`FZZHiT#!8)(JoAVJ95z#YotB$=vYl0{a?k5WW!eJLa#A+i*iE&%5Q+x)JZJ zR08X6tjNvs9s3PrUmH)o_ujZrhWaDFm@ZAMPuI?c{A~$rIX`5ZUPY)By-}g>I$XHf8!4*Q;jN0z z`JzJORSU4CN8WoCtenwAr*6qdzdKRYz*a|}tco$jkhRZPA?Vt*_}lu@QU_R^qw6!g zRdJ2Z6JBhUEI9dMxsKTS@H`ZsVWBvClpBduq3CKqXAC2uQBTIA-Z+IPE}9mf+mp|ADpH>tle@~8TH||9_Iw*FtoSW+??Pd@y;<#vC4IA&u(P9>>Liz zj8t~L)UF#?Rk*q%?1SZ8<6S$|$aXB3ax+ys!%b(c>jr+@|Gr}Ae`{Y(Rg|H)@o$;|Lk8C5D_2n!qOV;@Qv3?hSFatq-Wnob+Tu#YJ5kQgygO03v0kC@Dno4k_WWL6 zdc_+cMaBaXn$uW+#Y$=SrBcMa6opkG@Y=jJ$PyGOF3;+6mv)IETSZ>ID&%2)t(4|% z%Bstmm>s3FOp$e;*Ei@l0JVvsM5NB>V>dOg*R5?W@Mt%Gbc&3JKWZZBN!razf~ezyhd%Q zO&NH&>9nPlhr*F6G+(R3c=h!Vf9skq3Po1RT@_cTz^b3ApuJrF*7Zmgf0N99h3IQ( zpW`2p(8ynfbVXT7siYREq$NF4I`hU1kzhjM)r@>!#Ee|+zwhhgRP|82;$wa-i46(ytHRsjBk3&iEPIeD4BMBoa$=Bddmt$t`K;2WQ>Z=gH`2*%qOxnz)1t*JBIEz z*7b5aNBep?r*b5X#wmUC3e{H!-*X*NGGLt}B`ugk5Qh*Nc{=>*w%yr8;B@q|mf3G? z`x`M!=c*fhmS^$7G&5{2c!0R)sZp$r(44NX49Sqvll2%Q4MnUQm7QLaLsr zVsN_atU~qG^HUgz&ya!&8QAq1d|x30>u~(Wa;|y9@yTYP`&!(Orx6o4CH#&|Ad!H` zYy0%xREWHqt!c>E^&M%ix0=K1Ri%4eZms<7c{fm1fqSZ)%j3*mms}U6W9Qp;%awXs zK0_oPQE3r-h_z0wgB~W#t8t2h3TocwBYLUfA^N4wvO`D(8T5!%5lb!bnw*D;KMf2? z`7cBoh%1>L9a^j=$t0mrUhVb;(%JM$!;Rql;Qyx)Hu@nfg-XptV#4%f3%0Zgd+@b23 zb{R5PB2Z#=c#iNT3ao8$#bv)8?%|K7y&6tL&jz`k1j1`Kj z#XdMa<0B_sKgFTsQmznSbvPS)FZ5RX=V6};z11p&EE;;N_f+RLV*ez22NYOMk(<&P z*FVWpwt0`B(j@@7)km~XmTT*BDAh#U*SoGR)$aLgJ<^}Mevol{xg2U~&ijU;*GVcZ z9l%VwQ$Hm)HCTt8`YF|y`1(d)7Zs(X2Zx<0XWR#ocEG9eJEw=A5R@# zt+|gQ=eT+i_hS-?Zp0O#hB877s%YTPZ)k<6mdzu^MEF)VqH+TaYu1{HMlrI@vY2Hq zs>^#}thlXmBe7}@o<@}Nx(q6+5&QI=!7a8VC5bPAFoT;;-=0=OB z!nly8XWmi98KYC7+v**E&Ymft?S`$l#@#(12Ex5T$;e^n?eq%ym?4Dg<&>CFUAPc& zH_zuqOg)rNd9K5&5GZo!o1LUgj=D6*QfTWq0K4g}egm-QHnQ#GAs}^?S-B}+Q;gc9 zx<0kM8>~dO7YZa?0Nl`>yST9s~06B(7owu0+Do5K8GS zt}^ts{&oMqrU3JYPD+J%QjtB`D1q3*>@$#D@^-3T+BZ6a-7{r$jW9RuxdvAKv?8{4 z8$l~~yI&@65?FcHPir^grRc4G+dp&MhBnU?241B>TduzlYFPFT$`Wl|13Q1)23BQB z2<<&}xBh&2pg)&%bEOJdFgr8VJ$k*)OfG?;KxRL08AiO&y%#yf5ok7w`M-_BUn65zBUOLVL~C$p$crj~~dm!`mG8hye)|ll)F9Z{@v` zhMeKhI!nNiH&Y8>i5Y(Rw8d4t&j*FMrS2?Xi;{V%-9}tW#tB90eC6%2Z+6G)XxFp#0!^m1x2(;6{nRS+w6==(Alo$WR5SYZ}q;FR;^o#o@j>~NOOE9kRSol{yv79=q zK!HG&vkW1j>dGFS?Ty9MeFWLwe93yQR8ou3#Z0$o%L@whma>CmlS;V?*i`__lmtU{ zlaox#2sBwH`v_WGRk}F?x9Q8r3wO*~9`6~S01izmzv)SBQ`e9CvV@iq7y5Fp{IWSM z7pVz}?YD?P0Zm`ZcG)t@b+ZK&W{*=efW?F{BV>Lz7myGK=DqAiThTyvOS33Q0eZo_ zX}oCbw`I(--l}{C%N#X7nl}T7Cy|^5f$Zf*OJwLS`J!WK&4EoP~l?pRJcje;$3f@R#moFFJt^h2ZHTW)v+Hf_tq1q(EE0 zLUtle_p%qo>_8#-aUu1V?-?(Ojf6t*9BQMLU!S^|-9s%Tf~(tlWqu)orgq!}Y!@<# z5k!Nh3z?)J8o_GT>4$(qFmD-uBh{AN?3_S?#gsM(G=n`^eQhLG@n z;$sAdkT5T0FWN1HY_ROBNDasad%Vtu1=V0)%3ib~1thA9nVbeX!qWxkBN(pqCDs;1 z`ugW&0fFG6cb+C7rslhxHK7>HJK2kLT_71ew&%M9upM1KIy^Lj>tiyIU&8V8hwV{6 zx4)cx5Sqc$lhWcVm}y)hei`lbO9629ysyuCfJWb)mxxdRE%TB^!j%UzK68gV4|e%{ z37$L`G6w)4`<5~b0ZBfVNgDw@Zz&KBVOvAEG^vU%oauSRf!ZwlAr$z!+Eos!kO=M` z#nL6yaaX~N&u5?yzCCsjp`h6vK_L-*4U=OQB!a7nh@L@AfxCPYBHO4lKr~o<%Y7bB z3qRBO76r}TBS%VD$uw+ASh{--VsF(=1z8pJ?0kbxuS@YM7As$==3nj$xx)G6nLy%p zOMa-EfJyJHXC$Qt$iZjeQ~4a~;5>i6lprGoJqZjUmw+WVfr#*|HbXvxSUB?+W_cA6 zunW{TpVmwD&8Ks%3%%gWr_-t0b#cM_+mPC^d6QK_9{4fO97Zmk=3D`}J(n{VsgMU2 z1=G#mkOvl>*7YboZ++BIu?1W<&9=46rPC}FB=_7za{&N#;BKPH4h$!qi<#5_i0#4w z64x(IwMUu(l6xdz5?p~gun3r>`=Ab7w`L($7v%Lq&#-mvxNM8#08W*ggft?>bech! z&<1X9`soIMHgM@*CIX1-xtMH95Z5!IUPK_JH9rR-TvM<aY) z2-OaUV_a6?8qD?vd0=Nyacke8-#;K2eEC<_4g`ar=9ylAIQC|bhJvv8SCF)gyuF|i z2_i!ryFMiN&P(mY)gYz#?JtBo5tQ03e+e&;~9pXAU3G1{Mbkj({V(ifU&w;b{{~*Loyz(5j#? ze+Ve>%7F;a{eCBnuUM{-(5HG z8834tf4vDcfo4-GnjP}M-9&TonPEPyl_KPUMYzImP4j8_LLnF|!bS0ar~{7{pG_7D zeQwrF7=Du^mG!ZA=R5X0k(lK(CHPX@YMJR?UutZfDYrMr&JhNR!6js<9O$7KY!b$G z4iHb2tWKOvFXkd?mAu16FX_|U99yU0p$_~seVjcSC)3>mIOL4y<))t_7xaOy78H28n*QFahPl^P_2SM#9B zlrgjW>sb@&K(;?7)0yRE0+@T|BR%e#CUe<8@>Hc5HM=I9xGbgABt}MhX)evV3If5G zQV+g0-`3>thgdWhG?)(NF|WM%);6ow+&S{p|Ng9ub*FYMRDp=Jx(Zi$%}?40ec&<5 zXMN#Z`Vh^b{Zew!Q>B2*)E*+^?J8rR#tjGC^CFX3W@=M|FAkxb!X!6>MDX+23t_~J zp1zf@$mw@Dm2T?B5eQ0t*KLvj?kP6eB+^XXSi;*kuo(xGQ+s>V6_i=0@Yw~ zx6lZgR~~50$<1XT+k}N37*c+o9F*mFQ**Y`crG>1Ro=)eBkk_nLM}C@9iqOuTjm&H z*R6edq`zIEdS;lrkrM(4w{;Gi@S|)c%rOyu6c$s*x}Xp&SEvpcLLyk)O>aRW_!94$ z0H*Qs(Qu##{N~*yk@lu)m2V+*!3}T=5mi%lK_XbhTfP(s0(bS8$xki&J~iFWybJQv zx{%q+V{DZfIx7+4&FrIBiZpWX8-yF`~3r=!Pm2$JOhY_ z`bMCdr)l*M&0taS;g`A%%#9F825WBb`YGe;_P&{yMRp>|-k}#PlBU!6&!A3peQVo=B}9+9Jml6 zBtmA%{ojeh=PoF_2Xy<$)D-UuMPb{HlOPm@#j!gV#ZVNMi(0#9&<_@)R)ja?g75Nn z3)tqBxk7?~@Y^4qKzqBRX$Tw|fAk2;FoyZFT;D*#zP!P7=7$F`O9j`-HBAEh?ZjL} z;yM6#6Y%z7W+Q-`#EV6mJa-{w&z$O^7u;w0Kz{v!ot~G+uk^LX_neu=UuT5y2uWnT zebh+?ARs(UMOZfoMSMgdSccSm_6lGN*EGCnfZ}QBRk2B%!_k()iU4MTw@jY6e)4WjQD_X}iK63`Z^k7w^FZN zMz*J4CLC{el?g*Kcs%>V5ReSE3xvPxn>;I2^gH%DkvF04`Chwj>Li5F5FTHAf-CPT zaL3~_*dp+Xt_TUYf=*!bxPkw2>eV@#6x^}&Nxf0p$Sb~Q+j(03U zX+rjwy=71;kR}DeDS{ z)?LUPd!ZP7U7x{p$D2^I_TW14GJ&lGht}=;K_J^@*XO5c zw&Gh>-s}4jN3rrcNR|B|67QY)x`k|)J-?KfJ$q9#t7nwgWonr{i25zjL^d3_PVB>H zEko2VL>$>p5T^a;t%nJpM*3)ZR`?9o!d@6;y(3K9yiDI(jwO)p8f1ib(-JP%UMqtE z#njmKG9WLA@auVHq~6L<8psB76zVVk7Io86o0W(CoIj@0&D|uW0M+12tM%5jUsyMZ ztrWD@ZXPXzBkNvXuyLo*hiWIMSjYyqW`|F{1?NdOXRboN@@fbP-+(HPc+^5Dckv40 z;2TUp^X0t&;bubPEZ|7gtV|o9DM-L5tco*{)3Kib34eE0UhD$9qw#|K*Fnz91S2X{0=MN z$EST{I)}USJ_I{KiEOiSty!Tr{Mg&8bmC+CIuU65*`PV0LvQ#RG#d}}hVM?oN}$=G znv#Ir$b$4HY^+O7Wt0qR#fv3=e7-H3yXiYk`{{+>=|}gx%5=6ZdXX?^lT#6*#CN}% zMaS(2-d7H~TE1hye?X{MJWhUhAoj{;exU7V{~%2YZ9ki|@aw}gZoHVte6zS5yMgTC z_(eXmY-4TZLZ$c;bygv+L@-g$1s+t2Z-@dLDts$0I@=1Q{ceatri}CJF6Lx9?fOA; z-2g%2OUt`}xc)XiGCxQ-k@Y6w57Wi<9F8XvaP3)`nRv$^B;AJ`@wI1q@1Z|@?a8Wu zir+0%rrg`xQhcP_RIUl!cHlAuKLx>44VC)TGD*{ZA&@W?Wuw5s^zNlt);bQRn~L%+ z2=q;n$ea&>m{sOxFVu!bzk<^$w1vlA+tLvMKA zUDpKaJG>yj4Mo3UXBi*qFOM;tjc~hxnP)KBVT$c!=R3Nf@{whRE%LSVasw}zLWs<% zD@36;yu98Fp*T#|-E?vVio;Jb&ve8KAtP%FI)w-^S$9(#gye8f=Gl1N6BLI@ z$Z~E-q=&o zl`!(=g!u*GF{EOJ1!xPCjrlGGAY@~{_zG&nWMgbe)iXB_$pZ1ry_ys8%)K-OLRgp+ z!qP?_5Ki4&%AgPyo;mAnohgT~aOP$6Hay4*bK>6Ge1@zrT~S+(O(2nzUg$nh$O>~V z5A7;JR+xi-=)wrd3Ue+G#q2;@haN0Pu z4uh_6bvctDL06dbduTfpNDdyku1mlZd`QL{y27%tl;5B$%n3fK-|_?>5|9MK2|gso z6e*xRnKH+U=?Olx-w0u0PVk}IWFl3fWYS!v0^tM?Sv98P2|jd~4AR1!5JJK|F+IUY zl|fTtw6T42P=usP&U>LN>Va@Z2wi&}(-V9=YGTt9eCY5kq=h*nRq>u!0VNUSeg#h9SK6Kv!5KizRtx?DgbAsPGa}RZ4PViedKto-a z6Z{r0hPp5(_$^)xbzx5MJ7mD^34Sxg3ksU7!0lN-biD#p zhjV}mDF*@ItREg6_jntbgU0r>pN@+}JnhFIvw{?H+3Evx36YV-Fk*Y!57$p<+E2Zk zOc|{vk9R*hvJ83RG;%80G$A?11JN^$+oF)N;T#`2XZ(n+LWwx1_>`{67KSd)m*mZd z7;#SVK-hYa_muW{Hl4kYC(bFpKH4CGJaJC(5VN5!{9|#zV!3MQ6X&5zOyt{03g&nR zyFjrxkEhB*RvwE37EQbbg2h>1)l%aSEY6e0Rmxe3~6J0KQxSyza|Zi@)R63Zq;cNiH0=Gctg=RMMIizP=cg!o=0uImEkEmYTR^t z6BLcJW=xq9$&<#-R~S9k25jmg1&YR5HT}6C*TLehNQ^|XB1D?XQ>gRXeIF*|i}9iE zJ2;?ToC+{~>v|ce7w0MBQ6zExT$#UW6~gb>Zy-8ZJk)0j^oyzYLT_t%to&!y`b0tq zmG~iOyp1S}I$NA)K#AyV@$l`S&@ZNB$ac!@Eg906k*(A4yqg08#-AdM1^UH9f&z~a zYlbLlraV{qPv^N437ySWjkPHe7)eAHh!tC9a43Us(GcFf0JNs6yPshBt7On3Ue zr~tFHOIx5+OjYY^s=lRay)sbg6{j_~uMvh+aSm>Kd+ZpKnkM^>6gcfJqzKv6G}(*MujLt% z2-&_g_|f6x)JWMzQUYd&t|WP=a#U)rd5Ki&;8SbH&|mx zdm0g-Z%tO%0rY@GL*jOQ-e#N#@4SF^aaLGJ+ar-wPKZ19FP?3xAx)J6?c!7o35)PQ zOR6E^+le4voD-pWOClje!`13kfeGJ81@+=dK;_1XWPVAb>sqRs=7zgAMI@uSd#+6t znD8a2&?(Li5YtU?OV>B1N0iOuO(`=&pi%@Tbc#L^T6lO=+>JUX;rj@oRGcyxF+DNv zK@pf(H=U`<*)Eo~0wX-Z?sOyI?Hibly$BP5k*m`psWY69IE**vHb0+|`j z8ajQPqB6{&)B_<8BU=SELZAlIl}=9;n8x`ok&K*6M1^1_B%)z4s0o5}{0wh0Y{eH> zLYx?D3+T+K!h+|SAR?0mg*Y+d3z~Pt3dD)Abqo0yW*Oqd@bydBC6Sig0x~Xp7>Pv0 zEq?uh{RYC@4O{g%4Z-59AP(eED+bwU)wjSvtr!MPjh1NyA?%+BTqs{&3fi-3zpy~B zI1O6YMYv^$yzurI2o^s=c;84Vyx9a_#FHeufS9YV`gXSnL&d#G1a1t-U5M` zYG7xny6*K!=VU(O=B_~D0zDXKFck$;Aco)O@u);NDi`!%q`_7TA6c5W4QH-W86;m( zBD}*8Dl?Cs;eq4Sol&xs25D{Gx2T4mZ?R03mlz^tRbL)CCc?=GjqWMOyd=X351alQj`j>F#LFlHyGw4tck`O45?;9 zgf|!hnZpRUSt{(XOpUi2A)QB`;!!4P?f~h$-3SQTMtb=K@TIPwyd4Tk#am@mZT7sq z5Hc!TGu~GST@Id=EMΞf;o=+rxI%rz&gc&MhE2OSyEL7nF);mU6pM_f6{#DaoZj zu_Yp{@$@H_M5^2H;O$00^sT`w4cqXAHjpYFOh%1X5`#dB9?9zq0gy&Os2E%=^;oKr zt!LD-2Cpw{bloJv>kC`%K@r(W)*#5DP9}vx2(oCfcz-VLFl+1fqhb+)!y_yJ6@3bER2vD_x-AYVF=jlrGRpB!n#5bNVLE!fVwN=}LGf zS!=w1DiI0{0#WOSV`VZs8W~oRJ$=t0kZ?H(RGCv}^wPaLR7@Fo<^6^2u1m@qw{FzB z*1UD|MrhCNx>(DV!!j-2U)U_vc95Vot+|$7TTt)DKq4X0iKs{GoN~)cwGyDOuUP=L zK(;umX106F(Kig8Z}U>acCYdR5&~EiJ3X+a-5dGfBOXGQa+r4-wtGu3yhb_D-wPnq zYm`Ozz4Ab|5Ov1jordjR*_y7nK}3xyc&TBV+nqXit054j9K69Wzs?E^-e3qs41xZi z%(I3aI!^N$mXi{L?cU`MAoOV^vPsnLRl{%)4Hqi22M1BM{^eT+;UEI@PQjmQB#Fq9 z=3s#wa#|Q+R+C6e=1svLB0ZTmkR^l)gDC;DjD!%5lTbuXdoKA#)2}oMbR|RiA|Rpc z1nXu=QzKnQN!^w^8j#(Hu*1TMl#~0~PPy>VDoNr}whxq<}f8}Q}EU|y+^xlQfCywW$Yy)c739WT7{$`M?Q;`G}^AJ4sC zl0H-MA&SxJEvW?#MIvu~q~5smeX# z93!)4s$y$O3*LBy^(tMqjlGw_B1|TD$pRLv5k^vsrRjm>_oY3qOPpO|*3>zImmTGT zTS?^2Mp(D&!iR4Vx?OHNUxy8(=(3(_(SQ@Y>j;l<+Jp97MyjR?2oVJ}S34Rp1+kj! z{sWRxi#K=O=a%ZwhzRYuJmyuq7J<;7s|wiR;0Eov49=`x4g<+e=2~tJlkO+L-@NMx zzz`BLY<0SYcO9jZV;TvSip%KkV@p-yMg`(?L*?8;$nDcLvWW27h5ULLv7qB(ehM!v zzp>h-GxU{FvU-bm9o;D6(le@xFY$NIb&UEPMtpjQiPT5te6)^*)Ev#JXp+)>YN=|s zy+CTtvNo!~+GtLn*DC!UTQVDh)|{hwRXLS69c4tDQszxZHzY9;OFmBJaKG*`O?`_u z9pxcHA~?82dy*SMY_8G_93cSMocvHz@N%`&6Y6sr{!+bv1-ZGd6OB#CkOG&vH00(i zixu05btkI!_r77jf$*NAkD|AIWx3S88t*wu7av%8db zhUz7fF$C4KBy{VBMl)t`C{(IWcdWsCjLgL-v0o z5DRqc92ToVX7Hk;bkI&CI#Ix%`^wMBb`$_F_xx#rL|xWReYBE=MqSYWtWQrxN>%B8 zm(HvH?upsbc`L#@thhj>?#cn^8D5SA=e0`7o0QVQO_Bj5qw*eactE(0=6u|1=2qRj zGnn#M?=ap1nYu@ZLb>Dvl6sf5iAF=XE+fLYshx!=a#A}h;>5AnL9k}}I%ll|Mqn>Q-u0cX9$E0x}Z`{sOa-Hih2y2k9P{`OLBdA}Bj z&$Bfl`*k()lnk#_%Ff7Qa}zZCm4HIpR>KW0=qLeQQ9T5&R02WKxEP9(sydEQAYIpN za%LxZr&8XZNWcehmVUkzGOl4gmfC(-wJ;7a0X6h^iy+XBP^fzpP)ynhBsqBX(gLD& z$-!&W5DAUC41KJ+Mzuhru3B17h-09~2SQ603N93=)}XME; zcI!Z*E^Ybfyh|dqrKh6t@KU9F=&B6%?JQOiQm!pogV3m};-`9~iL2fEf`G1CFh@72 z)>%bB8RXGM_Ki(szTDO}yWLmlHvnF04;3f^r=VJZ-DiWnudj zfSA4wr88vVF0uyYI`YkWv$MoTc!6$#avkfYXr%~*=B&0u%aEz73tS*lH*~J22`MsX z5#<|n3vgTVA|VP&&OGjsrYYhI;W{3$s_u<_h;Tk`rJc7dmFL!1=PgTlQ|&fFb2@4X z%5~;y0^(&w3UXw~)Oo4Gr9X7)9`TcPk?kcK(;4-po+dktCaR_jMGBPad}@b#3Q(%E z;EldLMLxQ(U-*up^Nl4wKHPZ5zI;6Nv3Oa(P~#5o%^_)FDR^Dc=ioWZ<>NBW%$TVw z=2=Ewhw;I&2KO<_JwTO+4Jy;{X4P_!OBE>9SyNEPnoEQ{UIMn*r8jPX?D?f*P2JZ} zhdX{AYWiZVRYXTjHK0^SgWAD5R=t&@pIys*NY(l9uG;b%S2bWNo%!;4WA%VF zUp~jFM|iK&=Og$Yk3#3HHA+CusAu%Bed$K4?xnK+jlld!=ON! zuBsO+87PE(kU#*W-X@$-s$1&SMaUBQC@+0_lX+KrMg~KnGhtQMj+Yg7RO#{7ewH~I z^UbzS<3&~7+^HwpWwPCXPua;*!SJZ7%2*&wH$CaHCSqRlom)-6{=m@rVu_G<4-c`$ zN_0pfk!>*q6(e3g+RV`a@^wC+w}g}{F;m*kmgzzr(9F~>A^%6U*dL%DaD%D=o zNx2)6+i4`~=KuovIx-MGP>Wi>uHP(>sv})<(}q+XxwnomClV^;&@=rS)9DNulWKMa zYIRLzTtb#?>FDuU^#E7k5U<-Rkp9kKsa&k`!|gFKQ<0nH4dNp51eVa43B)rw2QrA) zO%LJxRO{m25``*|sxvW@N!on-)wIt0hW#e8wVodO+PcP7%W4dWE;j-m`gP4CJ#*9_ zRaemnINgNl|Aw3$tLx#r6l3HhYdb^Dax)OP7| z3|0pnK-{jbFKrPn7Zq`KBik+)7J57{txA>5C~ov5Pm>#EAJZn}?nu-eU;rdUNYyh2 z!>2%6oetxt649sTrLk%hW66{{d!9&WLD_}KGgzm47%zAu!y+=D>r~d5HH&@V8nWj1 zc^!y-${Hl#bkPWmrOcg_S}ri;RC_d*tRctg!@>I39~e5` z`u{0=lOF4GEjw(UzarsL)u6(MJqg1THz>dZ1J?Iuf(C}I5@ft^2mOCIR>ylIzV}Kp zGJ(vy;v63KT-@ATdz!mBU}AynT~zyylit^u>NRH_lks(*Id`k#C2&6<(XsMGx{KL( z4C;`*t1+l3*SpyYb9>>Y57mn&LI^M8NWbX{UF0u7V7h_hq5;jj>PgZqv$v}&C$vCz zI)TQ>mIoDu@|2hJn2DcEIH%mY@#JvoN1{Hpi^MXnVxRUASq0e|AbNKN0sSd2>t&nM zK=iJ>6Nodf(!HDREL)Ugb%x~Ka53H8AQa;zQL{KS?}}G!H4BhqL@Wp@cw*vyrJ9C6 zJ`{qyU32?SBMPj}lZF~3vH@bkP`t}k^x_ZATQ!fh|f=o7#+ zZ_C}CC9wiNaxQXgSl$3V^doWw}2cQQniRc2Jc3SQ8`=vNB}rF*4=40WrTge_uC!iv zH(kEeTcB|F$P+<7<-o^-cGYkn*N*@And!Or_O_l=zW8nfiPg`*{)jxA`&K{q1XNrI za&{tJGXr)MO}`8f8HDs>gaAOjj+5;OcZYf%7or}gV5rw=IrS}DB4@v^gKNyY5Y6GS z_Z`FF8|yAkZY#KP$Z*+wANWc5! zyfp3tT9oS4Dp=2_q8JUk(}z?f}iIjGOl7`K(>d37!=g(rVHW9 z!7Y9>Ob9CLiAS4T$3vDiT!_fz98MxIO0ynE%xXX-yNjK1Sjy*yPQXjl5T zHS6rVLa8#25A|xsBlPTsrvvScpl2tKBL(O!(6i%`ivHzC*d?vkfS+vN7N<^V*|B}E z3lFsHx;IbVAD&)MyLYS5vU|M$YXNd}WnlZ{D*i7}vg<~)<$;o24cSn-#oFe#?*rMM z$Tj0Z+wL~6fTj&$^(fmVCweh8LC7vAdUXdm>9a=WM|7Bv(^=O>)STn(mJIQNkX>=9 zlpC3tv`^|mVj`0L2P$^4YCV1?$9fjAEKseBjmYg^yLZdEbiS3Mx~M9-`dF`yG*#8H z-tE^=t!tjdmyvyssWirc9PdWAld+aL+Dch&&poD6ABJjOGvZ?5R=r!e1~>uqsTP}G zwao&ub;Aw3jf~gcQ^5S`L-rl|1Yp)${N-g!h-HonbnT`cr~H}Yo^O@O0$IE2<2tR| zkhLrAZJYv-tKI!lx48K$|J{rIwMRneuG;Cs=?2$HOYB?4n@vm!6 zXI%d}_2JAPxciAT`bHig^?XzXhznojs+o2=~3$A%E!b%*d>b19b}scy?$ zlLZpHmIvKzrXg`PfymwXwrPUQU5n?CpPBc-YWiC_&kLglvfScHdEWyo&r;I|dYD%A z%z9q#C~EOlOtM3!fNWb!^eJ3wD&LdIfnGd2p>kJUP`AVKfnIHyZ`SZexjE+04+z6< zO;OF)q`rK@cS!|w@2&=#Q}zj8jnnd8=Tcp**-*k;F?OnYc24->LJ8fw9#2tyYd7<@ z+km@YTgVQuT~JTH+eduY3=Q489+w3_<0HOmQLF;pyT_CGxrqAzx*tETp4=vb?p=1u z?%XG5d?DTtzI%*#jXU+VRaSnE&-iLw9ry7W-}QBY(p@nVk@*J5u_fPQR;pI-v*6h_ ze`I$GrMs3!<}*;bEAbv`Lb8?@uNXjM*Qs824%g)$-RbOW{!n{C)~>u;JES2Sw)jXsMvUWMwa6wD# zd^zU>a=cP^za>xpI_xF`UAvi;+K4^*W4rqG8}-8GbL<}Tn8?NWtE@M-lKiWW+m!0m=txJFtw!eRM-n&&f(T zI(_1Nsf{HR@WR-ZpRv0?Se?GqZ2!YHas;`j+J2^dT#ZyC)u%x*^F#42flrc7On}lv z`~qSsJ^uNT7u0jw{D_XU=1Pd&MS}V9hjpYEE$jlVyNGo9rT%;*pqE%PlT$eVAUH}I@OZQ=ZZVcg-~vw-5)?9i`^gg~Yp`bz{DfJA%LgLS^*kT}oN$99RuS|DPVZNyeR$KEIqwF`aJ{tyy&IkRYfX~#uIH9E~M#rdFTck4>XdhXo}uLSF! z*ae6$f4oE?URUA;SAxVd-t7%l7*9~Hmt|l6>!1zwy5ews{DVm_v)-=;mNUR*wqRx?!79^ILY~ zuNG3MP^~NPzL7*ud`PyCeOcM^w{l!J)G!swb*UQi#tP-S;yy5DkQ0{+zg6#n#q?Xv zRr5+GHa`cmtB|e}D^n2^xkUx9L1I4Zs=#7D{%W`6`skQ~#T-V?CDmKiRqe-LSAOnr zYyriD+BCdE+AdCW!_TzqGp5hVG2ROPB_5i(U?o%hB{(pk4+x=K)eT9-ja zEyJorra&3b;ZSM<+4>5qP-65ijjEi`!XmIaj!=|eNtDB26KgoUC*NBSLCn{ zW~b~@!LZz&;jf?2r-1XmsjASqTbcF!skrdhjE;TquZ|NZ3dC>>ZTlzVP0J_SjKeKl$-Fn&8v#Q zrCav^cdW5}d&Nw!Lgvohrs>=B`A7tB&yBdO?3GP5G3#}*>N`k6@ojxuB8cUl2UZB$ z#Z2r;Y>vy=mhv~J8JpD-DirMEH#7poO6;j++Fw7ms0snQ_cftHzs>|>DV0@TX8=9O z@wE1+YSznL-$ht)*KcW;)vq1Y-(KT-fO&F}R>pf(tZ75&lW;>nF^s%ri(hWURfyWP zxRCh!=X!;CrP|N8e!Szse~0fbxAQC2U2O}knZ9>C_-*g2P_&Dw+l{xo8@Ogh+T&7k zkIg+_UUW`p-5V^;$iCZ^q`dE)(WHFtjSRQec`j-5)O+m1pHOlYl6J+cZ7Sus{q^IY z@t8|*JN^3w%nCibTsHQkdF;SnTULg%E(h^4f0ix9EgkOcm(!do=fvRWn+g>Ycj^5i z5RkabhGku3e`|1v-sQ4!72rb>yN*@58n}VAq~o4X?0usK32WO%=H=kaZ>`J0HQ(V% z(Yq>|w62HJFGbU;PFH95Py^#O zrjwo5u+V?G3i8+~*B`FhCrU{hIWH$Vc0VuG@2x4<&9@B6>8;#5-$YVd zT4Y%LAv6N|i?aEV@sSQ`U|u_#lU?R)uMe$j2rW)`-|EtEp$DZ0^j0&p=Moc1W2>u(;#2ajA%wdK|Z}@~w{Bx^7|3Z|zG( zT&3;YEsJ{-WO@7hD2MvP%DSx@>-Ol6ds&6kN6YcOk#muK-(^jfcs9gFvuEoq% z+UK>4YDR>^Oxn|h>iafmEkRN_?vg!LzG_kn`HVEErX@HtHIs&E(!*RDgqd&bxwIfL;NFMoakGw%G4 zXQ5eq+2>@sn8jWSGNM$d-c1|Q+>>W}-OE-HX1_j>Zp}G-n`LL*PkZwx)>MULO1SxB zM4G7A!c`%(@@_1s5VklzLyI(TyUb@HSZ~6E%8@EUyk?^;nQtfrQ+HyMkvhjTD zxOT$fp=y`QE8^M;&x6eP*GINC2I^&MVl0eWk!y+i%<1>yiYA;B5B`!R`HbtZVY2xh z!l*mb#{fP(1FBHLCwNQ2{}Fza7^AxUV=)mkz=G> z^5!h#-fFfkJ4lYQMIE7fmvbNOA8P5@yEv6`UA_&>>%vhl68ovkUEF(jH4$I0t%&oP?p+8%YTJ6y9{YK5%bI;G~lF*&R zyi8;`bL+CS?L_x&$KkhrSOSUccbj5GB#6|DR(@)Gy_-%e!b8M#s)+>QA<~d;q}JS! z^*+;ccSUP0B1q)GdVARYz&?S@d-K>e+Sa|Xah%0%s%zO#B2kVRe(PL=sy6=!E79LC zn|~qY8c#K+L;NgNCK^_IeHl;vOuHKw_u}5Ki_W9ML#X##ZS?u#ZUNrqRVvikRt|p! z#Gk*JI@Nw&M+d6Y@!X?>c9Hn=PrU^bj1hO9QE%ONc#M}ulBbT*ul4k~$jOyOb*C|| zMvObynAfoENolOe04-;5zkCw>@e>Q1%Q?%HGp&h_%1 zcKt1TPcs6mkoqz%pCCI{7(dgl$41`Dy52MTmQ|9{=D&W!F#6WCRn>?0MD7&`=g}_x zb!38AF&4gZZHMaWbJ_~&Lpx}U3&e@TV`RrxxY7xCy$1*e+P&}KVYBT{9Zyvv_r8OX zmpiqm#yu~0>rQ8xoy;tHd*3S>JHRmuOQB>dtVcdeRdFT=xFU{yslnU?RMV4{_2IP3 z+&mzTy{TUnaqLZ9SK9N~o7$7xnfL5q8d+}2nN{S(P&hM+pwep>o#IcQD-olrLa2rC zO8qXkS~Q&iIdRbOJN33?^;=oiefy^(8bc4#g^XJ@-6_wj?Wa`^NUp9Nr?X7d9AD=P z*`^|P{rN)dOI?>vJu9O+xSW~-TZu2VB6?Tog3j~(k+@R7l4-Yc{8C)0?HEBsJk5UG zzkb6$fs9*Y#~+&}C^;%?C9c%dt<~gyp>AA)9B(-C%(+*QwS8>$xt(8wsMT_PcHE}g zooh-_$*O7Naw09Wm;vgjab>b(};P)Z_F3vc1D&x z09rb6+m~{?6Ss4Dha0KKak_i)V%UN(5kFJRJ8buAx?-c2RqlHHrgM%5N!!OQ>zeBE zo4#d&h@A81FU{;n+yZ^wLvDY1Up1Jg200O}Qr-0!0DTFsLeMssEXB7d`ENug0T8r} z_4`~TE(=MgU1uGg{XpV2Cj--Ojmx^b+2#)n!*2Lu)IGUtG1}t^2V7We1#_0PZg z=ReTVR#cBBCK`6MT+C$u1ahL5$o;Y6R@gO*8EH`~ELw*fW7sAYz0+TDtIIIr0PMDX zu%8XzzT;ZWjyBu3XKqOLp&cPQmctxd@dF*}x%be5I41j`uL%QN_~O$RP!i|cJf=~r z(Apksq!z8h(w%Ii3KPzcktK@1!)d0CgmsPN7safb@Agb3gB8wiag)W!2tl^Kz0*=7 zIXKES|{OrxMYd69D>@Lst7BAAM@7n7$R!-n0t0k{O9u?TE6B zUyx#|OHisX#Z)qIad4rI(!rf3cZ#ZXP8w4JA&p9f?tPpKsr?^?7p8(s^V1pLdZZ;n zwP_$l{2$+ItJTOkPMD0dQI^npJ>>dS&5zS!(K9jpLLb@f;t+q0@`AZ- zCJ(uv*w@Iz{r724MOv|2LZ$g-$gJk-;3IG(EE%g}XXRW~0oYt&nON$PDIU3A;t7%;0+|f#l4y3c!}q z3l6i>sWSNPxd>h476~v8qE3}TFF2e$I#mX<04g0^M~cB(>A>Z1e#;<&t~!H@zzwzT z%a;&Fe(vpd`mG&`3`SvA z&%iU-^)-bg(0cBvLn+xUY(c|LmBDdKaOPLvI|1T0GkRR%4y(kU{S zxnJ+VF+TdN#mLT8e{RM*H3r9P3F(v=bTVqrajqoYTn5g1mj~!n7|b)Q&xfB0R8P#ndIe0R^D3Ko4DjkEl54_EtsUGJFIEo4%AF>$&^hsW_O?%5On&aGdw4f|7%2 z6{h?qIj9aw#ld&K@J_|S6q6Z*El?h z&-*iQ-wy9723B04G$~PX(DRE5PRYUe`>_X{mk1HRyL;L;%bdg8gxX5hBRTuOc`0FS1`3IDe zORl1j=L`xCdQxHoLpyopX2l@TFL!(N#0YtNWVM4%a!J8=HF8q$M_*bdZ&@fIlsuy$ z)l{kz=IsS!P;b!Vjt&VBN-mM$W8Oz6Ld-H>l`e0Hz!Bg{&|)FOrZ%785TPX9VKL)Xx*zW@QElBKK%^ zatVSWvRl%ZD4~d4YI#rgDh_(qf<$t%as>1=q%7xya)X{hmFhGH&k_pcgq*6TsMzDC z^@sM0qOr^n7TgioWik{N%zb6n6l7__!DVCl0euqKv0QbfQ^SC4r-DH8C~?DKkD%b7 zXB&NLnBqpH6^Pr`yRH$v!E9n6k9=AA)+5;Z8R2|1s5j`h)R@#8bU8IFVKxb}guHZw zxq}}R9E`IOfp!glT(+QvJaR{dOC5xdU;8H^>t*HhZ?5wa0r?nn`8kQ4O_4OEH*&iA^)74|XSYZxkl zX$4IiPzem7oCa8PMnnQ{KcYsUOSOdbuqsdH&M@f0SSmO50Hg6C z1dK4Vr#`(yn^QN`19bLi-x|~dbUIv{p>aIp;H7DTdVuRaW$FQ@ukq{91I(RP4ORqU zxKh`$to+2jMjk{0qw3)IU^2^PNFmV)^tDFl9GB=C(^C@2xgxmA^bQksc!5Eg!0}#G z$^>SoEu?&xP#jbV%=Ni$#B9rP8^@Ii%;XG}z^Fp&iSZ&^>i)RU9b$gIL(=$3pdgwCCS?MRaORqn2@G{UMBr9n%iYv7?Pam#WHzr- zpk3r9g#u&V9YjFa-;JY?G`=Rwqhul!Xlp4XjcY8kO)s6WXCHk`>I6<9tP6-7&xmO8 zC74ZO!({fT61d+Myh)WnFL_b~i0twA2z7R>tx1Xe7)x1KY{dTU8T%B( z?l~z4*xrkcZuoqwD^9xE&@(fzn1wp42vj9-W2$Ouz4xlw+;k#JDsoNziGBVt>4A{_ zl-?ULa(agand2BaOMrdj@+gBVY+9@cI>*@>(bx=~<93BM0pK2c0B$QM6#~PO^h|jf zJvm?|6#}zU7xGdFWX(_?(7cp88Xzb4)OjKf-DC4+ZD1j29IDloD)xc-veJbxs#!-h zaL&7h2Li`Cgpy}!5IC02vsft$ipD*|X9=k!8jsil zd07OS#@{Oscio3`0H;7$zpNe$#lYwSsNX{}Ft%|P3W|aEb}^Irq8QiWsoX$5GAkha z{f)LT^y_8qRDT)mW$oO01{adDf(sch<25M<^o(ETP6OB4sf?_cg1uLrj92Zx+LX5w z&TMBOs2Q7v`n+c{cDLJvYz+Fw=2bqhfSj?dooQR#YQIMq8gbvDuK@?`z_hIf_w?Oj zpQk|ZIL13oaj=xc)Twa+OG)+$Lq*7qBa1UkhN8}G`D(;$$EIPZ8;@`sR{1Jf2{UY0 zeXWGYz=`p!DU}woW7{Xxjz_F1s=Z~8tSn)ZrV=lon(SdJIqBow$XyEcr5z)ZZDr6g zzAK>;#y$6}gk&kuF)p#MkN^WYv9B=UU2hCFO&N??97Crb=`XJ1bjLM2Xn5^$<5nnl zu#<#XtKZX35^W-P<%X3c0>9HhtR|XwaG$+o--2Wz zV(ew`@Mp;y=!)m5t3u`-+Jb?4^HLJ zzF5Wj*o!t27wS=db~ujPU?nC)*!iM~#8gv-fQcl_Ah`&T^X*6zI>*=MFod+2lte8d zYJ835EC5U-DI^=gR+3CZ!Y0^~%hLm5V2xr*bg zEm%n|!VFSPCwqTZ4&2wXVCj(_```=6r#U?>M&SBZSM-&8KTCyv@jbQO%FK3K+B6Pe z$FSm;&dYp6mJ9vjYaUdOgkIp|vBE<<=ogm+eB?v|aSw7i zy+gkEwH6K|C&m?(s;w)JLh=bc<9jaZmre{wHk?7exMtU`J_~1(w5EXaG6t&Fp%Ccv zFO9l);A_a?LVHe6xSNBX@e?(n6(mP|h@hs;R1Qf&KB`NF5f=(~rMZ^_K5ul%b%h14y+{GFKML0Op-!PCDU>iX8&c# z6kp0xgp8cuncPFBxJLZ;QOYZJ2ybhEthT=)I~>KkjYY#rJdRjh>$&H#nlKq%A^TXq z1nIw=bZtFTU&nW<9a>Jl^+#Ava_FZluW_}Xn}6@?Go^RttL>JaS+OC>0|_d{&CW#h z-hoJQ5gYP#3?ObyE0jRC*euJAH&7`aH$)iI*)=vL-vx$DamjX5`9mCq<>u6a0~<-2 zQ|$5w^fmJKxbof_crcorZ`~NT)#GTTLO}N~1^1_X7b9LtP%^d+qRUbM-Qu2-Ys!St zq`OOU1F~o}Ny(d$dwi#P09KQf-0Ae#nQVN9aPjph(;zy&i&45~54f8|C%Y?|l>@x) zx`5f_ILqod=iCps)dyuPFd#La7I z_D!3K+ma?6=oXK3+9qUO8ol(=jzwv!k3y!n;8Pk=UOSnq%QsrlksPG()M)u(|RwX57%(pK!LYzJCR zVut5S^||+DRmC)#czITB;j(XdG)LL4xnOBM8ORpTgcIh6U?A!5g!tEQ*ykU+z7}lu zzRma!S)PNO1UHyMR_K>G26T&i?%6tnCq^c3x1d{m`Ikz5BP)m{LC1LI7@ErxWQ#BR zT1usbUwc!uX*c=Sn7FLo-j4YJTwhcb3JQSfk&iyUVo>ry;ilmv{7cBWTv`nS!^wJQ zKu|88xy@OG6!WiKwca$G*pHX1Erg28y)QJ3oJi>?%ebmueI3TgFqw{ID3pq?;yJ4e zmJ?kmlJN&R#UeD-3U-@@6BM&qscm;(#AtTwg;24KO0B!Q!Emyzu|I-{el?$mZdy<9 zDbCi=EfzEFO)EB3iuq^L5@-~QNB6WO3@6NO-+9NEFuL?_AX==39FG=WNEB;DAJ(mb zM6nujScY>?U%?n&RRPGJG}1X~H$ir%BXmKeSPeO??XYPi!CTYu_aIWNgV^cK)vw>M zPak6?h02i??l^1VXr2v`x}_K$=ZW+e#cj)V$kw03c;7HoY^bmcmqT9|S_ASOohx z*gHguWmY;?iUh)y;aFG#s>RI9Nxy;dq#Myvv2zl9d}$sM#Uj|p>nbFQWmr1Cp8`ab z`wX4)L9|#Wf5!%5XcUWbA8!euQ7qDS918&&#iZQzu`&!0Qf}UzCa}cX0H|HIu4drA zHH}(ODCTi2QXzSPLa}I@mU|(x8=g!_PzfZXJq|Swh2o)d+GP$3#r2kx--7)_}a=AZsk%cC5Dx5o7VT(>3-WVq8;p zmJ}k!>bEwT0uXOIBgt$N^W*E15HS`pKPK4_F>VGLe;3oXV?iEB7>l_bJM{w*b35J* zLBd!Lna9DHAYm+G{(5GZxgD#yAG(>jm{Z@HCbh>`HKAZk(sNpp*{0#AX^23sSTy|j zmOSK&pA?hb9|&pq8FDr{H7on^Nygzl_Nks+l}s*noaH9Qg%xrd$R8NcG3k-@2&8Sc-CP{;=f%;n01xo;`&bDO! z1ag9qgj4xIh(guWVpn(Q7k2}kS0P_a4o+JT~R*-nYECK)2w^0V0`UOn zSqk>h4&XsFRF2i0&2cLrb4->-r2wWfBw$Ys05&I-0de;W_xm~dLerQmoVWRx5n8i( zQ=i|4Wrc<6j!O$sV>M@=?$(I205*zi_bMigEtBc&WZ8E=aPM9{a2&Pgc(g--fH65Y zuGI6$2m;3B+_+NDwEzOfYS5914B~(wF}NJhbsUn$iv=Cq9RuQk57Rl?R6)U*Hc#A! z*E|Jl3k%BF-T-_Tq>}C!VI5B&MM2V-Tn#tYm(o2V-MpX9WDsWoT#eV!`PP!2eO=Zr z0zlG@yXRzG&^1Y8!|H_AW$?4spOSjcg<2<3N;SaJ}hgG(xeeu6&EY5Le?PN_fgV zTDN029rpBXyD~(L)x5`^I1n`^?XJuvk)s1%T%T9;NN5;y?mxbaTOeZ0nmGv~00he< zZpTaX8M4MKz_Hjmbc_cd@v&BcjxlxtK&C&X_%uMyMR180m*XX}3}s`~1Fy#mV0`NK zB+Lg?j2quckP)aDW6j3pc zy+6+QGyoLSDeF9L- z8eE@O91@5dW5sAW9xM#Icb9OA~TuaZcv5I3$) zM#X9hS<~XoM+B+B(xmomRV{o~RSp{)9UQ*;xGp<|DxZYuMIYRPvE$_T`uVQrtr~#r#0#GxC4<%CeIO>wV z$F+NXyemEpF5cGwY~j|^FS?9^twkywYR0Uc=73mGGsaYg4^@9i;b~X|e@WqKfV7M3 zAOg;<8~1_nxNfZ6R3K+ukG}1e8PdIPvC0rRe8$H(1p>#5&m=xP^o$2|ar!XIxmUh%cJi*hT%86+xWQAry|(k;(6&oaIgr(J!L9_4X&cA8%zbT z0pKn;6~M+q2}F+CxZi;^slKeYRIa6q;kePR7$cB59(=}v4FxjCjnDMVXiJwwa9_P$ zgpJ%2S{A~`Y~;Q(buY=^<92#dmT3@(g0?`?xcV7SdrRSJfVkP0R9fECk&q>>xw|&D z!qw=WyAXw|!6kMt3R~f7+8C+$t#CEGv#uK3@ivx3)c|qF+=^F2#Rt806t4z|0z?2gLvOh&nhixEkcx zEg|zn!3}!Fkbtf+TXa_KJqmPqIN>)7z7fCXV{~VH9%B1M+*2&VbO>j zwdYK%BOoAbxI(X%fzB~=JQJT6s>W>3nFR@|#%#}-=%0`^<|4oBD);L*>{G}QqL<{F z$_I)N1-fY~p<5ty+>8u=e5pNGB1%E%7}lA#s@ohY#;gk|fD=(58{E8C*C|DTY}!hQ zA0XR^ACbITTM2>8lf@-u`BMs8gWLHd04c|^TQ<)NU`uNu`##|)ZCl1wUJJ#D(yfY6 z!`u5a2n)Wmgj%MIh?+`bAp(rZs}#wIp;6bx$SgtFEZY*mJU}2HgVwka-SYr4ogKxU zZrh5JK2y+3s?h4c7pHO5PCMfTM-0=iXiPz%nCxQr^oiz`dRw}OQB#YbQQ#OLdkE2h z!O6txLR`wGAT>Z#!%c3bZD&wHpO`&%PuFKth#H6%Xi~yy27yEpf;us&#YxaXs1vhd z&f{=qP$yeqlRx~+s2}0CxXcp~k-*6kS`&&Ao)MSsiUaYqv=pTViV|8d zaMrZ=%*f2JDBnuNopMRU1sW66h@#X$V?z5L=o5o^0r41KicC!%3g<_GYJj*3mjc!F z=QhNmMa>FW1;f*WHRt4Mfa_hi2pZTgNrF)4k8*R$eB?I7aKk8y+Ft#2t-91jV;fbyg|j_!;D$s-cB?=ef$qHdtC0LO@DnWK0$6bW%M zidO@b5Oxe0-Py#&LY_PkW91<5zzD+1Db1C`bF{5w)Lb}f1A8RmbQG|rmn>0GDK1X9 z1OU0_$DIrV)-V<4PXTL)I2DOdz9WiQ14Io2Q~l#&t^nJG(#i+R{4}!sk^zP8(&4N?38nedoURL$P}~Yd8k9i% zp`*6Efc!}X=$)!?HT{OEtI}RAJ&|#Uuq`9gL;F8yHQzF#cr`sP>c4)&K7lBPO^=5v z&kew}dxD-6s24w5CEXX^D*{7=}5gKt|0tVM>tOqzSQPsp$24o*0E_SB{5HBfA9ga{`Gchngr??d%BHuVv zDOHF^o_hAlv@j@HNM!o~s_7Ld=u{)aP3e2Y1tP`Oh!zK&!#qPD@;DpvhemB_$;HWx z>gKk>kg*Sl@;kk{D-tUag{xuJ1W3(zdU1S9wM8puFV+`_!9J@=v zsA5E%0VhWw=qRS=%*6;cR6o*aUW#DDM_LfJZ!7m18UK1KnK_ocrjeaxM2hw-mb0UH zHIP5@oU~;91LAgA$JNs_OYTSQ+lJ{c6pGovZDho3T{s8gj=d#m4;>{>6xe71Seb#g z0@eVLfdUG}U4T}49OkGoS8}`+u?Fe7lD8t(@EIf9wX@T+H|+;Rl<-l&n%+*jy0$Dt znh}Mkfnbw+!I2Opki4bvGe5dRZ`AsM3HAuJL)MsX4$TGBZ@r3dLKf(N;e&6@w|kTE7kt%H|+Bd zo}ttres8~;s|8VW&6^>a@qlQbffJH$M8*%Ckf^=JeMa$U*a=IJ?T)I0FPxc7BbvyY zT$}YR0mBV=%U--rx6Fb~+G0dBXd5qfszsd)L(i}!oW0}9v5p`QHpn(|WKZO{Ma9*c zA}SS1f(cOYnchpjq+nBDh`uAK+(OAP^^+jH%{S8tQG4hm-?3^-L_Lw2hG5Me|1?4xML2cYV2iYJG^yT5dKMEAbZr+RTSW&*Mi zozG~x0YXaAeKC_}_2p;Wjw%a2oo?2>L|@Z64DIC8{ltsxC-y0X%{wwr!5q(JdpHsj z&G93M0EM9e;K~^aL&HZ(5R%5>D8DeP^PQ6UW>mHA2w$e1y$f+u4Mm~>qAeZ`-OC%5R2soq{lJ{gjLgHkAlHmEj*H&sjxFZJhjZ}7M@;8Vd^HY=rdExRM;6H zo+hTk&Jgii3QY~f^W&1?uXo?rqK&$Ggox)fjm&J;V6rBk?!K{7ASgS_w<4^ry+*fE zxs2G&h^lx=ot|&?Ajegq{4Rx^d4FlUZu-rR0?)8vgzU$4<7mq=KQBKcK!InNj4Eqa zS542HDlcIneyfX6_nr#f{_=Jr(ukqPqPKWIFpRsca5SBw&w5YcXn=SGZ-t}jy{D^h zg`)xDsdpDnOYg)N-4W+2v1d zTAb!KL8~_>#{?}-7PK^YZ=p`yn?>dfngJ6g9ub9(0Fk6Op@r z+ct;#dJ}uO%%Ry5antZ8dx$nA9EC)BdSHK<{M=sFyO(IPkftn`jC?MMw$8c=d$&C_ zJ6e)7n~#Icm(APhEE~Oj_mvBM@c}?`Xsh4jV3K49Y|qd|%WnP@R?YfyECCRA+URpT!%hvvNMD z`AH{?lNox+;MYdZ51={Ax*E4*uO_#Q?s{0=UK#DCqH~fqVps2L*efF*PLP<5i%NAm z3Nk}immY*?*WIUp(46Jbb)V_yTS3!XcRZE?g;}}>^pWXgyFd20jX+{nzAuhVLWC9E zGqZ0QoEv41gt$BQngwJ})o*_?-R`9_w7B5`VRyXSUx?1KJGPNJ-i(@lz0;sDOBXFi zbt@2pF<9Yt1bwb+$D9*~a)oNx1^0I8q$H9Qh&>1I9 zGsn*`0z3^mn%E#Gi_rp`Pg_BbU3RzMl3Y>EA^ET0uumW|LNfqY(|hWr^g7-`WQ2y{ zOfx?ad0_hzPl4*}T5_h=R)6SdjV8KkgiAe5eH!BsnWdBc^2|EuWV~_;4awPEDj4zSJW}OFj^Hz@y7~bRIF%6wU8Qp}Rn{R+n$%2?ON# z-lxaa8H!|i9L=i?@q^bT@dDA>>U+krSwOUwS^=kK+BsX{8c(^1F6Wh#We%dXjMunx z6amrNCO|_Nnzd9C+;IW|!q|*Ee(qDQSwu8sAX-bAiXBHPh}N=p_PigL`~JO|PeeEK zeX*@T#+LCn!F&DIRy509Z+;v$edi1msuyOngp+dQVxo#9dj^$ijQ$z95Th=4!(Xtj=h&u#ntqJou6;xY2smPJ2=P~g> zdRD?Rj*w9xJ*!ZZalVE0tYmI1(M%*^u|3r1E5^CD6%d+LC`#X6Es&Z`>`Yh9Opx=K zzM(Z6T~Rx(e1|aH=DuN}Tz$(?&7*5hBr>;37#koIBC^K?+Om@Q>Lzv2mW|xEI61Us zCBfFxDV8qH5!pc`_}4O^mM+clW`e44DX4jg7cazRDN+H^mW}re z?*O4L%Yg6qS}71pGCYn7T%b2g5zt4{83l5)!+ax{{m?G3=DZlm9 z^z`GH=1L)gRAfz@=?vp@vb_EgOu&Gb6)d_mCYS2vI(32%iz%v1k0j-V@ zm{pF8nHL0RhfB4cnm` zl_9X|;`UR9O1o{W?gT^?mMa?2okbfz_g?jqrXi8(bmWWAOH+PkxyEwnwImDsUaQit zV=0`B<+Pr7f%y##7*F^P#{KOUto!Q65lmQjUcI#=>Kza5@ zd$#&&PZg^vt~uj32yk5UjC=s9n;fD;cXqj$E<>B5$(VMOUy6IeAd9qByLponY}3lHBp#GbFI z1A?_z)!d(2qR$B-R3J~ANIE)iUP;6g^gLEP&2=V-(Zu5$}L7cW*>(wLtEOEDMBZD|?#HBrY&vxIx)9N`N@8awQaac^DM3%ojKcY;kI!7j^U-GB-$Bo6{XO4(CDzpSiYzWsxmDrE;J*)ZOuivmw zAQIsq;*>TmoD^YIl~t*5P^eXH+@!*Bqk|V{)YkK@9If7P8Y4iod54pc2nTO;tGybp z*CAak29T&#jaBbNce4@iRnoRxW7!7-xi#juB*Fp2E!d8@TaDWeG-|66_XIgZt1XP! zj(2z1P_3Q&+qb#|H-J>X)ydszj`Sf>Tb%9)kO=IWq@h{6+z&KeK(ux^nWQUM{Ts=> zK%=%;W>+i>BDIO+E>;MHL*P~Iquel~Zu23*jdD*Zpi`UJ?%G#w=|+?rinKtv)-P%8 z*~4bKS~5KhscTRN*xAvIx^i#60ZC;vKXcsS<6#IL+B(0bJf)?PASDD6HMaYac4MCm zCnHnc75ahVZ2R*@M=8*oEiR;+YJUI7N|CGotV?ol`qDo!jJtVUF?Z6&J!F5`^Y1F= zWp^H0iMARG8Wd@7%L!<1xag}uezvY}9eqhWt6bj(AnDfAAD`l7Z-}gSuW`5bhXY}O#hy-{a@P^3+uo91W6 zC6e1;w>>Y$uL1$ugeX~lX1_@5MMTWjP3JD$(mL4kvMM*sL4g2mLWPTNLVz}$)wO== zD^90?CSq1&s)qn=cga1*pyoEdmHbRMXPo7M9QTUm3_6%deKJ#=t=g$Mn}Gstb1&75 z0|nY|o%AF?&i1cY_)7mh7C%dd7AVao#Fu&rlxC|taWN8$U(Dk`ZoExD^9r!4?gy#a zzP=;-Be5ZK8}Qrt8?*(nI0Iqqfg=*)Ke%n)QoJ7v;(b*keq$e4R(+l zBf-zeZGp>*zcp^2t5cpP+u5g|Zlhm`o&-c_Z>Wmq@%J736cPrmDwFh9xq;Wp8P9EF z%}r3IE#Ky^GwO{Q?o5w*8`+c3NC?+ki3m%WF`!BuNCtqH<5OH+IR-nY+E{wW+HoY;*YtFx z$-z;)gPiY+-5Hmuc(9#$M?jEeR^)IA1^Tq1=`SQBU_0gWVP;G!RiRfqz0cs+{$onAxC0p7w?&Hu zs)?%WcXz8vMRXT>2V=Jajs1+KrcXOc}j(WMW`_gEaC%6Jfztrj(LBa-)s-433-zs^`ORbu} zzV1#!^)>djW4fD+eeIZ!dcim!i6b@j%zWzTht)O$THGC5>?c- zJiDp#O1GHfBL_yx&77{BnLFaNWc#?qRWbKR!oYcAn#X2opJ!C4!`66}=&h9# z4m;}-*(Y>NSR1c{Ni z`K@uyn4T-4e9!LP(!KYJ!Dp*bP-k;0`F*XJe&yJT`Q)ART%z36F;2NvvsKDdKkB<- zfk?ZUzbTQ@o*~?WX(A}O`mglGWk%2 zpF?|ZOSm~aM)F9pQTmbPv(hyqmD7c^YvL_N`Xy1@Zw;I5ZIvMsmY`l+o)@)O<=~(` zyiXG>j^$g}hJfR`c_ni$@7qF(yppr&`U32goGI_uZ`dc0dIKk`l6kyVzbD-4TjnKhrmp)bMn#D2<+HRwaN3dg_%Z>)Z6xo*4>A`+(XsGQXXy=>kpW7&mi z32D!*91YNtgLP-7`F!I}Q*@8~4m8_3!|{rw;ooLEcw&}!qY;rrIUK63_6iXEXoR%o zEyQwLw*7JAWc#IaW6sVNBzr`6B*_%1sr2z~N9AJm)e67XJ2U88z2%g07)YZW|Fn^C zrNaBTO&KKNf>$c5$92Iw;R^rWH05bQc9wFLvY*RGG|R)eIL1y*>JXGoQ#!oRPYeTZ z)Vrl{LiO4@#mC|5?2hE2>G*>QzFQ$No4W8T_Fj%J1(7%zcmf>j#+>zV9@}Jcn!>|- zyBYBWIA1Y^YYh^H;^8svzFe&ARN+pZIF`%Lyq0z?XYfEz{8RDCGP9ug*EJftTSJ}g zTTRX7=DlNK?rY_Dcbv!UWT&#`F%#Ko%=KJn8h5T`59WkGuJqscXjU?--E)bygB-V< z=j#4|IO)Z4}$S0~=kcQQNu5_Hd-$E$tJMMRc8OFYk? zto9>~d=glAWcfP##cci7`S8p%XMi}LFcn-+iVubuJFhUsnp=d_>o&6eOuM@mRVt9Q zaZ>Kr2CUrRB39fmw%?l9mR+3k`sPwlAut=Ci(=$_WFyB$$2GAYYoJmo<@R?CbY3@$ z?XL%kNmDh7i){1Tg23BvF;^zXtTZ1Y%)ch;%}yj*XS zTIt&J#uEV?JNo-ewYYNZcv^8SF-{^u+I1k%x2x|Qft{})If%$h<2K&oPe~w)O)g+v zZmFRL?bwh@XZT$E{VYMQ{hmO3?s2_K*mP|-@6O)Fr6c+Lyi`pqJ}%3~W?e55J~I9FeH&N>ZT5W5^@>{ib8XfJik&|*1@khm zUn&;~i#5<+< z3LMWz;#SKBz$ksOUFoe+u7z5R6ql$|J6dI-DI2nOoQ{2;bNQ9X$+3jLJ}&oeerw(a z^-JqTz10iGzSP@IGxn=Jon_xhx(trj(8ssR(ABl~V$FK1M@AD|dB5h~79{Lj90m8} z!$DMrIX=FRM(DW3jG*e8%k0e520+|-Js{@3o!xaj9D;LZh|{P1ygfweCm_vl=< z50;g2wV&(d=oxQ6w|(6!cCo{3mSx5s39(D_1m5Zsvt4^8R&6* zkrf7dvLgdg`L$@T8y4d(BDhnU@h)KeK)?;`Z#zmQ<={$+nj@zm@03 zh)a-f{IWt9W`;B9T>U5Z38dZzJx)6&>&)7%y!fSB6iCdQL%_K9UrqkaQf@CY)JiPY zuTSmU$eL^+I-5;Iok7+&0^H<>_YH~7TEQS|t1o_efst;LQ6+S#hfMewGBin>HBf43&trTA}udTh#iS<%@9TRJ7+$74a0qd7?OgvKQ z7HxwKO!g**vs->fUAYZ&s$r{8YuUuc>fS8c#%;JN2l^h&j(%-3gkcuZTI|v{)t&?4 zk)NUmJs+`L8?&a5^y>5ek#6068hp*~kd#Wr^oyL>1C+f!Trpu~kgp0o82zt|L(=zfGPHOQU6X^_vQtPdr*#9kYyaENI32a; z^Jn?<-~96*P}^vQw?eBf)LjG?T26Dgm0$ig;84YVeQ(p+Iq7d8 z{ay|Go{mgT&-kA93rR{e_LjemB&DC}FyDXvhd(MEbG~rMUwtiGIEaPx=htNN|Ni?w z{^hIT|HB{u&sQD)$sVBp{BNIs{&#=*MD*0nxg2-FqKIi?)Lenw!FBZeQ%2sON`<_hx>fYAKJ~NI?@!@^*!cETkoTvO{@<>zx0e3Bf`4WQFZ@j8 zZx`h6H`b(ReErWf*85X`zp=hO^>-WV+f#qHvEHBh`;GPf)bBO%LY|Xh`m_7JcgWXM zKfB+1hkSeLNB4X0kZ(`@=zi}V^7Yj3-Q$J4p1R%RUs*rqp9gat=B|JG`WFv;@%XQO z1bmpk_BWX9{##6PU(Y^&PCN^WJ-@bi{{$I;^R?9c<$wR<-~PjY^^gCA*mKV~|M1`Z zH_}2#t5W{v5PBQGe(HVv{*CVCr~Y&KQVfBAea6UB|N4xP zr{2H#udI5!DDl4RA*k?I5wNR4R?rjvsXl1E=TF_iLv#L9A;h;|==1x!$Pnmb{|O)L z#(Lvkw-M;tW>B5H{|Tq;!tJBByM@R!0w=6SWDg-YS(!uzcgcok^8(D~@Cr|T^kDi4u5^cGHTogW$tu-(P4<21f@yN~`pcmSvEu1eYH)2FTN zSNGpdhHvd`n*g4LYG zbE=W;LKd23xwB;hbZk&`TH{+ zXz=c;4!~grWIu;rcSnL2`57!|S3z+v^yxy1(xK}!8_$ox-%3TFJb$1Vdv%|s;S&*7 zR#TR1)u$#af$2;=gQJq|h7dwGX8;emTcbL;UV5h1fuGpd(4%Czvq+l)MCQj!s*innTy8D+Vkd1i5M!LLuH44(iEimHUqhrcvwHUyyN ztegP;`UhgHES9slHz6{@oSn}Uwga}&YEBsCg&@?ray%X(P?6EM9-i3%Npq^ZBgV>l zlw*-8#BLZYr^Rs?bD71gEG`fzT`0@FRwJh?JN409hZ6;7LH0m~{vAc>&mpZLPKoZ;eKMDe=vqeS97^s^w3pvRjvt$1@hdo8`#r}1Xpu~c~yn&s+SN_ z#IrE_G9so_a)Tk7Y~M0YvW13De7kz;>*fT*gD7mrsFOyzMgoi4=5n_5Q8J;JL@m$RsHAWlxA zhATmO1_G4*8!}APAnwPMq@^01EC)1X3xf_2_!j`gthnHlwMTF6xH&EphAOA$FM96dlF>Z}&k@`dOq z!)2J7+aNUV9E&jlImxk+W#$FDn({-BDrQ-!9JfN@LidGWK)KR~N|mKcIl-%ss#hEk zp;AbpAuGD|MiYgG`=mw{mZPd?#KI66MXmDs&M=35Sb8AvrqcBH_?dNECCCp_0(w)$?b7ZQ!{Yf)KeTtTBlz>klGD>$L9});e zMj?YnJy>$=C-(UVqNR{>-DwkuShba05I#kux|p;gSc(`|rn^Do`Fsry#6>A(y;U&~ zl4|&(khmdI3JDi3A^WXOM#&oFa7J7dl4_1z#6&47wVsEIz&vj=I%1@VI~UJBh>;@h zoFx-cQJNQzAe}r1d21Ylh>Ak)jO)-P2+7tPGEJT_rdbX2Zl7=K$)H<;#_8bb7{!Y* zT#5ayqt?ZE;YvDmdzaZ^{&iynt+%Q`02^rI2eOUd$t8 zs3}pZEo7=G(PyX9`C5;k^%_wCPV3*Yv)z>2OU__uHg!mmL4-viu|k(n!Z@w#>U_)3 zR1qr_i#v26WL9`f{Si9jQ(xz-hOj6t!`Y7v5vy12v?=n;0n?4ZhQ>Kb-(KQY5KKNw zcyn@McQkU)B78*O?wV~`TimMwA$LaOb@@gA#J1bzZXEquuL5f+7P8i+<>-(p<&6emE0MR_vRS`h5kSq41= z;|Y86@~#wNQAoK^EHWB|MQN@vt%(SWQe4m%Le2%GE1fRRg|Dk|1|3)4G6+fXsn!xZ zKv)z~E@bc``4gr6Bkrw1%ySZM_Ja+5MfcC6tpiRBwerq zX!!AL8Pzj0v|vDCL6>0F)oO|pIAwXIjbT4=LB$-$YPUr_`6HT}d$&Ih1BzSJ69fz> z-wO%@iYGa3|A)WI&RmtBeVbI)h`~8%e?yK~G;_#4XO?tqkl_gYfqjiYZnM}rQ>~0m z>hrBSumO40UMjmyYD`5v9(EGe&&)apqfuQ%G+WZ(r%!v9g8{{DtnD=rk~dV!P$9P4 zcxI}G1%*Y2>momea3V`Rj88D&2)-2SD-bMkctTry#7fyNWu-v?u~J0fCJ&r}bka1Y zs|5*i<}RjtH|!@MaCAT2MvyO74)?$amO@(n_AM>`>=?@6A-`tpv0orEibrUpMP)LO zTVbg*T_IG8_}lQrgUBc(+CZ2vBBQk3h_tPQyNLD|qES2<^i8$%C}F*>s?bZ*3~rJB z0r5Tn?fWPhjSUX;W#G1ES29`RmpeNmr3|Gzl?tpUOJh&`Xfhs<`xbk4nn?@~C)R4p z;gtrFQb^TSjFOYl-Kr2(3_SE$#@AcRTy1)nK6wE|WmNuoXH>nh@BnM_HrRRVpNNan zTn$2g{f2%1fmkVO&DVQXlnqtEk%+h_YP%OQ#Jup4hmzfi>P^Jr} zH3GpJ zr+~Qj@)5>lKsQ&$(x--7aGH-J9?Eb*b+&+bDD8XqZ`&>Sj)-mF&W;lv7t{z0Bwf|h zIPeh=CC%07#*Ba{kreck>9wem-R&Snr3CGDxh z5FjFGBW;D~ZPi~AaNL~3Y=0_v+uNvT^m?}@9sPhLzg5E?<`JhtI|o9d(6))pkj}#Q zMtpnvJZD0de12<}F-*pW_q2$cA~NPMq6nKZwmy}Y_J_NcTW)0GzQ}yc#Ztk)e#1VA zxXzoJ7gFUexy=6vrXmL3Y?MMU6*2H;11*B7sC`?;6|~ByiX}3J@G4^9!{#`ISLrVL z(Id+Yd}dyUx#Z|2QB@#mVATcUFg?rF#cv~&n~N#Jjp!=P^BM24A-GB!_|Ud68O*J` z^)|(FdmEd0yR~n~Ff|({S(9D<`|pUWo=jZ5F$eb+l}l6K~uV!i1;yrrf8$|Lb^HhomEday@Ey*Ylb1&%6na% zc^gV}4^dO9%PE$Rs42y7X{QN992y6!91Ad@toeo@YRXV$Xxt%aN_9bn{Q3?1`~#6x z)WEOz>c@F6DMG8Pqms%{fJiE8-)@sABB?ZY?7TJ2xw=h|h@|pVWsw~lfGAgvz7R%5 zl&kx!0#Q?XKX1bqQB#VG9;AGD+-X+?fTm1LFOMFnCeS&@N6?gTF3qC|nj!|>ZE8i( z6fx*`WV@Vdz;lZUJT2%17Kg3Cw|HKll@ogGB1ONY{5NPTRaz6Gu2 z!;b{0W?jSc6vCzyH=kBTAR^J-J7@$_*)FK4E&{2Don;6w#^Ti6pze*hDPmsT)>Onz z5s4nQ{Q*&n4sT)+NoBgAMqo&BPjxzUd!C*H34Be8!;=?R10ZVA7t+k4Tk0M0+Ey1r zBMAbhghe}pkR3OR9>;)4^zfb^kyN%BrXSh2JqxF=#dvM~9qAObeCvX}ylB`Eo&1S? z5(zcajupXG=BV$(4?5)DKxl4UaJ8#oHkhG>6bLvo#4RwTc6YW>R!_=&qG9z+|s9E<>2oMo%FMSB5lExHK z#1(?um_wgBwv%;Rmk~RqocBHnaGSizp|wW`5_GSpZym@I}aRk3tFhuA5{ z1zqaydta{Yk%kCx+nX0|BM~blEqb`qMX;3WQh87#0-Q^w-hOHt)H4$dCiRU+tHRVS7iyt4$mrPTo!Gm6!cuY)<%?S7*^htdtk8K7Z;KPY9aMp%5%( zq$gLsrID(ErMLPeXyVbEF@fLbWFToObtXhh5tD9a(uj>Bf|e11*eEin4ja1>8zlry zQxgyow3%`-NR(Pnvo?aGgj;hrh1e(|W3s0rHj2oYdYKRneE#T{XuBTZ{O>Z#FoVD- z^ha2ZtcJiSYPm^bAS6`#aWeZ7F-;Yl%2MydVpGIz<%OwhG_I= zq&HbqoMXsqJ+ehV%FLuu`ekTCP?T6VWmZE_lv-meWTBu#9;U59g+Om^VXpOvi4tB$ zmV=Ne-Bv%Hcp)T;jGJ-!L`aknZNJn^%cjp+5F;f-Th<7~MCsE~W-1^u|?6{yOGl`~_L9vfoxrghDCaNO)i%o||c>NXcf*`~5!Az)WHz=I}Ga zbozx%Q>_?TH^a5ry3EqRC~|Bj(LF@iJIs{b8=!|(RJl46N1T&xb}yGc#5t+%iIvP9 zaZZZaVcr^-CiSiJx}O+sPfk=cUf}wjORD4t+<$gGC4t?o&dHzy;%e#1WhK#UWyr%6{HytmAT zeN!30wmnwd4gpT43mW8HqofD}f|p>O_>OF!g^ST3o=J{~ir~4t&rssu6Lg?LE?=!h&5SIDH;UajBPbKp=R@H8OK9I22iSm69j{SvIxG zMuu=EbJ~orm+FU4pU%=d?Vb(?>86o6SOp?G<@Vx_U?!qZI)4T-&3vb6I6{}C?X(Ia zbV>Nr@bBYOa2*9Bl!U}0*G9a^Zw370+CC^o^Cpg`_XrxnJQ&OBbLcr z?}wC#T+&@kxq2aVNww<=$H!q{HTj^p&SBzkV^$vSAeM=U@Us0KkxO#gPkx2KCE~$3 zl1Jc@$Hml!9Eh0G@ofo&GFju@^#OrP>wn^BN_9%#2((O}GG!$XtutP_Ag5>z$2=uO+-{KO6KqjJ=ah5~ak~ZHC z&JndF^hqbJh+5*IDf0?|y^5QY?J#_E=na{sPdKB{Tg(0&S)35HB=ku(jx+Wp!?Ks* zrr$D!)`0+`mJGARAjM?(z6Ggq8*X$~0_4yjTRl1{HLwZDf`+IiBr-L%4jTu{S#9G+ z&=NIg&3J&)_!1(D4@6}6g~$;Rp-NXbVCi=CQwA4B3jMqGuS;9r={wi1svJbu(uM#Pana`^5lRYEN8()PSXbPhmP@ zrX0E~r{#R;_r+r7l280hQTs}lZrERaU{>$p=(Y}u31a!^8C@QN+c7x|o%vbHn(oGX zGM(wl&h_gz48jdMg=GvIbxPa<180#w8h|D8io1z4Ng`$mTNw0s9wQ`Yu+eFygv0?T z%hz#63nHFSU>=&KDOrJ zCj@tZC{haon84{9LImA!FeDogZM_P@mEe@E$C>#5BkM}CBiC`@zE0s2_=(_rg5I~U z(Z2t-GX^lF^!uCdD5XS#QxF6L<&wxa=0R<4iNL-s_lo6`$T+h{DdP*$mB0|VI&k?J zM9uLTIq`WF7#42n0Ve|bX|FQ15}-1^TTaImPe5sM#x9ox#erz1El5~`j?V1gDh&k1 zE5D>2FcBPxHk}X>VJ6kbx2Z-1L|wfgVF~snZ5&%juZp&4EfI{nmhP!?DW48)q0B#* zG{v#7Ex(zX;=83UyIj%~=fb9BYe2S;J&d3;$m~ixgp?(?)6nvq=I0LvkqYUIZ)VzX zfrd;rd?Sj;mVufw&0W$NXLD5}3Z`#){$G%_q^e296M4B8O9o;v{jExUQl=4egF$MX z7Tf-KWv+YX9`jqMG!8&y=!JAO>GZ@zWVI(U)T9~uRgmd~O zgG!>}AX?c)8|4gvXxcBAM8!eRc8ZHoVVTcN|4O0r5d5-TI>oMt=rs}~!fP~TmP`8K zyXqXl2zq**ChrBAQE)O*mxD&iMFnvH*=Hq=b1w}f#DR?b3&aG1W}deClx1!R_3)UL zZ~3j%69(ILhmm?XfSeUZkzv9yenilSHJsh;l6d$Xs4`1f&R{c$@u%dp zNNEBKQ2GBL2or?^(?gp6i!bb0#E!}(UmlQLBe6GaH^@BodBioO=z()~~vkL5YMDsj`02wvYJwS!iNC54DmHT8uVt=C5qy_vB>^HRG1OD1e}xSy z5rsY!2vebRr>bc|QWF>l!Je1GQa&+=oJb@b&I?5g6WIisW}_n6a3H2Tg|gvzi#jFJ zoHYKeTgfkgT21_kdUBCy_y+>AMrBTYxm20!%4HCmi8R;clR_#a(p;DK0u-Su?GvH7 zGA*#vk^smW6vfl=tjNe#`(|2gsuq6jYdfMnQwYO@TglV5y+egz}10Zjp@Hk^e~^=e2mk-{_?mSvOvD8xSw6MFQ6F zKzb1^60oLEa`_nqWed^#S|nf%L{Yq@NWdC?OV_5;To=k+0YVm)35xC6;O#?K!NLuhrGtDRm!_3E|q^spf3M%_dd z2UiN^t8wCyLjg&{P~^-MjT{^+2zX&adJWbg?5d2^kz1n(@#Yx_EW@;LTL_0b-_wmCWSfW_cm=sN(DmVR>_(`=y6BK?iJ%g2 zDTSXw$Tr_&qeDouZ@x#P4B0lS0B<{xZ6g+6)FI>&jC_}Q1mlbeMZ087)ZG@2XDJG6u)<_}( zzs>U*iggnaw?ncGSZAzs10mbSYkKFowI&ZBC^KBi%D;~M8!s*mL|)v21RR5acUI6x zWsxo2UyyBsB~F>Gf@~WX>e;^YH(J!OGP-+VdtdoTwga~Jjjzd}*hsg5tbB&j^g!JC z8};MwU!u1OfMRS4Qf;)wZ-@Ip$4#rR#qdM@3Tm)lP)P2s^$XaWKk|kRxi{FFDXdeF zX=CsayCjilgO-UiP4ywugu`$OGHuW_;pICs{uwfQg)*tuLfub zf-3#>QPgxdBxH*ewJ4A~#ww22<(svN_x=7=hb?;Eru_MYeg*9NLj~D4UW0e_ypdXv zYy+LW9|sPSZGfir9#sn*~WT(2sjR!xJ;x<}=;} zAdSY-uX2i>^d}MV*khOm-{ZbBnJfV@EHgjFgwD(J!eq*7{=28}rS-UHm`Xv04760w z@QH#98EC2AoPHa?)+2UJ1SPv(NIg@K^tcu|wO`X^hw$NlL52)4M0lNSy`}Fc?i7E5 zI76GxvmtiyRlks#)>ezW`{!mDHa_efAM#^hIqvV}co$iv9OHrycfH3G$)@j!5kl^1 zo4z9;?)baQFjwxVfS}b7n&g!V8NFUDi~H%_$Rtx~?{yTKTm*K0iOCl6nr!OL`5%bO zha?)a`WXR*O^Mx*Iwvw_fIs-s8Ielr-0~VY5wvAniUcjlp#drgKf2f|l4xK#ZZjuq zq|B(Qg6B1)%m8z4(>Gjy{$SAKzO+cUk>eQ%UX;qI1$i~l%b94J#y}PgaEg{{fdv^e zK&auy*JctKGe8hqUQi~oRMVQjs;b7wl?oX%XtC~-^nwH#;8*Q9nyNA*0}siC$;deM6r{&^^*|gCXmJC;_BmD^O*(WvU3Is)2=3=4^JyB5RTF$3Hru2lznJzm$K zCmKS$VT7LOCB#&ta?eD>8_%jsnh2G)7pCf_01#J;Hzf387YAW$e8Oz0@?twxgnd2? zfl=xTC-a7MD2x*s_gL!Gf__65a|SZD+mjw-kGh`mdnlHq7kl7P2Jj0}+mazy4yTUA|BQ7aF4Q7b4V8%Mvt1!{1m3VY^;= zvH?|55Vf+CO+!@_?RrO=ta9bC7&JuL>5oSS$W{d}e`}7il4t@!8{#Dz6A%;yNxLJ#(psN_2rtCp)<(%^8d)0XiL4I@RWRpNW6fCVAqS=%f7)AExxbe@COK)RxX?!M&63nKAdn(?9Lnsst z309WRFt{5RV7%{zP$)RaHIo(YddB zt}}mPzd~TFtEImcf}$YdSI_W>#>wu1ATx_T=6+SV%0u)``=D0!r^he^MQ42?m3$JR zzB(j=d?*Opbq>@aA8KRm{P2*m9tezuTh5n%#k_dDW8@bv8Ed~kzS*`n1gvKB`#K>!P!Gj^3SVkQI{6O|qH-_Qp znJ_|C_XnaA4eSB@D|k9o;(QO(%vEBscnE>=<9Yjm$kH<=ypRSRM%=o+tDY-QY#{_1 zDzXpdAq0B4)2;;Ei_LVP0?LMY8xXz^^;)wSh<>^srv(So9kN^01eO}lXMWHHl_k7( zLKd{k5_Szj1=L;g{HVLj=71SPws|17P4>3IY=`)ik5eE6TE`P%wnOwtc`SbZU>JCl z84%fTJ@3LBvL0WX%yx(p`E(5Op`aF*1AR-Qf7Sy+Kx0S7F{;}WmpceJimc%_ikefl zLAa-QFORg9v_>T4K-I7X==LRi@5~?q8gl@_IHaDp$~H?=DbBBEf?#iGIlwg#)+Azk^SfSC0|RkV9PE`CiXiN4mc26&6=Zqf#1 zd(O^h=*ROF7y|2C9Vax8LP4~v6Nn8!K(rDF|IOTnT-05-U~WS${Q3&~C5?a&F`*v{ z8cM{kX*A4L(@g;VQ1b`-RDh5_MAAnnio!BiWE>L&MA^R8aVF3Y1=+glX_e4v1$vb0 zR4=~6J~POP;@?YBPN<2#$QEu$OVzbNI}~K=I$zDL= zKu(loD>b(Z#6w9S4*Q0BXw|Pw{yKyF^z{S0EHjzW*G2YUi-7ta z^td*EVebx*S9Rw;3onF2U&X|2a=V%!6Z)c7laqzt!ys5ZqsbdGp|5{J;nFfqzPszn zs7?rnuEuA)h(b8@)$IIu$xKR53}db_E_UvD+Ol&|=cRa0CLK-J&&MIs^#rh@1IU>L zG3BbH2To^B1}1*=N9fDLBiW-n<*6PB*gFeykcpdxl7%HNDJpg1yV4bvvK`}J+)?on2GQKD{;O{_;tN6<@3~n^U6Jek%-YebF z0>Mz4<~VO57<#o&WXTdfE{BBZ7<`X+KoAVIZM^q|VrU&Kp${ja7v?Wrdc=Yk3`)q7a*$8^F7&Pl~;n_(&0~MiXeSU;~T17>c(C+R+n+cF(9t063A5p z9+Dt(K0UuZIvi99anPzZm%HQV4~Aj4=*eRN-80r!|8L31AR+2Dmb6@fWN6pGvhNI% zp={&RS_pQUYOPTc+3MR4A%ceJ{6MQY zKtgm>&Ptw(2WLkj-mgG0H2M<>8Rr}lK{0g9CqlQ~dq!bWR!xcCT0$R`4Z5@I0NMPF zUA}|+9U?yOgFa~2kIXor4_dWSxlckLw5Sf|ln@BL^o-A>fh;W!S^}XM+O>Q*yk;oT zIX|Vb2ZR*zT?eJaoR(rGGGvNWo-R-XZCbl({%VO|UrEy;30nAZAL#=iy)L=8gdXVd zawZxFJ$7@6AGFSg)nkfd9B&_x z{edj)J<5BiePF*pHW`^djo1*847)7`9py5Otq1X~#%DZHLHU#1xn^KFlt0OxPf#Eb zSKA9Iv_OYi(?NDn{%re+Y;oteDUjSv_SEV>nA`1%6!GK}e+VhiF2?BH@KEA%R%`iJ zyq7{YrSOZP#N|Xh9+bHJflO^AB16fb^cnh zq~i~wo>i61p*f2BY?wuip^lYp0tqd4@*Hxw-zZw_&CFmPHw^?&NW*Tm>r7F@ZnY~z z)qyM__Lo58)3i9UEKB?#HQ5U!J!5DB_pc_s#y92xWQiVb8)6o5r_2KI^9RGA!?jjT zKprp%Xj7SW7Q$x<>vjNG_}Mev*K%uPW3ZU>`UzUP<6Qr(gJL!)4 zf_&L2;goSok^v}x1_58Xfbb`+Q!-R^GKm|D<8>5LpyW>P0+u54gd6YY4~BHuCB&zS zPa7ulx;=oZ2EOtlDAYkoDz0>>LkqO&M-qW5lWE(0_Bx%VY{SBJQM60tLTX82|)e3-BBcZP3|SV0Co}fp*o}ju!}lR@Kt+4iEwb z;X-6p--&=5uj5>UH0X;z0LiYyEN(>R_O}+u@md*m1s%|MR!W&;@o}Gf1EFbd2$ylZ z$8i%70`1{X>CJG8bRv$?oy_D$#9J*OyAkoh+his;RYKF`Waz=yT<4A?lt4kbfLulx z!}NG&rFlF7LmbrRFUPszOoDbPW{`#wm4)~auJ|AzN~=E=`VWOpKF1rP_FYEQ?Z zLL8JWJae}*na54flMbz@m_pusgVR60+skn!q7yh(>Ns7>SRB@hDb z>H!WOfe>g_$Ic}KQsruJA2P$8h(B{WhKiTU;_^=39HJTg16~{gaDFprmm7c&KCC-u zTE^vAbb3Kf!c!=`8|#Lk=k2P}>Hr*Fk1msg;CHx9sm_=~6?#+UF*caIOzq+hK}w`f zqtQzer)SK}xvB8TYyucZix-;*aq~1dBYN=ykDr=+JvMk0p-Sw0rgP<7hi$G)KQTe& zVL^E!TlLOtL#oWcMdR z_c_GJRnD_0$@Lk#iI;$XKhkZnXGhT$YyF1(~L%%y4p>3$}}eM`23HseoVYgJrw z0U|JGs$sn0bdb;k8JcHzu8N3s3iAVTHy~Ri#|J}*k6Pjf+2q)H%NA)t$YYl$Qsn-; za@sSv`daNcc?EO09NL5G2@G{g?h`AKwTvcl?z6jL~Rom0| z(w?4%=m%M15sR zeb~~A@n=8Bo<2U2EykFAO?!IwSp!|=jl9sq+XSkUC-kK~J!`4OgBKT6%bL&Fi+)bg zmNxbLmH3t}WVosH^-*M-qmIGLDYAs8bs+Zq+u6;lCr_Y#YbWOAWoci3+pX!Yk8C~? z*cuz2c*m4!GPny@h-@0KqPW0Rwe_)M3fG>z<#Qw*Z%;i-hYh?AO-wv-nX3!Q-Z$+* zuemwHJ+XKK{cQR?iOzmDeai>G9~j16ZtH7uNZ$IZ?rpOAT(VbYzbH%F`rDqEcMi3u zGc#G<)`OY5+b;RgF}b-tv9H&}wenYXqM!TuEBEy+iQMwO{#+*Ewb*j+{%gqVU(ckD z)mfu8f8%X^ISc2q5544dEZo`6eV`{hEH`R(M|-c_*4OmB<8t!V?_24W+xj?0-u9}O z+<@cac6$O{wmHlbx4(Uclyl^kSN%P#ysxj`zCqQpYmDd8zqd>i$>%KkTxv4+5T_^#dm22fQ)0W9kFP(=( zUN3^Qz@_FkbJ_}Odk^US-qL$0LiwP3Y11sQ-`jUbGD5!LavvTCSz5AJzPV*ndUpv; zil&y+$^OqD>=(#LFNkl2LII=5JaGUo;%b*d4?91V$j1i-uCZXKRP-BTDQW9p~`4v=S#(E-4#yO;7 z$6463Pa-0{+($5wt(w|X41Js_YuFbCm7cCq?)@*+f9eO)MBNT21Y&Nv{76rq$H?Mn zSHI7t+U;HazH&nhJ)@$EdK7t64?qhegq+OWG(4gGG)!1D+imaZZ%u%yp=S~lR9+b`h1LOZ|UET zI;hJP^<>}e+a8NK;b`}M>sh@fOS7XLVtKWB0Q;>y4I|3<^9RGg!(~VJ0I??^OK-C0 z2?~G1ecd+hOTGWf4H9GlA^qtoCh{H~-qy2+ z8nM4#6`K2ST2GM6zWN(dvfpPLAU&BYBrXpb%-o;2RiMf(Gk7Bbg-iRR9TEVAOI67S zQG0ny=pRhcvE#LcmSubJ6i8RP$|hDoOt0P2+g|u`mIbty%5UNc>B?A7q#brG4g$or z_Jn|lh{xaKTb7eR#?L2&@wV-hkEGj>vNXH)F)ySnO|RvhiOar^9gfcpXjgi{6w?Zb zSC$W?ihG65k^Pxt^$i;1XL)qnu+w}#M}AKA$$ zeQo6f`h5Y73LVp#i}9;Q$2s??J%McBL?T&~9NYn!%5LLKHA8D^;2YA#qN+F(0dFGY zV~mT!s?X9)k<4*y+~hgGBU>!0pMlnPT5Gw*`<3SEo(MW!=O^MVAWYd*^Xg#*A#K+@ zjI`|iTJ?!6_w}J_^{ygkXkS2`vdI=Y84svahFlIgeRO%xk+{*b8C)Vd(vE!d7B6nu z!sAkNX10O2m~#C~d6bOUWtV9diEOobchgXe%Vl^?VP!BC4lWw180MrDulcp()S%+2g;ENT1hv zPnExS95bSj%>8976v=x%`=b4Gdws+?bSk&C?k9+0UVLbSICh*Bz2 zMUqHSu9Z>IHZw#ii=&`5hRfwR);JX{SGqyu;|M5KI#NY(jsacD>d4kas%TZp@e!JMaS5eKbI(a;eFS6McPRzd*J~as~~^1$Azj(KS0mXk?3J52Iw4ePYe{R4$WnZj zyC9@19oH{v2%$=QEUT*?JB{VpwbUz}(%TJOuM9=<2rbpCcP6TQA(0K7KdR}Lb`@&N zz#bE?QhRzVm&ZfxX`AT|2;FQWHV$;NU90e~)-jHa4&CfD#X%gVm7Ns2*($J$)9jh+ z-+my(%`zF-3#sB}nLvujR<+Fn3mhIorhzWrnmUFrWTa_^y8se~sW7@#M8sWR(-M?H z9m0Knv_;L%GFZA-?kNGBfDEWZ@&OCSsD2qj{cH+W`C<>cY8FtRf1QViy4&(77K|)MB{I&ZwY(o@aO%dX`ut z8ABRpjjX4)KaltwZU@i#%bv99_~~uw4WC(P+qOLjwI>Q4( z8w?0^UibaZ&mZhp$Xa)EK*lraa3VeFu)@UyqMhb*>Xy*#ERWU+-oU>voRIOH=2+@J zkn!w#k1k^dR69*3hbx9lq3u2?0@)sIYE$TVno)Uqg^p+cK-#$zrv`&=XAw6l`K=*F zmAUVTc%~Zu(acsp$WoCr8(2WN(;QHX3UoWKKgjl-s3DU^$++mWMT8nTm1F|Soo-|u z#RgP5%lJgLDVF*!bUV!f&(}vX;-1gUXSi}ernBt(JQ(p9#Zc{BkLfk4PZ*XD%K{>u z%~u4qae_#v334`Gt>AIQw+)PWxn^C$C9 z$adN|Id1Cqp}yBfXmnQ3xm^`)Mf@pml|@KWOB3Nr#Fs)9yZZA7!|-cWoN6T-f^=u~ z&8gvc_oRWEV*!{rn0rIZb0(GW=VvzYLCo{V`^ECnogHiR>+8nEq2#&Lo;ef1_YqH| zib1{YM?u6-#A}}?b0~LCPu-ph`Vb#pxlMvjXXrAR325|{*9NoiK>l(*ku45&_#3o5 z&7r&&L%FlM&9&S>xidUM{G%%VF;CYSRV?cEqb3%0Lwd5PH2N4~#7;>UQ0ctxHwB0+ z57_NzR^A3n>p*8**72SwsCz5K9d4EnLJY*)!JIm0m^DelB%tIei|%})WqW#48BD1B zbuLj5*y^*F`|KQP8!v0n`t+qnZ)PCvS@SN2k)5o`du||G<+B4Ff}hi~w!8um{2bm1 zcq%~FFxA_AU{$fEWry6)9}Ghea$0(iC$!ZLlTx)-*G0n2n;Vb-HOchW9h#peQmz96 zG3(0nyLP{cR=S9fSub zR6yOn?iJAd^i@cmK?g)XL-#pNNFe%Y+hukLeAfA}MX5RyKVuI9pO^Qmn(3>Aw76;1 zvRsvwSa#Yend zf-dM#O}+Dh3TV@!cKJsT8;|>x3>i@KH4O*=>8|u^YNR_lfhxAvl9EFPw5CJMuj%qu zj&%0|@l`y<*9Me9&1JJES4SV`Foz7NxucCGF|FG{Ms3&E%_#~|(0RYy9}opK^|lKL z8ld)cnGQe$)Lczh`HAeu1`Dd7=4v{<4yc0Kk((W-4YlRl5N+nIyOD2R$J)fz0>8^MV>g~8PRTiWXb1glD zx_xu!ue@*PM(d6-wxsC<_F7?z`?hw>ni9a>}V=MRPvHflPi z&4QrxX|JU>{80Kd?^Z5rBIZ|@&mOL?|NKMmV!G6oN(bmp%npqN9Gr82VDJEu@1j~O zm6iiAo(rH6!ATN z^HR#_wUdU#}SPQ-c{fpJiM3d}btY&q8Vh5A8v{tfzxt8*| zvwyjkWJl;<&6UhAX%EWRaDbvmU3_tM69QQwL@^!cWsnZSuXLb~UWRFx2>oK{Wyt%q zGPDz&j7gDK-h>Cje8RY!)bt}=Fz2t-3PVYeSH^gwhcTTnQ=mVe>^GeNc~yHP zpd^di?ko<636x}m)y#ATP?E*cOZ)jfQub!8)K-wXXFXHX2wJj@70sLP(2~Wr6v$MO zodJ2}1%k?K(gfsR{rQAmBX2q^)MaZ`msI2u)MZQ4dvuruWV7li z15uX_qWO%9jB)BFc4z0PRMka>ATP_T$Saf70ohq~jv`-tWaJac5Cmoit5tl~SADMs zuh9ewIoWJu`5&rdd)cDu$+{B5Udp%Za0@pFXhBStDTbM~Pw#EKaKHkqG??X^3aoXd z+6Rj0EsfXhoX98rP1RzIC$!o_P!ASl~h0rjJHIr}lb)$}Xn zIOdzjG{S7rD6@aHPg82^2UXdA8=BCRW%6S*Ehi~x%BmrY2N{sMnxDznqo)GP&++3sp~J4!#X-+z#r1!n`ISqNIQ zxDCck*X%b9x#%cu)btl)pI9lGCKScUimQB3$Y;e%nmD*lvzlE$(z05K6jG-pC(cDjz*=0Ro_ZfV+&lRAWD ztGj^69E4>NC!y{pq>*H>yK#I2Sw%(G5iO)o7cDKz5yY2|}vThx6N&M?hy5OCO%m?M&#*l26Y(t^nfk?E)i)yzB>3Os6liBGm<5=&|iuIPd}BaJw%+|3uK6wN z=rj}Rvuw_TKx>xeTNV!c`GkJ|L4B6|>$C&ZXW_tnBFj}5V}%~=@O!jz=#;xxH`c*7 z)Mv@DZ^#hGzP;J&Hp;{KuV3@DaU#oY{QlM!2b)`6rCXBx-Qj?2l~2qQ(zDa`lxqY^ zv!r1h1_Y>hzjap;e>b=9azb0k%#wr6Jca{8Ha$~89x}6P;5Q;~DjSAl9y+sFeclTm zgl0YUE`Mr^f_eM!LLl+RI!)1FD9w^g&ph0R)GQR5aLGYE5>m6|V9@_^c`+A>`q z-6_ghEhDO==5L74l2Fe)&xO>iT5@_(htw?j*34)LNX>>Tshfk4nkC`Fo9PDtLP9+= zhOawO{hs#kLTVOAM*t*R2C3O_rwEgx}2E#yY@@!iqa~7gDoi*fTwikea<% z@$Sh42>I8{&^CzAy0zUf-OKt+hdI<{!=-WW>(%@#b4GL~R)Zayg%6-WOF}(U#0rA5 z-PQEBmC^`+0#cwio9(LuN+2ZExUno#Kq`(rv*)-&2z97gJZlZ$pe3Q6>8pd}EP2~ZA0H%VNvKhrrH>Ccr=xBGh_*Rm3KF!a3=2#e z0>RnlYI+KVBc-YeqB9Vj<+}c^!_-xpw?$`BYi5WS8H!C3VRtqTRxbBHe6Spq+ zH-P1;>-J8!Ruy|cc{$`}yE}oR_#ro2U1C1L6ArJPn+ zLc$G~Nv@$ZD~^_tpir7EwZ6v>08z9&UV`?l=yo1k45qHo5Gw+vT%I$JFNbyIHSumE zB-}7f)iax%`Q0I)J=@*3DsU;^uEEp;!SipmqmU|(C;A7Y5P>XLQY;wCv%{~^UJ1&x z;@jzPhw`l0SPot&&t4wjnpA;^ad(dmXwiy|rFb=@XT`=cS_#s#YP;!*|NOyz|3QxS za@AeNDBoV~L~x)_D~i^9p#W;M-IdqG06E&~j$V!A!k&jgK-9z;AvBm+@HV$Wj#eZs zgJd8*D;C~Qy|!6+v+N}hvG69|IUox+)xz>PK%zEV*o{-;+v85FBou0sq{&G);5DhH z0&4Zz+{VZ5xIb=FXc>oQtw>t8!)P$IV0$3TBrOxE0uf2eC1&KY&&(Scqg`&}?pu8j zt*x%82UZKSw9_=u%inPy0L(P0dg+h{!nR^+juM7uZML4SZ9=m)Ikx-~(5xL^fW>N| zP}@u+MU9|H>nT#~9zZsY4yvG0oAgSzULi><0{uqXX&c2*Ly|TLw8V#ih(Kq!Csb7HDz$W2p49=mv~73}k$dF> zdJR74-*b|-fV$SHyzv6vTJ!}Vy5b7m+H5DScTlNK!lkJTSHUk0aSaCC1UKIjZwInm z=cd>0@8kkB9PWWv8BXpmh|!8{y^%0;K0k^>oVA^TJgvx)5R2Vk+bu8l{w`*$<@I+j%T#*(KcfmwyCewBl8%m;*6d z%y_r{inx#LuYS)mu^JM+fIRIqr6d3?+J5;7Rtj3QUTQTLL5fzqD(n682m2)=F6|pL z(5v-07R8v%%I+fM`;+GNr?+yj!dS%1f2&69y^kfA-S*+@IAS*}9J(26zZZCD^;%~k=LWte+916X?(;Y1X_5Bw4eOxXiwqBOD<_E7siXpMVf;)yEZ93L#qY zuVw`&AmYt$q$P3I))+dpNu0IOgbr;p15s>0bZ8H8=JE|4TAs!qvIQjRmpTcYC9bCW zFmz~h%gwzWWN1aSGS3QRXp?AZvICOq9%oSK(oVBXIgX%0+r1cRO@In*QfZx7L4{US z+PcvIl1i)ExN_d_b0{=uyDKU73JqFO>5NT<2CaD3w8s|6Hpf&L4peEgF`du!19}ZQ zcuTgYB$c?;Z#SLhL#Wb5GE5o^-jb+aZ&w45WM1-hLZ(*idU|ewD6N_|BZ4P$2CC*d zHH0bvsz6o0t(=D`DgZ>yn}XEPsU2pRI%9(dtr>u5DI{ni>MW-pTND10El-l17(kME zX%^_syel`t(4ZYxe|%~1^o^5=I!>RaVwurpQd+;h*Kdf@B1(@dYgZMvxmjMvf(9+N z6MTlN*<@P5@j&9+6R-OW?qM;c{+jsUzZWIm4P5_x9f>zpY?b-J>645 z-F}d1fBs;vLATy(yyvwgMG*~`Fe1X1k?)Yu9d^&VpD*q6x7|EIhDlpqHKLNW zD=&FgYRztM<7DWyOvO{`nOcFSrP}67C>uh??EGF#+mw|PSOLCb9p zP!3kDk&1$W8gNoJIhUAN*4&h{7ISTyfos-+7;tkn6;T8+U>_K0nuQkdl|K90j4aPu zMZZzVBMYKDQ@!|axwdN(>bj6`VbHnYs+ICWi;;( zWV(TKNJBvQ_&S>kvkxa%fG`Av6@-u*c_7PGS9lU6g+99Z6FV9xf+R z-vI<#_CBE3$Q$i&FdKQa@0{M$GNYSgzmah`w&$)fk26#I4@d%+hYudecGY!%2_nH_ z+0&ZxkOV&7OcLES%VF7Cgdqu>Buu$Bfo#W4BvRePDMSI0;EXBo`1BzJV-sZNIZgzD zB%YT`_CD%bq_3u7++i-B%5D7FeT%()LRd1$pA2_-~yZ0R5kQo$J|VqkNX=9kHoAq zmaaS?Vq$Nkn~GK6@qqqsw;M^r75cw5-AGl%$(6f05CZzYS`RGb2tW&WcLyHuA_!To4B4`aUv0AcTRr zz~jmcx6D8=b&SiKGN=M`fyec(uGe^hx0eKn7x=!+F!6s};E@cu6(d~W`;x3OUdYv; zZ*T7KQLgWOOAH9b;_}{8Z=ZiLG_s;_=AyuA0z!~r6}Tn$=A1;hMY4R9$> zrohei*EfJ@uZ~_sFH76LcnXB80p6oYWq5gS%g3qc=WNcF8M81JxEk~foQDc9R|C4i znh`eV4GGQsJwyHJP@8;>b{_O>qgoGyt9e(tZ*h!%``ha_Z)4FA)9ZGh_FOVB73+4- z@My)f4sXC8exEIdCO4o?HpJ@ zv`gG;oYwQCyu6mT6ug5PFenZNt{4CiwO&fj?d7%njcl*w?aay)*2a5MHyHxKY`vBO z>p-|}w=>izgE@%k*mzTAQlHW^xV>!OJ|*YFZkecgZ!g>}H5WI9M#=;6%H8r|CT{sx)bV>D)c434lL&7Gb5>QNG9b$) zlsxry(QyD1)_jj{AR#y~%ZwGANb!rI?}4SkDbcQSef){rr4*BwayxW|5w(i-MJa5c zD-3r>9im1Bvce(2s?m@YhGptVxo03)XzEB&?n@GWyY}~|1}#&&70sa`jO{#bO|O{< z%ur9B3aAQCK9aTz-ZrW&6Ei_V7$FmskkM~~7k;tKJHhNFH9jDk27dlvzd(2ic=HO3 ze#T3{03@k>NuLjZrO1JxBgIJ~4OQVK#5qQwA&em%{nS$eeRrf%-2*Jh^{f>4z$0lt z>GSbNu2zM(2Qw!qs}VGW!5d;^(j{mJW8J}fm1N|SK;H*Kd&Ma+uB5{@B{S+kL>RV- zBUuj-VN7{Z(l}MOi=w2KI}og$kyjiFM1*mK&$QKg2G`Q}6M?!1^HaDh;nMII2&^Q( zAsCDS{s3SZh#n|A$R&L~ARcY224~CoT@PJa##mhA-b5W{7=H1Q!kN2x4o#u$^*lLMR3g zA=a(Gd~FzdVZ%f30b%4xrtdscAR!EUT_+D7kj?jsrk0BriHYQtGbrwX9bwKML${Q! zV(p9q31Ql+WCB1S*z{a+8hz?g684%(;Q$F?1VP^ss(S!&ADqnP_XN=SuangSn!-qG z4xuN{fH7il^-6yVPJjh3FqsEs4$vzCMhit6-JvLPhWwk zFcPKD)O0Nn6~2sU$uGP;Ohhqt1){=8lzsw6OX2n5ufhHooJggunjP}Kb-)+aWm&o=bOdE(F zNgt{d-4h0q%@ox0pc`0g2#_Vj8TAS;3V*?QtW&#Ecv1KZE@$_xVA{aN3kI@F@D36X z4{0E<%b3Z0p&zVAJX1kF7$53RY6tP)iYm3tX#(}&5=5L47s&oVm^KiOb|*Z8d~k11 zgn0wu!*_B#$OohAkG$efWREAp@Gp2)C}{Q5T> zjCtDy{oo-aEsDFvlZZ0T6gqysbav)Pr~(LNxm)9Ev3{dJkuQ)bJc|M53tZ%+{sj{T z0x{QvelVI6$wBu)HtKj1#z9edHX=F8NdgeR@|=L7KM0sxK|dHxiIYgT!DMbBo?mL^ zhoUf=vaa)DxJfpDmG*@1mO$jEC{4~Rsc!Dcgn>LN75OVV|3i+}l?bHCSM}|VQh2gW zAXg1IQyLMcD~F))YtqD9Ogszk6$^0{bgy{TnyHT03bF^&8AgJIzD zvN3<>T@{c`pn4=i190<4Sdx`Y42C0lZFWF<={Rb z%;xjOB)rPCR+yTJNG>Hz3aV$ct13(ppl2ch5RsUtUu@)puW9^M$;`|j*e{UI?tRV7EC*p?kg_|%YXpcK z(w$i%=-*df=_rsY#x4XGwzgcU1!9F5aJYUxNNjsRjG&&J0W%nSwg5A zj*%OuT9t}uR>!xOT9t}u?p#r!OURt2&KpHwDTRD~Nr{NwKvOycTsH7)n-URWP91(m z8h-1n!a%li-luI^%^Z|w63~r%CMkq&oRbtbe`-*_5+8Sgn-URW6Pq7bBBFKqaIio( z4$_|IxW7O+4%(g+-H^4q5)sYA#eqPpa-NX|Ex9Q~@n{9ganSJta``<3?Z;voiMsv6+$O3CPKkdTjaqE;1W^vtiCz&P38U57C<+qTxi zI!=B9DZvy-#SMv%dcOu?I1cf%ae^>h%qJ3>bS|#|06>YaVy;*jzRjt_w4m~C(F0(T zp>^fO#sXD1tQxo@I%*==@mxE%)|J7CPlV~fF}wEs6_Xk;#8KPZN;wkF|2EcQ)}cE< z-8rlx3R^6YfWv+V(E{DiRPJ}MhIwjRKxz4wC(OVp}5cQBN1aNd7<; zEfY1ZxtR1@k0gLEMVwx)M4~{97$)&+iC|{~NeUmwe`3Etc&`X=a=Snju4yM=A1_4VOzIE9^aluB z^y&*_Z6bD(KqhVy=*5pL?Raj;X7j?`FLOZ?4m+MF!X3}$3$mr@Y7urkHX>Bv(7?#i z)BP(kcKf^mFh>6r~03zHB-VkO2Ct}kVQF!jj{N}06V9!Yu5^%w-pW;tSBdz2{ z)a;h%iDOph`;j54P@XN9Rl9GKm`u__IJ0e zoTlNh@Dd1FIPUEauZAof=vH?gg8~h>*68=h5unpRcx7rLO#2Pb%{TyTGpfRO3N+!c zyTMfvP2W&}!|nzN46}GlFa*bqx3rLe!v^;4+iARA#9t}2qd*jH%4g+K3<l0RE+ULYlh_QewBUeOue#AoCJfRfk(~n@%V(Wt^CxQ{UIJ#<)-%P1ogNg zH?`fsK+wi3eC@qJPY&i;Cyz4J>r-b;(FpWrM+xBE(CR6G%P-MMtk zkU5PCB;|O_kdfP^v5&BTx;R=OAjcNX2-E@vIksqCzWDirVf-zv`tPF{AmDE}L~>W< zRU;h@*&K_@J`RZ7=Wr;)119?*8ZR1sBH(Wz9y)V}&fFB@gym3`>w1sdcrz`++T{R+ z>}{W;av)o$ak(}tpD@qoJZv_@n~3Psn;DMQ$$nZI^M>)j&VDtxR)f~GtPvr6Z_pU?P=2=Z~AfP;6S9tTQ7>G&dKsV%oR$^ftrlb!N_H(2u+PjJDuF5Y59KhiYEvCB=EM z=XNN_A)4o^83P0bIh|*V`4tGrA!6og$xDGClJCl#uch;%5r1WJ0R=f7XZzF*0&)nM zK?7YznBPc9B!ZxjD~?9)C-w_O@lUuerq18#_aow&9IA4NqCqwCYm}X5ptjZ{APg<& z>CS@A+*DP)$U{{QVKngYY0yAbt}03(`(-cy3Jg`gN2tnOiY)Nx1hN!2kR7Zl2I@M; ziBOh9u*fw|wW@-k;1ybaMnO>YZp}m(EK=TIR}fT*({xMJux&F)-W!IRgN@ zRDrOO_vzl1VNuudX+lH}VKldzH^oKq%+*M!kyq|CyUrH)9(QJ6M?$~XG6H2ehSJp2 z=UP{IOI~p<5R!8!jgL(sB*##iy!k|gp+7m37ih~317jNXcD} zoY8UwWGT2N{3FIim2-R!Avr{blzuu~S6oy%{w@f~6$J?SG!RO1hyy9dl>pti{(&e8 zs+<)Ix^W1HFZ2D3!k|jtM=DT~n;(e7pibxjgyR}tENzpYPYA&;*T5v z03|s@!$&zCc`7g};=AYH3>gdaW+=-c%;yF)wx!(E1el%%fVfAWiivsv2=T$xG>tI5 z5rW|Cyn(D7?lDGYbtq7bLx|4}Sqh25e$Jhma>w_=EJZ{`YCjif$RXnXjwt*oQi!8K zF^+aQ3po_y3Pbx$2LS93gf6~Ygdh~-x@x711f|o{`9$dBOCywdS%WR_V-K z{d_aCi+><&&vm9}xL*|B=@kV^atJ%eiJX>GD9Kd?e0q9@lH4_J$j=|_R|p!p7LUyW zy}2nQKc--2`0GW`p)Q9u#=co?Ja`M~6M=$bJ){7Fa|(#{bPRPlv@tH9>h1Zzs zLR}6PyCaN?0%E=f1R>)!?D2%++z?>r3-sk+u$q@43iRb-J`u)yunwYPKp4ZD7cmMH z=Z0!k^H-BWyvLCTdAZ6bTg~$?yVNI=Ric>(d*Ej3q_)DcN}pSP4u5jmOef|O=I7AjIcD*q8>^KdS8a=#=@IM$@#@i74a7 zM;xL#sG3N`yl?PUIA7eecuYUOmCBv~djgB69p~UBdR@4YUl7PrEpuXKrU4;d6;_dL z!rPpmKN!Xx6Wplh*z8NO&MkA85ZNk_J3dl}326R0LY)C*V=jhC@w$%(=3=ZfFA|2I zS+ZA4mokv$3pXAwi(yiD#!dxD(p6s)vX!^8FSN`)S0G7u=~wxl9ctos=)q>JGp{j< z+mEgE3wXx$+*;L99-9K56aw@7y;Z9mW}C6jM25e_KqIP7tqjfUTZGi+Gn=@r*h=97a;{=2#9j{_p->^V~ zE{&4~Wb*S{^Ff3z+ZN_&P;AuAWAoM>&mASkf3X7Jg=J&p$j!$@sAi1 z1>5MBEs>>eY&Qf{=~&>J;|dydZMmNa7;4P<{`O4M*Z~NH&6$D^1*&x5;VmV23N+{j z0W~-j=&EX|4G9G3Xqf3EtDisEuaNC~lHnJ{x2`klFGfh=a$|mn0aE;d7&jE@LX9on z0)Q<$PA`g~md&io1rl|z6t>=SgF%q4>BgaFeJIj}8qyOj6zM?OTFE^Okgc`NF{2Qv zgQ@C?8ipiY*OczVJ805X_3HDUrk?-q09b{eU7~hfm&+8W1)_AApy4hEzh`oSz9TsD z<27LS*vcb6RNeCykfr;g-p)gm4ioep;gO$bUdYd(cOtgKeH#7p18JIzt@T}?Hs`+R zI~>)I_!}BWs(DAS5hH{XM)pPxBtgf}5ky++;9LY4dii85_c#z%hEY zSR@g2w*KyZgNJz!ga>!L_FRjH-4nyG8&#tM5nj728g#} z>)sGZn$w;>Z9z1rTXz|l*|dc^K%L}_8qJgRqe4BH9=e#_t%d1OY1}B12^n&NbE5z3D_a zmqkMy0m&eLAr3F%&48g_MFLxZowc}zFz2H=aXo!K8lraYqQ-ImAyzB&nxen;3R?mD ze^t@r8&O)=A&-`v0l`#F`YH}VKrj{6R9c>YA(#p~CTjLIPXj2u>S=Za#MZHo*r8JU zL`)%6se8ilKpZ;5QvxFbgG^+UB+$Ge*xzb71lXGGOud7;d|PS63FrV%r%nK-m-P2< zUR32$S2uOy#Yt6CNe2p|nWkno&k0ipcqrZSj~J$Zf21G7xYksll#q}Y28!Ji@tQPs zpr>Oq0y@uQo&-Ol^E`O0>Or>bV1kG!rKwuxJhF72caWby7{=XFN)RBP2%!IB>-a@F z(Hkj~LS(6;J|soZkNbYkvrA`sqh?eX!*}{)3@x4Mjd2=c=}Zp|-~9ER2D4X=@iQ9q z=2D1a32P>Kyl!~_L9N|dTgv0(oTVX9WUA_BzPvB4ac|4-AtrL}qcbMOGnY0qh`N{` z2&47y6X(`Jo>PLp5X51W4@B!YJMK!vZR&}iaS!V4p7;^d(8?2$lEJWYdr?S(09hHx zs!v2Gd82!#LYP65ZkIiWIHG6sb^CJ}cc9Mgqaq+%kGNmp6o0HI;${3OT;LqNO8?7S zdx}&D@u@P9ZS^nF0g7D^Fi+#rdSQum5XzH(lrOVe7MwwYm5t+x=Q(=imn=#EWJwLo zyC|F|k0%m3#~Z0)TBuW^p6nA$9MQ5lr>|`M{K0;OkgA=#C^(a~Jer+jJd>5Enmqy( zU{QfYydk$jnX_~91B7g3WKbW@D%r%-*=-8WD#_J$`lE0%S*0iESRR}?7AeDdP6NV5 zUY4gSIB1)yybm34YBu_#JhiHkXGVwM9D|K4b5Wx3%7A4a9H|_Bc&KrAdXC}KX=+P% z$I1h|G0)#y4Y^KT+9eC@ToLKeMt#fap3P}NN=6LORW6k~Pk-?Gk$&BfE>5vBV2!Rf zBObd=r*p7&^_!Oplf~2N+`KZz5?lEp#IbbLCsP%)f>V@Bs(d*xx{l|@xg*8Bv{eE< zP?F57(t%oUNzc{2en1dNgFD#B@%DBH# zTROCf+e3*Kdhr56Ac&dFU;jKx(SI*mhkM*hlKQ^Ve$pFbGJ9A;`&-shs6VaH7( zv2c2l)S|sloQza?v3pK55}izI4Epls*|sX3OgYoz*lDf&#k^F7$Q>1H{HW7Bc|lC< zXo7p52qIgE{Y=a&(kxRcfT8>E3?xN@`%gp%bcou`kL!T$j_806WpMk>eGKCn0$REI zi4*|}z=O^;SMQJmYx;|@*~88AD}lD}^rX9}DgL-3;9(;^j!&bc{F?l*%!pU6(*_-q=8n^W75fC`k|F5?SgMOErX6?mcNiK&!4h5!O;IgJJtjAY;2kQ}546a3ao&o0fuDt`mfWi!;8h z60DfVfHGanBz!Vp=ztEks5=p-oX{wbD|AFR=eJE!bwYQN8V8i=tk>OaovJgC%*PT? zrb|WYYb0XP@q_4u?j({5DAP43-*EX5Ui0-%pA`_MbM~yOC6KvvhYOEqo^6^V0!+jkzC)AF7lR}wSY8TSaV

&uM)qZhy|4-3G(G&@oOP4tn+)1VsO6NM=W?EwWhA2Y+ z*0Yt!>pnoHBJ}4v0}sv=CBzULj!UUc_S|QZpK|Wqk#)Md2RYm+l45VF#JV2S-%@z~ z$#M`7s&i9TPf5JZrSFvRxO-w4cS|ArE7d0hQgu`_-)00v+`hxT4e~EeC!xk%BbzsS z30x_vxORX6tvZ-%m0V<&oPE5jCL6<(qCTr=v4DD=Rr|G(324<-)qUE=TOs>%o&{sO z3-s!#|YdGdTy}>#Os=RK^nd)j31`Z+5qvo>kk5YvQjB3AZG{ah7u+sA=8y1fC2G3(33kN zAyZ6_S5IVXR9Bm)DUKgs7oCTkU4Qm&M2`WfK8uXPh`dh(GwH9LCr*Ye?+;_*4@&-_;LD+j&HIJ(}_s z-VjXV>K7)>(6OsefYPRTuYxFvq;YI@Jl<5k=3h0nXU(lAH0!D+IUT(RH0z3cd1Hs9AwE5a-;?%?1nnFioYps%A&csx1#pFq-;g(uQ)_wZ*}s#(G`%d z8y?L(Bo2tx$&#tR@&WwA`MRz;j(m?7{Ay|m z^}3K@OsIgkWpx-H5VQk%TNYyt2-<tZ zs}2P1+`4u}K+w*OB31)EJ2I4(L>GE?ptZPw-*+M)Z!7an1{CgQdl;}R87G)`hsfq7 z7U@F*h)e9P+9gh8t5#myA#gW8kRTJs1ZnGpV)@^*JjCqc33#f}bPZ{{r8V1A4W#Xc zTFxvHLUygb`)h=Jgg3*4e1z-xH-Id)Q+4A)6;8iWz{Cqt%>Erw%>MG}_zS4nl)EIb zvW7+&vcI}rHc`7MTDSKq;Cm@9iU7F+S91iz3t6JHDVIWI#S@V$aMe@mc4Z%TGvZE) zs;Kj`pFbD|T~iD{(0g*T%UPc08#j@9MAL$C=r}no>4CjlgskqG-60%n&D}Nyh z;indtzTTTSTc&~_;(niFw=0DIXokEHg-EZILwq6gyO~Y+HA|H3EY^Y0MwM?y0!yuz z))`m!{G7$$d~u(3XBzSlqN&12&F1u^HR|d5enJV?F@Cg#3LTl>$MR4N|4N067or&c z+XxzR5w6S-^Fmg(rzfuj7o5r9f&RS4(888`w)7t7jw2T^dU+!b5vs z$P_7gk3QxyqBWYEV%bMH-@l@daAnZ+Yi7ON#JN^%MNuyc7{7oJE$MmI5fo_Qr|q5s z!WNzmPM>cV;+0105{&gK>sX=FceTmNwZ;oPb*=D8tyIyn> zF5eY={as|4okS1_Et4uIFC^5MD-QbN*w)J;w2`M$?jf=f~dhp`FFXp_j`Q?vfP-(&lK^tk;bY;G1SZH)LuZfY4UG{ zP_N^60z!(mPjO3so5r6WVj(v~G1P12xkZH*uPZqdAVr&&H+&&mEaZ*Em2D};`|}6; z1){j><-7R-P1~Z1o7dNH2i3L+61Vz+$pI8@*|=x0K+v|SmhK~=284*h5%99zMe=E8FBLEfP!u4 zZ>_D&D7TK&7<#rO+wUsjGP7Fy@^_bb$V!3<`PyjrKGUu=Lp{LK&^C{Pp6yUu`&1I@ zwN0&P&neVvV?OHK6f4b%tR-T*9Hf8SEctPUO0&*>i=BZp7jTHzmOsdTjDu!h;JbL; zzQ9y-4rtfb{%E!ypAFgV_Zt>e3aHsmA+|(s*^cJ7kglz&rQME@t_{sto<6IGfL918 z*{*mZcKh94yLtG3vlTonjj#0v9kR7ozac+=uwNlGS6+$^h}%xR$@B~2w%Ne8#fz#` z5BP0FM=A&T`B%QK*MI;0&%f#$*Bqn`9ux=VX%C9ME97^Vp=6j$f=)Q2)%3;6R1mwv#ze88LoDT zJ@JvE?E#brmiDYJ& zr0+__S#GS{P*e&I%7dV-R9)9;8m;e@@`C&Jt)D;GYv?U0OR1_XqvQoi*{fcp%K-Gs z3?W?^C36o8S!6X%w*nnxk*_LaC`^_h zhF~=TFkANV3PA>Wgid?3FNX|ryBDS?98uk$K;@!9TXAjxvbua0T4|fr1aE-iPu_kG zNFZZ{eIE?BA~CxsvX;+&*eM#-1id+R4K^d=-cEuR%8tb5Ikr2D>?h2;a+|4pHP*?;f*eDZ%4*X(2sUnnIl}QPyPz{f&k9UO zt?^x42c<#Qi35Mtod|v9?e%6A!FO>eBDn4b#Kmp9@O9qREF*}Dt6{7nhyhdubknO- zJcMoAeq|Y0;V!_&>~iYRH>+OaG}3$vPqLtW9O>v@2KLl(rq=aFO~G4mL-Tb+o{(AI zoViY!wqO5i#}&a zL|f8sVu*%{Y;D0+eH)~?uilzrHPdHb%4|Ga@CvCZ$kKvuo3CL8R(!$^+2i4u5;=Jr zl?5G2Kqm)ekE3|8(`eY28Bb={YE%|n_Yp&BK~HX%kT4_j&0^>tyD=4?+jcd7&M*cj zA&Wm3hlD{1nK{wXzT5*eiwti$DgjJWwCWr4kUlOxepUPkkZtNIw$&&s$hLd^1=-{7 zDk^fSTU3w1y|;$jN&Un717!~$_#Vu@=6B@ zvU|3~`5zMG7FF`q6eP$c18<_tiLT8!C3ul-eP7`Tf$?}o6p{~ALzIFM(B?NoDHzB& z0m%BMh_(_akZrJC;Wi$@D7aH)Zqyl_dBrIfzGE3|cYqOm$5#X}I?)_NotYtS5FpE5 zqlk9>ArX^^KGD4Ze8)AaX$J;;$0e%iRDcnrf;-g`AV6MEphsVpINpyo!uC#KPS}oZ zdnY3d$eCV9yps))#1QH4L^Z?z=|t2P#QfUynCrc!0(Lz#TGN zW{O+Ymco1PRO9f!5ev zvg1x=h#jy#ernooUO_+%V6!>bRB-{mg`y;3TDdGVvCP1$&4tasJ*f!M{;`|OZrktU+f_TIAWWqxa40^Iw2 zABgLOQFVn;Fhm9D_sCd-$9P6HoiQ}T`nP_5<$VmX{<)goW1%fBD?+SgqJZr4wvGMz zgkBRaE}-8=pL`qreX$8Dz@2h}BSgyHMz!vKA_`nyN~n!xgRUel8)5>CHNi{hxx$dn zF%d+7U!z()fDxDN;fSYXy$7C--~rr`4-1WPzoO0ky~l|{Us3i$dI}MVpTLQS;;rlM z-FWS`!ECWFfMa|4P62?z_=*~uG;xXp(A}i#(s}uaps;fN5NyRGs;D1=thhxDy@kzS z0HjCs(^CY1F@j|pL0`OAOa#>kvSQiGS)&;QfcH>@t61jp8)7=h@j%;h(vhPj;K-%}KT(Y~52Ao2)m1pBE-F!}<9&1GIJV-2q27S&8-*`~U; z;TaTw0M);=!(P5(_CQxGlZx(_O*O>hapfGM>fXMiP!MLPF zBHMAc>$bC^by~UYES-s`SOCX65P8FyYcN~CEoOUMK~C6`+rYRjW~WcUUp&_1hn=DJ zwfjR~T<3h-YCvQ$ue>^f(AY-SjX(idJhWo?bxXNuY^jz(}PPr|Q*(0|ovqqpQF2gnONb8nG5wMJGwa8hiH$Ekv#ZVweo{t7CDHLgY2Ih}@fZ-XG+}Gcvwxvcgq7B3H{<8B?5B zPOD2l$|v@kaxdGWN79EIlu`Mz+RrI#9%j$k0cNpj}vKYUJ%yE z^yGYK+R~wj&M43qUndgIb^zWA@1|O2@6*>5Bj?@>ZB$L|&@nZOPf-E>qi&$!ob0*$^bGN5$Be;U+V|v3C zoEwrJT5?K6ci)JcbH?fX*Ej6<4+w>Aag4axhCWyu(n@_3=!0A2Cm+AsX%uUDfI=P| z`N7UMSeFB1zSf&1H${EhjaDch@Df?NOKu9MblPdMN{Q`gnwbRP#4pD$6;no>Tf`3X zU^#WLhL>Lx8ImjRG2srjxsefhAadbk<{)gs+K-elEMR3KuvtEqycDj0-H9*~=oD3enWJwyG-(iyd1kWWkr4)7Ct|&J<&v=a;+`u}H{g4_9!HUDvspa0TavR9&Rn z83A-C+urWdU;ez2i=HoqlM>mNY`ZYqc2;oQ&gKX7K+?WrjJ} zJJO29e91@A-WEQHg1sf>)CEb~!j?DG!MANOU8csClu6RRzG1IPM-F*xKn`buLHNp= zx*8#La9f;E3da^{|HG0;;xW+Wk$9(mAO+_}oI1*iQG%L3`)VLe7GkCUmZHd|o} zPWvH|a@!BGR3HYHCx+F>FBO8$7{MvEs_XdxNU5TljWzk=*Szc)V@G6TH${=r!^7NN0~t zHfVz7?9mBGwcP8=b>d&z(Y+BYC0+FT{wXJX0SQRfzP}j;a0J)zX8DSL$#pTpRmfky zIrCpFJUlyePhkh{v4r^y4Lfk!gfYa<%s%}B(luuj8ouC_R;{}Sw?(*fY|X86(w$=f zcHk1#({2wr@Rb8qLk?s`n!OFlEw{yZAnkSolz2~%JMPO@MF4p%>J!M8-=aK_X(Lt= z>V9h3h)uExxPa52x<8r;C8r`LA}a>CV- z$O^kF?nK}QwoRRT5!}G`^6WU$!3~^-*B27^MYhBs3-%RvuslEwJj2!DWe93u+tep6 znYR2E<87&uXnYu#-aSEVK&MFxS@4Vz>D!hq&xJ>l>nJKtgL*zq6&PLGan2O$D3QAKytC~*aA?~#-TFEYc=7MrP`M(x;1l~T#0GVGI-m)*K|OLk z2u@2A;Hl^5iW|}Hdv%GP3uv(_%Vp67IB)?(;fP-dWPHQ)S<#Vb8mQ_mqN*i?E^DTS z0R}IyeLN+{%xclUHG6OMFrI^Z8(v`lX;TJPVB69qyc#?F8z6Q{ZyOdONz_RQqTuxe zj(hi}n1mHrH?MO$CKLi-nbI@#z~KLtFNXlGKvBP#Tv>v9n_gQ)p&kJ^EVkcbSC>@3 zx1X|ec}L!#SV}!WBTon7L>mAgGOkIPbDg9E-b{lV?{Nae?DuPqFFt36w88&df{E5P zCWzd1ATs`81YY@+$Mvyfun3900iYMDiUz?w^uMyV366GmL&Z1EENqKc3e-V)AFY1O zQhThQ3ShUG9`Z^<4!EkB)YcFJ%N`?CJDxiJ;*m*FPy|oOT;zm?5Lh-D=?5~8AOz;8 zIDt$*)ZCvVm7k@0j1@Dohkt#;e*dr%GC!Ze^N<9~TpKAX4oR^3xTkWf#E30dWL9s0 z9qK;b5~S=)-Ftc%BqB`Rd+zzL1Y@od5vR_Q@-TMH8&YkrjZ`}Wk-av8R0xh>1wW1w z;f8Po%LIQzhRwB+n?8u_H91w_43-T$QZNe6U@4ts96AKSvbGh_FW}hN9+s4X9aw$) z_V@Omj)#COSljr>EH#PGW*W4biE-0toRfTYvBZ%jWKR2!;h%Hg}Ii4@iJROwCKBBt)rYk3~;nn;`(` z&|Z)o!fvvr;RKeIb}PL>1T2dzj06zpE%qSQmq@1cg<|oSlA$U%Bi38$eA`N4(?u-& zf>558L8yUcZr^Y1W|5JQnU+q~BP71OfbehX$DRw3q`hjillQm}=rz;uo7DZ@mV6i2 za6PF9q{^gP_t@OkIjUuj_P(PVOBl4$#@f~cYzZ8T*|h@`c8(DqZ!@7eZg z;t(r|$hgL5=6)D5=}(xoFJRhhz-V$fgjQax&X%M;Qe2=rZ(Um{ykN6PZbKi4D@7H} zV00@kj0a+(PbP$|SCN2I(ObM&sdH4`Asxh=qf7GfZm0P`1eY+ZBVDQ|}Mbu6>G zeHm}wVE^s49!H8)l5-9&YmaDQa0wI90K`%Y(H>QLLp*x*ko$L8G4?1z%s(AFH+Q(p zZ(cU9-w^A()C_5t<*iC)jHGYRi-o>DOmtIP-(4D#~Sy(QHi zAq$piR+5thvS6-3*tMb~VA{hrEB69(ES>p|SZ<6B(#Lt&g5~&xUqz-PY{4?luJl&H z7A(hSTuy-a-($WUkKH3>Xa9~}ne692fx#54dsL`iEcORga0{duu=dN9X}v<&8m~+; zFK`D_fh%*~3$(y&($_6r0WB~lKmL~$Pg&^Yx`k6f$W5h;iJl<}UM>^L0?+~v7qJKg ztia6=`7~Ex1!k`%BRxOaQZLq%0w_|j#fY;7P%gFp&wbMREf5308ZNXT1c*l-z(!Yr z82ECLkfsB9?LNFXG!~!=eyuZ<34tA$fjed52B$y_Tpxdn?*wBuTc(Klaf{+8UW?4j zJ5UvfBTbB`WYzYK-5jDC@B)|ii5w%L7XVZ68bUnIe|^J#gGl=YD?J1X;R$p&JaPT4pVSdkXqe2w?`trT&*Hc5?yIazggS>{_Rz6;ok@yQph{-_}+_&CS zVt(LM0Vyf%16A-71+GO; zg{&F~UA$Im_Cgg*cPatWwdkUR-0N0tff)F;l<8FKHtlk=?wjemKn(mcoufh~eRM8l3cg@^nKC`T=%|;U$X-H1KN$|;*V46Ty(iPsmcM5nGz*l$ zZR@u}N&(8?0&?ANUXp~tft5YK#3qlEYh@XYNRS#mw&VqrBh2Lbmk8?ho{(3$d3dI7O~Zt1^BZ!8vsE&Z1VBK;STl21whMM`EdGWK!nTq&{vMKH6V zr@r~6Ra`)BCP(rwDiSX~l7A5rO?o8%A_r>>o}++Iyt1K~14%HA(}V3xz}DX($^~oi z%X|dM!E~eov%jRb;RvQX`z@9QM=;$9GroW zi^37i9gXz$A+g30K zzuE;)eQc|+0@E5TC9)v}e*J`;`R-3hfnNv89g&KGY$LJZKok7xY_1YUBGQ84y5TM( zEf|RvmK(wBXjdv+!V5f&gmf1yz(YX(Eh!iPn@vyvzsxaiN5ZNDq26_+S_`DW*ke*) zjHmGJ39+-eK=<2>gf203ztu=6x`5Cz*cBt*EY%kw(GOJ_6kPGd?g!!Tt7Ewr^0o@$ zFW+~ov9L2qQ?katA9a&tul+MksxNw^2cisYT~gUvgzT5i8k0)_D+RJ&?6F$ImnGz7 zTyq`fqf&wXcTvgf9<@!nFWjodJ_6Y0cpYL0<^_%Nejk^fT5%>?ooSm=#UhQ5U+R80WSew zHKG1hYo+)m)W7sEyi)PYLqafI>V_mMh#KpbDuoOfd!t-wG(r74jD&6z)W6u)izP81A8CUo6s0eIl<>Y9NLZ`@Dc$$fh)3J`i3qQfLa|U%Hn?&?X!- zzjW`FOcn*2UyQNq)`^DZw?vtIYN;!)ThFifl0#*p;#`EdOo=&j3 zJ4gmUm7)Z-@F#oYg|vh?nej4EG~Gm8J7$N#r$~iHnIYhC@$(r;%{9ev6C5 zwgW;}-T{OK{@-aNwD(~9rD;}Dq!rkHU*ETqy{|y_`!cFQqBB8gnl--49ChX$rdeS7 zr87Bsc+rOKw?`RQyo%G2h&IP23!yXDeJ+6hcTFK-e6Jbr;4sB*2%E`=ggztfrnU#K83NN?Pgy4X~7F;v4q}5-~r~7IoSHx1`qISObfZ*&L=Y6E?4;b3!J|%(+wn+4mf{{%iO;%?;pXWp(qLq@Dh;2cu4kz zkkk-8h4S~+84pCVFDp`Rg}mxCcATLg0Nzzk!Zj7A zY`X^zVET8oG}NlpONE3QEwsRE3yFOkT3~f>O~-PTdfv|^&KXyXxR;*DM0FKz)WcX3H~3LL=nF|UcKs!+6_#D2$UTH=2M2Msq$CfJYN+H%lE3o~xDJ1l+tNq>nE%($ZZkrM35BPpD(|Su`N7#MU z67?=3jhAJ2u7Kf&$T&eESRJfY{+1(!7l07tg~%5hqhD$3!Q@N5xe9g}n0yysSNxZh zTX-V;F|hVFBPSk^a0@_~eIOXqJ#SNB@x?N18QNE1@nzwL8_L5B&R#4n&YUH-x)1C( zh_qZlO8%JgGDwx^Edjcz1x0It*B1+;tvtuVg-q8eg@|t+@+tZ(BlQ9f7!4ZF39$ zLfm_~OgP0sFeX|FEpe!P)xo#CFT}kVjP=}Ij$cMVoHJnZEdpW^0x+iYI=sN_i|zFW zNV0_tq3p^g$riGRvU!^{TRsq)rrt&}#J<>GTvEl?HF2dl8_Csfa?tTxS2UIfnULs) zCe0STr^Xke*+M2%*vZhYPKuNuZZ43l(wX(X|AAzc-mLfL(&Sy#d*)04bE4jd;U@kw zJrw&hEUTE(H5IrDEUWC#?}#*8lob{+nxEKjBXlr6n;7cdn|8_Q)B+hREmo52xIn#1 zi! zUZuw20M^xFpnf50m=cj81s+y9_eu(b0ud|5*L6}}9op6Qfym9bO2|(MI0nM7f`@hU zeb>EYNgQ6U@i`9CRV<0?zN&(Bm4+b}Fs2mK@>*&6G!zJmkhn>13bFl3K4mU)9ESW< zm|~EyVn)9sB6ruDubl{1*7eo5N)-G_{^yAw-)@;CH+&(IY@tY8(KWNLkRqB3$ChRb zNROtmkjVq7Zkmy{87!@8o1Xg*%!l;>@WZ!$db6?#h>f{l-!SHznABB;h*5yHwHq1v zCJDLlRNOT|+j{xe;vxhDv+KH#7!bLtwMx3f;BCd)ct^C!lhB)M^^uYbWpX<_l5%;x zxy!V^GLWx8<;v$=d2a-7>uWgh;;>2JZGHWyk(I~+$pZsKuCFf!i1R;0uCK8Q5+^ul zTYJ}Q;xZiG)-wGXuXG@<(#mA^Y=+5oyG%?fm|R~gx!#jy;2;&^;Qs<~D|NVi-te}* zjIeobXEn%n8E0-5m|Q2dnrRurayeZc%{OmM&MZ9`X(eaJm3nNd+R;Wh5?T zpmH64C{E-sx2ij5UI)Y6T4;*<2n_PtpFli8;Bs||uqU8$Rny#a2;x?L`u3Z{+ggi| zaIwMLdR4!+_C$6w68%yyH%*A|61@_irz-AKUtu&bQ*G3}SMPgFJ=lWW+<}DsnU~heuhE%|L_67FVY9##EAoTE; zKM_LLb@at0-z+s3Y88PC(6@GKb@D(DeXBb8%7q;IRu^%&u7Kkr5#j=&>+EXe@F;e( z#?v`j(caw2$sAhXZ@s48oDJBe+yWB4F4}nYO!&AVbnULg31F!^Bk@3p(rwk9`F(Qp z@!mKZ!RNYMtJr7YbDer9=gcT>n^b!#u(#IgQL&kqW6WLL%E52uEf5srdjpDYj83}=F(<8R+;c6{W?P#o7 zJkn2kUSMxsRoxqrP_Va-<{1;S0f&hY{{;byhe&u-o)EKcYO9~O)`yVoBH_k@%ykZr zy;wA-+|38QiVq zIm}o0z|W+Q(#0z;Bo{ynbPH+m9tpS1a~tI#XFgikd4)U`&N;|i`D89ZVyta>oi(Lm zl5LO2bBBcV?eR#N*d3(c=k_Xr^lasoZ}xaR!C_Y*YmG*ZIzXQ0^*HyT?a|2gP@{}T zBWreyPsr0A`^C|4REYpQ9?u;Y3UWO9PAoS^mNXv|J#}I@-p8lzeT@wyoMBM4R_{aM zlmJnqk95^Q-nypBmJKdO&}D!+wKIS7K(s0)(wFl%A8u+q!6~2V?)hV$0Kzm=QMx%DA97{L*FVx zGZjb*bggleFw<#)uC@BS6ss(JtvX8Vye0vWasGzvJWAZ(D|I1$%dJo^pL{~nqd?Xw z%XsEE0+D6x7r-#@fA$g#QLB$4aj1Z&RY!<>L4c>V%5IK54M2yUnl>HGtvWK?#{rmI zm~fv8nShMBjb5Vh*a@IaQ&cClta-HHSC>(m2LYj>HjwP0$kPr%p6 zC7ES~&@OQ1#e0YP@eQzNxwJ4sp=rhKUhbPl)-3 zJ6N8QxY35C6;FIgZd4(3u#~qvlDgf^xQR|6$L)1H1)yqeesc`ZVQ+J}uV_Fx5`Kjc zLEehbx88dT#eM1zakI#190M5)d^7bAk*ySSOB!T#qh>3Q4 z93Xzho%xPbxieePS_nAd&R+2vUDM-m&jo}u>8ZtS&(!&I#&QU9a4MMIgGrNJYakq$1+0o!HDI zlb~y*h=qdawfS}`4lEG87GFkrEB*Bi`)veg{#hnUm)PyQWP)&G zL6B&lkr;>A$>(Ph4}oCC>FO}|2Xofb9~i)UqL_uOE=Gv zJ2fn@&433uB(OL(T><{WsmUu`NjPEY;dw`GsE z2x?bFDPQSWg4(sJL|kc3+N|6ug459|`dK@trdS&s-W%;GI*9iOU|3u)mx2$ELfcjcONn=g5kl?o7bU(Swe?Oq9&v*Vr!0mrT7l_9*X z(@6%oyjMz_2rB`GR>F;2atfCzxfqq%QAz2s z_^H@4B>tnPa=qG4jN>%nUfA*-i_R!YNJbPOhBSVW<;0ViDt1hY%%}yjmG~7j%tExc zfyAnPbVaPhm{|Rfbihfb33~;12cgD2ZwurKZ_2<4Qv}D#>`$aCkB^A=6Hm!=Oc|#N z7u*7*cwuDKod``MBggf08tenvYMb%3b{^?~gTy5gN8I8v9((|&C=)82)ba!r zx^N0shSwV+&2KWZVwdB1O%BsY?r9;%SzzG><~*xUenX}+`I7moaG+Ht-xYVYI17{j zcZHAb*Ej4p$Z>LCiHs2d<@VKFaX1)fPMoj8xRmWK6WfMvgv%3Y&f{yjTqmGQ;e<-yM(uSFS8S3+3mO0rme4qr-lax!c*Ra4N_UUy=fqHc~-Xk+al zRHrEuH^Ma(5>%Aq8;2{9-Vyt!V#*(7*PeqP&tj(MPw}5QDF4gY`f+tN(Q73*_p1Qs7 zSOUicI)%HgM2?fXuedXRLd>}?ZmhjC&&bC_rG`fcF2_WAci)lZidmd4<3&@4#Hli2 z?C6l_wDefWbR^tD!b)8t57K+$^vdb39F>V^%Qc+-KI0uy1}A4e94egtrja;55fMw* zo|OJ8I@ytre-kI@WY>knrV4UgCZdu!>tS?Y#_m8c|5YYjdYtt{XK?$v74N*oJCL=U z-82K^>pesHe(%Us+i?B7;yp_lf2YUgfzEQ(Kb}A3cjUYzgSd(lAqVhs{v2*&TaO&m zx+xmM$O=FN8!(jI zU$dnCj%OhsGC>w$Mh<3E!qzd>@^R~O1XTo!?vzx!y8?O#(u2TfK>0nm% zP=v&QY$Gw&l{sgUmFQ0$-@4da{Jr}!MV9Vl;g? z$;3~=AR```@RR6Zb%ex4L*zJ~a>oL323kg9?Nz>I6%t2aPDK#D@j5U35X_2ZCuNa@ zKsi?KU;`*;AwVkeJGce>jw`-pYwYXv7Zu>fR!H_jF-sQbKaW18y&ipCczro*4I{Cw z?rNH>axbl#v>kzCa!Ys>ZuG8`@nvK zh+yL=bSFNVj3|*1h5L!L>S-j*Ob&M4bVsq^!7&So-aBF?(~{gayO~?Jq!3o&h_=k5 zbn+px=lG>?(sLwJgY|npi1l7&VyWW1r3RZB`=~QnGeMJQ9w)F7v`#TlAakQF(gmo@ zdIQ-L_)4}OienasvTY;>d$*ElNnx|XsjMH-Ohq6AXRszhtE?5&Zvt|@b}N};*ZRQ3 z5e&_;diyc99NjLH?^Q6qn6g$NM~zcU9?m#%T}I+!21N8baE zSwkxcy`l;ygA>SNzxP0->@d`Gm*E8V)=IDg#iVW+Kh}z;#|KQ$s_ohg z0F!PXd6aihd$FE-0v;shyjZi=a@Lw0BN^n zg3+nQS$TrOIBe!`biFaos@~%EJjlJYJM;xh4Ff~eRPlg3e4^3x@{Xz2KM=8LfW$6= z6(g#|l>zf0+epN%VZ{WyV_aj)fN~vU8IcvU-;iJ5u-_oZt#$LsfMAieR7@?{37D|t zD|te*$D2wtR*fU)@)Pkcj?b>QM8uhSMTfJ6(ZBsRLyoxcg~Vbb{=n&n@@uSS+EejR z$T8Px%m#L&J)ej+HT{;&6?P*H{+)hh?HYl^_f!jR^@iQ=iRX1sbf?!1h`O|gUQZDR zr;EfT4wEN%U&FZ5G<{T{_3X`9%jL52UHkT!k2=@&mgaW+2-nv~N{7 z*)%0zOpJgjW#e-g4ogUMW-rM@8*U%{+Y%M5w_g4&$a%v9F9KTA+lC=P6JW67?2Yl) zhrf8{CS&)jD4CSyyU7?r7VB^In%7_N$fi(ALBufg|27L2W zFOlE7h=y0abR+&mta?h#Wnxy?WiNBBd&L)`)*0apsSwUa>zEb2LN7ZW0Pc*U7f(M! zf}Ve9(7D>!nCVix3Rg8wUJkKKuAWaf!K7QL8E<4YhiWGH_&RkWT*;8Ll2}B}%mH zOi#rMm26P!w=83g(=p?qTp^dm1ksuwFBVA_U+i_eLMGdcc*pwn4f_pZr9b6nLK8&ZWDwz)`;=IDw^*3gJ<#{iM^gnfba5=p&~5hF|_^-;!v65Xhj zOO&4Z^$bM@nDCa-CQ_qF&bA5w&D%OluhQelFffpq`YsM+i` z_v!mJI@;!>ilHSO04@0u% zB0T`*wb_7ilTLfzp2%*`pHkSdkP>B%oX@w|Nrm85@+=vcRIg=TaAFE$v@gXSpP4S! zU*9n1-x3*y$ou2>mtv9m{TcIL_q9*Nx_|`f#B5)7%F(*9aV+s+$TYj6jBWgzsJ24- z+TyFD1Ep&v!I)fSCDQ&t_LXgRqNTSlGiG{V>Lp71C(^Rbd>L6GeZ5@wT&?kp7&%dk zZSCG!eLkzOzG5l70gzhpLo-Gr{^edN#a;hIhAh9?!oH|*zLr3407GH6FfuD7u$KDqeRhQd zc0K{i^in0i1;$rP|Cm~_Lil5X^+xB7Ubr_nIAfMVaNEOvh7&?ll#SPCRA753yOzMAVsI2my5xMv6)m zg&PC-(D&;b_8Y{v8zPE!MN7;6jR9JU5{}+l8DtxY9Ub1-6~iPNtSGt2%@bc_-`$*c zSXD@3F9TWiq6lO@$7jb1ajbNidTuQ6#C9WgvsZXx+oLV2B9PA=b1dYzRxz+4j@_=g zuPZAwv6xnKhW%JV5^yH-UWFwVJLMf&**LKofnX=hagUv9-yH#dCy?XDNu8PsRc!TB zu}+oduk)#gKeK7FPQ=gocWj|R6Wd+M*wCPfZ81z@Sm0!|fR>3LglyNc<%_M|J7;cA zMNxG^Mhug-vok%sDm<|g!HJ<7v+a^{>h+~tmV`>F83hT2%{;}F6|(}aBvBW!f#i3)VFWSl#;y}}VY zT}j8wR48G)8^Z3Y3MFhbO$jCQPmGy26q$UYVMcWoMs6nX#>N9NTdWkwFYovr@AP@^ zT%m|9^%FVn$rVjA6ex2PCKkw+At}1~_!#kKXd=YNOpE=_5uOAg$D^-BgU*uUK7MLe zckS1Jn6as6dSito7K0hak{UlXKK_({aE8uOg)-K^(&PK*a@W2g7W%yv>MH!OrF|mX z@_0GQ*5$5^44Vo)Y&1+xj8*e%Z=^*pMm&#@^PHB;PP?~7ZCThCJFEvX|L~X|!|f{_ zN`K82MeLt@`#vlC&Y2rJe6iC_5!)>Eu$nAi>&R9Bvwk}^yR87`GuOR@?V62~-LPAZ zd#6QIs93O{UdO>@aSvD5FksS=_--jUo} zp^Tj#E57im*fk) zbFHFE_6m7sB6~iOo{dxUJ>!p&Gh!Q2UXd2NYQVz3wBHG2XG_Ep0E*bql(cmXAFLW8 znI9{BurbVxN03mGo1db;}*tjsnE_ZnBb`Ziw=f%+#LfGcP9i|H8uhlam zc1;kO+^Nk_p@WUyi{mzQuyedGO_0B~{Y19AFN2OMb-V0l{JY(Cx*70W@wj;4lz7LuY*)S^ z#YS32b5uBDM~wCO-qEsQR=&C0=6)b2?CI*Z8pAgCy=TA^JD#rV|86N$x?5-Lj5X}EE%ePeZzhmIrFiwu4*&w4QXlk zcV56w;z_yswvF1X}W~9#>*&g5}rYtP>kHr%bd#}M+V*Sx$e!2#b z=Xg@D_>?0z>C9AgAz?=C*b2{;hTn;XI3gw0 z&TZJ7Yx=$tzqD)ve2w384@L7MRJdYSE}I7IW!4Z?=Ry_RJjUX12wiM(AGqGlX^3wl z0{+<8_hvlP+z=U*TA_=LY2W-)rM=37&(XT0XNCi8cWErNT1 zv=SrlUX5D`%kkv4*u=>wWTYGO1N#k9-I*uNH^^dDixg+8t%Nn1n(#v06ybq~JvLe^ z#!WK|o0`j;AY8HP-{d8#u*F9IuKe+nHdI&=AnP%%;fsw9j->{^*#3cpJ$Ygm1UOzG z!fI{`4}6~v5XjE=1*@5HOeQ^PYI955BO*z!I?oB7sM!UktE->IpE;P+RV82UQPTd>xm3oP+#BE;>3EwMs6lt(+9>c zEt*FBRPn((?Eznv*Ve)T{neS>7r!%QDunEqGTynH`PTG#UdP~z9U&C&@9n<(U8zY` zp^J^SiR+8jZ|gGV13@Z}CA2x+@V&o#7?)q`Lf_dmVG%U^b}Pw&`4dBFWiVBR8FsoI zVljjnw#UvBIY6Hn^KOJsIs?#Z8(~@QKjLGC?}G2`vcexbJ*u4uSeyCR_@LODp^L5V zsyOgB^RKD3qD4m-mS4+<`PbgNYUnO_?x0tzZQ3h+@374bY`i6mI}pq#n#Wc)6tWl! zAScSS?B0`44I6kTFVlt0x4q%lkL%|@{bqiMKev<#<^s`;V_E`?ws8r?QB*$iF$E>F*cuTjCTH(RcA;*_8l$-!`I)Naoac z797t1Zkc$E`|$c%e*Wiw`T3`oyiExL%{UD*f{9WYha{u!^)>ihwm*%zJ zeIu){`fzB zz`A+C<8=9#e*aKfr|8u()}Fe!7O%3`Yti^0KkCnae!c(Se~2%U_4%K^ee>@d`J${* z^8DXL@~OXld(Yh_%{TZsTEPhw`3c4Fh(>wsS`F9hKYc6u`$k|`8u3yxTA!s7c`qdi zxz}FsRVtB3DOk0hr2=`BaumXQsX*RKRT#n_r4sp%OMTY*y;O@O_^VXA7v*2y-v9U8 z>+b9SVDMc(&->8hmh5`X6s!^Muo-**FJtdjw7Mv4#{`O8KmYn~KmO%U|MF+}|4y%e z`hWh6$G`Udr+@wPzy9@~JzU?%+qX{sY!W{Dvm$@LG5_&^!3kXF|7^g#m-@#8=27Y& z4wy%&e>h;?Oa0>k^IqzEOWX*i)<+$`O5Mm?sn03!HYwgqeN2J3N%3ClV+y=YinmhV zhv<#GmHLO{vj3Fl?rmri=S3_asmesdyoTn#{OS7hUz)NL&YxcP*q{H>i)4gf>*bA? zcf5Y#ug}sj{h9>)%3ogpyM7W;%ZXiz9A1I{+dT^=WnosO#9xqd!lZjm2CvfZGo=r_ z5N}0tzUwN>cvybCd>QvU8F zd|QR0)cY#*cLr#b`k#GQmvr=hyzXVG|9IWYQt!X`|6@=Qqrh%PMkt>`Pya>T_!kw0 z!|P=g(7AtMfW7{~dNptVaNT<|TigG54Woa4ZMXmaWgMm%0Z}JskyktE9NC08aIlHD zy9==++~>$w&6LL^pepubh_dGhu}~F=FPWNXyN%dE1HzYrm`lJ1Ny?jX->S z*Fo}irWF5Z^Lre{2jW044w6G>dOzW#D;%Z{m-Ioh3DF76XT~bP7ePKVx`@SJd}bU% ze3J8_@zpY1f#?!XhsM{Bj$5wAhsGtuE@&Sbrw}_XeQ5Mk4s-0^(}|A0k0A z%@^dTmNNpEnw;D&W0zRd#pV{`_2#2jbD z{A3+?k%Uq>96(y`u0S8PsVy`vGQAK;)P`70fFOl(1|CDcbKpa=z#N17p zmSc7)S{T5&%5B*nB$D4a1%G0%nI|&uCd844h>r}_y~Py*;v-F?pyp5x1y3;wyLaHM zQr&A@LV;|3Q4OaehB2Wpqo!;(Y9sFDa=+R4fFKT&L2U%97-WQj?QmHTCsQ`5AqeoS z;c{N}yn+B0tr5mONQ~rDqL0&;(Ztj4GQKfHeFQ%Yh%fay+pCX7bgSQnJA`^lT1bFX zip1Bv{o~Fe0C9v4i24{p05{Gt-4VRc4&O&?grHUsJ3X7UKm?e34M6=#GQ4Vz`Uv`H zL-L_bNYSbQ#k3t!oLJSLB}HJ-8o}`lVrL&(Biyx)k{2By>d%q^7^sin>>4G5J$mq1 zfY^V9*ogWQXL0dwZSfO>nBx-!Uq6UL4$vQAdO)V_5E0}?I0J$#`EHRLA*@e?+wwCZ zH-g`Jl#FQu;Z6g@&5QuaQcZg_Gjb#NR>#fJjNS;l5QxJq5FBAdfV6neQYa0G9j4u? z;^GM3{_(9lMvxg|#h=*kABd22RXzzx5FsIm5XAZTsE}O4W!%f~daLf$m%^x$OjW&x zPZAB1zFfq^8x0b7aP#YO)oD!oOwGldU+^iO; zjkt?5{~5IrVmU{-;x-(FZJ0D!tsv-+uxW!hGz+;AA`-?;xq;k>dpH@UkQ?FJ4Z?Tt zh9E>|fOy&&`k3gc0 zm4w@bxGB2KBQe%{Xm>M{z-sTPIuQN~#K}F#kFbb?IJ6P55jaQ1h3`odsf-}L#X)VP zsG3QW27(I~#C8kSq)?d};$cO%n>@{F1Y#+O7VJnNSNl+dM! zp}tIS(&evKcfu9-YIG1A)_wagZhs#C#9&k}kPbBML(5Czv_;7swBUdyC|oRLA5MR&7>$|SVtItRiDygq5ky^`~8E#j=|M$VHS|B zddD_4E^mtf-ZDM$yAY37tte#*@u1gIrHUuzy_UdAnUXJd94Ub9ZdPPs71b36oPXAD zeH`sFeu+58&2I5@|`vmJ*W2f{$ zu(tZni%P5`EMf`OH2?UL^$g-8C{`cV7D&F?TXC0uQw>D@i_I(xTQ>0&;A1FuH0Cpi z4Qv_luQd_GvxVbIT>_lAiWAI%Jr@F+rJY&Rz-NoPn#_7F*M z7vjh)&S%c__%<8AS z$RHm==Yzy(AKsqXRbsT0&#Ri|{s+Qt1mbOUDA~CSv5x@#5KWOQ!a|S_!P)}x6*lrA zSX*pqy9U5;1u&J-7!C#iaUdb;A?ja6n&~P0C)Cqa(g3Dkk?z*zB30HFh;4fi%q{J& zF4APE0K~Mye?l!+($}LMg1N;uZI{7_h;D7%?yG5@co4_ppe8bx%Xr0$$PNGpYm5k{ z1#yBs+9B*w*a$L`0GKbZLHUDW_SOf_h^UmqQnie*R+K~3m*}p#g%LSpT;Bw^AnMDN zNi}GRs4vN8a7W=hQ7wlzXoN$c7yxic1;Qcj%k@eN# zRA2zJ>`Hx4OAv}7%*>f`MF6teB!n}B6kBaGN!(BkVJ!mjaRAj25(@fE<~LMBu&y!9 zJ$aK3C6y{~?AH+)#x*@W_HDviqT{)B185I%j>&#eH z8x@f#;s_~JL)4QuANLHQ=dRFteVjf%C9csBQ8&({k3mF4CK}P^#ZL^I-%7wxb#U#d zg6YsfGDIfYol6EH`}@wrK}1CMHxbP4CHSW>PRUZzG(<8)MjDG*v8DNm{r-WBNb!rz zcmUwuP4xqWMP#^s4Ge$?&T6e)*v#( zC6eW*jx9Gr;x%1~lfbkGaV{@XBJRM>ZvOW z{&q4Re@COk_k9`hi3Bwfb?4YNxBz6ejSMqKUxfJu;u8saBI-?C3~qF5pY@xB133|y z;UlDA0sOfun_N^Rj+BWaO)gLQH`JIgd&e^#{B!uGq2Ej*AhOX$Y`rLs$V3~NIEms2 zd0Qafd(jx7xko0D&JkPsEo?9q@WMkQEURDNu-`(|;^7xUm_#<)$W$j}NMw|c^a~+F zBBOkSUkDWv_ic}WbP(C(BmF|?lE@|>A^bCynd>6nU8X|xhY-hhB0|Cu1H@xm*)LSQ zg^4>Ac)5gl>zxX9oI-r%g(`_Ux5bSYq9pFz%;%rdL8A&a{MXYuXmX3WUzVj%KTJjtGf*Ga0SW9FaLTuGp?Y*!Mu9L1CHV zU?D48KhEiay_j5LSp>=Y5)s>hG7lO?FtY zhiBA|H)*WW!J;wqQ|3zoi47axZq;+;h7E7G>bY{mmdnad`OIJicq*DKZ|IQ7{*tZ{ zPf2RiMRZ6+bVO5;wJJChKC$0F5F$|*_vvE<0Bdv4q*jDU$TX5lwWb3yB9jxVyUT8?MI8Aq674j6_zq z#xPMWh}~0b_?`j8j#lJHWS6yYPc2KJaV>Y^EzO2Dq2cbW;a>pJPK_Fg%zUDMT=C!` z1MyCc{)p`C*8Yeh+jdz?XB3DWq~c-qFCClNEh$fl(v@K*W@fd`w8lxl1;mJ@c6XLI zek;0KwJc#VNqiC$r6rdm@*}ddTjm@rkxmRDJ{llDBI8VEdm^&4$yN3u6KPPrU7^2A z0Kfb5ij;RGNaR3M2#}s483b1_AwV9eI9RCZ9Rh?X38t7Lfb<&ZtZ;bO++|T9VP^-4 ziG-Viiq_0kTg&0qz3$)-2a)AkBYO==64_#e03AQ%IR@hGTUwDXL!&!)3gFm1S|j@o zK(<&-QfD+tWQ)~x-zt1!ugUi^WjIuU#Ax3lxaH>Bma4=evCnFz0WbMeyAZVm$(PlC z$0WkPqI%Cb8lXuc4`~f95#&c?YS(-JBsT(+vyPx6Lw-cIHU~#tt)Vue-XtbS_9Sv6 z@^{yy>_%?nx?IK+?^JhY(hHF|BEuR+Lhs8`Pve7IZV<=2c(2LygxZMgHIBNi1R~42 zwop?*e}u2-3jgs_+x8maKRTZwHzL!zR@?ccI>@rF=|&=TM&?z#I&T8^slUE??tR}%5h`Xxfi>D1~#rpU)W-{pY$~+!ND0Jl&8gcHUVlA|= zgUB|kNjE2vMl2MzbhW629k&3#SCJG)fOp)j2n`pJ?Xj(i)=N5wkQ$MpU6M@@VG-G3 zB^^Wvi*Uy7WoL61vvGjLdmTOiV5b~vBigr1X6>RaqK>0GXilh*YJ2t0#c*0My#haAcvoF92-e0a)2t(N59_XCGHCJnE}W;E6HFi5lD>f zJJJVv5gFShDdLeAk+F^K?w;WMql#XUg$d#wz2fYP;E0TEh5GoZW9tlsAI|}fon;I0 zeu}(^jBPnO6Opk^sE_v3E&X_x@o@k#5!u#6xqHZqGWYe(*N#kT1V&_eT{~DIwgk|c z5St`>IOq-}GJmFZhzN1Bj|_xUIf#8^h=-^vxR7?;ad$8-ujFIc!CI)`IkzD`QFa!| zOMB=0#K>TDkSk$$v64)mMirRnVHfUW5MOp}rCd%SG2xYDdxUtaLqtTD)YZM!AsHe= z>Pl{OBtz)ID|InY43QmmnagRfv5p(y@E(*@{|KosT)20DS!}IlR~I(eB6{kfSmy?tKvu!6W6oxWE07W}PaT z^kx=!+d>?9iDU@oFhRAZzeO_SQZ0iv@mR>Lof+1!McMp}uR<*D)`i#_{`C#}{X^nt z6(j^#jpchhA@g9sY=!MYJAYK2#h_9Rw48dUu677stwucZe$ViAxRkTE#R#8^)x1D0hg)sL)e6%~&8Zu4V z!y^zD6~%SC$dIK)=y$Xz{*Z3O_8Qs0?#?UxQV51H4?rAO3Bo*R3eM4htJdFa3eM4c znx#|QK4Gz;7{UYtacH*Wik6@9>S9TrpG2=mi#E$*DxO^%nv{O@&<-yYiXpTCh*uXR zLzIiOb8E8x&Z`nTMJlD9Lq&H`m!KiScm-&I99dOur&xo8Un(Cs!?Y%&UfrokoDs-Y zJ*SU@Xo#>#v^x+7wTx~+OFViS>dl=L;8M@nU5GD*etpA!|FE8i5qq7aYN47Bdz~aJ zaZ!gJ6mn#zGYdgXC@kFs)x3u{7sNfBo(?HHG(Tk{SjrBJ9cf1CJ$OS@^A-m0(Urg! zV)I%`04@@ZEVg^U#+xEU=!8v@Q(=QwWa+00vB4{P^3#Njc#l_AkXQJ zW&RTaB8)2#Z+y@^U>Yb(#=o^pINZc)sZYiq;v&8u0>I7%@%UfPL27G9=q73*>dzI# zABcruHMbQhQfP$~)pEss5r}$|*c`Vxt`F66<>Iw{<dB|nbb&_`c%3CXWB_XO7vi^u z03~`N+enDzpeHi@Eg`>jSqx2xWv5`zfJk69d)CTj%5UX~o|edQ5ii>1GUYdjXMI6E zq#Fr+AJjwI5)zV>mnpxM)i!n_$2qAcFD;iSzgq?&74$>+m|LmzGP^fOK7pr6Kv0&T z9&$Ay4i^)$h7d2=1wE1Jr$Xli^^oo|A%}^2NcE4``0ef4TT|EaGPyU1&75*Mk4uQ9 zU@nt;lkgWZftSd=+bZEaFPF)^l@mA(DH$i1V zp@fE*J7s$>U*Wc!0IDEJQjLVj*JXO|cC(=g!8*Q~_R3{??{;&Y76eJUkrs_^D(@!J z%_t)(?{;&h3Sp?vTe%I1l6iy#!OSH-?{*WYm&;r>?dHoY=#dm7BY#}fq;1ZKkSHjW zEF&#mL$Hj1Q0uzP=M9oeoB6zz)f+3rEN-0<3$GCM<}LDmna~>~^i2^Y>3&a+uG!r> z;~rge=ubxl{CWbv^{1BNIU=;FT%!0^5^{_hQ+$JjINW85Z{_3%aNICG_V99<&%51G zXXP@Xcawsw{%&rC9-&V{&Jt2$HC)}TkhzEDGI=+7)Va(q$&|L4>4*i5kt$%V{99kw za?LV#x011A%`$g4NRJ^5cejxc<-W|_4U$98+}-UCWfKxVm20ZGyU7IKG4RdZt=w=6 zwjwaXhB<3$V_)X(2FWi()yznbK@EAgfS_YSV}x_7)J+T=_fs+el*`=RAR*{^nWwwm z;vnTx>WGlsR!?>7lw8+L(+v=UikE4++pV=y&=^tUl(5@{Y(JH|>Y47%^7Vnsy;<&+ z&NSU^W`fs@KEPHd5hT3BMIOb@!6!HIkJp6O{NqxdAB>L zuoN?SHziHRQ{8Q|(k?|~36(@tMz9zO6EMqN5oxzME&O5#u6oIt!iqdVekP^vD$8 zg3?G6Fk?xY%Z-ys!9tG9#HL+DxGd!UK9PBY#6hT-%o`*QLP(7ikSjHsi;25I@&irW z-9~0t6{JRnkq~q*X6^=wO}ps$EhJ7F@{1BQ9rI&(S0~cchaRLy)HYWRKeKm3vy;Pb zNqbzxJFynyMXEwV3%!`W8zjdct}wqR#^07SDL@D(qccKh_7oB*=!{@o_mk%!kR3=q zC23N4g3gYK_kfspV)W+kPZ%gntQ$&u|cag?e`?H3Y9 zsVW))AuWn%k#7Ayseq^kGfz?|jx3sC#LCoc$&bOHG_cu$%T-vSCb zE))J96iBvT6Pn`ajZ8lks~UPESRlQH^u(`k*l&<2n_LkP@oP&qIYbWE*MGx3jtx*1gtE@7{L=bU|Q*-J1~W9>`EL%&#Apz$u6$hkkv-n069j z5fb}WwYUdJ*!5M?3qo?a!-YasM{Y`}j$kdck*A8f?7wRvGg+$K(E@U;Yu)Y%zJ24?GO52H7@~G)d82@02*zP+_hz9HP}62YL1YVv zBP0qUIG}Os#>OCa2_ex=M^W+sxl0{y#w~OHg={~R>j=&gIx?1a3UKVF zYvtYtj<4I`hKdycZ^;%ClZ+UTBcNuHB`Zad*akL6^UcIqP!LhOT;U4?I4%-)brWHZ zkeI3{h^Qy8xFjwph+sV6IM;1`K|-V$iMa|wSKgu8rCs*k5vuJi09ldgG8R-TsEE*& zHJJknDk9j-L~r|>Q4zU}T*+VlfPNd`H9Hq?ltvijb?59wR|JEirocr(L!`M(xCqb? z!8EK%FCYZdugQ58`oQf9oMAwq-IluIi}hG1O5A$9}DKzv{E%|*=%%z}gnrqvza zT@Vbxw5rK-RS*oR0>a1N6bvjR_5c(_w#$U03&D_SB)s|vhIBvWxr$y0Mskh6hFf7o z(ope#3USnZ;n`&*PT;Dnk#PUeL=1DHVXydk7J1Z-F~IeR3+F7F|_R=Drxy9q1GiCbw>6jaVMF z=*rkg7+AXGUP5yIapS&)gn<rm$mA#oY1V4*1_Y-NQZEg`YxD!|D|coP&kMYY=9UE6#4 zO@}Fj@lMEMbQc_K0$LVX?$J!Kd&Om%Wexfi@7N5IS?^5d2JUWjnkA|OmC z#kh(cA1s&g*+;1mes8oxk-!u-RCJNDH--?0*a^X~yi%aHDB)xY>G3hs z4YTealD?E|vwZKCnMS;SkGJ^GxHKdaXbbR4Oui8Y*_Fbfh0G?p@tQf`NTQ+}ulv4( z>?}-?Yvv6c2&Tw2bHOAx42%0pwxmK98W#7J+UG_3N=r!CN#xO8M&fb}L=7|IdwzYx zeuHe8;S7xUu_G%y={^hji%oxrX{_YQpP0j8PW9$LSM+PE?$@4&S|yQoA#tcB6}7ue zSXZRIRwHq_MvCp_r=0vEM2(estHp`JLSn^N3bK(EFFx+tq=qPDQC~(z)DfqMkvJPE z?OQ;cXvr1FGPzn_rIDB3jKmcjnA{au#B!lFj8ZnV>MrBFgCf4LBP2o#L_}sJj_RU8 z`^lj>3`&^NRxuK9f&588SeTH%wJIchfM%W(5?5)WwChGJRkC zz&)=&bH6{sEpuPLh|Jby!uW<1)^80zIux+oMe=ix`!WF-U@zCvW+TAv0>Xla0Comq z=g3g%)f3^gC?qTb_+GC-dP`)lCo-~OVkd#`wbKkU_zen#uQiYwZ{BK}nY*Egy#wj- zn&YNPzYqQ?mBy`juE02K9S>(_Vz5DhV}q@{!(m- zFsknTL}vbWK6LIMGSIHa1Nhs@6X6Eq@r1(2pTHT1*7aGzRlR^b zko~9+QQ42zuKvfz4~szbfjB<`B+O!v^Zfc9E6Q7$m2bY0?PYuBW(oh}HQtb4-!R(h zTv_#e?i4TFNeft@cZ`bN$nX+8)29lXqx&hQwsw>UaJ;(CJio)sSjQ8o`FUXj!nxS@ z6B*t`X5O<*(d|Exou3yjRyY--dBT>QR!aUrj(;os2~(;SPh@&$o{_s*AT5k~-AKu0 z#fd=$M#7k5H`2Xd2Fp`{S}=Y*f$e?o_AkIJINyL@pU|s2;SntUnpjb%2vVL%^LqaE zX5FSd%j{f-Z{&C#zOTxm`zwzkl6ra~#a;9E(DqNgA&UJL;uUsEx%V9ym-mUUhlrAS z6q&>8+8d(7!uvyWdSQD*mRGi~r=*+wiR|Z(n;Z3k)W_%i`h@5j(l4G5buWkyL@VOk zkFyFqk>wTr>nWI?_b0NSy?073GjGV5k5O=TE>1TByYbtgloIDBa30Srsnk4*w4AUB z^ju0~Hb5$Nl}}{#_gMvFSgaOCetpBxVl9edc|3>W%ljOLwJW~)MrzK+SPS6J>QCU< zq`a3Dh_coPQgh%F^O+v*eJV~Q#hvT z2eNFGy*;&ZiMx^Q$@cXW!DXL7O!OXpgeOE#5S{n7{zE7=pD*cnr5}ib9^ao?Hj}@A zoh=jl4qQ>ObiE60lz*W8e@%o@%>aR+h1>9D;L)r*`L4lwQS$W%S?DYv_~3#cabkcE0NpM%BM)f zeDuxvT9j|(wuj;=kh7m%9rX{0rn zZ>sh4i>jjk-=C_ty>lZy=i&X-eTGPcSb)c90XZK?$=P#1Rdc4?NXupJe(GM{Z)E4W z?tW^2wmorCk5zzd{Qay~@1NfTCFt{e*c9gDDa8&yk>^XkmhuEzu61vM(hrROBU}Ah z&t3CO7>5m#n8&kL5NUj@Z6Db0AC(l*$C0FxBKkOzR5C)_d6Xf}>O9{4iScfD59;H& z-ku}4k~Ub!6Ct7O@swzppUC=rimZ_NC^PGG+zC0)n$7;~)p{x8?fKMxj`~Ux+hg;r zmvV%kNdM#c8X~;QC-PY6D;a9***v7Sw~vN?Vl?!w&rPl3DZ`BWExiHtPs^Qks&-^LfR=i{k1KfjqE`SnD0E-m>KDFx3K8}s(a z+!cFb)a>+J*7G?QvS$mO`CLjX;qQ-S}B*|F<5*KIvpv0HEk!8coQ>(|}*-2dwD^#G-?M;7vUZG|EvN+JXT zYu+~=e@cZ6AKUz%AGjj*ar9i%o4=LM5o{_K_)vaN2V9E(I4)FOe8fPNg(08c#Tt~) zZT4pbR#Cz9>$}jU&_0!$)W7Hcmj>K=9ls_cRu7)fJ%r5yWNLsV`4IxLZMzn7rRUf=yDXb%|?y$ITPrzLbey!OP#?ID1+ z(B)GuUgNszvd_J18)d-QhYva{D;W8MCrb~9{oBN7CxW)7hX}7HAZSs+X!!dOf)*9J zp-;&=42m~NqVTzVc&uhMqwK;%r1By_BLQR#((}MoolRr`i=r&42;_7HhUwSJ%ra* zjV~(k2&s*0IQ>0Hv6Nt{z@29&dBdEBi>u+7@*e z>*H11=n+OPJC8971<7USF=o$JFLKx)wBXgJRP{c>P7uVh&-sRJqgZb3H*C9@F8si@ zjnp2uGLTqy{w?rs$foN>+K!|RU(z;-KidM~PnLFI>LvdlkT2C0(Sk z^QhAcfjIUv2+=mbzN&9=u<%cx>i-eCJpJUMM|_CQt$Hn5%~uh<_2lVQjN%uIyNd4i zu(;8rLALZ|aaW#cfpb$pOZS7~W+O}!ikn+BVf#qp<|U6}yvDK5_9x*Q^dZgMgs~S9 zy*&mf3gCCAO8{Z))zocvQl3 zP>k1knAy!w8v7QkTLm&Aw+PK$japa9Fmc63q>Dk!iWXhNT?}F<3ckAgg@rw~fVDRW zs%;^ch{sU0(oX;q(c#7I2Hm~(EU)2Fq9cGn?Bf#Iu9g4@Dnv&)p7_E^<{omCdy%=( z5U@YU+{1X`2hBZH*-kXK&M=lyyp7S^gVh54Y{LS&?NeTK?jd40>D+?Qt091JZr5J? zl78;FY2Yv)wA>H;d!`WHDqJENZ;A4)5+f)CFr1kH`Dx(r$=Q)GL68X$;%XS+pl}TA z_I?Z;J~=&-w9Z4%#ZjWxfe<)3KcZ@n2!@jl-2_l}alZXfTC7!o;2kgXhL4-IArQb| z=#*&elgHWf`J)bjezFl8^>`ZLo_7Ph6OTyW>boYNy@=W^cN1b>d6>=fF8Q%XsBg`? z1hiKvns>>-!+RNXTMQfC=>|kd`w-{bnA>95FmkcN+!oV@cXk9bkbs~6o}O$KpA6Et z)z&i9BmqHlEivsp%nS7fKOx#1>a8AuzK2^_5Nc|0yI--@M zpF()+LMNtu2=i?`eW*_L!FmT*IQw-H=DQG&GW&fAX+MH`t7w^&_EX;w?`pR2&IVt; zfQFFWnr)$wmBm|Bdp2BnXG1UF&YQ5_0te%@AE>OI$WS2J31isVy-P?t4>O&F32C3A zdUx-K_dws-s|!ZEMl+HfjZ!2YXR-CdFwooN=w`6+E^ag-pFM>5R`K?5LpEvMMy)4U zINNYXlm9Gn-O~brv=6NtJpseCZk^M+wGDDLuLU;{z$`r%m}`B7n_hjGIwC^r#Z z{_^B?vyBc4Az3RMX2EAC-QfXtnM0JM|vAR__++6j2LKDYq1Gi;NClKJd_ z(O!>R^4WQmHM#UCMT_}HaZfcrzEIrLY~hRIo<<8lDDLGs9px%|me@O%C~kJO4q4eE zrtzZ$zYC!Y`wlo#INl*Px6kl0T6mSaV~tQ>*|17NJA#*)4XY%yBRmCsRS$VwteDK` z5X)<6>9vmR?WJ!&f_2R7PldAU3%&jITlyBEy`C41n}l{e<}ZyKh;~xYE{z*Rc7|

sl&4;?zYHd29drO&xbu0E0@|pkPn}HmCd9RQ!p#)okv)@SvJ(g0bH@VDy|~z3 z?s>S_bY=M9V#73Qoi`VoeHkGxwm(&cK^va*h-5FKU>h`#^3xFXT2Uhr>{W{9P9oTw zFxc{{BXQkCYh8UvobV7LdCWuXVALe(d=9gNALcbY9Z$TO*Td}K>r6<(deJsXavuty zNA>|u)6S8-QQIF7>jY@^Z1N*wy$OS@nGuL}hFCrQ706g`6!ew~LFnL|zkpL`08KkU z9w)4Y*9YTz$`|8dTz~!1z6DvwBf9SkbQh~yd0Z0Kw&r*RdZVC4M3c1Sb83vqo7w1L(`MCSrYxaIG+# zi1j5_b@y&isENN7P=l~eJ{p2#4GUsbgqFQKd?#U@N7!llt)}Dx5 zuiC~0c)yHvWA#j7Z=zZIS+dOy?#-Swps;hi)9nBy`3#{ix|$I7)n4doFxMG$!J1B^ zu*JK=0Vt;GPsFQrLN%kvBck5lCObRqj||0NoSAL<)No+}aP5qg6&I z-o(&g`o(d-N7P_|3%!Y$I!xGxHtEWH_Tmf|80?IoVg07r4lCaz3!lqrU!u&mv?V}u zg1EuQ-J@i%AHl4{BzdJ$Nvh_$H5u#(E#Y9Z{t3d4XE9#?7(oNC&gcpY`9pWzZ%tHo zM%8UQxI8YT6h>SvQB8obGvb0z+x{m8 zJA>*r{p>(t<#`(EvBc z&m^!T40)i`Rp@p43Gf+21bY>NTEl?F{1C}nt^q`_^Ej)SnM>_h^eG5^NDw$8s0IEe za!lJ8j$AcnL{LxdW^*~721B!F6=<0fkj5~#hO1PLFzsSv?V z=b@s$ zcsYqh20L-m*;7phyY~~`PXdRhJI5ET7X*~{UDA^{JpF8fBI0n?)PTXxIJ-{2W|G0a z#GKaiVu<(E>$u={BZrZ+>&prQu?Itq0I|dyLygE2Nz(^I&4{)OLwzaijLj~FdT3GS z#i1UC4ueB&Qu|S`hPy>~3Eofop(51xG;Qo^@K_W zI}fwEnu82>9%eE=$zU%cRo4^ z64*IZk(cr^UAX4Nx0dL_)s)X=v{Jw2GK zEqokRucdMpf~YwNOD0|qhnfU-L~619(vCJGp@ox-L)tom7*@yVE$_GXEdskgr!^xY z*g<}cMu@(?^25`~s{Xi`H);7vO0n5$^F1nY9h-F7;!+;4$c8zcIa{)|t zhT^Dw;UGX^_!iAeM5MGMe2ey?wDTBiGG&oXF9X zAy_Ty9;RT@M}i#LdYWVb(#}vEeLvod0y0*WcpJ?(Py~<-lZvt8!{uf&+If&AS+$|5 zJ<5OPt(#PgN|$ay!&oj$U1bj_cuAJJswsMwx`5FxPVsR}xD7|AhgIKJjMD1yw zLP2iV5I4u|M7J*r8ka4KHXR+kUn7TaWedUWJj|+mHQ4P0)Lz0h*zH6PpPJV?Sk2L2 zglqKHl2D7%7M;H%PkS=1b^eZ#!!V)Lvkw1e4z?0lptqAyOZzB(`!RC(6eq9%YbO!B z+#SpA6NF%3gX+VwlRPf zxs*2E)a#PS;fuX4i5%X^mMvN*eX!SGf3$B>-Gw3ENtcCJ;1C>J?w~-pW4<8@duZR9 zZ&<2a^r_?!r&&H3?pt(hE&h<<9#XXULxwxdt8qz)3mf7XH&-c%*j{+_({y0OKk-4w z4!IoenS|aDmK_Dyg5QQ#$VkE#$2sI$PZG8uzA*%;Wj%{_BY!F=2JMEN#0bY0o;S3@ z2}Ms865P*t!?97PU-T(WuuwJ+vnNH@Z%R;9Mnr@=971ZTIEzCe;M#)+n)5J}BMi3h#;*CD%?C}MDZjOE zLfwZyC$@6eoZn@76Q^+W(mq?+M?< zi-NUtcrSu`c*1`W+`|+8MR1QQ-0}AFj_h_G;qqNKJhQJ%4jog+fTChjj_CG~qSY9n z+lP7EdSwB+opU>R657Ud`@`fOp4=ZMH#VeoA00P}k{`>>&p8D}GX!rEo{y@8@=k_(6B_z9@ z2RiaWzdX6GYzPCXJxt_Q-jM9}Db%+vq$MBJ7slJvu{E3)0J)u$JJKg+tb1~Qpxw)p z`vdJ>p50M#%j6Z>p{%GIgxeqhA&4t%|zp~Yg>~<3Av)1Ui5b`p&iEihSXYU!%?LyLL^$|er zVKla%W!uyJ%6>GU+r^}>PFMonE+&2Avw?0GlRmL_M7MV-o^_6=_KV9Vx}BGMI9EY- zyEdt2u6t%r5H>*V!p|oN8=!XK=Zh<6plF1%XAS6fPVAR^4RpKk^Cf|AWVdUZB(fH> ziO+vYW)J#OBP>tsx@Pv7ZET{qPhqZ&I5vOG3C8~utUbmD=DG-Z^1@u>McYv8M6@C8=GoY7=mh)c)d5BLOPxv=O~XtbRbIYb3qevLNBcIIU5crs1hc;>(gL#!JZ<)P72V{8h&ESj_Oy>BnSFmSqO0&GGb1o^ z*sHd&tt&X}<$O@0oA@R#N_3;i@$5;!C|vCl61sagGC7{tlE1W(?B*maW9jdc0gWX^ z5ua^F1~-(^KZwspi@k`??da^(baO67i?Iev`|0d}fAgKS_Dr0!@3T(G$*syFto@Vb zj8*s$yLqR;a}$YJC?<>DDy@gs{;-?TPA%ZGspfqrx;a7328+Ew%?WESPWKAdE;O=l zd3F?2$Xj((jb_PP6%{jrGJCv7OK@|3M0}H(y?G+Fi)d^QT$0+`3%D#&yST`<9VV&0 zzgfyewU0MU8L0MdnzGyki#m#5^kgW2B#vw4UyK`biS7Rh)jrpYm0Z+O+-~vL*B|ZM z^mbvGeV^fe5*pcVeNf)4WWw5wM$WHV2}0Ie@ujuXEKX-<9-XfXLN2C{VIji!Um33V6KI0tx#26(&??q$9K#ZWlFJ%Kuex{FzC91@}K z=M5w#)LqKuvrnCz%NmAq1U6PQC#buCzlmdK=gSK%40E0?LBX7;?p-9|gs+Fl$Co5r z3@RJhLqV$h5XHFofs7Q=5IER#G#al2{7v%vNV@MxKKszwscBmdhC9ziy|=6x?hgXE z7)*xhwTIz;;)D2Gia^%cdq{};5b@V!GCei0ZsZ1pa^nr zA8=ka7z@R#hcZC!b37b-xJf1t0Zrs$`G2Cem-T_!#R}u5k{EKs%COj<+c4UC zQ+0zx6Z&Q9=V57A_*>J#t5~;&Kv$Z>5ud9t4ZcQGoA~YwHWQ1O>uW;I#4kW@7*^J^ z6Ozi7k}Pv}6AOpy-7LmoD8$>B;a&y5^@9M!cAl6_AXC{Q+vdQDRfb8{XA>o{FVZam z?n2+{1ziO9`sUg~;W%bKSqOK5ZFAU=OzCfqZJ1TYYCZ3H@yhSr#6Tk4=L=dJs`DbE z_ISTyxc9UHxeWK7&67m73rMSD?)t;u(diobplFG2H+44MPd}w^6WyDzvxX&i(M%rf zY;Y)qo%QY4MKb|q*0+Bb&E%oX65lSxkJK=stjE0pM-lq?Vr7%x{$OQ;4atJYCTP9> zC#tLw6EVyqz6@F5+J$=c!yB~r5^rKG`R(;hj3vOmzKF5lw|CKC9e$DD-o=N_Z`uq) z;Ch&h_mk|`i%@5qQfnt~IYfB+&;`0z2HY10OM3gEkoPs3j|pWpUjX#>CHkxH>nRG# zgMTHwU1-;QPU00vNtwRp%$fA|5B_TyPsW--32ag#{xuQnp;NQ& zS0Rle{HwV*gtwnJ>=p3#{)W8neEXtc=1mw*_HbQ+ zZ^vMwuF%l(P2>rb%RVoRUjcUY*s1jxilZj*+xrLD75w%l;_6A?&|liO2<}K>qwc== z+d7B1-{+-yWi4$=1aOyPJRk_}#=ZJ^iNy&qSRFWp*<>ia^P|}W_tugP4um^`w3f+n zA>7BC?n;Ea6r;$9aGwIawyPNV>i1ok$xSI{k&)pp3asNKGThG_=o-S4wfcP3`tQ7P zuB5n!aIVw)JsRUok6(^Ea_gq~7CO(9-a0SY{RkAB++|{qKKQMLAe0xs6={_9=C_jL zzQu1%WIRzQP-=c^YCKEcYv8yG#A@_*p%W2=m85qX+P_$>mE^QHtCbx0CRVF%HE`T9 ztJmxsCC7aTyLuAa-UNu;&Q+1yUW8QjJ85OVF%@H;kvTb{t{Su(^oa#_^gP&hoQj%F zqEwEUstLq4x4mZGn%s7hVpj$? zOD6Aai9@c-JJ2n#Fa0$ge1`a+DgDkA%X7)vxP6f=F%5ER~!5sd%=T2AI_oq4wh~M9ZAV%Nin33$&4<=g^kA>Ve z?|A02#}}fZ)WQv7M~wu)sIfsMabd(!l%oDFfps=&7DikDxMJLz7B=h zmsQ7iMhS_XL=00!yfc_~44u+(?d(6LZwZLGADSMs0@{zG0+Lt9o56=fM*ZOQA=47t zk5Q~_0|f3*e+8ccSlRZEn_{9vNepY#SYC)Avyc=V_7JEl&fq1rP7T~lVDnswBJ`Zh zB(yd$n~n)@p$PqBm+}i`<|Bz&{3XRdZwZ24vKdeC)DO5KS5J-9Pls4~ z%asjcr%F-zmEfuM#dYKoUz3o(cndVR3_VYDYFS=35IR-go!o4$-%2r?cSjN=O_@w| zD%&+QQiw!!m`Us143{5RW!w6mWO#2H#}jYq%XKSOhT=PJFF_=CvN0O_d#EJ$7I8@b z_i!^=>mhDt;)YL2v}Su4sY4%1GWn?*%YC8AW~8Em(RVjGe10hmm&?w#7*-omFu#ap zOy^Ts|LK?#;`E_>8=87cDG5#WnKDn5wPpH5B1nZlFZ)6U4NXOjW|L6!JgIt6%v9k| zlVz#Ko)5NZ7pw3*Tvdh6Pz*tYDatQK>J+Q+V%}M-Nx?67EDQ}P<}Knsr6hY5F-fH| z@^8FV;BS-T!V}-Qyg5W9U5a<27@4kb-c9FQ1&d&NDn~zWCu?=^tpbXPb8;pmPgYM6 zm3T`rX%C$}gwUGB7i7D%Taqhq>XBj!AtIFe!Ln6-e#^>Ul2e;DNqArt5*?`}0|w#s zIjJOsP<=gAOx~+vqDRTMe|Bx?Q|4T=A7p(1c`IF_sT}WFO!O$3S0E!gx@;v~&T6!}}eKVj{cH1xlS%60F#!&Q07- zo8Q{E;i>CQGbTJ${Ng;Pc$cX`(4^XWK9sI8 zj(o^MIXZf^VhEtBqfb;P`+D9SXLh=p?CjeU{j*j~dxSB{6c4(lK&W-iHAnUrpEoiZ zeabvNH6txzSI?)?l3?x3G!#O=YsOya*k1LGr)K}S5Z1{6#ezbk;xWbAg_zb!KV@H! z6yNB>Nc2m>MyLPKaVB~f&L|>bC;fJYnBVn+Otl90Ahv0^pyTwLE^Hd6j_UGIy9TsA z%+w*icg>{+vRB)0Ww$r+o9tB`Xi|Q$_&vl45AXSi;@)y4i=b6034VpMtia{|sukjU zxBDO$Xq9f%{wjf1+w~bGRyE=cH>Z7#wlM-1-YDXj`yEDpJ5sh+r+;bRrmuFP)rWuL z)*!d!_`+INhwkA+DVL5j@ypvh^p>$R*{eEo=PqmsMU!n$B-=prH0_|WwM{;|+1m34 z#=~Yyl=(yxZvoNM41}arp01v`9w;QZUo<@p(X4nAL(%)iBA=4Xd#|t47f#=uFy#}; zy!TCg0R2D$zi7$>;Uq`3CGy@WV)(itZbN5lQc?#q`zX##km}T*-Uor`SZVNVK-eo4 zzjTwlTB$gf246QK+|!Xo>{TmzoEW|e#et`+DygV5Rq$2)8keWgOLI|Cqn_ZaR&@3V zU&U{>O|aOjM}l5-VdFL^I0T1_8=?^s)Q*&`p`7jy5_`2$aTGb&+C#+=A~~yFigqK+ zYIC136@k$sjd2KGE!xHj%b_bCiu2qw9-dTA!dZvL@*&FN*HcjV{PkNR2zD`gLwA}Y zYAB3RRwCGBH7!L?C0M%+3dz8%MdvGBf`TsG`l`!x^_0IZE4He*DAH|6u-Hx|3Aa_n zMUfswq{SkD(*=pY7@zD6QOS^n z9BmRht55l@m(bZp#hH3jXQ6mC6wYoO-kte8$vZS()*kaG1Y6Dfd#zXw40r~A^xb>@Nz?}RwKc>Li|DS@0lt$x}CoPD>sa&ZZ`_7 zHX>Ta0;`R#0e`^Atyu9LK2>g1)9N(f?S}EJY2+4ga_ic$PS#vX{$}}Qz{icr-)Iyohoyoev>EzBUdrmBp3buu>{PUk--%%D#%yr&8xTy}n89xM>ffq2s{LO5J9Kt( z4VSdz^-rl;f2b-UoNj*s)3z?fQ7uf{cy{`|_|Yyw!LJ}gZ5U8;D&0!qUG{{)%1uiC zzRjq+-b^z*+Yph};m#B)JUMA=NUZXb;#?}R%9Dz7sW5G8%6z-Na?q?-neQu{{Z5XP z#eAr^7z?ItOz+>6I$6w8?lRdgjpXN*DgTn>=bbr!&v{2BM>WgGMR9h*-<;x7GU4ws z2Uxo`ZR1oaxz1CHQl(Hh$ai@GW^YT1Q>CzW8&X_x0c$r7^31iy$rd23WUQWwS43oF zO+K_1O`I+z9=d6Xr1`5(E{J&MgS8vaPL^}bP{k2CWOoXP)vy>dtW=$xmDP!GcH_xe znH`0*8)CI*nP&>H0L8gbVyCy(h7@-ZJFUf`mY+foA_ONoVeQu5D@;@PPbdzupdeOz z)}`R!FK{aPj?-+EDT0unxMW4#yGW>v8f z@+P_fVdNHCl5@B;t2S_w3chYzD|Gt>#g^if9&FskdnphuZU{bFw$6x&-KqGwKAYxp zD0;4wlCAytGo4}gvoHx8x27$eID(B^XdC6wzW!+6Qnr>aomYd|+tl)a;gG47;BNY?8mVTnc$2XC@Pat!K_*PR;DC-^-DXmsI?20VlYrPdQZp?>E+| zbcYqNerwt!ue7O&U2om^%T*Zp^qi_9rpvPTvGrref5}x>xzSU)F=+`)DCg#2(GG1DX+7w65@8>0ikTwB>A-#PH?P1+Rj|T2#&+M z?}c_$Lfm$~vcd_jNO3(n6prt$qJkCNROOXx3}6Mr4P)qb>D1Jae z!EnNGT$kSpW&V2P+Z=q~`gm6d!uYMK%Fww}7{3))8P<^s;xiar7*iizzxlrTEYX;s z`o*t58aVKw3Z(A7`+yl-Xp`JC8#Q0Gk}H%Ayd{Yicy#>;eNf*Q7OMT#FFtE&VKvBvSId;zY^MlIGrt8iOK*|od}OO;bo zIjr?|i3MEWmK47sEHPjko0#=$hHKihEe{rNRf4Otpq!8DbU3=C5s_G*kt5tNCH_R?fTN9|{{6 z%Ki4K#k{9+05)&z$|*TVz~&7%=t#GjfXy4bIEo`92uHmQ4%OlNw$$5@BaAM=`R<5- z%^RC?;y-VpmAnym#OGE^&h5QeQ%iXm4__xs8Na8811@iDJGmh&T;8e_N7V3nV^hxU z4uQh1oNOS0%^RM;*BCiq^X9G-1=O&4V^2=I7Xb`brrKG2=`5ASjh1Ol7{9S6r#XCv z&0F8^J{j1&aWJ!$299nY%{GfJ2=9g*SiGrc$H_8;OUD zb+m#v=6wnrE#W<#W^jFDbI$EXgU1`2a}rJ$@OWc$&dN5~U9^VxbiVDPwl^oZ;Q6-S z-E(kwoAGL}gTWitsh$=*7`)Z`>e7S38+W@iT!q43t6R_m&o{g+KRtqQc6E#v}2DRM^yA@>K`E zZ`+-idaZ@a8^#jL;oHjQU|wVXfXy45x=X&=z~-%J8$WHJY$=XEVe-bN?#K!_Si1H3 zZb5~oTV1a%Rd~9wb2?nQwwaZr;GwEo!{CPu`wxY8|P-=4L7xoOF&=_*QL0c1LkmSqn;TrZcZaq z94~GW-r4`Zy`O6l;7mB&;W)m_ubeQ4V^{pj=>+a@?4!=sx;?ap2fqRj-jHX2z7`GF zvOI7E2V=MO>IOlP!3fRDD13!J?`G%-0ZLb2BZ%xivdh&n$ z(Y~Q*1rLT=n#y4VS7f^72l5dzoxWU}%1>wsZ{5Wj*ue38ovder4IDx>Sc2&_0XA?P z;*&3UQ0OXj@{xSx3rvv$xOQA>DPC81t4{- zMK{>JAtbvVdjTi6kW-&K+MpaM4%=Yvh5!teeI9G%h_)R6JO*70bJrCxPS?WRPFll{ zq7A$YEz1#{CPAxmc+~pNLH3}^u~6v}IJwb1FI^1-R&Mks9GTODvZc7{8}4pPil65& zbEA9Sxc4ONFBTQo7QxL8(H7rQBb64EVcEDbDi2->u2X()nNbyHzQU(V%d6SH@^?eBwmTv7gl4fVUf6M^7%i!`m&SI7ownVEWvI|5;j> zBl1^**5yvg93Q;h5KCWs)quHMl>@5+aQL{pVMl&!rLvRjG6-C>688% z6=rXU$gYQTh1=VZqUyT}gEyX?wDPDhctc2rZtu2Jq0e)&(JL(9Xdav{(-oF)L(0r; zl8h83GK*Vd1zs@6Zt z69g6B0BPG@;R0v-Z@p+$xWEl#ZDNhe3r0+?1kXu?okxeqN666^?I>f}Y70hHpX3cy-Wz{g%EZ z94XbmhU;^W(R_si9C$J%9JW>9iZ+$$NfeQP#DiVRhxC;Nb7-AFjnhHlY`2`h@a8pX& zy2>|0Q8-@V|0d|c_635JuHXs97s%K;HN##~6^3v^Ff?Buv*^?ePYo6BZ(US|ncJ{d z|B@Uia3F`LhFa)MNFao-U*ylmix5%a^w!0UXc`sdr-YRlzRZ|KqB8wlLHI(vvD&k=1?U~A{FM39W_1n^?mamA#s(dKhSIwd=L1+7} zj+-yiB6qB-94XBL9Y6bRviaf<b(m1h*o*G(QVBYxN0qX;;}Ix=cSMkVBEOeFou7yI-W33h%cj0!_{oht>K}s^{?2 z_@|%Kh$Hlg;W^>3Qol#syZNyBpZ&G@&8*bF=$i^BI6$dxvmcc$Mftc2Z#a+wBh%{@ zPH+G#W-ncZ5nPqvyBS7sMXa7ZuCj#%^6d<3xb+Z!DlFfIm_R9X@p3Y?Ug7vg#8Q%k zs2nNEtyg%!aVVR+PipYCAhAeq*A1hqmH-VV^u!iRwsac6;q9UA=pVcsdn?gS27fp?25}&^QXx~tl zPFS{9RoK9BfQJ{%schq=bP>Q9jwj3nsv7LTpy0p{UT{qx^6x>Dfv8mq?x`Fp+nXRq zNWpO*yy1AZR>pmBf_qc7DvaQ&$Xm^Whtg>Ax;%G4F?q{jUy#Trrk9=zaDp>IOrEn9 zPH~;FR4g~Y(1I0?a6DhlPxath zE(L{$FoY`-RFXpl7eB26yiL{F>P{6@IKp)i6}4zuVF_2I_^A$0xFTGlpXyLZx9nbJ zsc?y#`^90b@Ps2kvERo!7O04GEFR9uvVAC8P@!_9dBrj7rqFwss4lZ%Yt;}tP26#I4SA+R^@h|oFVoXa9%9;uXbKb`~%xi_! ztQMFd?DB(xfE2I@p7~Tqrj~+oe-(ysMT#RtC`WtI>oeToIGD?}3>DsQ9L$vgBFx_q zwxI>X1BEQ$5MXp%<;)kDw89P!FTH*YL7_BCsuEP1PN>N(3!uhQT(Yk%p9Xbp>sMoJQ8g9Eob153I0*kxNXjFo+wXDl17>VG!3uUiMQR261F4cegfE zK`?T=4Qf@dWp6ijgJm4Ta5NYA+bawB34)&94+{7nR`icB_@{4ixWySt?fC?DafC@H zg1W*Wu1nE9UWo;wu>Jd)34GAjRE*3HpHEzwor-Vq+E}SiX11cn+E}T7vD!aE`_B+< ze>G0^5sF&@BCP4O6UT?Ov3al4i&MAVr}PbB>dIe^7%LkHUR>}WWi!Y{RO9h)Tjwfm zs(ut^1|Q=1&*?5YSIe)26$RzumU{r`8!M3cxysrv0Q!$&w)xfrzV@y&wY}i`qm2LR zLskFzo6eyS9Ku04BC$7r4eRzFTKkW}x_uJeHIDu0nm_rVsW5>P7~Xk9C`TB0hmRFW z7b#lp`B5s*3#$En4Gq@q_wMBXk3f%5Qt5rB2K|pnuJ=VWShxSs?SB+jLw5y<6yOnx zznw>{gC3#sztKUVxb0tO8Bt3C5eP=ckBrG`Xedr2RwP|I6<-ch89_SwYB!U`(7oqk z02N&HNUJSxBdqzY>;F+$9t|aLeiDJGI8j_D3-syFA+g`TC>b zwqxsE3Qh5fnBVqk*Xw0J*T zgFG`42?aqL%H@4mZ)OLv8tgk33t<%eDp`pHqT&;J=pzatuM0vMsi=;J3Ws>zDe16g zy3-h4!q5n>%qG+`HJV;gs00G>@0nku+#sGa)xT~tn5AXAKXr6wc4jhKVR8_q|J_39 z#Oz!$g2EGX*BBZyFO`bdjNtQ$8NJ_FkQSLz9Es9{QlIiP1=mDGZRiHjg=DKmDCz^M zG$9;R9GB3aZ&K0onjUi!JTusSjSg0NU!hUirs5?mT5}=N?%_I6B$Fuk zQ6+OADvnNRq*JM67tn9*8wzWwJNpB?r^&!%q|HR7wTcu!Lg-%dbL?mkP`ZllAd^bX z?>`Jo@II@I2MsW!XfKs@)13_h8VOoFP+9&+<6jO{VOW3<)SN%)A`n!Z{9xC9rK0+w z$}V{+d70qlrc?1!6kEfkIK9b!=t;#B278ck&@E#Zb^%W+4pyNc4&k(>BWP8p!QBCs zU8|ddV^w)uQ(4{%XYtW;B??bGIFaSovOpSwO2aF<4QHjITF&aeK`5R*Xtmy{Xd%0@ z>rRTZn{197RQ!}+3!A>&a~Imd5OknhKu-zwdP&K#@2rsSw_AV;Pt0AvV8asyzp9|c zXi!+bce}EFY!~n*tdZ`%S~?T#uwRS(7G?a@}HGd^(3x zeq(w~yRvgbNlv8*Z@csT*3z&n^DxWp6eGR4SgtSkB+5 zcp@Q8D5yAD!fN?W#UGkV0*fkw z(K|_k43r0rE4mc~`lDuzBCoHX2iZv13|?OoA4>ZTUSL+1cdSeU6ur~4BkX6g9yO~4 zvTI9DPyF)1dc;9167GiXgHn_TVE58#RFtL={)U1c6;0-Y5R`*p(@x-v(x!#YHnmaF zdk$enZBo&c$5xfDPbohGlB662U6kvJ&b#d|Xpr9272{5g?O6vDFR z7RL}t5M%)>&R=AqJ1b9d49wIYD_A=lu^pVV;1WMMvge$IlK9P7IVcLMe``N?9?Bef z9A*MGxd@KCNWrQ=9z_xW1v{QpRLRB)J03-LB(OHF1r@zGv4V}qm8}kK%U}$O?s1w1 z4houan@j^~3#a`aK}n$~;)8;81 zWD5_ACU}_X7RuTNJOHmTX{T)a=VS3$$%TV+j=r$gPqEZen0@t9T>=4&)wHrOcxy;(M8wK=SAH_B$S$W;Qn4@IF zSeI=e1ijc`c@N>jDA|a{#k{56_!Ng)T1Fa9ciZ!gYir#@)sRq>#>2uA?vp{UZhkjC z0k1)4)x|Uq#bEZKJqAYZIM{RyMj!1II0&==2S2 zRFq(0&fbb9PNv(pKIOAsRT&BkNiEhep>2g1HdD+z@SNZ}jRPkYUD(Xw{=^JWd|}Ht z5MGsW>2|*Jl zlUY2b46>PYD%y<}hPr$MVacg@t5i zlv4_zQ(4}P`nd*~ar*Mb*#(MLWcf0@wI3B(cdO5JqFvt-VYd;X_fh%h(ukEDH0A zzFIXpP#8utu0-5=_T4dS3;Qh-gn)<%iWVRG)H*DTTQzOM;21xYR<3-<`}(8(+;_&8 zLQx4CT#qY{JgIJ7K7tUG`|Pw4#D}u15;n*PxuE!&G{qb5w_vlAva3(|*)c^0fTCCS zKDE-+PkK1?sn8gTZU&^`cP^R~y|Dt=Y zZXwwSLf|V9+>I*_GUq?I8y6mA%e!M~p-!&6`fByJK+)-3^6iA+Yj_JB26JCs!|3}! zVix7f`VdV7gNh#$G7*HJGmjk_BGFG8z`)!XeV|a3F2a8y+`<2A$21V!6!Zee@0{9=R#SK^$WXKHonL;~ zd(?ND031976?JDh+n^@@Bit+xT)xgH0U3AsOY@&Nsi>iPA{e* z|3D0p9vzx`8WlCjYfkG_6fh3j2Tm$V0Au<@&;~^|RGjgtB=c+(5$8H{vAFn$>)vRO zy(k1@puW>1ddNVK7unWlpMASL*9Y(;12DR4aN{uhdV-+2fUJXdP5G2 zeW(2xB6AIHdX^1W@IX-+I^HidxM_wq;&^bg-3ae8i$5o+WqQ@Zr>c{TgXV#oiZ1lw zdXApGPkif~`j9U4Q3U~_LwVPSRD*C^uJrodsOUk0*LnnOQ1pTddt-#(-R~??G?L*E z9frq<*ziQr3+gat3TX+AOwYv@H<`-6g>`;=I}6MI5cP; zSScuagt;+-Z$9tZwt_gQ-&Q@?9V0sHE8Q3ejRJpuFA6NCevEJ;e2{YH9bLbxubd&_ zZj2uWMN{wBAMKk8t`J(#Ydo=5h;05!CK)V`aZC2)5{yCnz)e9c`=CjEX0D=Ib+u5jm7rQrSn__<7@mGv+4MIl=E3Q^iUH z)iKl<)7fXF53wt$uOyhl+!+6aIZrVy@=S-K z3coS+xa}+QxiD4hLP~;8CmPzVC`y4(G2&(@3gU-b$UA%0`2%VG2gNy*A@4u@trW_j z_1~tV{3Kk88CIdOUC(N_Efecdn-!!mXBu!1+Wa*tD)Sud<_#*jz_Cj{Lq%629zp6Bx*)&I_#}Xd!K3S{`E)ux$EHl zhs$rKMLdj)@e&V3S?wYBKL}c@8=m$0T=&a_nIcU?LxtLE1e7yv_Xo}Y1{GPm47&d{ zDta&sHLdlTd6;p;L+RIY0t$mIMz#77JAomnbOyG?D5UE2yWqt|@4rUH)9O*R2Et`e zt4C9JpSiFK(_)RVK@sB!>kL6_0I(=#+ehq8D{QU z=z8GHkV6TvF-0FzvH*%g^huLHB>mHYXUgRdfOnQ?n)3YPIu)nGNz1?eTG^T|&Fblu1rK9J%{0H2qT+$OrUrB3ZbfGShJPQ6bx;^I zk4)3Rt(c+KFa;83#mIC%D}`_;X3RX2KnZtZhFZA<33FmbT3Djgb>G!kbXPUuR?L_g z3!i+9z?^t+O){5DXIE#@Xil2Ln;0EXeN-3jKw+qLS7zZ>yr#DC{e%VgwO?z#Felbf zR^LxHu48_LDN9TjTzS?p;|t5VYt!&0X2gue!qE1L<)Qdi!g=QrI%5M{V#ZUjMrK$D zh4Iu~goiKjfn;^-`dX|hX-_Z(ZtZc*+2Z$RlvY_wO8o{9E&-)SU}^<0>@%T zVz;IPj>X}!4-L~)PgK9AkWd)w^qf&)S{nHr7VAe zgE0dgdS7a{su6msYG6*>U5djq%q&T~s&!yZjK*;&nx~;~9=vrxFe_#P359qXsU>G2 z))VRO!TU+wuOcLv6C)=9MUR#3rzeV=blGpUVfO5phBYzgL9B)9X^)r7?fNUeSk0|2 zOq6Ibx`c4{tBMPD#SChCbF4m@C#kRcFqjiFMnDZ&)u)aoLKL3q209AezV(z}zoqa0EvCD-sxXK4qrUfkott4-%rFPlo!rqXYSw6p_=H<=S+A1ORdlZ@ zi>}XX4R4mBE+H0JtjdSh3K{P`C9cc;dn|+H;~omOmJaMHZMom5;H^Cy5DV~?02y@Y>7D+w&r(R z*b;YFn)@6Zg8@Zn0%?+^>h#ksFo%SsM$uOv<&au+-VCP1-SzW&ZY)y>SW&M5N17zG zA3ZprXf$1z50_#MW_Z?xCo!X%Tk*eSJkOqhq7SJK=jkL^%##G04K(Ynre+N^C=Bgo zYd*Y942x-!Mn$gsFeT=Ecv~i*a4;`#0yf1QOd=|HZTZ>sG;DnR(SB|`)RSWNL#et3 z0$Gu!rW3_BOH>7Rm}n$Ab01F=%HnhtYE%h*yKX_Yx9ALF7G}fR%0~s_g!S&EfiE#5 znYz3}yM}DN`z?lnQ*pRC$d^CDvf{>{cC0X*Ar6M;XUJZfEk#@3u4atebp#9IVnw+{ zD9lA5;9mMFwO-t|D0mPvdbyob@F3=B5%9y^;B{%cCrkGXEr2i~W*Vu6EA?PP%#jKkGeX$z zQS=#I(_>eh28IbS6G_?F2oK_>ztvU^58|lrhDj(KOcb{0d~Uf6vJq1caU^NkA$uIx z!G*Y4@s*AA$yB4L@?20DZqd?ApXwS-EWEqh;UGqD zkpNA&5HqiId$!?1T-@ocQb#Bn-|Pn8rFwj|kEZY|vQG&v#2VY|Lx-ZVZSHH`Oq|5i z-wt15hSH$GHtl$+mAHE82rk5ozeuvxuhmL&Cp5QPVJv-n_IDJIV|c>bwgu=Bp71t5 zzvUpHGZQKT=$E<-h0zvVji>gb{);FMl;J|mVEXzS>`?nrC&qeFQTqkmlBue z(8R})VY|n<-x?Qq5O-NUXlZCObuwOd5U?OFwtCQ<1cgQ~=`jIMV#d;C>otB?`6l(t zk^lOmeg6->#5Tsz3n6TYqswyRc+X;Z(O`pz;Q5Lk9Qw>wbX~H96}H4oGhJ^F*b;}0 zMtCD{(GqA7!q+(16f?TMwj#U9D~8S^I(vwPn!HGqIoZsdjF+VeOo$H-$dZzB6BZ&EpmbfMC@Wr}1_(L@RN;jmMcnvcHzXx~&YvX3toJc=>0k9QV4 zil>dd6eGitxbZ;K%oL8qVMXgko0*d)Yp=bmY+HG0?u1G49P?!n22bM7gU@=GO^4q0 zvKoUYaal4bQ_KQo7kx^P7Pu78BgK!bMcDMMf7xF8L-D2WCoCyeIkRbgg>r1V=1n%; z%~=q`du|;M@bG=GwFpdmH_o^49u6L4_YyR`hYP*;x=SOWEbh2_^=aFQljd@I_-qlq zSU4@Vs@J3c6T z$e>TZ50x(dkUXNcD`=XI@iY%)bxIk=!-dC~wKq^`AbITsx83X>$HDDkrz@dGhM<7LtK^+)^u-{E6hU$5{2{>0b=y&gkfHa)F&!z~B4Gic$dx{E9Wa z>3Rfr;t}$h)EXPyiQC(p66VCw^dYUf!JN48K#LyD$DtAgrT1V?JgZDE8O_0*xbYy1 zqZqgo2Yr3hUK7fp&1hP1!kidEEEG)(Feiq&APbMQ8!ffa?6d1bay_6SD6d&K5p#fd z_6;A^-P2c;*Bh*fF`={gn+J)vDY}1d&m8a}Mz97&2%=*v4|_7o+_vMYrzWP$Zu7T8+a2hnw&1LP{4^8VR!Re2Nb#0V-=SH z)3GrD%itw64dtHpmVmOWOl_5HgfsEvQD!w0tcWq!KZdoZi9K^|ZsA2-hMjP|iM*^) zrmv?B?1_11lHLb<;x0kXY{!k%D(&YF?qXfgyO&cC6kOhP{2kh+dMt+n0~i($x&n76 z*}wj1KervSDOCo8v<;A1?ujF>fVogrI#lu8wC(s;YEH$oQ$m$+p4tbh&5rmb!D#04AU#bc^2 z1czy{hSQr8NwS5otfR*DxqXr2SZ9!=PBh z8J;_!oFn^eO=W32E{%0%g!4H#TvSF6M;c-X?6vl!wOGv$wvp7 z4cd*~IpI;O^`1Jm>@pwM`m@!c1;yWuJAj9|oRRtZqy5}>xC6KLq(Bo!#*AuLf{S2V%mKdc z`>-u$kaivVVOt#WcJYV8ACyM_hZD(u!2sY|%qVS5Cv4$b+`2xcwNls?hw%l<<3M2` zj&zrv*epKQHo5>2ogoxOaH%Wjs7HYm1pU4vLnJ6F(l|%|&HxR5#oNpV&lE>y8I2`l z+D5P9Q0&$Xd*WtjLzN)f%)@nnf+_N%A7EF^Uw`QkrHD535G3GET-Td2QHpRg4~YWG zK5tqD{EC;hvDrH8iM3-BlHg9<^dVEz;7%OkYuMKv$}vqtPR;NuUM6n%I3tp{p@U*m z692Y0e^J_pXb*jLh&A)jKcKAjCWOGOc$_yy1lGj;4H|(naTSWBdoNo^m2fiug{^+1rPx#**2GPW6?tL9nb<%Td-_8;Qf%=Jui_;POU9VLwQndw(5#Y| zKox-o$>ZW(UjmJ<38Yudl4;)L0%&~k)ytnTkp^DH2GIB#!P>~1YXhrdoGf^hiH`&2 z2#+IRQlUB08=(WI;%>~2&u|ld1{w0^ZH9n3JB`AjkR)_X>ET^GmmohL-NpnUdNge@ z4`*VdgiIoVGqF)Z#w0^I#tq3d9bUyt+Zb6>xC~6i2!x{bWs;42<#fSj=5+r&6_b{X zTPU;y5m(8(83|f4suT9aU05ZLR2OT8R3R&3&9GlJ1)iLdY!~p~aOX_{X%Ol72{Q$xnKf_oDIU$N_n|(;qnVk54!9O0YMYsZ4!9OqDLKT%Nl{U) z8I>&_oN-VvGM)m$}6xD@yChWEjx*qlHE{@_w< zPN0DWP|OMRSM8RVK&_4kOo|Cm-1iy137;94S`Cll5Dih5YE+KkhdFp#_?e4Cghlaa zZ(?HEqR*r$LcpOoB$$*2g~Z2oXM+<-e9Xu15qt)g4Ic2*lKAK|tllaJ##+Fnn5SkY ze+bH^uyViR&x{LEf=O`~+0uA2m=sqjHFtbOeVhqQghJ}$#cIO0c#ao&6DGw5dirLB zNpS)_#dLyAaY(62^ZTWJOF4#xiUR~U<0(?<@s|l)bBhiG*2QhVxumczJ|dNxeFy8} zEt;w6C$J^v*=PyXgDo*$&PL|W1GdCK(_Hu}gx%kKR`?W8FCw;PP%{jN32NRsQjJBV1VDQjny51mBpS-mHsMo)BC0oP8jiyVEYO&%#~mz(3DjQs zxP#>|MibQ@LajtMNP78k2M^+{O?-F4a(I3Kv|%}Hq_&x?upGu<_USUCuRj`Yy)G0@ z&rVb-Bui%}YQUIyN-;_fHpE@*@Eoo#6irXKNrWiVq>_7(hfp*R%N)kU+D-V@8$!`M zkaV~ZH(}G41(9gbHSIyyQvyoMZG@J7nC-9}9#Ra2iXrR_3L8D5ajXV)Zjrn_S&Vv0F~vPM6-(5yfqpPRF5fNO@Na2)PZ zauBAFGd=#xy@)tNd!?NU$1;-V2Mc1JnKUE}I1UeO<9Ey;U-F-9b+qRd8p|woq;j;4 zpC(JhnO+in2E$>FWx3C?CE^TYa(|VGGpr!@r$n4-$MrZ=5OuXniGt-Y0*jUb0UU?B zguFw*x5I}rl^pOKM$pyveQ<3tXIeJ323&{{Shsy2T*#+vD!z!fkTdNfwqQD3q?pVH z1$mOT{`0c=F9|mu^Q#n0g@O$+!Z5fMbSr|;wB<}25bz;hUJ7@UfA=T(+{{A*b=Ndb`uJ3{m!WK*Q5Y(8K)%(2YY*MQ|P;;@#j zuK~;9&^C@Dpl~cpQv0f^i5lxDb(k@AZZb6+@EmRw{BBigDn!Lxu*w>)fAG5VVIrYY zDfl%Gj>8yBm|W}i8jizV+Zccc$Kfi)Awy-g9Ti6n@E}H5UG35mupmZ^O2mQZykFWk z6w+v*80-flVuac?J7fb!#6^nJE>Lj7YIeg0yooWyNVe#O8dk(S3_FtroQNC$_RLf{ z0#y8l2Ic58IW&zp8h8xqxd|s?{@{5>rt#GpiXUC@9S&_{x*n7x#cxSf-o~&qbl3nd z;vpq(kVf*RXh<)qCv_!o^K^$`70s%8(eaJWbC^{`Q z-+n5acBtfyI7ppox4!d7Y5da+>dHnYD(29_b{H`@$~%2OvGageS6QO?jco^v<^o|uxki)vIQUO9X^ zk$d?EBhDOyNvjuHb0$mkmxg<83OOBjT8DC^Xa=gxq*2IQV~Q?KG>AXMhT9f9Z;eS5 z4TQWkCQ&qvj%ZRAQ8ewcO9JM^LyBWISP>&INBLd#r+}hqwPcVezAcM@uJ}O8ki0bZQ{@Xro;H^p1@6b4s$U3y&1H0-J<7% zZ<9OIqTkzLZ=ITcZwI7OaFqHXhbeEk&^nh4!{H*uFH3M7Mtl~{t3m;P;V#7t`bz%e zzeXc|{eD*VP+6Wz4xL?E)cg23M9j2sV^P3Q7|}&!8&Oo!0jcO&4m)AQ(h-@%fqO6l zEt;W8s5->72oIPCBhJDy$yuo&l%^NjkwSh9l%D(1+>AQWCV}{vcD>NP{%GG&h?Ie6 zuwUQdCyap-?!W>Ds@!xN|E*K;B+nlr#glv^YwI6Btf&cR4&gP6Syn2@X_lK_<48*J z%LlFogxAHE^?}O{qlZ*Z@rN`wm-XzJ_?VW(qk)@CTR1(##{mUDwfvN6mmC*(q#?e* zI+!MJD2Ojgnz#m@r#v@l4-;OC^1ZXgy43Vv`f>XM>I6aq5@U$>q#7&&S$esCZF#ih=Q zC!L%|dQ7{tLn=HunG-|Ujo1t2q{m-H;}%}vdT{WC1ILtjjKHf*Nb!?{FH(n!s^)_4 zY!n;b_-!5v0t)0UJybMfqvGcY5(EgQOS(`8 z(-rts$>#|YAqb{Rw&Z^O(Y~c{h_g*Mm#oOIAh6NAO#1sNEiMLG8A7JgULP!e%D}{6noiz*I@d!Q}9bZv%gYuYz7fBd^j%u z7$Rh#_$?pF@}I4tc-BUuzTo$*|8f%&Wa_nF3oIMVLq#9KDhL1cl+6W|pyDZ;Yd27m zGem_aX6BsDWvfQTlyokUbt+y0=3<&%NvKA9GN@J)AdB|WHkHJ{7)QiewkX%v0R_ZhM%je-MOR7r3wlYT(u zV4LjY4VH*>DqgB(d5RQ=w5W1vgNmnd7U4`Pp2k`4gJaUq-3(&2|n*sa?;);%G6u3 zNoC_0FXo$-n4L=AgsdK=Vir8hTlFcwXo!~mPm#?|WgjY@%aB0%If$J=lVI&K1?Tcv zBdtxm0n>bSyY-jCk&r`zd-&()GB@P!AwC9*u1yrdcWvTPAq03*aTXE^M)sCX273dv zjprmHa(|8p@t*D#v23Y04aqJE3eG~36&q9>2te7|rudr{$C8F_{(VHq)LQ}>XlAK{ zijJFYGZGvL5FFa6ctL=DK2Sy`A=yDRs5lA9&ZJ4jZ!7F~T2vg8ky^Q__;rOSNeX`M zvC9i*BI_Fi&0?Lx%wJ4~3>1f71R+)`dgiLRj)LFg*|Z0xW%R{vz)Ho*O@jOe6&IkO zf3ZmM+X|E;#hETPSS~6hx1oiBUL1Vq{nEan5G+$=D8P?#AnPq>q;i6aZx6xLsQBSQ z>{+GaliZl&XMhjj2k!zqNeN`%s#~k`uOv z<2Xx(8G=DkahO3wleTfm3HsuDP|>MCnp%JR8OrW|3VB<}RG{u`Mh+Mc{6qwJ?Q_)8 zka^42ddn$RSbs}V-_=cc`J%t=|BvCdMClBb0@pF_g4)?v+Nsxi! z@$Jm=)s>`u1ymi&(k^aEa0$L~cXtWy?(PuW2~LoWySuvv4H_g6G`PD3cY^aaxkqyE zJNK>sUvJHV?w;zdsjm8}t7lL5Olo6Jw1mQ0VI-OG(-AD4wcO{%m_4~JX=o-mJ->#e zcdJR+x!RJa`E`XiL811ca(!1eB7(1}5mkO9kdU3s3K2qfct@855H#lvF-1@XQ(fU+ z&!JqsBeOH)BvQ1mg?gQY98$3bqX62GRg@JtAb7S@sCDdz7t% z5Lq@>`F@}ahb_#}(G!_+D0+{46m;QB|NLOe8`Gx;$)nTZ$Bg zw{KY6TQgf;4O-r(kgcfC3=lA}z#_HAK-f0Q@&vCOYyHH~!n|%L>pP3@B~A+VX3%=s zx?%bzYt)0vOG_~*tc=s_T%p$b38BJo7HYK4CL?kM+l%~!HZ|Zo=Ax@5l{KgUta|g= z1m|Og8>i77ZEEO7lP68e4uTSdhBlMlAsM-!^qk(nMb$}5@t-29$CTb6BesaSECZwY zzo&;0Hz*=JpO=lVy-Gn(WR2JeuimdNa~NK^%}I4rIKu(x73!{(hpSAA)CUlE5LLb2L|}s&QK0P`D4wWK`XYU)0;&g^y+{t=AW6Nbc|5mj%CW@H1`rSW`*+SI~EMY zldj>mvSV~kzTUVj_~8$hJ||~r!hfOMEgO=C4u3bWp$%ot^kC6+_^Z>h1$Sz7i5q-MWq`RoQX(28>y z9;!s~Zy_U^eUe_}w1KjlM^WKbjn0Kb3nO&-*s{kxnHexxyCIH$xLm+_h{u|cun{s> zaU0J^tISlyr%*!qwM{KwFgZ!{U=UG<#=_(rsQlBldev*ACqkl@W z6nOicSTFr(bbr8;jam*$nCmXV7}tGbgU+athlgamu7uM%1d;5Z}{sL9sZSc1S4{9HxpjS5WIRJvFPrO)Ut61bc zA+*II&xbReG+|GmXFl%~%W$NwqEjR0&CVWRU>C}&T`?gM>qQCAjo^7LP`t*vJ2i$c zs_Q8A1tMi!sp(z)maSv+-s3?8#5g!^1Uw(sqprX#6C!)@e6ht`|0&V!)Mbllx#Gaw z0|(k64DlMz0>vuYxhix%A(4P0f0-)$9c5O+8fSQHL5l{0c)(;_O^&D^%!z^irf#UE zBixm$Zs=Yui&D_Gb>UhI)@G;x-!lkr`RvDWye||Gai$3o+|~to>LXe5PBTPHWW$ZTZ!Nf44hT^3P8uT3Naw!q+sRAR zq-W7H*AvbqfKx{nw1e|hsH1cl)KYs$cEml*@Gzn zPBBmQh2^c6F^Xukhn;{-ytdSF%9Dmd22lX$!G1wrO!X@2aZ_pPts|fDIh}u4axQ2a zW|du_+u?+eyIHX6;S{@%VTii*q#`F9@APKq9ie#|xf7+5R}%?*UFlY2%N&L{+0Ws? z^S2(w#4TSt@hy9(lZuT@2C>7Sip$sVhgNy&G{Mwrb;HcNC5=MRgEE|&9@;%vPKv(Z zVmo&8xmw~P4Xf?AFR9w5^r_MG@aVlRqko+Q`dKEb-;l7?8JR2hIRDE~R4f(YYq%(7 z3LEZ%8#PWT{ODm>A;E|Uo^E*!+GrPQxuP#LjoN1y5_-&pgC;SnY3l4r_mG5m;qNO(7W!Hs8IZ?=Eb;Kg+bxoVE*+hUMKTXrrNu)eW?@P$0C$=!5x zMH-A%qK$a?76opA#pA3IRbYq|PHDv|4s9Q@J#UFv33|@3s_-N7%33tYID=iiR@kW) z;eZlqvuwQX5+|t^Z`15uik~TM|IItDl_K~4LCVg=FI`qk2ypIS*=fRnYuLDV3A3Cz zpe1(JnYBr>G>nn>2k(U1GZCfTD0z*?ZjtwW7rIc8X^qXjsCAP)aeSchjNU)0kdu@e znh*I2RYdayjg*8|SmK*p>D*IRZb@uo%vmA!sHR*5VFVXZySIyZ*-l&ls`Cm??v+`@ z*QpQ9?r###yH0H8TCdeUd~?dm-jCgVpw8mf&(`wztT*W4dp}F~CfRWn!B8)o2f;AQ z4p()2K-w})EDJ5Nq{N%@6QxY^W>ATb51j1eG0P8kEWYf)VY|U_b6aRLhV9Ke5|?c{ z#^s+5C?xTVzBJ}OORvkRiaczI?nu0BS1czB$J#?pOYTY;MV~(BHqE>d zNSx#+c->0f{eemrW#+A_068QzdFno9x0tb`jFx}`m8=Xe;`#y`c3ns z*usJ8l=;b51)>+M{AknyiVV@s|4V(1%FSKH*f5{`^q%J4ig9LYVr(q-G0M8xj6iIv z!}oD;vJuBlaFkTyJV0EkB1P<;kH-cwY6^-H!4{|YhdeBtltGl0sFqQbju$MjbGF2tXCcc0GY;h2Zzx6qM7 z^(iuUn$LrKWwwthj#0MWU=s+fjHVF`uf(LZw`DeT3Lqe8bY!~l#(KUxCd{T-K5uU# zh5qRfcX_}cZAoCZ5_4?0b5yaXc>hLo?9GnmBFg3)uGMs(>f$BPnzEJtqa~%z$GzCc zqlhHJJE!6EwX0z3u`es5+yt&G{FQcd3^DhWs({^164ChMi#;9qJ)ex}1*h52ON#Bt zPYX{znXXx_qo1lKGpmh1eDmLa(~|vjseDFwH8v?edbi@Ke>eJPEXlspgojv`h)(FW zD<%(Pb`xas#f585qz{joIr%eyf`WT2=IqVAsfq9XW4f`!Q`(e{K^$-AX38~h z9d8j&vM-O>jt*!A4`H@9w_R|wh?++l4n^e#-ou;H)$|52xxAH_``gX;KAqbQS=w?Y zyLc>P#7uW>*}9oMKAC->H#0|hAv(iFA6e2-8n_zGwXpUi!hcts8|dI-qXi!E#BjAVpjHCJFIxE>^5KPWxoPcCSA9!hhFZssuWEl1rN93oICY*stIA5b<7%5D;=S_0gU1o2t52(I0*^2L zWIpl@eoJ6@Di-$z;j&`OSn zhe;$0nyF}6-^os&E-gd4rN)8bT*0UqlYuT{!}l`N3^4VM{i}MN$(JG*Tq_45pSsDH zt?6bIDzm?+TGiaP4)TW}V>L)ZnYa+GSbof&fIPFx@0HavgzNo8y;suq6q!bVg({i5 z%~tV^IPFA2n9)iljq(7TfTSq0OWrUatk-28Sw(Mtpd#0*f3-R~t&?voxVqbjANZ;w zr#M2e4T?^ZM2kxLefIXo=q+dX<(#78`oxu{I5ZcaO4KhKqSa@{IW}Q*`byKMkF->j zG$Qv-c3&$}dlNKGP3D)`SGfz4(j zj&4@QwmO1x*#6B`HR4prz$C=AB6Kzfv4-TW*ZS>{8;O`yR0QBXzKaAXU8=MH%cTgc9NK-Ey1?WDTIhY_2O%N3Ju6eKRBf0<_AAO7@bx2@vz6dp zz3D*$GPoG!rFcFQRZoq;k8^!ucP&5t-(Dw`lGId~XEno=3Ulo*!AmnM0uaqB!cF zl}RWDAACI_;ijsjWuG1RN^ZQ|<3Yfur8#E*aN$IBpqqf;Tn$9+xnJP3{s{+AwskGv z;F(K$Ch1#8j)R(7!VryrFu#`~9F=v{NC*S96KtBQ(tvg_%H*s=Wl{tsrdvv{4YrOo z_>5e#(^r0BS|G7FBAau_oL>fi6~m^inFp{9M?4o@wzl28`6X%Qgp4E1Qs(8zEN#folH7;HQbEKAG$st`=u8GR4#j+gLX@T#G zpBEB>2Tv8P0EpzLiY3_4XE8{^4Ya_Ip~H#vO-mm)sA(t~K8dq2MSvb@3*pI_@UwkJ zwj=)7%;Sk}JV;mmu^x_`QK@LuN-_EsNf0CKh9Ti~s1LR1Bp7Gr2Lt5~TgI5ceAvVI z(qJ|9K|%gKE7iy~@Y~+@9@1(Wn(~m?$76c{_x& zZh~r%0-iO!q5;!S<`xk9pL<|lgH@#_i&EH{bBGr8*X-sDety(a9t+*&RpzqM?Pghz zggA>q924oRCs6?#cs?vrW9>z|^;pIz&~+z2@Bd6?#lWD|z*2xLRx%hFQUyOQ(x@7( z4CMWArusP-lI}#G%}J~vrquo?QB`5Aw*#8O2I;FrMa&aHaN^CYbnY=^d6O8I_;I$p zONd^ig!9<#q2^xMqS^HL54{K;mYcDrPFGlhE+|!|96v1#QU^%Fb;0`(79(&S$T(@y zut!%^nElNHJX8W9AsxdysifihMF=!GLN!Uyt%dMtw#1&piZ?KB9`n7FM~1sSkW(|i zbkKH~_M0Q4fg2l!t$Y9q~tQ$TxTlu7Lb+4jO zHmdHf$%*95xwgPMY?A;#TolNh$JE@RqQ(-FE(sAUSq~v~Po7S4?|4SV7nRw|Y)O8o zYr_^<_Q+Ggp7?go#gwDm8cK%QhZKdb0O7#!27BN^W)S z@ODd|SOG5_XI}#r0VjkEb6Cn(khf8gSm8Uq)pppv;ngRtR4uqRhKO+h3S||#75KyS zx}(!;k(6e7S?Ewk2VGg|dmGB4@f-vor9)*g6sn@|W^ybX+D{SvsGPF*y{h>ipb+0| zH@jypt&rd}v%F)9Xx{8NMBx-%OhIYHUbaQy!ZcW5x<&yaHA)Kf9C6|ypc>0IzoQP@7U;!+s3POG=I`gelN+jz z#`y5lMa8JRG+OYo^4K|g94bNWxPaKgN}6S!z_llp^`i24>S@9x!&Qm1kQ20dxqcEC zCNGqKCbQvD`CQ{2u$bUfiuGD4hRu6M4SH>krwCL=Pri;S?XP#nhKz`vBfUq@HP30*DH4)00(6KF}&2h~`cfCdK0#mYev)c=?+J4A%!prA#ob z(7Xw`YzGUnbK(d|$^mSjjmCPbnbRcqTDPxa=2q!(icS-OM{+CdOh=UB#e zT<1DXhht+(C5UY|14t1gF_lg;*A2EmoaoZm~kHfxG8Y+%i|+ryB{hP97PH7B$uL{o_7Nw=~j* z`kn^D@NJQN8v9Q@K8V5EFjPs*fq9L_c?_tm;etwlC`}pl@VM#%;^Z0rp42CoSUW+ww zMU^>a312r=PV`ii@)KFl&n>79xOp7lM|dw37@gWN3>m=$V+FJ#1Bj0z-duK2XmBJI zLfJsF@1j%jYOqi>mJEKz-{P95kT(ncrmr%IXfH6!$j)#7P#DwQ9csyziPNaUu{c%;=Xd83j#Qk@mbAX5eU++;M`uBH5 zIBXlyQ3WEqXI&c+a!YrD~I}Nj=!8I5hphuGDk&9O4sVOS@e0c0&@@1$?MLprLJ8I-RD!4=JkAF51sk;%T2q$b7) zC%lcua4?W9@3xQ>1BXEbq8g9T%w8@@8xbMU1Ej*lnQ@6iDX9o1nZTlejz;W|e9kg< z*?#Uk#!OzZ202Ij(Z=&oU?x@b^5c)Dw$3KByT2_M0D zQQS-yZYxbw>0;LP&x=w5RX|@_*YMcnLoRm^CHO*}0twEFLZ%cOgQLizP3u!>TFZ_s zp3=}x1!IH=*@ohxyuc}ltEk31k&3hcL@kZ2W1~@_7L;+&CrSf1y2Z30kqQ_0s5-P^ zih*Nff&>o*>sb;zlBuOGAssB3YrN!WkQFvJ92YH95TDAHxTI&)aLjV7R8U%l8(uXaAeZ_S);2c<6Q+X=tE^1IZn8_uh$N{Bf2E zF|v!9eBO6dibN-~7|Ps8N;kx^NWfrzaJm zXMhtMSy9vgsc_HZ$agO%wH0o1fRuE{baUqlA`9o5Q54#^<`6QBE7P9F6}vncf;fuQ z)9)5Af`N5LWkf|NCz1Y~8C}SVYD?wN(qIYbKT)R!b&by|`)4>GkjeVm13&OQAeW4z zen#y?_W^pcG<{tUp-i^gQ$ozsDJy)7o`Aw{LuElF_XXR~{B`d-)C5SPB+RxLF%5r$ z^ICj=%62P?4bZT@txo6GpBp<6r>9N%dDm=K9JwD2NIF=(5Zalb-GJ_}p!5-IZNx!? zOsY}~hxqU~vKHll5|A{J)U06x8rvL2dFLnYPK5E~0cn);RxNyp<06@%R+?AUJjemP z(RLJHZ9W4D1wELe^KbDyk)u__LfrD&nhS5i+tA4L;ku|Zx_BJ)cdl=uzyNz}L1-zI zZQXR12A=NfAfZjr;G0n7HLe+Tqwray?*LLF+GUtW>+?tM_1}rADOHQaOmAG5O4Y(I z=vIFWVxlGSwWmUFxI^Trv@`%IJQrNXxt%{}&*uqf_r}}Uma)UkB6c-p)N!XbAhNNN zIl11*`lqn8nL{0^;mfm&ULL}orQUorW6yUjdPf30uU5m8zrG~k@Y{s9#wDAi8+mg* z@i`Lx7F}*_mGV(|b}3s};jTe^KYAEl4NN?~-RM(=o;VsM_h8}sL8^D-iuAgZl_vdK zeI;rF^FyvAn~H29z4N+dCcFUPYo{Va82yt<>P++mbH zM$IJA$x6{UXf+1FI9^=H;i$Q?1Q&@2@X8S@s(=EzmVwhpt}AGJIPMQJ z0)^^j(VM3?l9(v^c48_+Fa|q31r&u66_w5;Nwm;s$i8JQmlIN|Gf;2B$QZ&@N8tpi zP^W2nLgpkr60o_oYI5El6n-f~d8(fqr)CkmnN;~yQ1`Zd223he3L%jo0In2(tBHUg zaw-zlo1eu`(^ya0Jbv$XN}$N2tc52ciOOSwvrc3{C7Fkm99_FoPwkOpcgwv?xBeZR zL|QVgam5Uv#U0p@hw|i{%v~m8abIyQjyC~O^T-4gznN_3k|>M~0i|1I3nT*9wz(R} zNN2@7^I&IheLs8G3$cDBETXb93uSt8Uexk)kAQXX)#AQn)K{jFjyN-)`;OFW{9qUs z`m_IF^Zc!Euy^{v4O=hdfCSzfgEwa(->%sSp_zZ5V`%9DT;PZGz+D24cSuaAu2iX0Ek~)P)9vtT*DL z><{6JUtKgEGp*=Exn2kuF@Eq@4CuI*jb1@ROa>4{$kU2TnQDIIMQ?_Y{F4E<#|4 z2eR8PkgCTJ|J{+y`6fzVa`B{bihzQu!g%LikjqTy@gdV__I7N|P*^?e#?v9eF46;L z!>2w@UyXhR9_`_`a@OfCR6Ykunga^&w4*Ls#X}lXn7Y&p;wg0_9I}F5FFQtR_Qd+^ zqoYFBH+S*VzYdU2ZFYRI{zP02Jjanr^b^ zsuP5${15RaGEC5F#_Bxgz33W|vPT&x%Jj7bceL%~V3#|Rwe{ME>V;bRK?%5q7$T7Y zIP=rPCb2rHQO-n&RDcL^YGQu=9TB^0II8b};^&x$)O2asVkEJ@k$xa`sUrkFA` zKO=z<-KPZs_RBICci4XBZ<^)_6)|C#JL^^Z;f=;w-sbPiP>*0J2}*bg;VG@f#N7_^ z3SGdw&9B(-=Pc-Yt7?AC8Xm+XwX;a(Tp4W402G>7L8Jns<%Zx?`$D8^rHUiBY)e9c z9F(xwu1MY*vKOD>62MvDcY34ha>4+&t0lAYR{ttdNOYSE#7|I^4E7){YbF{gIkP;= z7q+X8#1FKnXL65(*P*$`HC#gCz6{Zb7`|7uh?x<23|9~c2e=+^=ckgkx3N z!wM?vm?`T9n`6pVZ@?74HrU?GE+Yp+Q=M(9OGh|rp25Dee3c58il4H^P6(%1elgP0g%T9lCK;Y-7IRJk9*I=EiZKh*?@{bJ(q2+_c|G{})V z;tLB6@h-LlM8HB33}WB_O`>i^4a`91ABlsz_A!Y<7j&t*maf>e#tQ^}JNb5I_9{7e9-yhJet45d1s@`3~$bQ5dhKIQ6A zM%R(_W9GuSTl*pvVlpm%Lm&Ypy$ z;$JYO*h&YyF0H~N*_3a(oaI7MGFK+U2D^_i zWzn{hOkA)XpWdt&m`iBRK60r%V8F#coM})c+W3m-Q5|Su9=HtPFs}GwYr=h7Gk``? ztlfNEy%ygxjRcjV2@a`<*d_3e;IXvBCO6#0o9EaiwpeP6*x`ndPwO^#7MLYe>W-4M z;Y5}kAkPUlPF@rC(^%KEZ+LPxisRLK()l?%Cs2IAYb80K*V1XuST~PfoMq@e2Ff6U zs<;X#5T8hj&>yyVKMEfP&M6x-xG$kgXzEG?$J5}7+$%MTM8zVn(5bTn0od{th7fU^PYtRLzFXHr zs_oLzmD_?Q-C3=(4OUDV5+Vr*#)^KPgk-NWN>YDtW#yO%g$Xru6p9M{7$QiY#jt$! z8MVkTGM<$F4eG{3VnYNKX}2WZB9gfoCpeMr5lK?6-hhKT|3Yzt&QH@1F*DTO(tgch z=xR4S8K&7kr$jwjwX>2eJ>;!7{5S@293I2zz#3xChED$ z?D-&2YZGaqREl3BOq}M2M}i`2rR~E>mM>|;%zrqsAJNLysMCopTUMwm2%^XM#pX1x zKa}~ykvFL0h70I*CGG}B-h8uAYE>(FsengfIH+67gNnRfP?jYr0lHoxbO4eq=adRR zISGoK;EyrPj@*W!sG_ERPIQ+fOVR+zX@jdzP3Wm&89{!_1m;4>N|rOgjd-IeeqrL2 zDMJq9>t-z-^B7}6@oQvNsvvaa+=8fWig?di;n#tP7WmBkP@xh^Aw4eAmYdvFgv0qt zI>muyLc}pDs_O{wCq})d5{wH2f=Z>hdgtxY$f|{!)TF{HnV`o%7$a}Lr-t+u~qR|dVKun^v7wt&oh1lUJqM`1;@4*XYrHqg9~3V zQ4PzEE#t4^4a;n)RDa$LOn)5kemJ|S@Lcrv+Py63&PGGN=5ra^s+rCF6hC-g5&N1# z>ly=#LKnNJ3o61@Rmt@;z7y?Y^E2C+SDO&@M5*>hpM07A<+ zEXO5pQ7922^*t4j*G%aM!q%oI)di{{Yp8N9kux_yIOa$rY;eO5(`CFHF$rPiYVfL^ zw{st3WV~u9aU=?!uoy-H=@nd|vx3l}f3Hx>Bw>QTlUpv@ZzI^-I(J#6MLxJlV5-{_3I!maD zO4KhA2s(#5NvIo#Ma}Hime$KjSBCG$?;OR8h`+r$8%#%++<0qKJXp6vsBthWUu24B zq2?EF-o7cAf8!Hu-VV-WWui%F_ZWk(dcc ziv*EXc79u3e*<{5tHk`e-r+%qz=;p}yyREm(ORi_>*@((@nf<5w^z0JOWryL3)YRW zzQcQhCP+Rkh#EYLdY9vgldkr0^h^dA_EgEu>y!K_Kbbt^V5C$;POH~*5xP1ftJ5q zHeX4yJmJ4!4)_$})r;D)$aX(m-Ms$({<5E*w&K;I_wbj)eM<406pevoM+DHe0$$!D z9Ku?WuLb<%!AUk>&cr{93}~KwJ+Dh`XHSaOsIz${KSG66qe^xT)$XWN^0`Noo^x)9 z^$Lum6WS4PDPTWAX#yoiD@#2R{9<0$4Xy24Byo7@oqT%d7_A3dCz>^C9JMY5sIHttwKZ0+s$l=F|5T{kxR(%N!_ONjQ0KLDHk zj3i32CP~)IOK5%jgQJr+$Vu3L_U#|;o^hGTXhRtFnxEpihW_j^%&>L!lh?jC%5RGI zTojIq)yUiL6SJfE*+}DHH%HE&R06CX!8~QE27M7!yXz#gtG3;fR*~wW2GVPoCSwxL zL7hso4$>E$h0*+$5cDA?PFV5xvZbHuKBNC_%UD zHLIQ?=sS5MGe;Pz|a8t~| zJL0?=tvc_B&T;~)5(>9A8fn30vpp0=4cjs?;yk|rTt2t9_gLQsiw>S9>QT+du22LT zCh+)@$}}imJ6!@PE0hL^Xa^{|7Nx0|t(*}5lo{E9GL;#E^aq4NU zTb<~c;9a@aoPgsan5{qlIf{QW*f`PX>k)|FSX1=aMN(wJGm^E=6l$Pdwa~>I5atGU z#OkwIK}C4kZ;^2%0p;sQhRGEc=boQ zO%pWu1E~+K-R}K)$}D=81OqW*7_*`P6SFeudvL@mcyprMMiR-&6*fhlct(>ua9Cxd zH9YnCqUg~Bv-9J^s#IdcS|uxFZ3&wVMKNFX2AL*v9>kJ@#-2D__S#p@DS={;rxq^YY;_cYl6Ul4O*N}7Su)xJ(4307}+A^NFdm}kafu3=1t6c7= zqTTmZxw-K~bL^O-p>{IFaLK6|iyheXoD( zgGJV(9fm`-8?1Va)9Ry^stdt!1qy5x-RjJz=Stz*Q_U;s$}q3iGWO?XYvu=Q-*Dlz zcN3jiL5S&PJEFmS`PpymKT)kz%8E|j*fT?Oxne~!0-}JiaG*sX);uv$HXjkEgju9ew$R4}PFe()Qo}jzjaBGv|5k{rJzNy18?A!V|#p~$^5@B_IO$dyl z83eacf`P^g_p)b|v$1XqCkp#F!<-vhQ+yI^7{SZ+CuaO9YLlTX6`G=?^;D)ew?c}n z$a1wcL}d3J?{;$#>FQrOKsyJm&qs>X`^(~xM>DYp{NUo%Ec{W!?h)Z7E}~6Rn@53A zElXg`O1M|?*%64kJ11cc9yV-E(E~T8kaLvRyjf{RakQImNK${i<7DK3hTu_qVjM`x zG-)&Uc4Z}I_R86ez93B6j_CF@9#wL+ZjXncb?#aCyxq)_B;&RBM9E$_N^6;tFkHhu zXK`_pI6wUL8gxo0H9+UK4!3}xXsZ_ze`tB0MN68thg_4TywV-=2|EJd4yn}Pz7jS*juzmOEIxCE(SNy7ju>Gu2bUSqEaW#aM)IN(!O zSnH=gaq({nPp{FG{N9r$oqXSkO%-}YmlFo}ofUQ5Y>wn@Z)k7KNv;0^YOJ!w0ja%9u1&kS#jVTh2^V!8C`iyta@$nqt}EN z=~ol#(<$25s#!P=U=XqJ5|IyBL=C2Z*J82OxVEMh5_yQTOM^8X-0b*BLd0l(${c zkB8>_xoQa%;j!-D=D)+pdL6^MoC$Ef{oM5?FePTaBn zumZ?wmSkE_@+$M^484j3dzft6Q4UQs*&Dc)C*@UB+BzO`Awto?I&Avx^K=n?cVUN0 z(o~nDb$$>+^)xMY^C8P)Afpzccwy1kT|y^_FhGVftvBxYnjyAjm~mu!hgW2OfOs_F z`7owA?7`#mS#>YtSVMC9+R+>8f>WeHooVP^9x=3h>~)%;p)sx_ct^AfAM+jBFNfU_C_v8LV?e!BScX-qQ$7JYS9g~0Qb`~-kx9WWu7 zd4CnOrG=a(c0~x`FuLm7iXb55(okZ_QvCqnP*0^?FNpSmG}GI?S6zypblv5s&Hz&T zJs6@_K0d%~arr(UQ6CT3hUf8J4ElQ=h4-XaKZ6Z8Jv}X|9+E2W>?Wdl&`<4K6ROLt z9dNH!=XpNep44UJSm}A%vZ;jms;OE%tUh0CuIfELo(Mc`Ub*|0Z9anDhoDVOvq(>!=1VBJ zseses)wIV0p{-}5thGzwp%aO$tDmb?Jtr?hAPK#R?=rPDadLJvHMBth(8^Sf1KszWl-_3H)T*TG&g0CH8rs`6t;5*XfuMy%&aW*9IOB)b}o7j zHeCcz6-QHBX8;R`q=dkrWa?z+;%IE@1md9JXlJZ!>a5M6AR-1}P%(9P22~ezcNSN6 zHgq-xFme8?iI^RzITP2f0zW?j!#hwJ#L)@B_UEZTM1Hx%i^#mZAZ{S(0Kdd@0x(Eh znm7Tp5nhB>LeK?(IJms9L;!L7qbbv0P5)^5&d}M=+Rpq>7Jo=DYwB!h0-^wz|0Ubs z3^@Ls!Qb6LV31dk1u*gR|9PdCmj9BHL5Tz5rJd5>Y<_j~Pbw$Eud6U9F)<@BF~3v< zWf>8eUbOs@Wd#}Mk1RU^(~H4=H?Muv{Me{=n%oIkk!-C41B8p0ZXbk_0z?km$ToBnfWS-F1eD>Ea* zpM7Oxe9`@XJrMq;uyg*M|1-zI2Fm?b=g;#mDM*Wd{eP+R=atyl*Z{1oFJ}Jz;AD9b z{$IRUxR?N-eft0w&KHxv9Bj72Uga9$;iUa^l#|? zDhVz{bU3Y-eL*_&d^n8-V{px`v#ZgtR=3ilvRI(|>w2 z)4$yDm#_V&OS3TlqkRyVUvT(%qOPhZ>SXq8|V^B{)wUquV^j@g{pU?wI z_yH8)5J1v78@l|4x)&Guo%g>-jbD(HGqf@NFY!efG&KOt4Cr29!^Fk~01bn>3}V)X z=1u^1Ha1p91O_1|^PzE z{YiI&!JB=?^V7^Mhb=UZrFAzk*-d?F@bQyT^-)!dK&R)53|GfQkiZdE-6Lj7S4Zjr zcoQC0_^lVg=*TB`_qT7sVs!)+UPAM~PyK#H#{ZGM|0%@&Zf;HxtKZDc#KOeH$ok*x z&CUrjuu_@utgNh#*`<#<;2q9dX|n3K zx?)VDTrS<&E7x$WQqJjWuV$lLpq2v%+R6&o+dKI4?QLA!1p%=|4)9hf4lEk^dx|Aa zZDZn06e50^i>di%TbH9off_mS#TEu{nPQ}jsC(GM;Y=2%-3+Ib+jA~)p4vHiWNvH^@dg~)nVo2{k(Q-erJ`=sA_`VSb!axQ zvz%Nco&1^_?k3C+k_4gcl3?_#%&2ru2zy#=&qF!59!0`3mV0ak+o0xvhjp_=qsRRW zJO9o!+y|qwXJj926}ynB@aver@2q7gQTx7>byRkH-if;WMUs-)Or+FN(wj@7c6a4U zlw?1^*N~B{f@})kj`)hmwaDk3(~BQIH!GEL1R7b5wI}RCY?^yjKQqo;k&q5xUolIu zyuz_KVpSs!t?fM+SJxfkir5mn#T+QO`hkbF4GVx$gqx=)r^iAhu`!8XW*W2*S=d0C z<&1|oNvB`q)+Bv@vTpQ%xovrGj&DuAN>8KJ+338nNK#)J!smlNAZAfzSb(nbY9tCV z%8A=D3-&4E;$t`50SszBQfJ#)tzk)NIu#-PG4&yF!=z@^aMl8aqgU`YHe%9T)Y;WVObWPRmPNyCU5a}Cn|cAb?J^QS>M^}CUX>lOPe!J$YPC6XeI zHus=c>IgR&$s6nFdWWj(vPL*T$*(3H+eS*vX0esj8)J9u3WZ4dZr@G*xbi=k{Q}Q8bZ@^>#MASQ|IHK?nhIzD<(FX(5o$?_zdS*V*bv)XDb}T zrpA~Hme#ciO`_Zu86kkzyHfpOV@F(>ueLtVUNqw9G<5j0(CfRsU&D_&gYC!f5sZ>Y zuQt0TIT9UOY@}%CN}LiQ^iwif$E$a(DmCIyPPEaB1#L!DpwLb z{2yw%lG{b3+&>hGNG?3{hfhZ|KH-Rnwe^s?_DcrAS#{Z#vTg08zXA|Sd54UuWjD!o zdA!}Mel51tJ>Nxv9BAJjb5a7$GZmATf)SV^9AoY#sKb%deN{W1(2%|zHQ;CS9jVOo zOW$?f$s#9aRLmzi6=)C3^Dd|s2YxW{w@t8w)5LG`e8djl;aB2$wu#DQXG(I-_ts_# zcED!JiQ$R+0QqyERle@b4dvoF-qeX7d4PGS4j;akAnBm`^xl5+b+pkMd!t-gZ(noN zdHu(GpX-Qv1!8@P`0b5sHN!wQlnTcz?ypT+M|Ay%GMZ_KQQZWTILwjQ^j)M8aT)2{ z{_0OdJP=zSl_%ni#L!xA?{~Te%NL96zb#45z|^9SDMY&o#oPmbeng_57bhr8vh;`h z*pwSG%b?%7Kk$T0$M&Fa?e-C6jtJG9s2MWAr#`oOsR3=KdxgVF8t2&7aqAt-7KVx~ zMT74%yrgfMu@G)Xu@Hd*S0d9oWHN;MvdX%}VYG_CDfx$cefn(09O)Fn5Yz!r>)t2=S3bqOup32x={GrLNykzD$j&Kb-w= zDX;)tcU_p07?*@G@{rb12FIZMemHCHJ;Art5G3xYi4I#*QW?4&w2hh1sLyL$sVSV> zQeFW7A4p{kJB(t=6{OHe@(-F-O2oUYr|m1;K1PgZ?X2*?;F3x+L!YGdRoTG`g^Dq zjnS4-cEjr*Tkkq!NcbGfiXEHTV^3?r=pWl`>iNC!TgGCqY%skhI!!`@seKOC2keNX zMXsajLM$oE+NK^Gg?;KgdJ`N5mam+V@T0xG#X)ptNS>!(9*}PBzRks%Mz1E1?Zz|6 zVqht<$|k!ky4V~oFMs_S>}yt8m#$V8mOu>ylxz7stp!01qtZ8|Jxg<1&afG#+k8kC zmb;gBM_&2;fEBlsRipf%-m`qw+QPbmzw8r^9KsI0wD(nP*7fuFonH7EO>RhDNgV(C z-Bvbqmkg^yMCI-JWTPgY5+iES!(c}EP#@fYb>`?>(9~g>}s718uS~(kD-T2!Qz1^wS6HSXMW4DS)82^tFl|` zyyykII?6}zeMD#%U9UU3hG@RQ$$ypGSVhLXXS<=a@e|4(aI z9uH;P{S6XQT2Qi$B}0~3%#M+zm>#kf3Tc=bMwn?9OB+e3X_4uXL=n|PR1z)7URg?% zrIgZ6D_O=?ziYIi-uHc;-{-miy6-dRzR$U@>zwns&h`Dy%%Ji-or4;4*O3AtS=S@4 z&`zS_3YAArZ;>ONDLFfwcFTTz7Prp<{4`?>YVL~K4E@78Lb)ohnT)0P8y}cIS(FkZ zS5_NXJELjFs(V*+%7(|V+x^&qlGT*s&(&YueoLSr#e0UTKXG>0A!^V3X?a3$_vlLI zoVL#?iQOuVAFKTLRt9Z}9BzE`^fA34c{Y84N>_JX0FfZr1vOmu;J)r=IYd-$c1C|? zV#(F*frGide*WG#Tq``nFiX6&k@&EK;%xUxzTG;q@AkH{u>vRkXl2#xf!zTR`kh?P zgQhmWyT?Cwvb$R!q_rqqVl$Nvk7{=?4F#=+r2gpZwp6K0!x;I7g{JnQ1$T~i*E`90_DY#t#S|`@m@%WRp)OFn#^PV}rh}nClwYz55aD-G@ z?7Nh)C-WO1>n_i@La2(l_V@{p*VoE$U#!&h$U?R(%^>Rh^_mspozm&yTF2~g=hSsg zr3Wf1OlEMLo?0Mzh2{GFUGH8l6#l7!^RIkXk-v$2sN`XKOEYyKz8 zjkbnW^l@@>Tsj;>Li7xDS4deuk=879=p^b1YCH^Y&-V_pJ=^cB?7nWyZABr6lmrxdS=t;9*iOLYB@ix&!s#ZGDzXsfq4xwS;%MA3xsvT0VJgI@e546_2-lDOUK?-fCI)#&&Lw@<-z^(vP z-vxzi#=52p0px})^@q<1AKyxO@??XvOJ}6^38#o6tu;pL>eRXHle*SR+&ALlt=fZ5 zy5##D%4w*#t5;g03#%7AY7AYn^hNiHVA+#e+SZv1jAlhRUJM=R!5G{(LU?7YtgBTb zqjPKu^}H4s&gbj&-BYFcwtlgdjt>7LPo`G7MYqmX!Fgp%O5u(Ze?rd4JayHI7Mjc> z8)}}|ZB&i*HO&`zfHKz=BVVE2scTnxG}*QRCNy-6nVF$|{U)?;ESFahNT^69-quie zRzGLf7QTw(&dPh(_At`LY-vI^}u)QI=zroKSW+3Bm|G}qs3 z*Gov=mmhZ!a+;9cE^BRcc`j+WH@?HIW7ccmICfmZL02fY``JTs?W(2ME~G0NYo*$b z>lI&(IOp=EHnc)J=PyH&BPHqOXuicdVs~L0wQYgdmzbUP-IAnFgFP?yMy>7V>JL_s z8o!i_zb)=j{*-hltIKh{&uyW}vC$&t%2nNqnq@GV!#?HS{cp!^6^nm3vgZ1{kr#9C z@1Ex$n;zDi=kY50nR@e!g{qPUi|S_Eg1@%U8C-^t)UV3&ta=V9Z-|b1UtXW6Vj7w7 zMZA5%b^@+htY1xnG+2h;a5YnbD{Hj8)0p3%Ws13FI__|ds9m&pOexqYaYw(HcHkp#@eCxLQ>|I;nRBB?f$6iL zu$G>)!&CZP#>gD5$0~_R&h~QkaGC9#H_wJLscV~1UGDcXE(Ca|kaLErJ}{q#`S8+4 z`<||lLZ%8GG`HxS4JrDd5ODk5>C+>equaJeT5^!x^#$Ym$)p&CWUP|*G1S5#*F_a) zI*+gkG?nZ29fKg>d38SZ>Ty0;C42P#*uv5=0cK6r-AkVo7fQ-! z#!2kZj5;E?_<5&!e$UNlUew@1{N|WWVHWMsU{7y$RgHan7Mv;To`3Pvd&8P|Pw#cx z?VPCQRHF+wPs$X3lGpA$bmg^^bFUTN*FYa`Sz_v*+<5s-@q)8Hs;?KlQ%nv7t->F3 zgeMoRdN}{7=lA|`wrLh|>)GvbhqpbeH~k~-OWHY{l7fmDgWqEtgO81F zdTMNKyWb##AbzLrRsA(Lkar3q;a`tP1th}2_ z)Xq(RGID-aqnhP=*$*3d@~6CXO2udPhB57(BE{$1y>>b9YPP~al0DR{!l)#;yROIi z%3#s;WvXv$1qOpUv=}RdujG(8a^US}o_(qkLcUja`>iV1@dXHoTFO=4O%=z2l(9eL zSH0EoS;hY7khFoWUjL!+r9dKYK#3@+_-|dvZB06)#>czI@>0tM;S5GjB$hb-mqK!SNBAZS8drjXlST_l!A{ zbxbO!&dt-!pA+R1r|qLll~aiEXy|yjObJ$)dExxx_nLe4)z$dCF}XaqOvc^N(85bR zUSLOy6?0?{ppaRaRP9kZUVOJ*cofb=s$mvXw{4Q&c#CfCvCJpqoK;EZ$e}|y{mW&b zcQu?&>wlWBDTUo@Lpcz?rLQT=j~$ooGV}iHXO~MoTld^JAC|hT{vEy9tmCrTrh>ep z&MSXOEtbbE%(si(kx`kkJbClj>lc@rI~t;kE5pt$*5hG>!>8`?i&*o ztvkr~WgW1{W6#lzETQccOwl?|#q?u=+GkqrWl!wW-GuBobDzB1KsJXW*JR-mSMS@; zuE&-hAF?;8Py3=rFyCGCzJ@^`zi_ss?%m-VYQx358k}*lnmLDRZn9m9>*O$qc$UTt z+M1To(fmP^ecPf|JZLVGRaTtgOfRT*$ZI8&gJM@)-pyLlvhCERZq@YOQ+uJBg1QkV zg+iToG;5Q~5n2w)b%ESSmyT>B`C9L#o9zuZ11vi)Kea*MT;?Y?KXWv<<@(DDZW}+2 z9=PI@UDjdcTZ5i?;5=soY5hA!R-nPgrAzBl-tJRuiCU)?%k6rDmz|>!_$g27Ot0OE z;?KsgfefRv#m3MPSl#S_sE{v-)sG!H0ka2R9bM|Gqx**R(NFe@&{}mw*!@Hz{PobA znLgv>#exEhJIkU4Ck}rqSsj!y_vD zkOAeqoRR$F{wB-PQimmW%r>`z&1+O89btj}Py+ZVDG0VmH=!C+@R* zaDusP*SP!BK8f^#ajs1Og*0WAEwS)x+Me!(R z3%jaYglgB_SvmrXh@@WX^SxfWvT}#UC1B4k79^V(^^@AIJ_J@YD}@ZDX5+4&DJeOX zQu1xS|L?JpAIm*a!-+&fu>{=r<=)SR69}iQ_C%L|qu~@S z3V&Vf{b)D=gfRhUOj)Q+;N_DRYLno!zrUl4#!l`sAyp8w&k!+5aWM!4GV3QcB)VK8 zRDlRp#f7R8{85TfFzhgcFDJp5lgt+4<_{^(8=5OWBsW(~5(3dOM3`7JSrHSv(oj8X zeSlMd;c}pG1KgSHjT}QLImGYhvqdlsct0^QF>$217-TnOkC+6oFD5B=1F}dMKSxL& zrDP0)UysSCIS#p6IpmRbs9a*GUD&3W7IA`qoG+bK&(F#7+vgX>;_uj`5qo%d0zaL9 zBq5!@Pg)S05EH@oj^DgLLaEmS?`;GVs4eCgQOxR@P9wDQ`k_0{>|={p4)n~#MbbUJQ&YD)qqos!S5<{#q^ z!H4DyS%0jMK9QuDl9`9B=8NVaehabw1;YTG(gI9=57mC$DhOP=_6o<^D zlF#w;GDG>{8l$;VVSFmz$1BjE>B-+Ey@wxtSg`Ma;GlX*do_3q=}syA(U!Q#U7`Fq z<*39h8Mz6kQ}(OR;bjb4WQ?9lN=lX*r6kSFk-a-hT~-ozTuvtIpq!kT7`CTI`PcZL zAbL#hbiPwSej-C24)#A_AvESEE@WmA4tfRvJ3xJD{)`ZF*oWdW7?eRZhq+@M5DqMB zS^&dtGn?kRdDUva%^Up)RG0-x*35ze_%}48a0<(aK7mJZpa26i*Rpo8U!f&Z2q%UI zvw}ecK*NKBLO8^5bJ)Z!L~t$=!(q?~74AlJn1_QCl*?oWZDeqvC}V;#(g4uPMo2UQV}wM~kwyq`7@@EPDhB6^rXUfh@8(#O+?-+$d;koZfN=n4 zM8Gnl^89FQbC|7@J=8XU$>DzGyFkHkAYkxsum5j(1?J}WqW~uK+c1~`9ijuE%g`fi z0MbYTsg5;5pa8_V8i^-j@I*Ah0D&YT5N7acnqcz5t=5321pvywaqA?_Nw+fDt3gPR z^c*Z#+gn;0LRSaSCMu06BED7{W2hUA%@Iuy-WX$yFh&w^SODdD>A3)3F%&O-W2htO ziz(nMr~Xja2oAtuiBNk+2rpd!tIrdLzu7T^i)MM!`2O1?PGLDX{P!^r4i+VaNRMd4 z^y38sM44>!PeShBjuNWh4~JPicF;tAQT^bwAezWG4hR$^@R;gHq%+yU6p$Sh77HNX zV8EFna1hlnk{S4r%K(rjX(D?qgScN$f*7J~BnDAJ{LNwEMpPP|!VBWUNN{d23(jTH zkr*rvg+u$G&{TvEnqY$WAy5zqA0z^S#1p7U6bk8Q3aE{!4ax=>tbri=syFAI5|J z4+3L2n??t8927xTRGGgXA|i(g211ltru%|HU_?~4srO=W zXh1odD#K$%#LcNP92$`Frpho#oQME9O%D$!ep6)_GzvT27c>@)_{A<3ZSso@Zz7@# zPPKu@6Q=uzLEwIsf!LisRv5sinC>4S@L{Lxp>ZaJU&acLFadzo6kjlyDKajb0%$qx z3C^x7V>1oJ6%_8mWCD6F*h6)J!pR|YCKMPGk%!4PP){>U8??>x6&Rci0gqX3X@$e$ smm_TOmMFlKw8r8wmZbl!;VokRa<~*WcOsZUNyMX(vP+gMcU&R+f81$=>Hq)$ literal 0 HcmV?d00001 diff --git a/paper/figures/CollDetCinderblock/ImpCtrl_E057_resultfigures_icra.m b/paper/figures/CollDetCinderblock/ImpCtrl_E057_resultfigures_icra.m new file mode 100644 index 0000000..7c50e1a --- /dev/null +++ b/paper/figures/CollDetCinderblock/ImpCtrl_E057_resultfigures_icra.m @@ -0,0 +1,119 @@ +% Plot results from collision experiment E057 (Cinderblock) in one figure +% See https://external.torcrobotics.com/redmine-drc/projects/drc/wiki/List_of_ImpCtrl_Experiments_Atlas5#ImpCtrlv5_E057 +% +% first, execute: +% experiments/evaluation_settings/atlas_experiment_comparison_settings_ImpCtrlE057_coll.m + +% Moritz Schappler, schappler@irt.uni-hannover.de, 2015-08 +% (c) Institut für Regelungstechnik, Universität Hannover + +clear +clc +close all + +tb_path = fileparts(which('drc_paper_path_init.m')); +eval_path = fullfile(tb_path, 'experiments', 'eval_atlas5', 'ImpCtrlv5_E057'); + +%% Collision: Forces + +Filebasename = 'ImpCtrl_E057_coll_FT'; +figinputpath = fullfile(eval_path, [Filebasename, '.fig']); +uiopen(figinputpath,1); + +xlim([6,10]); +% get subplot for |F| +ch = get(gcf, 'children'); +delete(ch([1, 3:end])); + +Fnorm_path = fullfile(eval_path, [Filebasename, '_Fnorm.fig']); +saveas(gcf, Fnorm_path); + + +%% Collision: Observer shz +Filebasename = 'ImpCtrl_E057_coll_tau_obs'; +figinputpath = fullfile(eval_path, [Filebasename, '.fig']); +uiopen(figinputpath,1); +xlim([6,10]); +ch = get(gcf, 'children'); +delete(ch(1:7)); +obs_shz_path = fullfile(eval_path, [Filebasename, '_shz.fig']); +saveas(gcf, obs_shz_path); + +%% Collision: Position xyz +Filebasename = 'ImpCtrl_E057_coll_pos'; +figinputpath = fullfile(eval_path, [Filebasename, '.fig']); +uiopen(figinputpath,1); +xlim([6,10]); +ch = get(gcf, 'children'); +delete(ch(2:7)); +pos_shz_path = fullfile(eval_path, [Filebasename, '_shz.fig']); +saveas(gcf, pos_shz_path); + +%% Gesamtbild +close all + +fighdl = figure(1);clf; +axhdl = set_fig2subfig(fighdl, {Fnorm_path; obs_shz_path; pos_shz_path}); + +linkxaxes +subplot_expand(fighdl, 3, 1, axhdl); +figure_format_publication(axhdl); + +% Formatieren: Subplot 1 +axes(axhdl(1));grid on;hold on; +ylabel(sprintf('$|f_{\\mathrm{ext,EE}}|$ [N]'), 'interpreter', 'latex'); +ylim([0,100]) +linhdl = get(axhdl(1), 'children'); +delete(linhdl(1)); % BDI-Versuch +leghdl = line_format_publication(linhdl(2:4), [], {'Stiff', 'CollDet.', 'Comp.'}); + +h = legend(leghdl, ... + {'Stiff', 'Coll. Det.', 'Compliant'}); +set(h, 'Position', [0.50, 0.87, .10, .15], 'orientation', 'horizontal') % x, y, h, b + +% Formatieren: Subplot 2 +axes(axhdl(2));grid on;hold on; +ylabel(sprintf('$\\tau_{\\varepsilon,1}$ [Nm]'), 'interpreter', 'latex'); +linhdl = get(axhdl(2), 'children'); +delete(linhdl([1 2 4 5 7 8 10 11])); % Treppen-Plots für Schwellwert +delete(linhdl(3)) % BDI-Versuch, sowieso keine Daten +linhdl_rest = get(axhdl(2), 'children'); + +line_format_publication(linhdl_rest, [], {'Stiff', 'CollDet.', 'Comp.'}); + +% Schwellwert einzeichnen +leghdl = plot([0;100], [-11.1;-11.1], 'k--'); +h=legend(leghdl, {'$\zeta$'}, 'interpreter', 'latex'); +set(h, 'Position', [0.21, 0.38, .10, .06]) % x, y, b, h + +axes(axhdl(3));grid on;hold on; +ylabel(sprintf('$q_{1}$ [rad]'), 'interpreter', 'latex'); +% delete superfluous lines +linhdl = get(axhdl(3), 'children'); +delete(linhdl([2 3 5 7])) % Überflüssige Linien löschen (u.a. BDI-Versuch) +line_format_publication(linhdl([4,6,8]), [], {'Stiff', 'CollDet.', 'Comp.'}); +h=legend(linhdl(1), {'$q_{\mathrm{d}}$'}, 'interpreter', 'latex'); +set(h, 'Position', [0.21, 0.13, .10, .06]) % x, y, b, h + +xlabel('$t$ [s]', 'interpreter', 'latex'); + +xl = get(axhdl(3), 'XLABEL'); +set(xl, 'Position', [1.25, -1.15, -1]); + +% Alle x-Werte verschieben +change_x_data(fighdl, -7.5) +xlim([0, 2.5]); + +% Größe des Plots maximieren +set_sizePositionPlotSubplot(gcf, ... + 8.7, 6, ... + [3 1], ... + 0.15, 0.03, 0.13, 0.10, ... % l, r, u, d + 0.065, 0.03) % dx, dy + +export_fig(gcf, fullfile(eval_path, 'Collision_Summary_Cinderblock.fig')); +export_fig(gcf, fullfile(eval_path, 'Collision_Summary_Cinderblock.eps')); +export_fig(gcf, fullfile(eval_path, 'Collision_Summary_Cinderblock.pdf')); +export_fig(gcf, fullfile(eval_path, 'Collision_Summary_Cinderblock.png')); + +fprintf('Bild nach %s gespeichert.\n', eval_path); \ No newline at end of file diff --git a/paper/figures/CollDetCinderblock/ImpCtrlv5_E057_R04_impCtrl_K300_wall_colldet_move_away_021.jpg b/paper/figures/CollDetCinderblock/ImpCtrlv5_E057_R04_impCtrl_K300_wall_colldet_move_away_021.jpg new file mode 100644 index 0000000000000000000000000000000000000000..30715421600165059d55fecf8b1353a86f937277 GIT binary patch literal 143232 zcmc$_dpwhm|2}@tFyxr2ku$NWWSN@tkkc@>Ig}(JnNCI#!lbCRoJGrF*=7zQMNzz> z8aga&P6;`sMv_9M)AxRTKA+#=@%!ud`+fg-&*SFd;oj!C?Y^GZ^}Md<-;uwQfHL02 z-35R^0007h0e{~BPJoQGG)!7b1_p!4%F4*e!xiK=Y>-#qsHz0l($LY?($Lh@H8eHW z)!%NQsfpZ!+HQu%U@$tymbTbkHm2s7UH?7^L{?T-euF$hK>@K#Pg8H#|L5D^4nRdl zQWs_qh3EqkDiEj&9!`ac_*hsKgJ9o`}+9@?Asq07Jek+Xe1>n_Vk&!__GO#=@%|$WL~;V&&w|; zyjE0voms)=a4UIL)irnSHZ|Y7-_rWv@sp?guI`>^&xN9a!J*-i*P~O@GqdmJ-hU9! zFMs*Evby%|`;Ya1>w*B#|1Jys{@;cDKk8Be>ynU^gi6BxtqUR%4<1kzNhv+F^hO6F z>@ZbTe^;6e+%flNW2dZvIq9=nXiUG{CPU2B*5!Xo`>)FW-xYTL|5s)IXJP+WU88_J z6av0^P!+%)`05>IZFXr+T1~+h-rod5S%Uw?ip8trg}neT{vTVb>}^MjS!JIV-amQaM@ zv8(LtIz(?2Kw03!jEZhf=ltxGto=qg%Q^JWW4Hkhgk=>}qzx5Oz!GLfnYTIJ1j>j# z9`K3f+mIn^)c`A0l!-ZCf&yB)hYCnx@J~ucIee`|QdUzjFN}@@L|v4YZhRaP;C56L z!GRKCng@f3;|q*XR1chj`o~DV^&5B?6SoH*2LI^e3>eS2r!5fR93QA_vm|xF<2!MM zB|S5GUYbIkI4>*qloo~@t+UIaMM9b`#0u=S2b7Tz_~gt`Tl%zVN!ZZjHJ8WM^5yu| z^|@aGQ#X=h_}rYrYr6Xh$tVma-}1Nj(|G2|tDB0re|wJs*YGFGe=_PTsCdAU59_8`xVAhXb9 zUAyoXP}=vbdUu41JeB?cE%xr%t5P!+K(m!H!v68AaLe+|V4j?aa-^Vrp>ESRvP|$^ zO+bGR_U7dyqfhjUVDM-qjKV=g(Vva|tGj|DWplob2i;?T9*9{B01}PNgEJC7q22S^ z68i#c`lpK~zW104tObXB z=h;l!89Uc%itgCbK7ZHz5mDIwmiYbH&585<+qzNWuggCI^s3Jx|H+IU9qZQpnC6a& zQOesHk#Jj_Ka~Gz*g0vk{bW!6jtei@Er?t0A(01;RgRR@$wigoU|9#Op!M=pX94PSdK6aj!Y=h!SIA`Tm@3s^8ell}j)# zQY}DPE>2c^puZc_{*^GJn2eI6Qw3Y08et@pTlXSovJ`@r+z5&EC`a_{oiop%7D4Qr zvjI3?6(8FN_JPf2jaPEN_n`ycH6EH;@H0#keLq`gV4XK@-jEnvifZ8l%%+~(Qv!8? z@yRAml1MoPE`;zxREF~5x6luhQBH;PsKhuHV_+mSLx8j^R6m4==ngdP3MA4Q7D#>W z&Ad$gN_SdKE4P~3B9JQdPNeFtSd{6&-xbrJbsYJ%OviSa$h=qRtd6lgwnt@5Nl15e zu@cG7RXox3Zr_7l@-m(%7Py7IkUM-5b+MHb#s{`kZy;|Vt1sg&?+FoYh-KD)4XvO& zgLmzx097wLmi?|oFo+?BxgIelrlqaCO#SklnG&+Z&aNVfk^uOaDo&OTs8?^=lu~$j z2heFmGr72fk9CX{)}L^mfv-R@5c#+ZU!t^J^pvk?ef_=dAn-a_Y?8{1D2%a|17N~*A)`DIB0$UHc%gYT)plT}8HQ=W zR!YPu0F3_L#9*|LrdsacdXDssuZ2`DO|JSyaqq1|NYJ*>9nDbQfe7jlZR??j!t@o+ zq1K@i2up$nA}k&7K}EvgO+ZBn+D!_Zj6_VLsB|f;91fT(kwU=ZIp~4YVmuZOag%~h zlzyb3@wQ&T4lOS&@i?p6#%gWzAl0TI2)nHKkxxv z_yzLqNItL!o{SpdV1QzH*aAI>3PSmmJ45t9=p#YWNX2_5ks-w^RiB2FOKRscfB24t zN8Eg9y?yTRYcC^ALUP-oqm2){_=W?YkJn-V zmQTw~<=Ha~bFkq&)j$X8yMzgI=&5)|6m7h%KMR%Ek5k|ycp=0rDM<%V0CUx_|Do&xU`SmR3>E%AFKHKf-n& z&*6hbab;ck+AIAg_jZ?vs>dj4fu26GC387t6xuLU>nl-BYniP2%4GK(^8`flTF(=P z9B*rNP;Q{{2$7K$HSoC0(qGHj$jzei!-YwD{aVNG(SA=aHHThI)B7}0vujUnd(S&9 zK1h(bbHx|b1v`i6XaQgZsVua0w#zrRrR*rG-0yoi7^GS#KIPvf;^G4WNMx*?+U zxGJhvH#D7Zr4%3&T2M9Ev)Mt0ZjlrBi>LxVKvqpGkh$J$3aQ$nbgjz7#!5PX$tK%65 za-#fT@%Vc_svSI;Ofv3iHn#KDczD>ezd%|leh8{nyE9N{-hT3su$aL_R-|2o6LC`i zp+n32$-_~+tt#jQO?l=srw2rEy5~=_^4lB3a0zo^i8ErlSfLB0BrIRy zs0#qyxt!T}UTFS;ClorA)h>mE4eMvwMk*J-SD(v%!bE>St}_9vG><+~B56&`1RSkH zd}F9OYNoa|*6EkB;gId;y6g%*m5`iYnj}|`@BwI@DH6yhbh0FM@NrUly>-amL?C*) z09qd9kn648Bu^|6Wwz_iCW$WUZf-`-OyrO+>d_TZu7M8SQA9VG{88@CL@8FE3IN8zpGZqjK?+Xv)owD{j%%sa!%GRG-E8U2h| zQg+m#b3PJb^iyOp!6vIf84wH1wyacK%VET`B)hpNovWs{(ntf%2-=qW^;S%7?LC2M z91P*~tL9s9Nf_55Rbp(PXJ)OQ4%Y~iz43G3vD(*5M(+#^O_Kubr%&wvbjDIGXc2~} z7o6Da(*Nnl`}h@$x%_gwX?I&MryW`8dPVuq8jgP6XyYIC#X4jK(V*RUL6ER93t}_e zLXqC4We3!w(;Q%-iV1M-LIrja?qzIQRF`E9&Kw@5Uq-PjbX2DYK?v)@P}&wZ%0P4^ zq=m2L9gG_3PDF#qt@m%YRF?B3uM?TTQ77i9lx98cHjxrW#*^%A8|8gmMD>Db_m`vz zB*|h+mZbU$8;c1m>2t*Zuhk44@90J+Y4kk&JaqZ2(skbB`qWEM=7_EY_8I4RSreRR zNZnknP-hf(Ea_Ty797csjR%?gYEq0Rk#otqXs$hcWhP&Yi-6VJR(}Yr9{cQ3YP#0{ z{Kd)1^jGk~lQ2o;zj{ zTw&n+iTck;Mx*af*=)WQcv63?P>0VfQo$YyE7i?I)iEaJ&UG%%qMw`1G`nbOH}BTt zvy2&}lil!(9k!GVPan7GfyaM=i_V510QFMol7R{6iCXsx&dKP z$bM$bB<8xmUH5@Z6l_HD5k|#6VN=N9o#=)A6jfD5M4fZ^%Y^AGS8`r^ zRES$#TCS))c4IdrI%D9QX!xZuL7<;1nebpFu(C#Jv>7(`7 znue$+WrO&=UvkskoKcQVG-eb3xfb#jC6Y(o=Uu1gK$yB_}!{D!bPr%NIorflWXA$;6?<`#JI&{af?y~f2lZ@*c;T!CH)%3AT=CdW24 zzIisjFBB1j)NN^-fBm7sK6{Nk)@~%fBQ2O+D#&*(xL1+_sfeI$_s>6 zmC9zr1U2+yBMqdosO&-NVv0+21#>+=S#h z!~Nuu6?EV~bx4HDuvu-~yD1AYm^FE?bCf7#vn7YKU$Bj9e<0Kk$9Qnn&Z$`NtE zuj(-pWPz|Q2iOu>SDrR+?~x@D4OPazbo0JI|}fOxZ2bQK^q>Cra9=~XVp)aj;1`OsU#Og4-j&4GY04hlthi*X&Wa|(|_b&wEjE^>}RO2bK` zaBMi(caUNaoMspH4b4~vF*{5EU>M8$AG{m6BQi|+Xts?UX)Mw57ubBz z+$Qewt7$7zn5)V(axN3cP&2&0JyqlDTvIgkM>uNfkfRsNHFfHVX#>YA-bcenxwc| zWs!?gRA7)i_!hehOX;541Hfpo0)owp0tjfn@f4xg7KOYmlX!-sJ@CogBMS++K&Eh3_H*|NLhVhpG(8_a0MD@ zzmECmcFvnv8n|jw16{(Kh@2&X=V#@!RoC%lg*@~QX$YGO2$u=d$|?&UomwcR;EJLJ zoWhq*v70YF1;>ka_PF|ZHe`(}KzZXCY!F@j`1&Q%s2i8&QE%>oSepkki5d$?a*pB()FCGaS3rkMdMh87ep3hXqNCt(A1_Olbtapd1t2;?p3k3zV#Lqrg z_{TUcO3Qm`PFP&YdY`lvovOX^maBIuQAlDQ)+H-*=v~8vl-|F9#Gk^NAb-22&NfDB z^KT^X2+>*1=|43e`1g6O9%Y{U{y=Gc?l17Xog=q=D)Z2nJ^zD<%|4Jsssn=C zAS?(MLhxot2*^)}<#-2>a*p)@(iGe(=lxLWL@@ww3KJHs{!3Zs@jfXnEa+QI++5Z# za<*0^1YK63bFR;}%77WFxYCy91`bgt`y}KONtz@EBx@xF-U0I@g_Sk6a5^e=7hI5& zR9D?T$V7ho4r4f=B7mxM4N2jrD|dcyR|84ovaw>&(a(jW9OJ6bA{WC8mXgo~freEYc%Eq7I}c9tv~!U;@$bwsfyo zR-$U)lb1D2ozn|vt%GxK>C)_1S>8@~yS6^G^A26@m3Ry=S|7>4W$bJSenE8c6dlK65zbTa>Xuo1&=#WST2T2$LZibHG-{45j5q(y{2QKEl+hu zHP%u-lli9~w0GPWaV%#U{>B&UzPej$2He{Ww)fZWv_i27o1H#>@buz&A!Txc78yIt7jdo9fIUF>gH1_Jylj@8E4 zRJTy~#jS0;*I;!I-9mF;IB-u}M>$A#OzCl2;M})IQJ&-n(J+a;s$7{Bu)Bs3aT!cB zohoLKDYRmN5tc_4yQLHW1tG#e1tGai;G`lYa=jmykt;9`OhL7L11IEkyCx2Cl%_#Z zK*0-uOr~cnfy0t!DxwLTP!L`t7;ZU(q!Y~kVi)XkSKuK_h)7k5Q>z{tB zI{l_9Q@gn%wq&^S965bs?JyI<_t?oQkdI{s%WyX^^IU$TaF*3G_ahbq44Q~9&TyoV zQxP8&f-+vFZVqg!f=8n|!k6)rXakvODL0gr#=#D43N);7l{=m#rE4obyEJs(xl0M& zYPeGQX|BkIiu+`JlO@!Y^Et}`azUFRr+G^iB-UBa5WI3iObH+@B%Q1@pAnWmwJEb2 z2(PNdoWDt-Ejf>?Lwqqt27&Zd)=2e z(%;^gE+FOH!nvTLNHybU*U5qUimv)~Zr3h#2gW5=bG`e7=aUAF^g65L&D~eo%@PtU zkz7bPxvEzyDp0HE%L|V--x3Q8He#Arz}0h*Bz_-A+DFP*y;Y*s9fO-aZDA8YD4nk| zz;KcVS{OrFs|OkaZ{IP5Lr~gOp`z+u#5ax2^h@k5f1RW}oGP13v_F_70tEZW0kKsDNdXps$o)}*vWd`c4lLMN#3nwIJSQ$=KNC<^_yS*r?Qi=B5u+tD(}h2c7Ntk^XQ zfDt0q#Y`#05)P(bk<}D7Q4NF>C$8nC$vD8Nbi7q8F5PZ`vo1`5r(l56bW@7&7VuJHk$P=v=E@zQ%^0N<3 zC2({CgU{3CnbCIbD9A5L3#Zfk*pawP>>wSo$Zqd&4+)aJ1yX3 z`I=|Ab6LN^2E(+X;#3SzU(!Kpe^TPfxS?9)rMlh87g%qNyFukAW;d&(RC(W2_txY3l`AC1XB zTAl`jrmWs&4ORU>t$}q<bpxDSuwsw$C`ShnJS~@; zbr%F?u0_B6y~o%Ag(gRKZ5v5Jy8hEc9c`;YoM#D~FuGY|_lf?~_na35_G!Wrnd+_C zhYCW-nYPszgz0WhcVY=JW+aAPr>pfTvd6Z%h3BJ-VNWo!GKzS@v`mK~MmFB5Tem-d zf~Fa%NeU;H_(0Rx?R!$|4BTLeKmvBja|iw6+@ZkQtv%2>^kxkolZRu-nw_VkseUgR z104^y_6GSylwPh%z_2v7n?1v%S`meGX}xb;1T3p5_4#nK#uB2c|%+7IUS zq!rruxw^o(QJih)OtE{ehnsU?sB(Xvb-!BzkE-~#jE!N?y}7&3dq+h%M#_iBbGno; zs}Z~@5ZdYw@2mIPNhDzu24YYb_nlG0JKip#M;{lG7~}^KDwBevBrLj6AgV3_T-{JB z`VHHwdVUtB$asY2X?EE_hCTk&O9iLP?%A`%ZmQdsi85(tC#St9Hr_w(>$O3NyT3zA zTp2_ix{Iu9en>w*^F39g%^<;BqW0~ZCW&2d`Q>8L2>e3@{Xa_}d;jl@@nQq~dn|~E z=l%x~BSC>Y^<6~kjyg&8cx(9!3F#_GV&W96p)D*Rv;@s0u;J{tAnL{9r4u+}kDf|M z?wD|eoi5P)9SI0bu?x=d4l@N)EIw1=t>?fYvLhTK#5WmySl^?Tig1pCX4q{mn5+Q`@PBhPfxY^BGDoDgwD?j&NxnS zT~vKtfTb?sG9wrwcS|lDqRW$?p@;B}-sU`a%5az~k&y;Z&;X(>d2*4MDYr1b4%v$f zB=$i&dhzj?{#D*-Y&GOHR*YAIpD$vuq&j(uO`Q+pn{ASO&|^pIcFwqa;N(ygHm0?Q z1v?54!<=V)#VP)xAO&zB1>Q!A^~gfwq!soUp5gwA>;{psr9&W*Z``h{__~JKJb70X zQJm!`tGya6H}i{{_(C!+SLgZ&lrHT$WgQm3ZQ}lN>4?Rsro6nrcgDwmx;fps=Ut8+ zsN1ArcJ44DS>@SB^Po&xgGxhNGl`=alQ?{0dY@tW-qJA5w723Q9opmrtA-sqpWft1 zZPTb8S$Q+N^QcL@$*~u0$VyRHtn$DO2snn`!H87HGDh-+(X4SUl!q zVqYYrGKV30Nb-TYarjsv8KPh;yq4dryJaX}OALB>S*p{XNh^8dX4`tgz%h68$G0kE zD}(Z|V7)ClN&^FThWH(nC-fRa3*DT=fjsXA1sWG@v6@1a-4uta0b#m8FK@2Mvg%2= z@Dm*PCHyo4eos{PD=I`5>p*Wh{w>DKv{ zFdJ2`{W6OJ(}TYOmh3q`k&#CH@fz!AALy{zu6Y+rtNPNF7ZjzJl*dwHdU14Q#hRpF z5J1(>y@r+FB4^ zZ!dQ~X@4C--5p+^8L@Wy;^ zZ=yb%_{7UI-{n$rwl*E>Kepv*x=sY*&tG7r{({{5UtWI!(?_4}#Xf#7L1A3{_>kK>U)&TiXv^Nx~T;&^j3) zWs@R-B?bu`;^Sqxnmz!mUF&xhIEtcrLhs`P3E#QhkKh22p%DzQE#Xh$;b6)t(iREu z^%h*tvg@%ofr56|c6glly9k&)!$z>n>tIB(Pw@G%uKKwF3)A0*72V zDEWAN&{5_|ih}^yIpgt$jzgss(BdLFU}7Nl11b_z05n0}@vw7!kR^vzHW%zANLzE< zbWTY`4kV=J>6%(+Q1+s|s!7g%wZ?;S4RJeGUTcP2Sh`+50k=`DJ|cbyiGm+3KR^>Id7TVaT%G z+A9UaZbOx4C{6P-ywF?M`QNjrU21P_(n$QVd;D(BVC(09zAfh8AKf2#%HL+t9`gO* zndD8=)6;6Y=ardrCro*tc~>55a*}?mM_iHR>p17;B~0y|2VTr0`55Fce>v3`Zr9ajxOXJRa(1O5artfUl-R}o!Z2-n!xk+0 zmrMSR<2JKrBz?BPE8ZQ*3_N>P=hGg$RmrOxeXk&^f{hNPa-CbUnq>Ylgiq=6k7n96 zEu-MKq$a1YuKIZ3k5oL_@uPxGq1AK+UgQX@WtxWNY@;6bmR+y%h`5pd-3R*m*^-wu z1L9(i;~UUXj&o)D5jH-X48#Pv1FTw~*XC!`60I?Wrl5%9arM99gC9sPNJr$9v+@h z?E+S4j^bG!86g*J{;$ke=TbL-&dnz6W_bPuEoZ&_PZGt#s-^wHc@yhF*=GHiO=T6k z4O<<`j@ca;8M-r?fOv1A{=#n?tC4e`F32j>1!GXppv|`Xi`oP8)vh{Deq-mEk5(Jb z*jwzUgP3J<{$&!xpR-BZ1!Yb+@jT^lx|nFKI39KJuzHoEvspe~fuw4j70o%~us-;9 zF=3N!uFI7r`mIQdKA#k|Rdc#=!<0%@3xm3wd3#cdobliF$)qtx!sh_9ZyHbl(`<&F3@ zgnjwsqG)R_h#2g?>1z@4z5LI?1fA}`z@4F=^%F7%pX-yJUb+8~H=MdsHP9R;4PxG5 zXSfgKKXkzMf1df{Dr3KJ1AINdK~@@+zn=mDxA4(_8AVf|^BfJQdSnxE8yN40XxO;| zIqN>aO4OL|PPeP1DRmY2P;kA?W{?tMCq^QPv}!|_l%@y54Co<7D1sF+eU-z4X5*DS z`?~{et7&oIfOD?I72a{m$pu(+L9!f{+&%c98K5`-bvAYq(x7fBO>OHWO_B1MB`-`{ zY_1muXkFvjQp}e;_-3jG%|_P!-}{HsV1_Yh7cU*WA{r!s*A3sRc@QmqwY~-@-yl>V_7X=ji)S(h{I?f)>B1=KTW~eX z*ChjX1MLJQPf~bTI^S9|d__|TWi0bQXCW4ITVsXyY<3=7JE*<8OFh$~D{AAt`_oHX zx1ial8{F?-ayX&s#DaqfH>!{!eBZ3TNC#XFYo5^iz_ys2upBsaU|Hw2&$WXi{KTaz zt9ykj>YRutDrv!9leU(ty{a3krTq@Y+ZDP+uI-ekpd0za3a7P9Y!A7XNdxyp=}Yt@hSBzN=LivZPwbxaoVfrKw(p%) zxljL5?wR-g$%OG)myb_OhdLT6R+3f*ntHf8Ns$8GcSmMQ-nVZ>aC$M9?c}if8)naTeoso>o?@7n>rHBJ{QcF8Tl7UaJ9RXk=S>#!GwhY6!g z?#{agdQ9)n9aB$L@`U_RJ!E75Vtcy!k8F#T_$!;^(y@Pm@Znea^4>`M3Hw+1n7ytG zIK$Iy35Kt1-mNd7(W4!8-%q_Nf#u_M`KiM{V!p+6_=3Q>HEnXB8m*}vDPc2xbub)J zo`Jv&--8t#?~^({SEOHPUoWAmWvGtxmK?J$ znRQ!a#CQd)1t8ZgEYZ%74>ackSWQu8APpp)#|WFNE2VCIb=&8EuBfJc{?>zHEd{hj zwwcy^+x;sVzvrLc@QJt4xFs|%3%mm1?XG_9MY{II)!1-gOTvQ3Tlhya%foq*P$<`0 zJ<#XuT(QcGt+<15oA_5r#u-6O-!?HQ-zeOTi) zl3C@wrZ@f~u4vVG@bO88-|JiBSd*xH*QT$5)%t!+zYyr+-;wv!#!$v%Qt=( z=-R*R`%hW-|32@+KU-3JWXfu@uX76h*A+|F)8IcuS684?f+bMifyR-kJ!zsp)! z)^s7))9Eb7K9Dr_#d58(yo(0STDh2E)#n}M1g2$|T)d;a6L%$7DYy2XBZ}UNy=K$} zMyV!1ocp{<;g5HA&8O0PEeL;sYk1(H`cwB6Uiw@6i!Qux$5wbJ*U69{y}?q}46-=^ zv4B(3%xYqTD+47;TwSg15Xuu?;L$)Lu3xveimOGbC_!$>f=_wD{~bIaF{9Ddklz$) zFTCFyo?%tQHKN4g6eZV}3B7@l|GHit%u|UzZmh7oi+C%M3&qtt5ocGRnT?M$DgxWp zqpQ#|3fiO32jWqp;Ym8ZE`+>>tGc1HDA7m=3@=!g<~$%=iH-a9(Uaj{ydX&Eemd?` zY#^Gl+*M+>#*#i~bNASb>W1+H@=wnn6JCC{a%-ownCI1}M>2b9eqihy7_$Yknreq7 zvygyBb*z260F zdgJc*TKy{SV_QHe|3p>L)>rH^Hg)Dl@+`vAz6V@gNI?#;cK(ze>TPts z*8@Us{)*bcscZI+)YW*}|F}rr&Y$=7;|?A_a%cic{4;2Gc*2&D^rl^Vu>XSSq-Zu* z>1QSDhLiu?ruX-}EDTM3*Ua|aUS!6Z9J@l!cmsdzjADOgIfjCo?swz|B!u^ti|7^>FbS13RWMbkb(g@$^hv~XEV*lJ z&`uZZQO8W9WGW@XMst3O8oL82tWX{9Rx2h&re|6IQ{Q`?kIWy>#onXbneW+O8#t@{ zarR65*A`#fU)qcFv)8h}vij9W44U`ICxzBE!J7B>-(Do?%KJ+KOIN7Zwz21!SHp4_rovcv3^wC8p}CPSVjFcN-*&;=P$T!qVf^Dpj&_+w zmElBX<^GG?AkllYqHu$L;gS($+G*GJh|>L{S1N-@D)!fLrxI(1brqu?PE>uMq;ZZw z+xLFMv+Kg$&$&$w`d@$3j-d?}`9RrzsD}OB(lzq;$#`i6YsDwbfWyx!0qs^F1cW6i^~W&R}XRxl7JZ)n~YfUIKFZ zT8;uAOk~fwYG2%2YHUR*Fjix&)i+y8~?@1k?8SlZg+QIMubn&bM;`Ol|K&TI-cPlFS{@% zMYFjE|3Z45s5!`0ckruckC_;z?YcW|o;*=lRAauU@ZsBa|C%?m{wa4=7!GAWA8`+F zy~&B+RaHUn`OmhH6tIQ7`|kkQv~@t{uibxv+~;rqv_AUMKm~&eu7N?|S^=147@ID! z?8X31R98&cG7BJmwgO|AAV-%AL@s$sFodgM^yv}|!_yL*I|Ev*2LVg>_+HYd zhyFqOnb@ab468E(_uNdSj1f!B5aUEeaNmKLn;iw%R*3~W58)}GZza3R>Evmuco}Q` zsMKS>ZK%^*m?%lWbYZa=KpWdpnZAHec#kP~YD9JOlFngD0*V7kq;M6cG??C<>8Ob> zx#L%F!hQP|FMS~R%1SkszxNR}rC@m|ElcYxZy;F#96=`|F&)$;Z_P6tsMy&|lbptq zl|oiRd-2f=!nADol&5r=g5J%?Whk2Hs~ZgBEm5r0jE&%gWd;V~;{yRHtVSeOOwh8D zlQyM#Fg?i+PqU=pr|0s)RW_Or#d(k2`GTXMvpJfDGGBBR(zINrMo1B9y}?KbI6DYN znc1-?Xj?Gnk=ov$7+-_EHtxC9mZWj#+C`mmhoOgmflc!|q5a$t$Go=Kprt1VWNltt zb-^iqy1w2AV@d5}yNN0oa(LNiHpH}&IsnWgoLTk`{BpYgi0ZE|)XoOngBA~uqlJxM zz=yW35*({KG&aAPVYn~$-tG^PYQ5IX@e_E?iEDqh3%9gBPB`4-{VARAow9t;dP0A@ zqtjDx3W#l#at&g}X=hgaG7+Y{t-ZWI2EN+h{JnNM=_-tnF)?`QaF%UCO)6}qyisgV z$%ouI@VS25bonLwreAw^j6gLbaYUW3Py{WZ-X;(w_`2G!)lVy=f2HH{*@moK8(;rP~48*@MtQ_xsSu04I zD4bTX-rs!SN^irQB{ZiRdF#t3Bl8e=Gbljx)`WxZgzdfpd8-@Cuu%_~-| zO<{W;klt#0>{`pChr>tB0;RLIfBC)bRb88Nyj3S9HhITW>(;Ml8@z;Pek)G&8*G-z z&Z1>6b3+UA#zsY$wcGb(-}eZ{@&l=d#^0QKp%-GUx_?`pSXfdw>!fu*D>bk<%HPw@ zqiR>GnDrOX2x710T3Mg)ANFT-?z&iX@0jVQ{yIa;pS+v55=M6|#2&H2(PWppGWyQ}C^Bl#DGrU@=mO+ICn6FuBlE8Q~kirS6w(y%(CWD1q( z#FtQI%-x`$F$S*}@gsaNxL*LJy4X^{MML)qa4%`eOYE&nR^kGBMp{UOJBImJ@5zd*!4sqF_JaC`m&k$(ZJ4bG%= zHT7&;=Y1O-f(D={8{L7OvRd14Rh0z-iPmDDZ}9PE&N6hgwhay;!-ld3>K}TUp8-&8 ziL`VNaD8);V?!3~0TYp&_t`_02Z{)Lj*bi%g2`=D*|7X2d7UU1nl|yGA8*^8mFYC4 zBWLCnAU)L^K~|$95Hl0L90BFlPdOm;6>fpFfom(-fzQ%*{_vkYZ!GmD4q)lp2 zLDmJo{SA5O7yZ$u*MX|hXe%baJb;+f#=L37#*{$QydZrZXX%!Qe+)Uldr8)|TaCE; zu)H`Q7v%R;mWr3MQ1FDWsr7Gia=t=|)7)cmBDyzs|MN`C+Mypkb)?oCn44ZNx-oa0 z9yYt5(hfjU7Xq(sikP1|>=RV(z!YLWS!{Y)eEh{}^1g{}_sw>cIcx#5#~+&)M+0b| zj7QH^KvvcGzoI{X`1~ta8vzK`7&C94gP&gd$`qpg490`p6Inr@-u@p~HShipRg={` z^;Y38FdGe)@$X8>n{GUCcEQ67HgqjV&KysG;VE1eEQ~Q%08W%5xdJozZ%S<0%GkQ_ zJrjsSirvf3vcUZ!9vHSTr+fB+CqY)>>G1N5NJuow)t>0pTMcdt(S8cobKT3k3Pdfk z!(0TW)UHWYjDsDjlT^ZccQG^otaR2y)AdC+w~v%dispQ<{hS5GPI*+Q@~q~2x?{&0 zD=%@`%RVp!HMznu6o!++ee`5G0+e0BL{gugHzplk&^nza?d;#$^=^GIyNgwFq=*UJ zv77&m>JY&v#Kh*d6zb{6}MClO@71a>Cu=Bo0zj)NfByN2(7`Y5S^GmA-v&ceJ@U2$p5>cDIpe$BnrZP*+I?KU~(T zZ#=Q*HTl&=2g#MWwgZ7Jd0r&9im;9O=bJwS#{J&ug0A`OobahmJ|Lh$-_z!C%7==n zFnu>q)u#Ppo48H)zt*dHLoFn$4R^tHXA=h>qV;|hYbxPkVKwRe(c#RTPPHdLj<^_T z7iQat>&C8s+H!oc*CN)f_58NQVd9U*8A(6;jmbH|vLB`S_Ky|(Xtl9C?^9n@T5Y3{ zMqAcS+ZDD}j%{5mx<)W^cq_cSRA-RCoqfEPq#+NsY@FOHz|>m91Gazs%GI%TBI9*u?w7KEns?2Q9%JO*ou@qh>6!Bv=oX?t zWAHxHQ+c%8q{p4QAgsnzjE+^*ZuLG|FZ-Wq z6B0T(6B)SyHeXMoII;XVX7`1~y7$}QHz6O7ZS;~3fA!?yhi#_e2RLCNB$WW|=hM5K zp5j)k)aA+wV)ZrEH$dnYJNWx`H7<*w!cu-j1fgxvX{ccgu${l6NV$ozbat!p#)sBN z&8nn(I)}>4qjnFacjgkeq+l@+Pr8%8{BbLhT4caVl^8 zlC8q70?)hUc!)v!Y4PMjqtf;0b0sVCRzpTNLyvPu_gQ##cHGK$D?dG5xmi~C>6QEi zzf1y3nv(xK@Yv~`h&{hd9zGU#sJIU6i_P=RATYO1wj#z?wE<0gz5H*cyR@|ruo=(EH}rQ$;f8aekZ{3`u^ zcGY@ScU^fQ2MFKNuYQtPwMgH6+bqsc{ZwU9D}NJ|T|~@6=XLnWHgnZwVvfmPKGoJ$ zVB`w5!0UyMJtz^bY<2dd9Q+Yslz%G9rv?6T(-vA1xky-`L?juSrhE|ie8ebH+$_cZ z)1vo9>SRIWlbby*Ub<+Xje}hIRAf)>64&{J_FPEdO<u(j zO(QQ!P5t$J;)5F2V;YRr0Q|0eH0S>pxc}%kJNRpC(y61HuTxFB%5EKdpE_zBC~BtI zSY6vpebtxDdnx~}$H5x<_V+1SyM9J2~K68H}t(E9&!TrU2%<1%3dDziPH zGVA)EVER8fiqF_}Mv>|)SVW0}xy@Wr9bk`%xPedfk;o1rG1kFWr(m|ZZYQ)3)29e( zr={aQXW^p!E(&O~1g*it7!mpUG%79=+J%H)hi_WM$$8soc;*g+WV7lS-)ys8Q-KCy z0BDnQbeN~QyHMX?I)ZHzIKArdv7f~9=f%a^N_FOTw7vsOuZaQ~l6$3g+X~x=>1BP1 zMB(&#>DiEhp4GV<`5Ds z-ds+%gfmt-$||}GDS@LBq${MsmL}n6qY*QJ%Zb88BHr=RiRZyTjBaIt4N=pS?C%n!szjqZsmq;i8KU;{odhtDFnW69Qwc`>~`788@#X1M;MI#q(G;y!@9O64bbKRvZ2 z*x~H|BJRBY*$)4|AA8gmYS$`a)d;m`5qob{tB6f(rADnZVy}o*iA_r>ik8+^D`rtO zilR0(+ur%!zx#J`{{!EH&q+>l@Ok9QbzSf0>-iEDy?-*K)QmO}`1O*g1&s)d*41ok_KPYiUm65Rw^4jVO+F@UZc}oU_^k( zZL;p5dD^X-?c)Y&d%M)a48T^?M*g@G0X*z}HuSW$YxT!mS5~UM;K#^Mrtem*Z~`vW znGjKnj%H{9@bTxx>|f4-1&b{%9o|~1LQc`Of8G`TY4tPg-tP)}9#}+tLm3JJJH7OL zTMBA|%wtYYt~7bVXt zrCRv7QHN_sGOep)l{J2!--FTcW)-Ggb64L!Qt9ttTO!Y&AJ~58(N^5qG5=CfA_apV zU=jL^g6~M4hI?rK1H1^+Wv*XZ>L7h5y=>M*H9qw~tNX`qsgiCH_2luG*0|R_zj0d6 zX-Q>AH*gI$yZXUQ2_C$04m15)qEkzKrv|;I5jAQe1yCU@jC#gF5)ByF30 z_1AM-?vD9F{Z4)56a&0gvX6xaP0{MgT^W)aTh5O6s2Y*(Wa37;jY(UOsy5^<%U2Hr zzeORQ%4kYt^P}c+5?Vd;Un20MyYRA^UsfaTOA1uZo%3EnRi&R^$lySLg+J0lN zTQPUQpO&xWME^M7avK};@btOM6XoUof~7arc`3O2v~)@EHG>K~SK|TS_J8~>qfZZc z)nMpv-8Qpn9fwrhdW(#AB>f zi*@9!ghny;Ln@jrH?tHiAazBKhm%%c(~<*XatM3E#>|RnECQ_;EoUBWF%LG1u-QCj zi6`f4jSRj0v&z0_+TDu2Vo)no{xp|at6y2T^)hp=aq$Q0m*CM{sr-=WM@>uiPXppE z8TV@Hey5CBbh45d@}!hJ&kfFVWX%dv`f5URJNKtC!NYr!g7(H?7W7KqC*a+p*z69M zg(&PhQ+L%R;~3Au=AHea##UL4cF3&cpDB1Q|F^jYsi)%o?EX|cvf*DDrLVIytyS{k&B3$Y@of*_%RvtapF&sh{pGwm8{KE-yG-irzJ_4k6%pMa`myq+!;>QoW!ryWw7bhQ#i<@%@=$naO~3tm0^rqxxd> zn0YVIk9(TwY#X1-}ZKc=S zf#Df8H6NW|+Q?#Yf_efz(4p~-spDCP+E1%MO^50UnThC*KVAaux#M9RZ1QT~vrW_R zsc+dgk@wxQ25SUjUzG|mKmCAmytSaRIp@d4#c6{ULg^kDfo@>mf#tfZ7B&8SMAHMZgIgw;Pk`S?>5s@|{jrUbH65?<`j@xH+?Ka@>=DG(=bVfwo&D4* z%Sa2vSfP+N-wy~Q->yn;O|BO~Z%od7QX9^)Vy11MfihVMpThIWuGByxKw*Sld{XMRJN zy+y<%&x{{_EFn0T&p%1Hjmru7v0k(iAE-vN4woJTPw!t%(;dvbIE8B%fuskOP=FZ7 zwYd>B54e~_f)fQ5Y!wvjW+lS!>F+SEWP{z<{GxYKC?;BE5!Wcc=L7~C2e&(&-B2kI z#Q`YAYz8;;VhiO-U=&@W$_C{>!wlm;%?7&{u#?6||D;>(nYR7l1S;>YX&9ve#d(HS z1di#He61o{%ovu|Q)wAjJk?`gjO8aSH6_Y6{t>*D!Qe3st~;;py}%NCz)6kjqo(7o zEx4z94qKrb?j0pFNdQ91nCyU5GIao(u-;ni?J=@z@uq{@EUcMySkX`v^M@lD?cymha~QY$0L&_Yyg_ zH^J1vR`34iX}4UYoXoZ(X-l+yf3}xYwVS~zYW_00w#7u}DgEeBAYyJlKDc!nY7H~HqwUnyLvE`OhqH?XWxgFrj`Hcd>j&4%_ zO}E*~2tD=t`aqnhl` z@249#galmL`ueb~L&<&I2rRlDLO)t%4iC(!j=!h2w|GhILu!vD;Y$e>h#}L&wTby+ zv%bezs{Jw&ktOf?W5`Ez`Nq4mbFu>dNp?X>$BxV!4Idik*XG!O_gR-L{%G+rQwzdI z!gmGYxP3o{30Bt^YtOMm=WMXpJCZ+wX#lQ|;EJ^2S)3*5mt^?_^!v z=^wfT!b7qft9;(=0HX#;UOM3>D*0I%mJ$xSCVy$dc@x=|BQhKmq)+rvzm)E+cRO-w zDBgVlW2Ad1Yb27}(h6NBXVQop*=E9pyE;xkQ;z)ZW2HUehF98nbB(YR%nt36YH_#) z!nb^tqRO90Kn@)4X**DUhyTX?A|n2|(wiufEYTJqHj8;9F@6kR74v7;n^~MQPcKTx zMoRF6^Kl%*Pbau+WV&{u37>uMgXVX9TO4U#s;k)*K^?axuFnTo2`5aLo|K$FNNn|d zq9?UH0_5Hn=t!q~W~v{7X`6OtSlwR<5@N_r=PFt8Rk+%(B$h(M>=rH85Cz|fA2wLb zxVO)Sus*m?H8ykHQ#;g0XR!*W42z~g&aJh4vlD68ecVVf80dIW={Q&eopd0|+NJpY zx`a1-?B$lc+-t*2-@3O0zop(mZaToM3ul^3V0t}mMKhRM-&R&WSp#+UT){vlBx0ur z*ba^X0u~Km=;;kV9pS{f`xj3CfYme_zR&S&w|iUe@M5H zNXBvW4)be2os~fuCRv%vR;Azf$rCueo{Gy;k!_gON0?@!d@}1j6tx2#qdbCLgbD{8 zq3hc-7T!%q3g#uuW|Bko2Pzg2ap2j+hOsTdVZRk<7bJ-U^s6}ietMYkn-pcjrNd+% z;fR2lt4$ko8+Ju*q1@VSVsMIEC5@{=a&>o^lfFLW*kCgCvuu~EvgoSMG54}T1M}6P;@5jiOcU=H9oG^zV8E1m}ZxkM?+Y2ZJLp} z`6>m?h~!&PO?qxcz9$)0?f2i=$ziNPRV?}Sth_I0xbSn~SzWqmNj6@J>OyMoE{?Nm zyX8nrha%P@XeXp@%rA;E@zv8k15vBNIRs^qN2|04xKF3W6m4FBzg1^)6AqW*?r^;r z(9*=egL->HiuPf1Q$shCBXzEUa$;0^FJ>+)NWXL1CtTRix+Oo@j9|<({xg za8Fnbz0*4qk0u`3tQCaMjHgzcYT<$I z|IR}&cZ=u5G6()=Z0fh~$aC}~bL0QvlfTD)JRg<9V_G@1xa=?`gjo`6nJb&;?59Ei z|8dE=s^}`8e zq+sTEj@^yM4{~!ja30-?u^$r!v;^&F`AxXT1a#KaxueWsSLT4q61lS0hbm_PM&ua| zHoTs%GV>XIR>{qOJskwaoI;GBO>zsOG=f0VhN4ktwRFs96=6O&1_c6q`rDlDSKK+4 zde2~@mGyTS*$;FU^iB|{W4pYvX_N*^;KqR*eFKTw9LF~mz7 zEt5Q=ZBSL3B!&m#ir>E)latlrd8M{|ByCJ4h4FiDR>8Kh43+77`5?ZFYO;rSc#uWija(^8hzY^GJQ5r>~2b2Jav7{`z6%5$B2 z4|4J1Q(p{Af&}T`{nc0ESh#p*zuV0$kzJ67U(}0?Ies@p9PowzY&AEX$r@i8YLkbp zRPU5)^+JY9x_8YM=p_y(L4*SYZ`;C(5SlrDW{K z1}Dem;op^TgX^ilg#@elC77sF-g%>oec}C#wUZ;A}tlOW<5e#-$cT=ni>4o~xm z)~ofsehK-pZ>Na4IV2t`YAPi651g^qFONolT1v6SrxfmCMt^))9h*Tl)skBPU`{Z3=ShN=G_fAL00nFZ{ah9c09m=d- zG#(eKr+}VKbt>5pTNVoHnl!{kbMj5O}LG1x2 z9o384VjWGT*heRU{ls!5-`DOj+V9OhQG8K+cWbz|M0&oZ8a&@tvc{%aT&svW+G$lR zlK8Y}g=p_x476Z~aC5YeK)YtNfk1)J{YiFAep;I>EQtm+qgCyW z090X81J4sv{&??p^vGrr4GDX1)=iSW4!&De@O}Jc5$v5~GkeCo@#<3EyZH*h20!JN zk7SFrdYSLv#aLtqkZvOMo)n1eO+`sTr3UOj0lnhIcr`e5(Aj7|14K?(&<8GtMwA^7 z;~n+206p*84Yge;ysULjfw*hm2o5a^Twg|j_1tP z-T@d7nPTG?b0yoQ{UT0*xcX5Rl!TV3WbF_7ejA&~n%@41G0vL81{UJbnhjyP1fx8q zpbEK4R)~=~X?bqIol`gSuMcTE$E+AXgfj)*^>A==kDnHj!Wg%gczw(5$qJ$DkiV^M zsbO4p`cc{dT^!&w(O9L#7>se6+*XS+0fG2e-`d$b3NyYjF#gV@Z8Frsf#YN7=od-mspbsq#rF7}7vQ16 zHKmsq5w!+Jq^atr&9UJ=)B8Bvie;O?B_?1q#L5yn&~9Kc#cWZXCoEO zh!T3Si!kkF6A@5II$pa>?WjNLh{fEPnOxd$@fXlws!tV zR#Ts)e5&SKiN*B0mLvBB8*FWRIlT+*lO2<)^nW`xn2+=YyLg#C=!R`u;E}KEy64p3 z0!~o7CC58q(1Ue^Tf5BYaI{kQ6L_*{WYg_#mXrTjLm5B!a4mz^+o2dU6H7W0p(^Kv z%*xE+Ak$BkRt6?`=HN<2Y)0VhctfI>pM;*`(^VFfS(jUZH!EM6ZxO>ybarbRetF4 zx%7&Id+%?& zWMx&8+&2*FbBZUCAc8w@bju+kry)Q9PI>1A{Uk1X5fxs^Q?+9tfF1;Y($OO(BSl5x zvXLLL5^Y!s;Ej0%&^L6X$)0eCuLB`@}FBZ!QGL#c|4X&nFwNgT@K?^?eY-c1g zCM_qvG4I7l`OG9>)r8dyd9sO&nE+ndVfYBC;EZ{*m!#1c_q}W*vbhT4>1H_~RW>)= z;Ye7)BwC2>2&%qbs2!*_m~d!B#wo0X`{5FMpQ{y5m(U$PF`KVHD;VZ(SBjj+dfnBS zFh;riINjTHe6r?QG1uj+QW3&U-=j~sy^_J%J-gqQ_)Hug(9AN(b;&N>0CrppqQbJ%rs_*WI4dwRr+Sdzb)w%@wcoh$U_OvF1yravf?Qvz@?q43{imI?w zr;b`{e%)p2X6PeVhm*the6dr;JvE2jF6C&k*=c5ZGOTXH;+qm(eWygZ>J}1uxecz$ z#$CVWA?wH=_%)hFLs0l;0X?tf9GY)>Wymw2;NJYY{r+7(tlRwGWUdsN42W)|AMwOdm zL#C-RJTACk!M?9S@?J!;o|Xu^)x0bh!xWlIw@yzbc-Qq-Wc={Z{X-}8zRMRw&+n{) znFo(w>Mg$wlSyaD`cZ0EMA7^wCt|DB!pYKJi$Him$&y^9<;4b;I98Z!mXD;Y=f6SJjn-Y`_3tI6eGw))W=njq{i|1P> zk^LH2(lHju9Pp>s0>MGb&2~Xcl(CvtXKOR6!{`h+}q+qKu?@QLV{ zz#qHKZa4pJ$BMdJ(}>lM=DgVrQF2xTwv+aOt8f1RU41xe!#$RsgoqvZ?9u$hI=Myg zvWUWitlj_}nT}O&tI|GlwIMTVLXS2LNxy_YnMV8iv4qHQ!i<=lKAw$k&MWNLeE<(I z`F1P6{8cRbV#X=nMk@Ghl8_cFs4{b)yhA==JXer}GjD?EV98x||AvfR*1-JgNrEvR zOo{7mq{L znLv(^$SDzuvI96=fFxrwB_Lw08$&yBDeo46bQN%%gG{|7ND}Y}MW2^3uKuB9teOnJ zWZVKJrWd6U`uoL!gX`j38LdATOm&_{FxhVKc_TuspwBDIJEt+>8s*P>n^LS=N9lbNN#t6%rv645o} zz+XI&q4f$U=oMzTl9_j~0RY2c7pd84K=98204xza;EBU@u1=%|9t0?>qqiISlV(it z!d2PZh}D%S79=Z$R?z>*@49Ebj>`n*$*asN7?wzzMHHADJusDZZ>P_mtGz$X9*cHq z{35kgX76UbqA>3Z{+d(hY%f<=! z{i~o%Sq*Z1LSimRb`-XgthJc4Ev-T!&jrA)m=z(7nEFnx@ z6@DzPbFuP=m)fl|>Tex7&3}^jOF&hG+WePS?!^5A7(OL@|Lk}WxZ;)J3HuxN(syvo z*_r#IlipHqvuo;$byuoNo8A0vp{k|W$P zuKT3r*V3pXn66i)+**IDPxx`Jpgv{eV@tuaw*#sxPM`q@#ritYS%#&~WU$B0V({|@ zYk!)ZCnw|ITvYJmV1XaE^_VCQ9Nog2xAYC0#Xo>)tv>k~B`Dc=X8K^yyzSkTfp$3y zM}pyB%L45t+Hd|X&$|||H|{MJ#lj4#dkutd!98VLZ&h0xUGb8+qWkH8aE3%rrcYDZ zELG3HOo|yw$K%=6D8#A7wDojpoXB60xjMhp#{)c@qBbg7A^dEtBpUh|*!f&RO?obt zi?;Ov@QdqZO^}YGC%vE=Emp|OllvS?d~HGuHx#ObKfx05KWUH)@{+-)p!<2U5_a?y zW?WxmmCRUqQQ_A!t~qTdo3Wf7hVf>Rb@lpvhkA=I(^1vr)5}mBVB&%B{Wi|PG2I_GGvC-n72Tu?Dfq*xGpocV z^d^&}zA$w#J*}4~k;4Y7*0Gv@GvHf7M8V@JLf_dMZ$9peRIV(p(h7qSu0(w7d7gYy zn}2PX`Ody5$U<%+&zju}@eSzuIp{^CWo~X1{nZSGGgTpd6MvM2zq6<-H;N+I7K+BJ zh$RSXB-)M5O8o!%FtXsPA1(8y8aj;&u+xK(^68FXA3>QMLA z$jz-;H#FBFY`yb&;*n_ngNM)l0qizpZZ5hlJw#{!8h2AJ>5$aLQ}Y%9>7SqB7Gp?mr$7ohnXv%{Ccr2+?6f* zy@`51h_j#PVk?f^(Df3oeC>)_kST5u@|7}0yLNlvjZGcfsqCb3RXOsTDc5GK1@aRH zIM$@d7@6&%y_d{toDvih-P)ON$ha+PcL$0QFw~dMjLf!1FPkIKQWz5CoS1tumT5Aj zo3g->1$_}uQO78pY2w?nQC^!Og_jEf;r*qlFI`dd@8nY&%K&%0T^v-TrlBw?`8$EE!F+B`Jw7*d{_yP8wb<&9*}}Jkf}*7oHL{4{EsX41 zkoqmC#EYkQPm|55iikfZ_{HI&(Mt1C1Tcx4Y(zp>ulSzXVu ziw*ap;=gB?WSJ@Tc;w@Np+WvZ%n7{a$12R=TSA=P+DMvKm-fxF#n6u6x2?A>v9c8M z4N)wn+LD%ma+w?GFpOvFKfs=EKNV%wo{X~2h3b-!uWU3eUuo9Ju=8xK& z0(A5uzwAxUIAt2q(Au#H^tT@t(h4*V#xzQz21H77Dukm!y6Xb0f%@m#-1By~}kzX6flo zJpwk>g0cTsZwJCYKfmI@Uk&_^R)G@VK7$YJ$}Rl^{Kso^Ah(_|fNW{Um$l%{PQNjO za`*y^|CAE=l4c|f;4@g!_%wW=&L|qMl>Q5LDWE_E%ag!3OCf$8K7+mvu zk_Y2-I#&SwK{ewWw^Bgu@8!JRs)P=%lr@y3FJ3{LtK_Vc85usrgM8jFgI$GnG;9SG z6lF;c9oiXVPhI_M(SqJyjHTLmga1mWaG|QdgrI1lK`+7|#=cagG4#4jxh>Qmghtxt zDi;8I=?wsag{@dFe!sKM;eEpmj#C{yH6_&s@#B@kb8MNY9yS_!lQ;~xCNP5oFdu6 z`+3rV$79mfH9#l4)4S)`j0PIZ7EY!N0vtg{pk3GI$;Nu5a$M0hT40xAJVLQBg+q~7 zc_2c|h>oz=xM<-!d%4YTBZkI7fW5jQpLHq7YM{ftlrB@zqoIrsL$TW{wT@m7Bl|CM zSzK&Zg=)FPrz@twmkb`?L*&;iHtyLG_O5=X)vR-r+5h@UP*7&x>%)B{PW2760IvGp zowJVi^IY5WuPNy_?Mu}I6m@KKiPU2)YPxSKJZiQwt>h=DDS)S@7*eCVqM~2oq0(Y*l{UW&7WJrPm}YDFUlYl zQ*44>fA5WHO#({C_Uq_v)OS7darvaxe!Xg8wtKqEa8eJPN%Qh|*sTn(Qq3g;P}-AS zT|AUY-U4V;%Tz#xHX1~VgLfV~{Br7~|D3T8BA<)I-^_a4C9a{3ju% z%~Zo}P>q_Vz8P$IGSqEx4xDpLCM!96oVxbP@A75;VlrGzt4_n|1)W|tdc9*|fAgKe zAM{Xn?Pg+g3&J2yTYAjj-s>T)r>|>AYpR74EAKeeVXK(@GAC)tJf6No0q z(__;o_U#{o`rYI=bDY?kyaQ@WY}s`h?rIyod`#hN-0EejmDayZc}=F@CX2FcVGrF` zA6#?PT2lsm^E!Hbzt0E0249_TQCUe)qOue~2-I`$pr=sk2(AcB?|Ch^=x41YFvKc*USN1=L=$*BAEepc50g!N~x0#G8+SsUR6D$Vtf^Y z91*Tr=-sPFEZ;JXtOHc`HEI69E%U3%Qw=B->>O%|6J6nfST#L)|Z=5n~;G6flvX9C>QAdiN;{+l615qv5^v9^2h_KHsi zlE60-AdL#(x6E$Y76kUTl#oItD>Yaod)IT+Vz)WHtkR)FKq3AUVf{yMbaw0{{H%L+ zOza2aP%R0xB`pU6uHKUAU`AUThYgvJbvjuzBKPAx*duEBt1Y(U3`Z>w`5$VU=yFXX zrkOGU#gj*U78PdrKn#AZ4Vup! z@^|nXl+i65=EIT--V-4*0-V)1C``JFelebFSvRsFLPXBeLGt$J<*`pidhKdu9*B)d zF(TLNb)ExDqtY7`6Bh>C;?++FsLk^=TZ?iD482L=M)+7GuUP=?hM|Ex(%qk0Ru^CK z}0$H&MONB*?u1eTjq zKG;ob;+wgQLMga>k!$XHgE*O8$)TY=-^m+)tfgqJl=r(L9q_v9N8nj?=I7uV#-zsN zrZ}EWYS{a-zSRFv2R|=+nI?8uDfqVMudSG3n0=|gEDF8qppM6DoBpG#`)@onoolae zk)i*4$B`d-^gZe0iTwX=E@E9`8OyO1oMQq~o`ACBMYQyHmRGTCLOodCxI;CHbXRTA zS1=my455lsm#@J0e&L%c>}av#w5?(QS-cl=dq-P{pj%nm@Ot_Z{DLl`l88cX?BQt* zdF2M2SgIoMl(s=nTX|P-HQ~^J%#03%53H);2lX$I1y%P3P?4dPywZ4TF5}p=&CZ3- zucMMqw_h)OgNYUI=+%-%YduVlbYX+xCmSJEI9D*>MW7B4t5bvT(E!|k0A!OJ1XCGy zMr`F@nQid#A8X64;@$v&6+3F{ai#dJkE662X}&K&XdO+C>E*y7@!GWj@IlLz5m7f0 z7ii5(ruV#tY%Z2V60gW%^IXs2V6$T7CTld*t5@4IrO7!G)`mz$j6pcyDN*LV>luus z;MG}X-KvCs0E8vdEFN!qf-PnY9t?IXa!lj9PfTN>vA33nRtqc8=7GX*h}lfE*?}VD zH-;?V=Fh8Xt0k`fTw`md^m_fk`tVBr&J1}C$u_KCczUn`8cAUm)c^}MuUAOv$mdVE zM3F{ne96m8X(X&|csg3A8QdqNVi#oJYC;{-DChpgYDA$#O85h|@uyW@7E}$w@7(fU zjQP&OcxMYzUAk{AZg_Q``?v)rCz6fY-S=pNP?25-Vj+B*J`M3P3aN&t5-yp;3ZUt?foAQ#fX`r? zd=ZwQHFGG7%K68&h-Wvt`z9wA2 z?{4uOZRF=HBX8sp$U9x3A9&X#bQ^nDJM>rRl-=j*g{3D3C{$PKlpA+Q-D$6QVYxoP z_ES-EuE0@C>B?`^QeuiGd4E|m($ah=SgvQq-0#%2H=MQe&$w-qd^1!m)Frkfeitcf z_d-fb`LQXuBC}{23g(cicqE()C`E= zw!D3<_1oU30A$l;Xpdi4b<|pMaU>feb;Z6t>rBY%_yI$k_|&xov6UwJ{2jYL@G{`Z z$mUd0V9%bzEB);Lh?dFSww4+vt$DiU_2Rjc%mN=7fl#D!l zT8N*r(S@K}r8Q)xWR{5PA)m?_vQt1*%J`07(mG^lr!}Q<`ZIpSCjKkbZdd;US5eRQ zX`_^6(he%4+DQ|p^()BgbB$MeWb=$zh!C?kl&FT2V8`n1-sF7hPcEMJ$;ONtG18c) zubrn`??fAoiHj8ly&0!9wZcTqg4*+L0;jR8{oDfa-jBYB17UE3ICcEcPl)3j-!f5H z$@5JS7dV#<#w!>wm@!u6p8y$>wSRy|8BrEr$24K3Z`%jLYx4SaVB?hm;to;MPhcR< zTKj^*MRbY$zKLNDE4AaZ@gaIwf1=U`Ud=3BljoF;`HZaO0cBAZl|k%;O<*zM2L>+r z!%nMpjmBQ^hp>s$8k{8qsq+wq{G%}WzFLs9ZISD+SWjK{a(xd8AG};N#<|yptQAc4 z)@|e|uaZmo2iom`j$6?0z?2`0Rq(u1^3|;x2KVMH?Qnb-4DwZ_Xrq+HUyBk`zPR)T zNjjFMNps5BsG0gN^#o+V_1e)~dCbC)1^Vc@LQdYDVT{d*9LLOyXYIW4^;-A7kJ-GJ zPpZ93XvrcIl>hgReb|T{RilVxkjv1X9WU$S1nyN!Dchwjmb!$9AuuArUv5l*#Qff- z6%VrT4I)U=%GFU?gD^aNsQ%6n>+6M^d374$v>B(zjC*!`@^_pmG=#5G+%_78yFZSs zH@vy(WqQQ1Ik(yF40m5AHS*RtzB|qjuim9qHygF$W02p}j|mBy+Rl8JH#k=YmtLTp zYB8XLVB%hlcG?Zx;XwIBzS8|{kzZ{`Gn=A@pF}q5fIjfYtIvAM_9mIu5yebjq_0`= zbrew5$&y&yuSVOT&<3el>Wx90oHKE#<<5?XX=1BT>PTSm7k7292DY`@h0U4*;HF&T zX4A;UeE__F-uH_Dsp??oS-(%bk%(#^rl9`q-|v4%9cHZ%xRPyEEub~%zdALUzXjtd zM%@2Uj3KY@TzcTs2*v-CK-|T*@p0w2D&q^YfKmr!cy+znt>=28Mg_@RJt4rY5Yb#h zKSu^Z8ByF4+~_%FsN^(CL%xz5uZDM`wF{I3(y09rB9K$AQ4R<+0;BOIQRu07Xp|}5 z-me>PjF&D%;arug2@;LuFuj9vRU5!%bAlHHrgB$a>~qDYVmCrC_wL?o}9`I zfM^jzhyqMBsP6O=0olTdfIU@v#(3y65u#w>M6*>QY(s084eYN%;8@nu?E-cnBtjUX z0ca1KpW^i27Ai+*;NUri@o-c>oiX zyJ_uj|8mnw)Nf&0)G=?rVz+3Ma{K1VT=Qm^fXh&veG?OL5PQy7#0J&^1*58C{K0Y7 zFMB_TTIX37b7rdRp6wufZpH#gMe8+mjmkO~wO@A5YDbwAl(@`obP!+Q=`7 zos9kVr^okl>As{*&TwXhKDwBIQkC;$bPTH6AqZmC#=WK3jm3lTd8Si4&t+G+O2kYN z-AN$AGELSMTBj)_N02PTEDdMzs|wV6Q2uL0^r&7%Zn|C|{#quJF|ONtR3?q#AD~wO zZPqq2^7WK%>upkb%|ecBezP`k+w-+nv;U=$lIYyDMAX7`d}OxP7i(}BE&YP+2HHiLZ>w504%qLa7z2i{4{Ym-h zJ&EdK>px{8Z2lDC+4}9)vi@Atv-aRWn;k`;`){RmUhS2z%p?`_xa)9v$q8S{k)ci} zm@Xr4_P_hbk8A519p+NVggG4FOKoZQHMo1Kkr?pV*Zb#l`t$JM6F-y3x%c`4QO`CK z6*890$DYOqla0j({{uuy2~&5!j0xF&e$?FJYoy8C^y*RF@`1ps&Z#c?^O0L!bjc;NMnL+)tP`o+j@i7ccO{R*wrXyO zBl+BSqpllvbl)Fohjxw=uPCdN1J}%OVJ&dbd{uDN8z&3;$*EGWvB?9&m3($C2vbG& zbc0tqZ{XXz36SVSAmgD0^St@0 ziL#nEm52QX?}Qc6B!_p+sAyU(a~)RE=7+ipXt+*fN*~1zYPIky;e)rJ7<;0{Dv3|E z5>nBDdd>u}3onTU)hPH-(||Oxy)uPgFnQ<#e6rLzLmiOGr6VKCD9WO(K!w8xlAJ7hZgzClAszK;i*_60sr-nmXX6cMq|7p_A*tB3Y~XB{(5f97$>VNnC} zAh-lF*hnb~%$Y>*(qZk9D!EE^ZwRY+3&QA2a^R0rKm9-VUWwtx&*D@XbH&gE>L>d#xQSxBB4;Di7pd^NuN=ozy)WGTO-Wtgjs!8TDM zcCb;{LdEOa!bi5m8lIWwLTQba&*ua+<{&3Iw`BWN*LNHy=-8r4%fqJ0U|2cWf>Ip2$t9 z+*<-ye#%dO`Nl#b0 z_SDG9Cu%C+Q<&7Om&lI+38*B*hEJe6kX#<00Pb6t1z;6jLN8}E-Hy6_jF_BfPX7c{+w}Tqz`4N z;CB%4EEh{DVAB~B!@E`1oSHK*pi`qn2t(VEGN=cG;R;f2P7T1nucxUc=`;5Yc`@M6 z=t;YG_kVPyd1x~5O83rcAjD;Zvu4#D^$J4-q%y$=p~}pAFp{6;t6aA(Fu+w1 z01pA-Nk=^i$ssIDKM!2tSbsu~42Qnkjv=J9ByKZEw{!4lm9-_7fc%Ih%vR%ivN3EG zZOOx_UV9W_HN`uiG+YF)srll6t2TbXEb%@3tnu`7;7>Y|=kI#OdUvJKF-(v!9oBVf z;oW(|8_OxlBv!yYXVuOHTV3uujqOS6sAFT(l~gJNR^_{U4#-U6-`Cy_8hUgJvp$BC zO*Y?uzGd}mV6}+6sIR-(sQFGv$IbL}4wVze#g@Hqnp{du1wYMgecn1`<1;KriruyB z>q1;PdB8_R62|O0SJ>Ip?Hb}EQC4)?q3GG_D#>z|VLnv#U6p}GXds`L>HRq?S?BDM zSy3nx#_2$Az`Lx}nAy%E%yv(AJ?gQ-3S@EUZ12=V=3})E$6vzJ*iE(iqK7ZgAv%go z%PyR2Nrtj35nM2V$l!W%{5^ZRWA1DBU2E>i)sX4N?FyN`BBZfhF;}&S#m`yML%7w0 z8e+1H7Q z-~$!AmAfA)&P_w^50t{F@=iEvYdNMnUN~4~NyM=2G(@jsT%_?`uzEXxMR)Mo{XF)J zF68;-GnJ#X`6TD}A7<2a72RABmd{h1_E1EIgoT6&Bh$Fv{ky8~&y<#)q#oSLJBK8s z6db7LM*4sHW8mOP>(8DT!a@7YT4r^OCH&>5#iSxt27;S6k>`yHtRc@yy}E-0cf1grIYsM%ewx`-Vkg{`JmXFQoYk1rN`@q z;7sqZ5c0$%n#-%(Q%&KV+EJ?mZ_mwVPuGUeIxpKCKP8VS_Y!vP@SsL^?LjlC&Ms9d zvp?@qm9^*hkwVmkX~(~%G)4_t9e>`i|0slbo3(I0MrL5&U5KoWyq-;29X3avElf6X zuuW;55az8$&2m?tDc}8+mL?|NA=~DIv!nE-HSu`+-G|76N(B)K#U?nChrg?dQhC>@ zDZT5fOsY?kmU0@HL~dEWE{)$=ihO9_gy&T1OY$BBBh;2QpjPQm*YUWcj-QBrp@*$Z zX*S3v>6+5h2PMy0MFuss60ac9WZuA)nLQ+0sp>SG#0QdDb)FgY5#fqDG-;r&t$+hT zR75JRh7jO1>=yG!SoSpI56&u%q3^4ip^?S=5W)<4ZT*CHmmHP3etEqrmzW%dN_9?8 zA-BRIfhvw(%S~sbp&>hIazds>>Qezlw;fG%dN({zmp+KruHxau(719Mp@3NvI)B`2 z=yO$Dg9pFS2w}y&$R=)-NOU<~Lz5@N-kkuw}z6GrjTJi>uK^9{l=_ zO@>JFe_(A^)mz_KbLKkz zV(T*Ksc6CJrTSv2Vlsck?WrInjHc+Uhqy~x4H00lIyxT^^ zLxpdb@BaZsgz0^*`7|6&go90NqF4VzVvBzXHK^=t~9mJ?8tqaZPG%jveZ)e}KUz#a%J1U!X7{lO*} zs!qt(NANWR8Uy5el?D!DGH)GJf9lU-QlxGP)(Og6f{pudu9uc=s{M8pM4|2Gp)_Tc zk;&R!EDPBnGf5r?_d*lUQ(;Vod>LAb#=OO;sGVe^KIq02V{|HbjiHfu91oJ)*5=FB zQkd)mX{qD8OMFm@fHv4y7vp_d)&R=h%C>*^>;)m}K#PK>1!N?IR|FknG|7|?jkW<{ zc~>w38F66@Qc1IahgHZ;1Kp!44sF=|S)#Nrq7fUBoVmRQfr?_2H^7x?U;54ugwsIa?8p6^KzLfqy_# zcZr>%J-1Y!O!7X;mo&jnVYkJ2rQyPFK=J}>WpoWMwky;FJcOgSH^o)A3M$Mm+O1Jl zPc1^x9?TB?0m(lUe!mrRejOk*+xA*@SMf28{-zamjeyaI?Q^5r;z4uyB{}QcEOAK? z+b+LybmyhiQjl@)5YJ9B{O2VTfIiiSj$y#5(K32}H}tD?g-x3CIm@pLKdPV-I2|?b zX7*X-%y>VflCC?1j2#W-JW@(;To zOShQHcj3uh<&wNY$`ytag;%@gE|1~}w^To&Y-PE7EZ&(kYJL}i_=&nuft+*t3f>+v z@g(b7a9&%%%+?x_tCEnNUnM-S{d81PQ9_|}AwHp51DsuMZ|L)aVeWx}uG7%4zdtu@r7Zo{w23K9HiMDf=MAdz* z{c#^ehj`b&%yeirZ1uxGnj@P!mh7}fShAv;tw^H3D_TvhI7|AXM6~1K&b^;IJ#zU? znU!T!`KWsHhQt_I1-ikH)6a?|OGEC1~rQL zbex-5_1gw9-<-~-DZAB<8~*fzk^2{?bw_=3$E!ZCh>0`4_nSYpUh`chXC(f)ZZMqA zKDlT;A`SlDGe4c>J25Bm;zn}fqFb}~1xT%YeD#h0ttI#JVV;u|HDP+g0bApQhRoAy zGl#>F!j(If`2i?-8TP=)UfF@$3QrA`k%AGhAx>|q50Gosc1kWc5>H;U_bH!!a_a?h zRL)Oi7qyHoPZGhD#rx8;$r%(pG!j3J9OIYJQwLrU-yfGGFG2$^t5D%n2B z9CP>DynqDHS#@OZwg4h1QZYnZZ_7So^wMky>em~(*so?BZv( z)M7Kp`Ihbrb&Z?V^d98jK~`ppfPM#0UjuW{yJ>~I5*4<&KnOR0uIW(8=-vO?7Ha0m zQLPc`cWuyN5XxI8Jd2bNBQ)T+TL!Ffk8?%3Qzf#^SnIM!wB@_X|8%SJ3d}^tF&<*= z`}v1p+<@lVnhgIiJQ~4Xg&ag?ry_g!-tHjCoWg`pN_%td2K4H^xlYHlw@kxDmLP=# z9Z%wY+}yp$owVE<>O5?zNA+DdlK>{_o#Y`dODu}!HoKd-P*AZF{LPoOm)e@2A_;gD z2@4svTHx{Bd*1Nlrsri&x0ISZrOi!D#U)Mol3zQ$c?2YxIj}b=CHv{%fZT6yC*c$@ z%YK2CB@w0Av6HOzl1lyQ%?=(U@_z=7OBAcmO!~}kuzaJ16}%Mhf1RBoV%+-OtxiG| zTYF2=7;#rKV!$eG@1)fJ&#B@HnfiUQ?n?d0rqy3#a1Sl?tkZ~_kUct;@RHTUxZZJt zrZ%aF6+bpPVV}_xI3{VJo<7bo7132JIJ1#}>S;YKCgp<5?ggmHm)yj7e7WlCs<`hY zj7$isvUZ5oG5Kw7<;i2;@YJ%@Zu-v*tK^*MpYrhotD8B4YL!uyYQ;(8p#hwsN6aoOE}#WBJNC#z)!00 z@7g<4wzK}$u!;KB*Im89o@wNux;w}n8dNq%nhFNa5YX-pDH`*$=5;QngKM(P#wRc z<=XEG+Sc+_rv~| z8?b8jZf=)a%&~1N597SeIRH-IF^%}HkbrkDL@htvCCy)TA3mjX`_p&3@(~90J#5A$ z`Vw-HzBdr}47=uI{>9Kt*^Tj~9Q$n=*Z>}SOQO;JL44>Y$YhGMyzfK12Yu$5Ke;4} zlG*U7=+i!=zdJprRB%_{lYaRj86CL46h6_fM<+XS9GbdF#zIPAfjp0Lt?$&E`6wC~^PpMBluc!#hJp!kH-V7XK{(QGzU)YXm zW&OayVwFAif0CouKCOsLEPAXQ?-QgYq-OUj$y$O(B* zS(IR#ieFFW9o3*jq}gK@V#5L`7JpNoTjHd=nMu`DW86yDM$EpFA%<2};d^BmI+BdE zUaYY3rP%rPw`EAPXxUx|viAj(KJ!0{%(Q)T~<_W`Ibw|J0Mrtg_O#oCCh9)mlaxC3UT0-7% zmh4|{6H}9n@Ihxep6AVnT^-SO*t0+Sjk9cPx8-ETe9T z3WmEVz&E*;60V_xD@oRE#y*)JNnU;z>`(;(92KIq?6fN0SiDMliB0yf6Z@6hVHZv{ zT`_%RL{|w?FerVML(^Q!Y^zFbtqx0B_@PsKNuniM2qRn07;Y~CS9A267vPjP^S+FX z3~=tGrgo#VsU#%$mE~won7X<+CZnki>{BrgW(?4GYO@9Mu4c7=XH0UHwKyue*1uEN zJS30a&O>vmt4dI*%+O<<%1cr-y$;t$qPl^R&Sc2*lqjC}s(PpLPdx-#-Y)5s-wX`U z&8sTB@-_Z0XjK_>;>kwRW^jd?>6~3x`U-C%yqG`ck*x9V`YK57Bz9*BT1Uu-}LF3S>j3$htf@$Au z-S47Lr}@mdx&G{P!K70=LDF>o>wobdgea2_| zt}#u%A$HEsi&NP#WK?(~QB6UaNh3uq)I?G%yIOIrqH@`pm%cB|^0$mG&6+MB?@)QY z!S1|9)JercdQ@L#-zPgGjfa2KIZ+L~hwGl!d2YJKa!Ufi$b2fgT{i)|yZpA!ES(&{S@g{z))HZpGgWg?T&a-moR1iSbl7IfwN=(mo5J)~Ly{t15EO9g) zP%e+jG|u3Xx&K6w*cfc>bj33oXWOeNQ4C022nm-R2sG|F4)`@~pBwiUGT=tm-Zy*^dg zCN2|84dQ9d{&07MrfbR%FozC;u0#~#b4`x08>iwzGP5>};5o6f(qrF84RTVs{h=r$ zLMnF@EAtPr1o>;e%k?q|Nn!t*OE7IeL=Rlnavy~0jWvJzluLXBj3r#u{*yk;Wfm zY(s=Oh4U#mOw^R4gvWh^K^*ibG)6w(7^>JP+$WnYOwz-ZiDxNZ%T_6jNC5E8Pl&lB zfb5+zue-G07vTbcA}L@rPfCcXoI`*mA<^v#kXO-DgK-1{P{#?B+R$0P!vJ2GY_0}8 z5x8x*SQ<6ILJ#L%JU)oCs`=vac1d2S(FYALE(mab^TI%ujCeiXv(L@#&I^roXoRIM zn;ef>P242h#mR-PeAmo?v50eyx-7?}cp z?#RsU3rs_*d;>ORdu=}2!SzMs=0bWu=N~uF+85BZ{R7Hon;9HK(RQ`gCF$3(s+}v% zsaEz*N@&{~wN_Uj#{1k}Yt2gg<1zesYtzb{>9Jv(ghKt*FF3m3|) z)J4-sAi0d5FkZX?1Lu=Y02jsRq7)oox_ z3v#fyiLKJSS@bKcB=c0YLF#Avk9)&6ZKxs&I_f)JUql}%4kd_ANCMSaq+wsWQBWB& zkK?Q2i1Z$1De*6ii08*@V3MZ1mosdfNx<}JYr+GZ!Xz0gX$}}a7Rm_PuHy9x(+nJx zgcY353(m-=yh8cVvEcXs;OUo=E4R)${cHArh|F-|#Y6PF$Iq zN-ccVllUpLQdq*5l!&Gp87X_Ah#yUv-4dEuD;-{0lGR9~U}(2^0HF`2owPfyPkPr? zk=+wmaY|XC8hNjXsF)u1q_{nl%Gg&o71&6XdB@q#}KR|Lu!>qG|QL* zvBHCH_?}9m{q1$uGL}lJ{NjQhWJW+S&#+km^M1#%1k+Dtl*HgiIja z>q4N*o<_+VaZ(bRBKuT8+nAzDFMD`Wwiu+xa=eG=k6{&O?VmilSgYZ+kM!zutok}E zeErjG+fiipp^iO01GC<5ISCnW?Q!Gf_sEyR0;4v!`jq0IQ>MM7T!ByvX2e>qOqYjR zIXFxZN`IpY=-qt&0hL3?PQL$LH_La@6p-(;ZYEc8E51LdTegy+6i#O9IPB}foRv!C z?7o33V*sbmg)u2%3Vm7xy=Fu6xIZOTB@MI> zK_kP`g@HUBiSM2^)DtHdep|i>x&XU$C7I4DlgEvMSc`KTymgGgU3!MX%8-U3rVov` z!h(JwzeX4X1k00R@&*D*cP+z}F&c~N$D-ombY~-HQ=7p6swM|0eE@%xgh9_BQcsO@ z^bYAwc_<>cgGBcfe9bm^LJju=J(;i;&UjLMvS*|+y+9dRR^qUXRi;zqFBWFm_wEB6 zzJqv9SiTx1#XT$aZT$iDSwN(xfS8crMD^rOPYys=fcP%zQ&xWv;3GXW1b3mdpC2TZj`hNNBHr9R_)5GByJpGrcHbkz+-nhuyW{$IBC*b^@#kF6&?AKEll6K`u z%SFOL1L~&4WYcx*xCdhGUI!+Ot;DbDx89>7R^=$(T|;Y+Ur&=noh;i{y(4W1HjP8N z>0va@zGX(Fuk-`VJvVg#kl`b%O(p}i%NdMW(Q7jDk0!{$HMwKYP=DpNncz-1dDdIt z$6)|3eD$_yjH!TpHs@7hQHl;bT;b)oSZYLfJ{Hw}5kBh(5EWW@P z8GU}8Vx0GB_RN^I(LE`lhY#why=nshOl}0Y?hef>Hd{3Z&Y^S8Je`h-zHhf+7iPbn ze+_2gEXgc*>IEa89D!zr&%Pn)&Rj}l8FROSd(Y{(vmhO~JLdb{u_?MLU-<__na7!> z+^^qUvrGprWoSdU{iEzgc5 zwh2uh2T#rK>OUjO{lU$ZX=*KGwr9vu-jn$K@aq9Q@nE_+k$ucSw=qN#^YnU~dY{)? ziZwd|Uhi(iLfX8S5$|g`8yCe~L8Wf1)U5o2sR7=iqh~{OWr_k2R?w;L0!wIq&Ua%WBr9ifeY$H@GImXG=mtylne;$&dccOppj~HTMMaJ z@3o}(^L$FC)IA+-81PNy$S25jaC_TE-M|-v?BsWJ6i!MQ8Qcu)Bci3@{4zWsj7Fc} zwT+I)vFmZ;H7C`MItf%GqBV!l@9XQ-Ngs1>+7wv=_w2HHZp6~(YUTS%Bci0r6#6%s zq_iM;Up{xl@LWt;U5{dUc%8x5W@I`;#gN5Y#}dNsR?!m}#2%*L6Bj`;&5hU7ygejD z2Hxm$b5W!c%XpAYxpO1FRHNV z{!uHDCQM_2rA~r({SP1bP;FTxf3T%6gX4UBLVheT-Yj9h!<7B|Wx=!p&HMSgbQT{s zDG+xu*99D)C+k&wg4$MIHrdW)j9Tm27_~)u5k&YQ-1RUXNm3GlH9deoB@8T=-S}Jw z7~A;pvBEqNk;db_jRG!slRH=60%Q;?iBeSsEUcA(`g=QQKtWp|v)Gv7mu?t9aA7uB z*CWHv+3Y^u{3Ju#K#1H0o3cWr!BIN@oe{Vf2ToC#)|5WiR1mn+zXBT7U!>~_k+1ad z^Yygue5xJZ;R}>Ap2k`M3pnTC+X3lB6Fpc_6OrKCh}XyzZ#X5zo9U9FP2 zVYQFle~ojo-^i}L&~gG^fI|P_7ohb2AHWaT`(^R!#sB?;F=>J(heH+5#biHvf~=0A zlV=A$4g+@zGqysxTt_LxZ#R-BpWyI<8I(aqk-AvajvBpSQmz8RIsT8sayXdnK1y00 z#_7t)L9zoEa3Q>dfe9hyNmN!S{6Hggg15NPn6_jaakCGQYy${Ds$2-2II1`!BL;&i zI>c>tk~##9TRp~8)pQC<&qe_IG_pprZ7jkFAc8AS8EGu1<+`o|Ff-a*tF*lScQu9( zk}WXkNdWQPw)#0Ve1exw4%!NKz)+Iq(g~}ih0}Wlm5@ZJU61#}7lli>ffB z_rCe*sC++_of=qDF1B%szxGxV#~%(0NQI8yKcHBNFFkLYBi$nAnUWtZ9%`?SUsrUw z3Eue2JbWoLWqW|^m=Uyj8EUT5iu;H)fhm41el)zDFAYT*w6^ zWK@(`bmT5xuZT_({uH^;x-FpMtXtNLtEOJ7ViaA3*54RSHrx392Aa2Qk3Dz^D)CNi zK-ssL$6?+pF;+QP2(dfL}t2Af%5hYxZjxDj@xg9Kh|;dMsCuDRV(a4yRFJC2FG!B|iXc#k2ZS_h^=tX3gBMt%h6G>KM^~%+qI1Cas@>qWCfW27^~Y%4ImZx9QTw`Zkp#r+1I>FFU?EnnC)l_(s|8A=cIpASg;xXRh`a!10*sn=kd&}Xq~E4e*V@F ze$V-3k4u_CZ&Y{LZs9N)CVUU}X}0kdOiia6-N?SU(=*i$<$Y8xvIuXO7JXBgOU+pk zm%G87TtY_LHQUSYWB*=kK1I}jYM;PF(Q65GDIUytuOd#jIM!k-zUz^*FO?y`_GaIK zU-N^uQq@`ajQRtMSGKB1>@vEy^{A9E$UebfXY8GV>Q!*IuQ~4L?7QIAp__m!yr;Wwm%tfb7yh_)MepNN<6|V?kZX1bT``6OD>*#4iV9eB{hVT|QL~>S2{; zBHH$4%9YCY{d|ADHc2?&WAhtcNS#4;2H%c+f#i-oX%N4^IB?W5ZsU#p33EO+<@%dm zhToCHijC(u>(%ZgoD8YNyU={~lGdMVQr`JobjT1}b8@WQIeTYULgXxc&4|%TO|^k> zWa)wy!SwwXIA=#%cXrQDr%RjEb|*KzBp%7x%YRtJ0i3xcVH|F<7LkEF{(?gcg-Kqy zGzz%|t(UC<6;>_U57$*f05U8L+q#K*LECUBhyb|;UZaP6i~<2M6$BF|Ktng-cRuBl z$@pMGE=oS1a!QAoH&7*4qM=3|e}Yq%G*m+B4CPaviY z6mZ&2iUX8kzE^D=_@ zx|mJn^wUfLBC6H;L#KjdCYoMEh{Do7g^f9hWY`%CAWt`SZBeo-X2pWq0i?q$ixejA z6lR|XEw-(E#T~YdALIkkb5>d50e4A_Cg*&0sUyQ(^vrJorV|!s%g=pn-iQJFmX^2F zl;0z`t)?-~fz48D1q&&qv?75s4+5#cnD1h6=8BLx>EA>8o2+aTy#P(jxW5^C$*+YkI==h4o(T*)khoe^bnR0`QrK*jsLNrhwPk^yyV%K*1DNG5;MC8jVXP7_~)s zZzC61*Xeucmdl=y!qF$WF#>%u=@kI|ko(u|lPZH*!;0*_ys&Mvhr#j2i(`ct(eTCp zq&Id~h4mlM;P$`8u^s;0djCB^{h#L|XAB{n9ZMOaDJCebMneT{A*ObcPcix^njB~= zmkK2SM;zo+zUoTGq(>+^K@`0!i7!UZ5#e71TZ_1kRrJH*@SW!*NQpc+BTrp<&2WZ%c9KIRzmvj7-$$uYXuc?5R3)M*HV`w z0haFcHCt(I`IDlWMpnvj#=i|y7X)Clx~CTY99YwC!HRxQxRS_^H#=zW=nojM36o^P z#vlr3(9YkuEj&m(q#rdsX}CUx1sQvvmiX_$S%DT-LSX`=T;>h$E^%nhrx+;B4>b*e z05ZS?h^CNj4hpE7rNnse*@OnrY91aY=Xuhl=$x&ZPR2z&3UdM0q2$JrYdCV#`?EG1e zI<7HAyft^v7SW0X7WnqRKAP%ticPoBUy|5*a~;%Dc~(jr2e#XUSU)_PjC;e*!t9tm zU)nFxnCgrXk`7R0wRA4i`GQ0|a`I%~F&iq5OQ|)&l{U68b7@oD(+nq;8Ju-Bpy*hnUC|h;j(a6DtD~O+ze@ z7^&gS5*oDubbqE%hK>??N@Hd7qXI>_Y=@p0&y+`DRC;!}HMicT9Ws0RoOVuXD@ajG z9(tb~0qS~xR=Dc3VeYFybreT_S{)&Fdfgo==IIdECTTK?m=d4VjTgOP#QI&d^v|O- z^Vb{+M+Ru|eX3P$3I5EF%~)`Mz=li0Oq>YJ#zE$r+pUx=r?dyi5f!+f;J zN4{8J#wniV!uMfKk9}j4XN+LIpux>P(X`k$HYs3Qv7>MB9^^t*#jaKuKS9bEf{KYS zl40j+n8=zaQS>{j)?0~b4Gmm$uWb%Yxsc7{GPY}1NgL6UF3);pgW z982Ea=yftqh^|n2a05O4dE~Q{+Yc5DAMI_Ks&NtPWXp6Of4-UE~L8-YsDcBIvUOWZx)WV=?cpK?^dNniJP3Dj|~@Kf#f0=fB_T;UOw zea+CYqXk}FYMf@UTuHalMgSiq{dfVv=jbVwV=bH|5I4RFWIQLx z3{jQ1GS2NQhyoTA4f}GNHXsBtppy1OdRz}=x3vTBM{Py+3F(1=hL|v!1Xpa7q?6y% z3EVNfVDt0}DtIYmRoXBA&KU!x`@Bw>G&~TYqs9*vH+W9#K`ebM zpJ1Gj4u2gvO=9tg;VsBiY`AfW@NaV;!If$h+`?n_=5Dc-n zcwfR1(xQVpN*GO*8Rgyw3Gx?a&&g@cNO-rq`uMo>s_yBz{ha2dZ3iWxN+nv$#I-*| zUZ0D^IknrhS80ZTD>Lt_iukoEmz}eBR6}Avlde)J<>9TG-kQVg4D1%MDYtD_5DuE} z$T0OxBM)2}&6O~<)W0q5v(?6f9PVnZ&c0daVACz^$#$rcbPzZ#?nPPN^6SC8Hjxq~ zVW&_jNk%>d6%~|UeBKXVSzm4_X_cBUk;zX7NkN|3Sx)s&>X??TcUq$EYaa~;gt(>Z z3cPtMUt^dv<}b`z3Gg-nbS{t>D(_$$pZyf!X;HS6M`$en=s&V{b57*DI z!JU7X&vs%5|G&<&n*QfJs~HWl(t|0x0!iZidAwl4hv}Fd19hw+uulvX25oT|L#UOd zwWlXQA*DhXLkJy6+!Y6mWFgcCSZTPxS_F+zC)5G#x2ImN#{C>|6RYT}+m%nw&rGvo z!);^QJI%DdN0+B(FSx>WvLHR1aMCNZse{rXE5jYkhBFeANKs2Dh3EPAp94ix97XRv z0i?7&L(2M77c!!+mZ_kvr(h5mO*jEqHh_iQpBhMJ(1E1o1&o0WqXF#%hyli31#?dQ zS|ttv?M_9kH_CCH>;ptS-#tPCN=h5NnpXuPg8|^TV8jIJIerB}FAT8aX#IT`(h&4i zRyG{O@Y_7dce%dstrqaUFw5!>i2Be5fmOv=6Y)C9?KwDh8U}U5ZAL*_XT3 z2eCaLV^A~{W{tG}xM0gK)uh+I=u(3IE;HQiR5UIsE74NU#nSx6<4zAlPAhkg-3#sM z&)v^TG>1n*pN%C=YOkJVcFZ_;zDTj=!G8S}w?;A5a8UbceJqvtJ({L@wS|A;h4fZi z`Fk5;M^P_Z$ysrQ%=DY&oN^J?2K(2cwKoa- zK7EY$bA@zRwe0HaA9D2nfTRy96EeCjho||SJpMLj*d(E!m@l2tI)2=IXkw|WLPQ>g zxFu(=Bx`>2S}U|`Nti*a)71>Wmn3U&Yq0fs63;he;sMnmUHs)38LIVSx&f&b^cf4z`NUX$zcuycd+lT)=EW+Ti{_P zsBgnVQj)*1mGfc;XV3B!^?qon_q*q{*q_t(=5`9d-yii*-L2QG+pSyiGA~=kLBt0+ z>d;s&S!gEbl$#k77zd8|&y_~7BU&QpquU1$MwSr%bVXvKQ zq`1AA4pjbe_4-*N%lK@;$NO}=MZy?YmOTWMx~;+#R09}-Mi}-hk{MnQSgA|Dk?58^ zuA$7&UXwPBecKl(7S?bNF$X)QUz}!}i~0vt&$%{u?<-~XuNP44X?emC!`35<_>;`t zXT3+!fq5ToEHtG*_tp>gwTq^0@i+236ccA!@*dZ!jx>I`usQM{*X9SksIYg^P|mh7esnieM?`GzH(B}OM0Q9;oeQ7;)M?OTWUQZ$?b=?rG{mu z4E8Nk0i!F4&*IeGn@{6!d?+rCyIdvxx3L8!0(9dfS_3;`GHyo1W^RrT%F|Z3`eB-rxX2@CaqoC{>3#wC^B<7hp1Eye(}K6f8T4%B&T85agt zdi)~8;;U46MHDg3&$69s{eqfDo0ZI`-*r65jg|+CQ$efc3)J>SXEE{ueH^pS?m5-uJ(p2HyO?yXmLLwm1Lx{nA_~2y%g- zkw48hCMCWM!fnGZjCp-iXI};*{4NMc&;{Wp5c74;2>)ZOKzokc(`F%t(@5)ni&Wq0 z1hGQBwNNSzptM(5TV+V6B9hTLC0udxw3wHA&xH4Cd%aOdr!*-KdbkjN2d9LENUKFA z>cMd5cp&xzZ4v5}OV*R3N5yI+YeIH(41uGi5}_m%!|Y2V+v!&kL)!)voajS!)*=xv zO)7x&#+VA1-!mHOgQh4NOG2peTP?VQad0>wBwR_DUY=fYCHaEi>&A_WL&7^w2G;c$ zIt7Ey@PjA$Wb(?W>4nGrN!JN!Hy5x9$6fe!LPP>5>Ps;#0^q_Cm^1rAqxZqjOF_AiY}!<+(Nq${O&Ra_qK z@yPnVkN#PSBakUHEbf5nk~I@ypm^l9Q6D zyubNlV4aZB-o@aiFR|urc(y*kmcb~$tx#cxm zs%nVOV{c#S*~UD~?J29!wQkw>J0I~u&Sh2bFh!;JQ34m!XLZoG`y~SAcLsZ!6o^f4 zphAMm)xHt$Y32!4y?IL6Vs<1+)K#uEUCoxMhgI7>2v64^ZLQ6kO^xg~xuxk(vuKyS zS!`;R-INV}Cu=vj0J@iiJi&s}0VbPLzP2fMHTIwq<(%-gBu4fU=KHgnc8~IUty=`z z8YZ81Sww^dCE7L)a;mINn&Iw)&r6g9h&2vq8Hd~U6B~Z`(sg-eLHFKX?)S#6!n!;Qe7{m_cRTCv@`{?CWM)lkCG%@$?d#z)1)qFg71xa z6M$sAYjo6FYBusvM;nacN!>ORf*~lZQ>#ofoYI3+&69H;KIG)?*`wDVHGR|;x-Z?r zb}IJF@U=y43Kc8tH{9u$_=MH>*!k`!q6G)t)fkr;+W?m_6)}R))V=^l&5L2!#&dRP zH00hoH?3f;{m}sTL6T$e+&H!=clMnWDc&pSv4&OlsLiPMo#-%;`9QP1v~ZHsa_Zvc z#@beEXG!59w2r4x`hDqDl{6_USL}5ZG0TzWVfl(yY{n)?AzNb9$h~~P?irtTsWj7@ z>3={Bckr7dur5->hcML~`+#GI#b4r1Xkgow*yva)loGRf2w18q&LJl6lyMT~L zacXK;37f_^Yd+-(IGeD-CYk33GF&7$BtU|J;T#T-V&*oiDH6P3`IKy)pc1TIJ~@5| zUP7DO0E+pFXB|M>!g<#+qIHbk&U03T&$6ccuHUf@_xh|}eY=9~eThet#5II}W#KatRadtN|~=7I~vh0}-8IEGW}AV=vRlkv-t3B)?^7+a(I zQT!`j^2K?bz{)*`azkDQu6>X})6B$yiBh}Cb<)eLaau&xx`s>Qnjv9PB0N#dKAa*{ z_I`{qv#{CYbQ^KpqQtqT9l{q$-kB%?ESzgECUWd|LETd6u;~$P1x?LUZ?T8(RAoq|Hf%PW-%@mUK@)Vw!O4iq0ZbW7lg5m^KCu|G)%3+}sn&8|kI_CS!+_v`Lb-dwfN7_>U=wBthzUESv@mKOY zfV7tT{6EY>;mu?F_h5RzbLZ1v*0BFKxo!){Cxa=`NWpobv=bz$ix`bPeO)X$>nQXO zGKv?Vpu~8Aebv`8Ua6eSUJ%o+PzqBZax8V#7(v}*#liA5bh}HtRZ!>55Z2Q0-+($y2gE6jRX~sczp>M=grI&L6F$QEWFM_0 ze6?+-8?GrLb=UF0Q}|!w@D8$ZtNZfAw2cerRM?Iw&pIIySOvSu=aT^z$#|oJk|(Fd z8xy>Wh<`u|hUl}Rk}BTU-*Ov@fVh>gd@*@A*GbV1oaGb`tf@JpIQ&_0LRi}d(1$CC zrd+2uLlqDBiSOn1x8U591ry-Vm_DN@Ra02G6x6TMP^A2wBLHYRgkdEv(@1Rttg)}U z#sKtR>ND6{HU&s8FVI2~od-k^$dve8POH=1(=c8yEPNqK4{)K4VsBVOl{($Oeuw_5 z3j#$L9cr$jRJiI1V)M_OhS!^C>#K;jKM21is;9-DU%KBj%Y|E5pu#%3O+(XDlc%no zLNA%|?61cg6)ux6d#96KdLQ2i82DQ}EzI9cj#*B&=*hhyz*ye~pwU9P-g49Za@(?M z7ZLY-O+i&tbxY7kw!>pBupvZsw`pH#t!1s_~yJ;GwC9A~=-6>$VPSo4~z~ttS)s9WTT&hzr_aFMK#u)7=(#funs z)0xv~9mPdySeNfoIQ*X7jKHo(C-R*0Vf)Q6bx(@e7ZVoXYn8bWPr~dRi#L(0oI$VZ zEPa5S$wnr-TygO9{pl*R{X#Z|Q2&F%zE8!PxyJRIMBkGsMP{90hiXC`%Z6FbgJf1^ zw}eaya>^@_(;a8&jBn2x`Kpmqs~Dnuz~|D>3UcV;&t@51{iP4?gdmyfJ(MFVj+`v_ zsZ>rfO_CX26e+!pbA3&;{d~#W?H+ZV!f@99xBQO2x%-v>yq6iwcKSOCE-kI{ zxCRX^z1*|9^Z39#_EST3qT8fBBT6D-iVV~K4TBkd(JnkS>1H$gQ%Pjp#5b`6R?XeZ zO}Fb;<#ey3D=xc@R15C^_X-8tsI3xr%u*U2_(Vt5(_>hRfoiksI+358*6>fC#1Jyc zWUqd3Z=SQ(-2YWknw8btK;=qR71Z9N6!9?EoRds`um}@TNJ(f#(jo$OmN^EgPb+yl|PZ^^liiOTH@LP-Ag> z-LUqJ*sNroV0_UzOP@>Q=xFNOrd*weEqB-{Uo#1WJP0JF zHlZ!jUML;bcf9QXYv22mbrk)Pg)TdCVuCt+Eo=GhOT{UcFcFPWp;=&C@fWo5;}Cy?uO;8&TU`j{wnmfGf8Y+w6%rXW6I;f|uE zbCJ_mdeaT;QyS|7F82f%1Kq*#v6bu#)6(#2ZEmZV4?-ye%Vy@Hm@@`@^E&3i>i`|g z4WSNOkT!V_+QL3j;qWZQ!;+@o$73^R%(*2YPNmcgqsswxfPc#c~6GnpsZO(Lueqi;IQER(Yy%(i4J3aH|hCgK4 zfMt)_;AXN>db6^GUyWhfQ{SOQWcOf^N(Vs(G>35JLC>21&ojT#CwTV1dIeRWK`8wA z^NX?V;lCP$?EiG|ng1UU^S`foca}RuSM&bYFurz2jgAjvrGB9H>Htf3Z#H#XjRJa# zUrV}jC1C+x{Cz-ji{-dal6nAt=N^ohbOi}#GdR`?aoxKQ0uFf&)JHkn%*Yt}v$FlR zHSdtWPCn4>BPTFa0jX$)55DREL2p7Ov;p*UsVt05BjLnLn=kx!jh=z88h!wJO+8tE zR0wU`aLs^l^FVzq3rqE+UjYfMqPA*_U4*dqx1nU(kI_bWQc}7*5U!K7E(Qa~wNw^P zly|}<0=VeiEMB?5`onhA258xAb0AcDCWMIVbA&WDPi2UAA4sum=l^5wEdQGR`@TO~ zkPr#!mIkRQgVEC69RdQQJ0>6@D06g=j?p178WiaoF*-#W5fG3R`CU66$9bODas377 zb>n-78*I1sd4E6e*X#LIokw8vVZQ;#(gyI`83p7JREaqi5wyWq0yjuagaT}PGiB4( z{f2flKtDibcpVqzBrX%6a+2f(++4md8aAs_V){v9VPqj|13$ioRBKogz2U7_($f&- zfis+1yKbtU5?p+iRmsZd=YkOUTDrBUZ7+uS`noyyO1ZgOv}SEx>HBKG611^+kOt89 zpSrHr{51ia&)Dw1i{9(~B}Zv)X;|WDe0q;Xe?J}+E8|UcIIzkusaQSqBKRc80S8n_ zIaRFcTrC*rvU96~Xugy$50o#3Rc+i~#8N`fEo4XyI%heXE$LE3h!E@P-9g_6T7KpH zct$5|7TO=?I`r;Nj=Md)X`HSON@*=OVCP@(K@z-Ka;f#0sZz7$piDRU4t7J7u6rz;py)^uBtOciE}IW`JXq7_Ok}dE>#L1r#ueg zJ2)^=c%$nUCT?nej7Nt2c+>mHbx7gD( zK9(jf7}59}J@Eoi51I`>s2ryw)2mig)Irit*Y#(Oqxo+LfG5(*Q$-YZ5Gu#^ym4qD zTD>S68jk;y?`)-Mm5KcK@Q0|Q(?g4CDP_iWHKI{T7St?)GOnT`rvD{;gN5(*jYtyj zq-?q(gdt>Im0mFTvaa=OhqUcC)pS9eeN`HvcuwRDxEoKtKrbh*^iTF7rfd0FJwWq@ z+dXASvR?IcR_$ELe!MEV?s*Z~@A+j*hkv+Z+a=QXr$NJXR7FZC0n@qi{ilr4S50~p zT5~eG78yq^gMlxlNk*L}!(EFtr~FgY1+tmr9MW%%i+Uf_1pOeWv_t z&=PljG)-X3qT%0lflxlC+M35-E8{-4te#u=wWTO3NM4ntJ$x#d8>s-{U?Tz=dm>vp z81*&s+pFD)teY7*QW46_o7R#+66G@WzfaM>d}4ezo}*7w96n<};T-kUPB zP<MN$CKO#{l=#0`;oLwv&c8a`hB$tei@2B3)}abjt!A|`87`n z^G4gxzr}@uWZy&WrD6X7g69KsYHc85u~8;^6j(#A+y?~p3xtDJJ_+eU$M8{%WZhHs31smkI6KxwDF~H$|JWztV9b2l##u` z52E;#uOL~u7(20}-O^=(xm~w(`*!lPhv$b|{%L*W1uMA%^Gf5G>tA|HE+1=b*i-sr z?PKZvuCzQA%{W;H^KjPF$;(D&0UK6G>pp4jW~PXz_wyIr53|bRKfDH^!-zKCQd=G_ z8}v`!r#=Ey2i0?(X2yE>rwIRa{0E>C9vC56#X>QkqqR_+#}vckMm0oZ%At0v7k!|8 zS=GXj#sGiF^|<;r!ga>^8XAQ3*3vpxhtE`YAEZ%d4LnoAByAN@1J-}r-D1ulayas2 z*k5skRZuB7pbVEm@~ZIO$iEODREF?#pfB5vpls5T(+H8B?RCLH6=E3l$Z(lLPP7aE zLinPnWYb5ko5ddi=Y6J3ftyHli}bws^T^?sU-oY#duW&(D(Ne0xB7!6_Ooe*2g!WU z%#@rap?7^SD?3M{ciXA6MhbC$XQ$@W+VmF_5Ho1Bwqc?dG&@TolxZr$o%DrK5RcpG zd>#dbb|(=Cw?bJ(XqF^pjb=oQNw2W+cbSAcp|5;tPiR9`Zi2G;OBQ*~T1BLVOxxak zsp8^FE{+<6+&GYq%_!0*asWg@{cWp=tT^w4DA$BIQXM3o98OymobC-4}#KaTlaXHNuV)m5tCl{n5^dr^tg9|CLOiLat4m9)|s#+xNF+?K%%u#^g>yYx4U)osJB=M2F11Nf=Y=qHahLXamIL}Xg%V4fBMHG`G`To2b-!oLKDtxu_yZKiETVPiJ*34Ur& zKV6Asdn%T+@ciH5)Pb83lnv^MP%9FmZorEh1D``(HbcLJSyCLlZb?IBNk91*x&xga z>MZ1j9?k%B$25Ej`+smQkcaA%*ozMUYD4)&(Se2xgfvk38E7*V?l&Opf&=N3MNMPU zpoTc#Ec6jBoHCFezrU^uN z02O(fHG-m{7Zt-tr99HwE|!Dfvd6-~)wE|(?<3^_NupoD^BL^X2UF?~hI=k5P?lK| zWY(TY)RTttUsQ0G!TMu;%9RQ146`JxR{CJSS&n98Gt6ElDTJgvqO9@Gfg2V7SDSJpL02OX2UI9X5J!|C;HA(3WB#7V z#n5lBi-%Olucg0n!QBO~3~?3#WlLoDX$khbyIpe)QO@3f=3bXTo=ha!K{2>_U9zu7 zBS4$oc-o&m9_q+BN#+f$|E{ytZf5aG{=B~j1P+#AbU17~$T*Ul$&)Kw^(QMuAdX(y ztG5gE72rv5GMfEHSL5m}*-K$Ci*E^`Z1eZqZB5!{@9G(!dw(u*w)!pgCYB57q4d$I zN9pv37DA+p{p^;@HGQ8($yC^#Hb@|7;5Va+%5>{DD(w^h}>&aI7s?)P&AdUH6>!M8!TO&4yGSD+$7pY84`Y-8}T8 zd9ZyU7km@x<)BZs05cV$agy<~9_mxdNLzR)>m6M8=X*_X+C<<& z&nur7_|S`%JW6;2yM52o3hcSl`PKX5)_M78i`510D}Q8UA^Y}3m&lVo{1-BXHV*Fj zz|I?zCr6_Fcp99UDPCdz)Ja~1HUqQwvsF`gttYVR=TNiy6J}R;ogv$hnmqdvwm)n! zfWuBu4PUK3;UnXZe63`K=O#RyPIr+B#kE}A$B zV$UH$?KOe1JzFtxl;fP_YZoNFoCt`zU7uFABG#xq@+o}B%qh?2?XN!rxMxf5dr4mU z5oAze=C>M3T95(y&4f3Ya1<@ifqDd}oB=YaHG?CK2|Cckq+)5+Arg;7F^N8CqSYzf zaIgW(8~ugl=--8e2nYZ2PeU5zR6Cn{1NZE6>Wq7DH1a3k&K zgyLGx!m7ZJyq_Y}-r46;I#`j|KPrKx<-)PY^IK>EFPV0tbR{OG1ktF`pWHiTDG;sZ zlh<4F)oDbMI_t3ju8$!{!krQS$JqcRkx;aOfiN#~CER;SVm8qkgnn*7G#*TiAyfz# zr*#vlxSda*sa|;8B>!j`y8GdKTo2%uP}1fZI$cc|0Z)?dgo?LJ>p)t9I78b>g_59x)`v` z{={E#XzgDNUtu)p&&eWj!jk2!wDvyL<$ZW;5?}B@gh0ic0=Fc5mPs|Zm?8m=bU;hC59RA&M-edk381#SZ`G0|=vlsOw|7l)1lqcYU+U}{#KTw~f z4n(tRD9OL$a-7lCuuy_;8v+I)wZD8DBScxz5ZN5spHobywh! zJx`mGlz5=wg$=Mg#pO)q^6KabQwFAA#@BRyPUqW2lw;R0xUnnezL2#F>=KLAgKjr^ zfC!0;H-LxGnJt0gv&_E3c08a4SSlD6Ztf+q`T2JmLF{e<-`YNQ4^KKI@zWrR7%P&4 z53n=MeE4040O*!emvCpKk=XH;l)KtsNn%V4qWNigewt`pDpm_a_1x3-G`#hQCtP6| zKIp|?KJn#@qyg+r{_`{{dGc*Noe%)VUTx{CmJHGIf)w6`pnA&bgXmnotjL>aZhm*^A3JTu+T=Ol#c%yZo#{XS|bt z;^jKk(44aS{gpD$eAP?%F(skjKu|vOG@NoUCrFp?E{1P(xUIVBZErsFix-r=RnMQT zOV(St>64{ct|WE3Ny}rlW&|H4;ln||PdKlghS^AWyACF^^EANa`B*LBV2X={Ph&)E zn@{}Mau=;zvLME4O)gtJH#c{))9b?m;g)SE3-v;tRnl25xvIsFA}W$p>hT&iJo@TW zE3Uvh{w5YF6L)=2clHrnNGvx@ntix9^<~bBJp{_s0ZMwv{(4 zIaLwGTr09aud4w8=CArSMOq;I{ZE+H=#Eq}kweATSdML8#kQ&XDd93GR6wGniu-N4 zKy-W}<$DMSRNnA)xOfRKK(bsd;yGUm$wQ;Xr3AhTV;A@KEhJlm{a1p4%@RuZnE-Mg zwOH8lu2+qyg1dc9iYIo*+0i~?PqMaK)6_ElJ)JQ#87^B}wuc8UMVGQY{qs-mXWHt5 zjk@ek;J~Wmm_=u}!KdRef?vOYlhL_J!MX=F0-KI!cS^qHtk`{lxW)5)sd;w^+n=4f zLhJ&lPk-hnHJ+xA�NNq?k=RG4(^3;PU#pb4_;Bg(0%~CwgCf=a1R}Jb&xb!I=g& z&#fa^qLI=Ko>rRivg>P(%0gndxrw6{Kb{Qfu{Clylu?uT){vA-qS+&@edRP5g}6S{ zK0Qmo_#xI&>D0Jxk2rYwvD2iwImp1re3UFNt-6A_JEMs?gAsuE@+`hI_^vrIv9OLD zw5-g=qHHRKU|(L^!ZcnA{xquykjAUcc3kgG`%!qNto*%z%=)^R+l|jbu|(2OeUpO1 z=K7Vw=L~M5Ke37S76Uy=KSc9qX9CNC@g4y*UvZ@Jv+H8VdOPyV=~EV7;TANoF0eW2 z3UBBH*Bf33kgxHK4-s|yw8#SHJ&#R5y{dHJ)B)&vX88be5s8uyEy*=WE_X=y%q=Fw z0JuQYp;_Zy(i5L+zbK?S(9q_=q-1k!rpi=o(Ic@P7$?MOP1W!QjpqZ7TuA%ZLP$Q< zDNk=I-52!>X}7^*dwE^QBuZc^NWgw566Os~Gq+QJ#OItcg>l>E$Vi9&p;xNih9=#yk{7 zy47jo^`Yyp;aH&B+;=)gWr6oX<8<`B-!omVs;>0XW$ocG#ip9()|1kIOSqE z6zULviV?O9*?>6(HSB}#cx52g<~mHTDy881_Gxw8pfb$XdeUyPqGzc@7xqo3UIOrb z0Rbuj8|dM(YIuOpwcV$18D4GXp+(yZ33Hv&yrCEe>Mx@aPs%0UBlIyz=UR#^>8W+X z?u^Vn7X6z|z=G>vNqYC~TeY3{6N7a#$x~~%E7{rE#EB*4-4%Km(-oB-_svjFE2jE5Vd8!x! zi=K$(;55?x71ueBpkssODlsypDp{(iuFK`A9TW5N^$cHDJpG^*Zo(hl46&yyqh|Pc z+yW?ko#QgDzZJfv)e(c#Za+LQ=(%&Ct_zXC6W@*=Ze|zLc1CH#@zCz0;*>STLq2E& zCy%5XXF3@ONh5i7( zR(OJIUgb@L$?1tAG@80VW9)xA-+4~1{{YU0uu>F0(|g8$SH5jRrl|Fm0smW1AS>xV zfNj54Y*pUtu6oU__w#?2*g8%TfCtQ~l81;|g4rNaW8>JFiSMvR=&Aada~T;x;^MNf zK*Q&<41q6kPrdG=;d7vl?UxuhU=jxr;mz`V=of@ArJ-)zN0?kYgK+8+o@T%^4Pxr9 zpwfd`Je>_5>MYq=1BXNld>#n~{X`3jT3iM{45D2~7c}T987GFthT&%oaPzqg)rt~h z)A-DMQr_AC+(^|e6(X%EKrpqp3jlAV5W5_+yDB-ONQ|8{7erNGAcvbwGFzf=Y+MB;E(|eXJS}aN%#J;WLl2H&ee5X5t|{ z$#9>nr%|a-`JtZzz~mvwo-#O9s?G+6u4FkEgni|Aig>b|iR6YTpz)Z*HNPFIiShLv zDBSyTW434NIf^?>9Tab zt3bLLr;!yc7~$v{M6auFVAgYWbr|^-JgZ@%jE$C2EQW4|P!}k`E)xlZ-@5+&d;pU3 zW|{U~QC86{%W#cjO!>-w#4S)!GEEn(^n zVm^5*iU{G<%Qm4MY@2YW`s_o1SCi5|02Xg1IP2!V8^50K>j~8-^|mcYKj79jp+lrq zrzls$i6sLn@@=5BiKIK6;dkXwI+H<=<5VgN5vzsD-J@|OD|Beq(0@nQ0`Tm5}JrMdk}+wsxJ>8DBlp_GYDTCR2HhiY$BE z03yh20Bttv>}HCsShUV}y_Q)krhM4WmJC}wbsw~)&?e&XwQu`I)?v9`Z0BR`)Z|Cq zvTnu}ja3~iZS{$YvRv?FwcW({o8D5}LLNTkTX$W#rdDzh7Ou<2p$7n5;~GX4Kf9NB z9a=ssvnQ}K<(ZnbT|6S_q3lG-tq<6wtQO-iHtjV~n*|Eclc8AjL;n~{#_Z-} zQ;{RUsVBsu5v*DLF$n@XTfL`d7OK$JH*wqLG|k1=DP*#v#vgGFL=OVx&W=`P3X;mh(C3ax zv(zd&1iJj5d}rEn886}29^dk7vghvb#pYl$!O`t<@Ap%9bA()PUR;BzRw5}xBij|bD}5~&#E_hWj1exe4sw83sxUwtz> z{ek9k!YTtm10;cZ=QpGQAXC{R<=ZXsJ16JGebqzQ<+epum(lbUOu@RG5ER2H7ypKS ztVn-QIrQZ8nS9p_Soi7nMwj7PqE=~wNI{wp8p_jGv>`yJ_$?l~IP;zQ3?N@&Gw*1v5oJvU!|b{juQY+(f7%#B51A?xJk#yu1J@k?)5| z8k|zW8ah;nm|dvsAB&%;x$&RtiC9x2Cg$!;Iy}m@V_qj+a=}b_vJP~0=IHBKRyOe{ zb3RJw7I9-?q)1dhAev|XV`A39xw<)VZB19H&p&`~#=LX7zl!e(KNhxE!X6Ab#hWFM z;%NS@0(^xVwjJBZUMLyk)L1z*v&~T_w!>h%7d)+wgT$37?rkV3w9)6B}ql zWj^|1t0Y}a-rqt>Y7tJ^IY^pAt@FBNXB(R{b-R3*<7#A#tP}SNkmid>gepgA7S$6x z>X8NmKAKE?Uw(NU*>r2YXtWl9u5^kLy*t=bork*c;n-0_3#NF&>-giFLV_4|=}Yx1 zaX6zum8|PYswiAWP^oApuTXna$sU+Zp-cG#^usU`76S&I!$) z!)GDb2*vBAuu^~=!z5+H#E-dlR=%1ufntViH8`7%kDk?+F<7GxZN^>OG3O>`M;&=978(n7+EeTY16VlACa#UnjG z)$@|%--TLQ_x|tBPc$H(cmEUXC$NCG zDC@RmH6lF3E~g6Ri6Xaeec7=!1!Xc!pz!O%AJGo13 ze#XjK+|lPz0whfh&60U4@yMZa3pTtx88YjEm6ZHm4L7fHr z8(1|?%2m_0@-*`U{6yQb6W!~x>IAvnWyfvC)O9}1Cz&Vs=N5yz#p!k8>`8d zB_7*FF3x*cl}_4WfFHx`gA3DRx;DPq(xV7R8%#DofR9 z4sIQjBGU18O1X7*sz7Ht3mFg@^W)13ki7TwB)J zxE1c>a*wMmyax6+8y5xB9q-v-Rc=Z;r!niOUA3c9v(%?qN%AzICxvE%r)y=&NV8rB z;0t$YmgbS=eQ~P;1M3L==eyaP()&PNDs?H%-TvCEtJjtXmXOWhqM4ZTrLjRmatwiR zAa}^N($6a`I>*@i<|7;Y*;k!2cR6ncu>0aVP`%VC{Y>3aiW_4f?A2A{QjL(*u^Ny0 zW}B!c{V+Xv#@F4n;mCBI@JTBg*qie{>F*}g1Z$q?laay%$olpljaV5!dL0U7=fLz~Zj^1}G5Qnh0wl}owX0R0 z*cx#y4T2B(N2SF7N@i4L$Imn|?v>hIEl1z5jJOE7wn^bn$F3(eG21E+^LMMjYGP*F zb2*h>$5!1VgJFaOw95f=rvh$_8c;g}tsMHgKfX_3Kfx5GeLht$uN-l5>)hmYe+4$b z_1ms1;K!N!P}i#Pi?H3RdVs5_pVu$f&iG^6>UHM#HB&>3owcae@OvzmV<3bq&Cv1( zi`J_$<2h2OS$Bh%x`k@~!PM-QcenI>L-F3uggV;3!#gNuIvWH~1UVU3t?FGSNp zEP02Km}B#;m0Y!Mf&F@l#h2?$w8vk#DinwgY$&(LaCJ$8qjZHddXLUnUF{~Vuiw-Q zm%qB?v%H$VMI2EO)w%64b6RDp%z9i%63dzsq_H&rCQPhaakFr>k?)Bjl$SXWqYqCl zhiXwq=c6c3XWDx-DcZL4WWLvRdP9_)s!Iyda zyLEny^xYBOe8X7e71XE#wmm{6r<8iACq?bf5Gt0n0^~aUvP)ynMl@f*$os18br?U` zF!G^%t)Hg$EMY+))7vVquI9sV^7c3fw@#jM9hGe&WN?lou;Ker_=!^Id2In#6bXx} z?CddiJ`+qK<|LIq*9fal_~i^6Y-UY=K}9ZV{az;zLPII0ssZ^5#%v?VI2N<6N@d7| zfTs;@M{0sT(Aj=hvgoM=fm$nY3a|5KYe4x#@!eIO(;d|dPKkHPB!#agIS|IGbd~He zrIM`aVg{UHaBm0$*MsxEQ8i`DkA`199&{;oKb6H%+ zaFX$5N2+w~6-mWCt3iJVQ2^A+`@JH7=s@caZkd$_(G)D-QQGXR{Z2>}1Y(Ubx$o4WX_-1oT8F=YC2ymDe@W$U8oC=)^5#F%^HT` z7O`zDcR^Q^A67+2cnk1xxfq7Xh8lSGIn3vwo`4P&;8ffm#F~LeUN{hzaq$}m zCY#;W8i;KRMLelh+x9aq#3xNP^bJ7+Uj73R;b<%cCBf!@%G0EJx2Mf<&`r1N5+Zjp zK@~LQ(7A~CR*s4k(XYEme23+d!>^n9)n^+-w zz3U4=>L<+3EWms`l8*=ce|}J_7x47cZIM5#0Ai6UQ;ms5b&$qnS7Th^JORmq9N2Uk zb6L}3=wL2OVgC;|ant_}j)c^pZSS!$l7ID8EwA16uHmD+#a-wB|G*e4$00w&>c*!kd(+Ca|XF=2KQkPigHe0;qT6qsBw z-rWT3n1zj^q1m}JB1m*7<`cpy`91)yN|1CV%<%yBeb)y%&aaLPa~)_%Sx?Va0}CHA zt6C_{EGLACs!x8`Qh<5w=`iz=>uTV0i;o~nh^TQ=m3wSZS+_F{nwZEB-)iv?BGURW zrANDw3BNZ*dysU6iVm1)L?H2AGwYj#==lgvPKg-E9{rHS3^sNOVbV{KIatI+yydqW z%+D&kPiqG_z;tULB#R%5DuAa~3QH&WA{^l`Px*Z^_U(TWiM_!yO)$FwX=>775KC+t zmG&(*BqI-IVo7U1f;nT;BL%MVd~B!djbQbPhtkXu8_jO94>LV+7jlE^O{mr-vByFL zKNq?SAor6kh)oPo(e zjU3aHaX939!AcUU6E!+0B&QEg%6iDL0T4g~wPg=gJ4LMqO=aiQd%)!BRPUUC+=(Tb zgB{fS3^IxY4oiqCD_0-e<8&TVW&FEx*v)=RkBCTE)hsmcC*Z;Hw()UMr4o7ZF`te$ zO9@iImEm`$aFv77*{L;mk+WN+#R$!;#zDe{qiO1XzI3L#w8hil$#uz*dbMe=Ch|IJ zF(*V(Lxt4STm9Bl(TOi#yxvmbb)_agJ!SOjZi6lTjV=x5dUWmRBKu_=it6it9|0EJ zFS?4r-DxT3!Js^73{=cZWZfKGssau0vxAx4%7Qt}J(`II*RxpWu(=8t`u7^UCUc{j zcuU(~wc|Frs5V6_}m~JCN3YmC@CibTyP0zhaK-Sdg#^l zh?L%5*7>@qxjU3wAUU3IjP>yiSL9l?Fa*kIcTqR|AgjztGs`_TC{5r`Xsxp_8`@rx zo)p<=@K~&I^9Votqh<;6BsroR_H@f_Z)`VTED9vLuFm{{@jOEOu_lkzWmr}6+8%h& z7q-O_<;D^gzW&`cDQl3VBd7P1yxyeK)BYfiZFg|%~2d6rxtkW1R?d6r2DktH? z{D{rYu<*@e3bNYIneL}6B7e6Fecv){-HE$oLQD10>+e!bDXwE^=^or39W3!JL153%ck0kfyD?Yxrxt;`7&}xyjRoZhFAsz7} zVncyjBzb!Phq{z{`e*l3&Mxk>#`yBU)1Pv`GTbEj%(8SN#8SJ1P$!$iMc zE&>C$`t|Td4>CT)&4?B9oYz5J7=9>;6Tr8Q69`OQ)+}Q=_aT}F$!_$`fRW>rHZ-{XncA+MlPtRku7Wg{fkYnC4^ju|_+=!pvF=V`>z|?RV8vsvHJK3zXb`aBJpTU+U1Ka@_$LdirCie2omFMJ}YLOHb zW#m!`0?Mxv+`@X!q>X6}+R;q?@tob-OeL>ODq;vfM(hPJR|%~oQag`J*5(muT6Syj zB6|n7afh14%v^4nC#t1}s2#U227(ys`_$dLq^^>-SIg+?TcJnpwWu#-7Hmyt$gH{` zrbhxSSAz)D*`)LKO4gdjHk49JID0Su$=vIilah2xM%{6NZ>W{UW-?jn4~xuw1+}4T zKJLrmrGJ*9+DBHb_o71WBn}sUI@^1!{?c`Qxp=Y8Cwih$WUdsQ{tC-Iuys}D!$FIl z?zCd^mZQWT9AilpyNIUfN)6EWYLY!NpWM9zi_d(?*irbAl-eqY%S2oXEo>AaQ)QK` zAvoXEYc|F`-LtXTCS>63HpIT@cW6D5IWleaSj^8RBygaPsldXt?UK`S?8D?3XE+bg zR|fhWKo&*R>?FFIbWs=^I4}NiENt7p87#;0*OQw01xe2o(JiAV&vGZl1Njs;UN!e< zHJ8hG@dkrz z=izykV~0sH75GN;^IX%%q&2ud_o7 zvn7$RsH9#{X-*ceZ;(SX6~!vn(D3rWP@%ts#zM@s|0Oa1cy{31&TA8`F45YcUD@>b zKyR`DeN*vdMW->uJEp+$$A0RG;cl~KH3<+ArhLBCRz_F(Kv*sN*i0%uW&8x8fD`_5 zGz^W>#yG;}nQ*L{l1=D&Z?v5y_i7=aQ3N{mgvoejmJTCoj`;Flc_hpPbl$1R4Pt( zqBsI)pHT6kx-yRUCbR!_G<_DG(>l-Ub0pdMS@>9kn7*c*%U@A&ZTcvigAwF}MHGDR<~3WX z!Mv^U#Of7d`~w2bt!0(#_TK9J38onWN#}{eupLb67v^x}&j%Awb$GHBZS}7X$=sHL zFfKThD@#vc3jWz_ZM|CB%j0MS=zsij861B871|vs>*&(=Hv{cp1-W|kn5#8gx2`X7 zqI+W_LJh47)?4j&$bXtlq36~j%`~ApnaHv_8@OP2a0T&k-v#MyQ`(el$^pJ|k@=Ld z!7t8w>V-QakM>-U26g5541(_hUu1p?u2(;QYS)@f9(EX))EN5CS8AH{%(6i=MSMQj z@mq!`3QM()BKNUWuML5|u^4$Q>D94U^;dwb<+70J6h7_!;^?Q-tPps=)Y(pU59z;7 ze;u~z;fg1e*JVj$D|)#gRBUUtxKp$bJ-1o<)iiMBt0Q>q=oFK~lt5tRm}Fft4p#VH zYpa-D@&&~o=0FhRC&cLK4mVx67nm{Bn`zV&!9)Cd`#9Ky37paJA*aovo2&j+dF7zX ze3VveDp$dA5wICpqD<#R_*5nfTL%6dUA=hipzMwA_?3Xed`P@IA8HI$_{QIGW88*! zTH_eMMXh{kueQAJcRy9RGmX^bL2QeaiKo-kEV{6gV^&L-^XZ2;WQ(irbg+zzCRE$+ zLlF*@jhJJ8kfModfy))8g)8pnYo|y{Hiufsb#?z)aL#BeDtfdTZnr^cZed(IkHwfY zh>}S1EO+E7K6G>8oJNfWAa1P)(*me(-eg;SzbjKYOG{BLhrYcu-hTgKQnvYLKErj8 zbGbRE>xZVbe4X!CZpE@pm_>)5!$e2}b%N>hu3PP&c!FJT7)nC^BATMgGgYuDzIU2#o&pZcLXCqzj*Mlh?#rO<- zB9^L1wplD;>4Pe(h#HQk4G6)g?aq%r`TW7h%9RBAwu^INZIVMYQcLP$Uh%%z?tjv- zbBFjy=a|{wjApQOy_L(8F&`2ER>feTJj67XQ>+I~cU%I*i4DHL6XQKhDa%W$nN&R0 z?T_9hBl_tcyYB1VE8^WZm1B)7u?|FZ)P6C%Dtf9Lm|KJ7i{C}Jdzzc@IXwS zb=%}1YG-Pz>H;BGsesFm{=cky$D$(^CGQS0T2q%tpQ7@Lliof?+?tyGy3ej#q4TOu z(N$E{g`T~AbjQ`z^h`FLJzutnoRAOc-RR&i2eUvXsd-TfKk~L-Ots$4I~7;xeytMn zSZS8Jhc!M}W+#0oI;*ZWk3LuuA6Cc3?#-0wZs5Np{H*AL)Z#K-ay4@*av#Hc-^`9B zvHt^jcKHwB>f-I-XH)#tG1iHssJ9>P{kwDHnq+gkPjwPsvmAKYzq;>>m78emw%x2t zWEv3CYW!sNs)Ws{%cxg06=4L=kCwQhR}HGTGo3pwaS?#P91)S9dXzSMk@{Fy#-jjABEEd3O&(lQ#`fM z(j(n_HFQ?*KmD1`rNi5_-MG_dZGmQCz{7*Ap*4y|ts%ZRuULj69V@TSaoe`rfVKL0 zru6f`|0+YD!S0zlT{nLWK6>SJ6LD2%IPjUS{Z~U=^4M3g?dZXE9~gtu4oJ)!g6(QZ zpPY5g=VupBhH>n8=QroYxfFRoxF&G%E(QXnj0=|ZNuzy!1A#5smyf#~P2PQM58@rL zXb@tYKVQ*&)lgzRm+s?fpXy76| zYCM)xe=1B4d%qzW z)OR+PO8UW-nQ*zTfOlwhfrjUN#6j$P9S~m6t6+a_)=I)Hd_nE(uYZ&py$l=( zc&tQ~n5|GXi5&DE8vq&$jhDy#h$my<$l%wdr&+ruT-B~7Tnz^HuM8)zJjnh8*z9Kf z9$%Fcn;GtM*#KH2=4trhTh|M?iIv7UIMF8%HLHaL!6vcp_1llc@i3z5+k zi-S>Pt@thBX=|VLZ1KFE05dm&M zPa$DyY6cI?-!5QT^hBOAbHa5f<2^p}5GJxD_cU)|2`mR1#G$LFYa}R~@THKfH@(i0 z%ly9iK7L#-FGM?*pd)^*8pOx}BFR`nIc3L}14sgTaJ4FStGntbh}-71<1&nrD2AKO z$Shr=B$s-R;!9j>%@NFlK= zEv1MEM!v#Mq2ic?(53^UtZW6I;}hFjL#H91E@{7-%FrvSqKtlFWlmYd5u z*JH)=$00P|6uHIN_rqK^F0dU1J?RA`jiX-!m$XUso=+)42~z^kcy&>;I~f0w_g6d6 zdzMlpK}51#qJ$ppi(27LzCWm03O}vZmP&@t5*VZ1SpAhl=RN;t_#CauPfxF*k=2n~ zzE2O}36_v7_Y;Qk)`{!=ZyK)auOa`}aD8Ay^K0Q=Rr>Ai?mvLh?n$2c2vP*(c1nk@ zbc$^f$u5hEO~USNB}*qD#3hntI43aa=_DwF4OEYf`j`T$kOXl79L=Xh&%;k=r~%!) zlSqlbE@;3rnf<-y7hjY#Q?c``LWx8k8MeX>m_INUO1$+i&}doXk1yiUOA1_(XQ0kH z(Nxz`m`A9PN!q8%1WN#XdFd`nWM>PVB5<{tT_oOZH3O)#u_&J70e~da%-12;4=kH` z2tcarY)+H*Bvk8EjfhH32OFs>qn}A`M&R|7ZeRkC zL*1f;euKe<(FGQYYS@o>;Juju#e{x~VZzWIEg?^|@jfd{%c8Q#u`I*RH{gO%B$+nW%4r#sZLZKNf+rj2}Tu&sNJ z1H}_{&9JPUH%oigAJR_v>Q3Ir@E}}hAzNhGv6a7jOOM~lB2|Xil8&G$ za^!bC!*x*@(`}9SU^{=v-g-AVE0uM-{7HV-$hTj-fzb{D)wj_*5#=X9E;+m3oN(BWGK(@ECV>tIl8;#!vR z%E$DHY8ZP|4s)X2{lX_6?gR3$AH-eCr7KaGbvE3t1Z(mIqqsUjn;#E`xVrl1q&#3b>Av;@MRfiz%IT!jf4v_Uj;l%iwX zsww@E;itvIgt@2PU$W)ETSe7qPq39TfXS5EmDB9G)!O!VnHT%uZ+gC~4$lI9INtlc&rJ$@Nl zbcUU;DL;_GW3PSlHj<+Ag;bi342_w7p|9CSZK&?w_x`75X&q5|54207zty@}9nQFR zIFurU=kBjLx}WJ@^A)Z%Hjktz%5}2SlvLe`HA?yQm3&F&vuRA(m{G@r9fuA;UqQOs z?9Y~Td4OV6I}uW_-XR!YMcL38MLlB(T9rMA!d=-v1^amrdJvlbWnO5ptj+L+;Z3&ZrwB@mGhF z2Hhx?-(}w(uk=0f{fYQaFUMOe#Lx46P)X&H@%WJ6nA0^72L$`8c<=qm|xozt{e%q7<)>So{eFOi@cV6$8EHey;xxU+4X zquI=Qd@0*kgnmQ*Rs(%Xm`dARJPG00f#nt0%qb5PJX?<36(#~K1RzIuC2pQq(2W0( zQvUY7IWS?D)|hC=Ub3!i!nmzPRmHY9Reo-4|B$~iznS>eBmO<=)f=xilYnzDCb|=T zS-GgqaQRq?d9)KC4?JX$>(^wolsuwcL=}b>>4@9N;N#2F`yq04x)GSaj*RNI`iObq zTXF7$nE@jGd11%Sygbk>t@8yBUl;EX141KwKni<{KHL0QU2|1 z8rIRa_EJap%7H+eXZF=}GJ%OZR$3_E;#maGMo|Vadd2m1M{03vm&JCntpI&tGCrsR7;6tx1*tKyukE%-4QnDMJ>00!1~WBBuEnEGUp zNlm7nm6O=xL*vNlRgiG$;#3n{Wab1P_fG#GK%>2GUZWkDOqgB(=E{QAovz4agjlwi zCK;N3o8&dB=Idd`hb+nEBkP-j+Je1EzRJj{FU-GFc9GzVH^sT9zISqLH1m>Ml}^uC z^y%KT4k$yf=qV#mj&2raVq>S;6XJSUH%;%S9pAla% zhHNH;cSbk$j8!DA`Fs8HcvFLojyWMkY%M1abNUFy-d0ouI&*Aj7vUO8!r2lfcEs~~ zF%X#8=I7nd1{z#JF;m(CPE2!{(hL=n>qnA!CS|xvSUF`x(~i?UOeB z7guTbdLYlt5#>zj&7tnkrS9U8V}$dKeRgSK6i`%ucECGbNXM4v@@^BICLo0?TuKe6 zu0Dw&21h?0rpPu7(!cX9TL|CRIU)#HR^~{^Jz!z|2M`n?0*xXu^#qyF%76FQZ0V4pgeW5r84Vo<$8h7#DTaMyM6Ux ztpenxy3_jVsU_W)qP7-&^OMaWWizwdayarVFO!~}D`ZFIyREiyq?E0bM@g#=x0|xm>bNCpa_;4vJj$}s-T~`z zNvuP0fZEkjjs7l+_m6paK*F#{JeeDns?t;rn@#%{#n|3r3FB`!p?R*Lq9Na!e|h)uNi^L<@V^iBtp1^U-O!Biu>t|z};e4{1QU0L)GOiwgH zlYFM7!2y1B(w&`!(MC0%p?++}y-BSmr`;&s!KXp&7TsEB1U@iC1() zyAhnUqU04<{74_KuojZSn>Cw$Ey1RB=rtG%L`h>1(MhVVWFFE+ghISymnzvBbNZYF zv~5e37wqr7d#VF3ukyA{JSUuDRqGvl(@id0N-q!_z93vM@sAL1L*N=~ZGwPzM1qs5 zNmO^KcV@CT(DY~CC4SE@!{VeAT&tTegW}qs=oS6O?5w-xpcr1N$;Gd@RgSLdII7>q zUf;KoTwBD(3Ay?@*}KqnxZlZ`YIW4ctIurnzSfco4V)#x#+>dvC%CPIi~L!r;<*QE zuqgEJ$r2g|SH^s!18Pb1!wjq>!zaPK{&}Y}6%TiXg3S3v(!VT*GjPd+* z0;rLySt3|4Oj!zt91Pass<^Dwb9p!9?fT~s#nN`ivih}SFJ2VqsbBMYwsCsXvV5L` zRSIsfy^NYmgk4;5nVpouWznX_nS{Zg(B>@KI?6vi6>olTUcW35q!$T7%zd%@t;bGP zJD@GYHQ+qlcxd0)<~YP$z7Zo4ub#*w&*+68lxVB|a?7f-q?|2_U_7AmOpGXwSWf{6 zUQ~IuwXEG4P|lNHwbhDtk#9ta^v9TgPx35D5cKjd-qD0j zavR=zYK$t-{4Oj<&hY-wOgVs$Q=@TI+Oy%Mfqn{$aD$}(q4_I_9lv)|Tl{(vAJ%@d zMPSYFj-|kaT7R*@c+hnb#Ej)3mHHU!x0O_Tfl!9bQ(8 z>i7FG^1XoJ#z^Z<@0+`PLJ-*DRfC-@&XhZJIT{99d-eZU!E_qI#m+u2V6ZJ*_qcxFh#JP%37lvV%EL z7l^r?j|de|zA#xoY8Y;fY}J4CUY3(_ruqf@(}3Say^qO7B*IG-EI}j3C5(95!19+$ zqGv~3--cz4-RKP}`VB72Y~#JtaVY9q%mV2oBQRP((SX4|^@7Dy;$`AF{j83A-)fEHADfU*Dmvu}>Dj;+Z8)fkF~2;g?M2)qMyL8D%+tv#`DaGY&KGzd2ciZp zNWb6mR(TW`87N}KFr4HBjmWW^{djAP4SfOWPT_t@z&n@JysnUZkE|fmcNY=2Ey0Y2 zD|TW@(4rU+@R5oXcMUfiev~$iFNScfN_OD%*3sVlYG032UPbztCoV_-&HKku%RMD-biLkAfQXc%Mk)9%)LNz9C(?KXBQ=jCq^}v(kiz zV#6ZBcq;v|dEOi2i}*kzx3+mrq!h+JMdx_Fy`BQTk<3Frq}Sv;d%IY3Uw0n{ch(I? ze6%R}cMe+;@!w=bygU8*pv?Q9w5w(QbI5CqDtO@M1G4M9#tj8vxi1$!lw(Z=5_m^u8<+Iu)49Ek21; z4ldsB7xNO7C3$2EF?E;I!o*%yVORT)2Sd=QH+r@g1$cL}M6Yg%MjzG@BuJX7Lz!FR z5&Y{X*ub_)!Jj}MU@<3VoAXvrZfRs;Ms_11Qo3EcS_Jwc6<*w>r@6?uGulxxPX&y_v8?5X8eJ0#Xm>NF4fc3D0lOog2FYt9U& zl%D&Wds~3ZCG}9-b=yn`zfOs?+p?$64k7D)l68O)73rdyg1H^o;>?GqlPRLH?}h$O zUELY}B6cG3B+dCD|4Qt#3gLuCZ^}Pm1EwlY^P-U}!g?uUk(J3&kO8IPbZP#8NV^tV zs|ZFR;T^mAG|rzm^o>E+U-+xs`HG=?+!!O=8tju6Nl2M-!fm-Gb5NFPOg=|mQf)}A zk`k#JvPABgTAXJKv=->GT=c1Dse2dBhrKxS3*gS=vkR9RuARLZ(=NKv`Yx8W`EqQ~ z@d_}XH7q>#I4dh5pc+#q>+=^!HTd~oWECbxPdJr6k6FC287k*2U?(gq%;_4D@GU>y ze#})a!Y}41Dp!+NWzV`!IZPa|HvjF$x%Vz7$g1tLdw8|qF5GJ*H(^m9iSGBZGqlC!&l#etm>xkPwJaj6JVX z+oY+&`2Ft zi;C^&PP^@%qS|YTnjo+BsJUr483gsgP}K1sWnu|3d^&mGYI&oCJBg};WT7_iRCLO~ z*^yguOLXUZ5Jy^(Qt6~P7t&c#wU|)4!`XQe8AcS)G-y(rz}aHiz}2JQ?{nK-uJGkp zJ&9Xz0PKxP(?2~~O!$PIDv42(%MxgEVW7CjN?sUWD%2&43mlAojk&^?J3rJ$n{5%6 zI{oZ=U+I7`M06mFOXXEt<91iWiF5S4^U^xNoqdzo7)Zn==FL@br-Mx*5NwQfMyhJ< z^2*9`<96tXw`=&Gr{k(BC_1gFu8fy;6Kbm*S@Py3iT7$%@kX_?xEYu>Rk8WnYKsug z@~B)lVqe9sa0rBWC%(&$GcS@vO$PDt2I_I^$I+J6bF&q9o)NctvwJMWHv6(O@@xR- zsrG%`PWb(a)1$p`MU0PW9ig1VIC(spbY|y8}R_d4_BC$DOyBV*0No<@Hg_9BO#L(JWCc<3 z^lGInwGcWXH27TDsDWp505WS?)}kuSRq1V|DF1b8GJn`7|T( zo%*3fA3VZ0>WNa6>5XE_{#ZSNqBK+@;jyWa*fVYc{X+5$fcEL|F-w6S80%A|gIb!Q zimzPD-uiumsSq2+hqQV;LC;$QA-u4Ser+_PrXWRl66wC4!rP%IaY6dDdLMMPW2u`| z`#D&_goBI4fkGW%d;V!q+4q;ilW2YtfGt!Ow2`plNP`kPAm=eBR!x1|?DgEm0W#I$ zTFOzoyd7Jk_E8JmMmzu(hUja8F!iVo>Poh(6E>(#1oVxvDRfl|O*rm_{kPRs&ge1B zoP9HDEIVkY=c!3yw-e6P!kCs1r%P<)P{gKa-u$H^48a<7(h5}s zyu!)5^gdMajMH<#4!21i2-YJB(zDx5J-^faxfnq*Jg7a8kXx@JKnJAXO_e3V%aoq! z(PGL4N~G|=vcMI=1e{#4G}(*l!OG*H{N{Gd!dd4%)X zA{)~Sx?T3OxVe*T`{tnWq1(uxgamt@hFW~k6lHB&(o_fP{rUrEq>V0(;j3ieq;d1&7R=Y#8`Sq9XKQEA%-uIP-DC>Y)|F>qF z)fe~WDrGr}z1z}m>88}^_dEtqc~HxCB#Oq30Ab&8XQ*beV^U|j8~X~R%ZUoRA{^@y z<|VhKPi07gAH>EA75~Cz2vbV->RP#~I`&{X7FnQUHyK!-Yf2lHYHjv~ok`VX**@8l zGB|QSLll?i#JzW4IlkO!3gNHF=C{G)k7yyCLtd?s1nYetplh%_KPTW^Y*ZP}e-n^p zm#>jg277h29a>6Q9tLIPS87xE16G%{6u^O^7 zrPQsP7^{k@?ZlCLXhu9)W*FkjOcJf^FD@`bvUXJx2DQ+N~oI`O7rrx&l{!r=9W1_H;Q!n}ckTXlOJLAN54`w(JReT|`f<m1&&TfObKp}}(8NF}hXE(z!&Bnw(Pa&onLx!D;;XhABc0-~m{rPs#_EW+H&i^8d(V2mzv zUzU=Yy2YtE!Kupf?9^%8Bd`Fs_!L&$2zZoytZdPcZz`dKjdq~WWAen{G-2ZsdKeU- zEd9h6AWOL^jSW+~?qYk(z@*0HXfMg^NguYfbx)1tSxpQBStGAp66ts`LNLcB35i#j zRU31;ug8;BK#rqHcCt1}d~i<_@bb$KAZ3IjdU5$xCTH5h zdc12@(8_8l#ZTv^)}Ha%M9wP&>zG}Ra>%W4;jS&G9d0Hn5Jcm%M^cFwTAvk^kXtE;!L>oH4+ytU;TrwP@Kf z{)9Jf;)|-m*Vj(-?<%k%U&J=jRjyDR-AkwK!Hqx011OK$Vr8)gFn)3JM~g_8h~~Kt zV-)@MoqxEEL0j zGEhGjJL9P{WNWv1s9V1sNU@XTw^QH+yDE4SP7D7?$%!shm29FJ;0ayIIcEKe!>`)V zpak{SlJ%pt;pH>2#VqhkpMY~>M8s?D7K3KK@eK9(^|P)eIQeOLD1qatrEpm%KLW%` zUagiUiR;sZGpV&Y>#C-S2uIA-4z5)CPY0%KRQOUJS#K5&>V7hHW)$GoQg*VIoHv{7 zc0)VA8IdH07C}tr8e5~~%o}M`lA!pe8W;Txyy+Pq#W?dCbb`?O)V^g~AajGSB{Bp~ z>n&M1KSSp1E9YJf-We4q=FC}CVruwZO#APIALv+R$Z|105SDMciWGqV(g$lU1cZru zzLWlM*{SNXhT_H>(}nuTbcOl{kRJRFz%pn)ZGoxCBuA14dE(F$7MCp`&L8>PVP>^Y z0OopCLL|yI+^V|}$RcHPgblF?$qrn~TQ)My7dDP*J@Et2Rx^R$gY^O9VAx~;#T;`2 z_h)=lfArTUl2%YW$xt3Sl%SJbq$8Gxpt2JHBf@zchh}oJgtM&aV3Q>|i%*92?P%Za zgylM(2YbGqTXxn9L;iKd(FW%CN2n)&xx?*~uHf{vPXG+uq-vyEkx9E0eZZV))qZZ^ z_a6lc?)j#1J2?-tG}4!V1{~CD$&I)R+1SSzw}^zdGA4*Zf(pDC3dMDe{@Np89&l$pyjF*YFXDR!O?=@eA?8e=z#_l*d%LOD@pAE!{6Hm z6dcz^*XDp84D0*#XD+X15OW-UvLs#&K(YGqlSC+z(sWfQA@s0`k+?~W-}m*t3GF~G zRc1(1KU<5HmT7H{=EfBC7Nws|tx+XzxDYh$7YV9zwL!%*UXMtquFY%PebQ;}sAp!F zqSCmVe@ycO%VKshz|A4$WKMzY7j8)2YzKz}&}$e+S-5ZQL{CxLOgZ^A>AFZ)^?ng% zbn$ozvtX{U7yDQT#M(+0J>Iq6R8Ft{qWwgd;3S~Ld1Tkb)=F`bGyO{nFHTRht}-GN zYE?xS(b@)w{(RGk6g^d{A1WvuWB`BO0WMX3aaDFH=xMk5wKo5Jb4jsz_I_Y}xS z_WVE{i8BFyoGM8>a@HBaQM|t0MkY&x=MkSVh=ylU1)LNLO|Ux>FayLYTpuSwl^_b~ zb#PfJf}Tpmm%1582oeLu_(Z{OSiz87XI?;90`kscpBjKS>Uar77Ak@;KS1DQ6ElvCpU=opy60 z2Qs_K{BK8H=1=L&K2x&q5fO`UT5TayH}dH;YnDG8u+TGyJ>B_MB@(Z$g?#H;ZKqi( zM(n9I+fbP+x;F@P!~0;w7IiagXI?H{lF7rls@!(NYBs^Z1zn$>h{a9`vI;Z(#d`W~ zS$1PX@9*5!|CiYyL(F_!|$EO z=Zc?wq2|}U##z0U0f+~#cA>_RA2B>nalR!;RsP^Xzl-LXJ_#`HcP?)@Hl6!Ep=5v6N%3 zw4mMSOlD!b(Uw|^&eddc=aW|FZE7fT*Ew#Z46#!+SIOsB33O>0-D$c9!TC%^hIOK-kPDCIyv@7{nsV3R7MAomS`kt^kSr< z2kVyL+FTKGETHE5yaiA1SKgooLeELMh}oU)Ufi z{vGlw?(gz^DcOzQw~sq<8xeDHiE01~O#ZH(ystXoE&G(YuWx1-p@>1&iItNA0k#wl z91!VTE&yzQ0%#w%i4hwUPo<(b95MO@2OQwXNzE4k>gy71a&xocXK|I>n7zDnFxJup zMGqs$yHq5vQ7Vrhu6DujCCeY+N5;m5o4ElKH}VJe5z=;L)6JS{L^Wg>2NYr*73Zxu z!ZShy=uY4*IqjP}zmHjWJuyxP(-CTV>96*>kL4$o70y<{J$s17$psaM(zH%)XLr1X z$OJZnLg%ilBr@4Bq_A1(CA-f$A;nnH@89K?dCMo~#_bJgsy!n>?dx)g^_zVCT9uUu zS1l5R&x9Zeq;SF?)66SI}7Wq?c*B*93ymT>-uFJv+Hmb^5N)eyaAHoa8=(42*%@gvg-6!CGgjwp&M+0rjjrKW$&aP`Wd~dNWwKn_w_Yh@Pq>)An1!GsS^W3yq~nVWxk zRV!Z`{7a@tysXaZTKP8>n!%((|J@pqLvQ{qJ@fxERTtalA@`UAadPK>PEVyB0FJ<7 zM~+N3;4>891vT4hW*342pre9f!8~DDs+jIhke;`ujH%scZHj3WHz&nd+*Juq4EXS} z#Fhib04T7X$+^(O`bp7qSuO_yNbO01ih&-A01j{Ua4u>|J$hR>HXWva`S#TIkG=du zzatYu=ObA;Xz)}AFD9TUzWcHyPa6(+#bo*>*ggV{!KX4xpviuzYl>k6#T>;pQanoC z3{D&<0akZ}Qt18;RJ#$t4D1Mv<_P@LVB5*{bi+eHlV&5y7lo0iV0i&H5iB-%p7~BX z1Y0@*yKo!@-7!0Mp-pHi4sbor`*zwSYBl`nUq_lN*r1axC;*3$~SuIeCJI)b`5FGHp{ zA$!Vf40(?1Ysn~1t(g-|K?2w{B{Ph=I0_w6xHcUvV3S7x6ZA|-Tb_=U+9#2q1%N50 zQ?(=$(y{>hPa)cB8|`|+6@6hpWX9X9Asg)mG8@jMCB65D+|cgsBs+8hRqS)9vY5R2 z(F%$F`MmbJM6{}jG!{K%%PMrC-)Ucn;Mb%;w}_72u=(-5-V_l;UGC-Q6ZPDJ9KvmQp4n16m4qD14Q4%b;>w_~xT5S!0aGhwqdYWvPIgn@i+w`1 z6y}6v32K(JAn6v_#2TpyIt;9`1Z1+mX80|xyPV{5Bsh<<#CWuXAQr}LHJmnCaua*cpQi>aSW0NP1&=fB`-EeV;*`v ze}8^Ps4Z4)`r~yPfbxiT>o;vlJnJae1wg8D*mHaQ45wStpx&fGrDFX<<7|NTcmB#{ zzWFZx)||~b`l^CZPk;z7!l`V9*z)M2vrKW^ZlUXnUIXlCA9CVU) z98;TpTYl3yp(ekhA-RlMwHh!FQJFK{_2JUvJ44BTA+g;9`)VhB>cMaHWMn(NN+_T` zSQLplEPIb>$=BWFvg^rH-dnbLK750o@HZ0tvUW0@JujaScdgKn;Kt((r!_Osy)pDngs&q&Zu zVF>oGXf;)Y?;U&mAQw8*`h}$8yh-0EJ+l~sO*2QT`~%poK=NDo5~)9X0^1H^GF^~= zSsU^XKzfcd;!v|~+P*o{J;gtv;kD=Tm3vGlA8mZZ^veQr?WfCa7wGzXS3G!NC4K`x z-m(?HcODKjKvJQZu!W4cs|DpF{o<@<(KqoW`{QOB<{1~&;-Ysq5mbU=U^b?}*y_30 zZ*56R%c_lgSB2wUN+2fkA*DHgj1ppNz;}?NNb9aYE&Ik)AI;{g`hS1&#vwkDx8Pk1 z{4lz~@uh^F?W)E<%`H+CvHF{Q!Z)Y~UF> z``!dzfU}wiXDBDdu&hln+u3lA&^-X~lXSaIXgO8^?j6RAVIi(Z3(yi)jmzWOY^2{z zXy`_inIcxwlEothEnZY8`TSK1klpjb-?TW+69}G9$4CVrK&nK^T#G=W z+J0kuh+v$%^(2{*1-Bjkmde;b^i26nEl#rO6jm2#1JjRlQa1mU$f%n3V8ZA6u`toPD~PjjNa3 zsrn+vub_zp9~(yG;!#lVu-HOMrN-Xzy=Q>KPN`f|n(WVxG`o#-QseO&T%g?}|D;y7z$D@5*VKcB+0x3T+dE=j9%LM1n}m@f=43Sbt}rS4|d;ajlVDZ#cuadcL+(1S9Jbc4+iyz5ig`D?lVZBaKGL+&O1&+(@u{5i9p1BQ`R9@-C}#|R5LxJx4NwKN~y zC2&6hrpjW0_BA;3w75VAV0cIQ=f^P6gqlW5kd7FzJ75Qn1F@O;GDs1lQV=xVrmrZT zgs-bbPi&t(mxd!tsEyzN2NW-cQ!miZ0%gtwY{J@%Nwvgh1u+DNkDE7+*lU~&Tz6-h z_h8{e4cuS-uRf$rMX4trYRH01qOM9(A&;N_Fle03AeB zG&F*BmsS&`4!F0@=SBGAdDBmJSk$71H|pW3*TEE4*OjDMs_e9Iu@nJxE2Sa5@e3nA z-Iy3gWC+VgIkLZ-dFk%G(2$HI)zE-kJSA`*BYFT)*|_~ZmBMb#@E-uxfm~crXf>AP z)5aXbg$Ae!yhzr!hP)9o896(~8rN0}l5qaO4yM>)7sJ`tx1gL1dFi?-*3v?~S%a`V z&CA|;`*?xmdKY>a=Obo+B`%9SPF%S{_a~9G#-6BV~)WydIhJx9B7RwVX}#^kDPsgNU_V3 zgZ^r{8MFCp%V%<&yfkHx_n|@Z)Hs-FiAn-zdIv%EC-X+|+FMH1?ql=WA#Oss$=XK` zz7;ktP4{N?%@~;bX*x3BtT~RGCCARltQ%GL0v`tvH2J3VPCl>w#`=y@)x=KlejP0YS0~=`qA&}?AZ3r`B(EjUB>p1a>vGF4$e6t zP>m6|T9VWgPt(;{PX{*hK>m7UjgcUVPeTjzyQ=br@;L9c=2|2H+-D$pr<2ak)lIN1 z-}G|nE0$%aa02fLjhXU1LovQn^T-o_fkR$jrxaD5LYyQgABsewvk;8^M`>?N1z=PD zx8bXwz?QM)MgZ{7cUq1oo+}X>Eq_Lhn{`_vr4;oXQ~Id`&og`004#-!FkXI?a8TA6Wa86kwD5h z{q*?oCfLl!O6_EDuF)r$y86f>aLbd6-ql6_xSCwzZL#2hmh=S|`v;MUnS-c0!F%oX z1rc7P2&`2>_risFr)=LyW|4$ls3P#47q6McY!%}2`KPh5suqBVwWH}5)1}v%hyzdo z`-zWO<4o8Tdm7dbcIaW&neV;dbZE>9fdMrJJQF>XBEhw*d%i{f9U1y&)%i~`pWU}h zj2A(aGiK)%!mL_A-MIRI_CrqncQ@>q_tk9OA81lG&DFD>rX{8xo5_&7(=M8fu}8Lh z%EomB{bnNlIppdY`<&jG&eiMsb&W8_4!#rXkgekbzPJ*Z1b<*`YS$~;rijRUA`zQx z`V*+}CbBRBpQE*lup?!xV62?=Y%aU_#)z&A9;cOOBY-jMl;6BK&Y()!ru^Y>ZHLgS zrIG@W{dOJkKEJx>-L0h0rVy

Ou(bi;5pyN3XYkW=`X_UDwUJeD7o=r-+- z2gC2B4K~?sjWZ82^A}AU=5gyYzR%a+gQjUGddr1(g#j}-5+tEw#W|SwzgF(uRI)7Q z+8+QbmhN!GdQ4X?w+Y9XxrYjHx}>;{`zg`@oikoy^bjHL#|3~KKiEANX9Bkb1R$nR4?*RHocakPKW&Ad0{_uxA+db)Eu5>k0{UppztJ~`rr zjCW&=>9LK7z$vfF?zCT<8)$`!FnKcZ%1R2>^FQh@x zjmdbMEe@2iWu5yIaBYEGTA>$zE_?Nc+INbWcMwjhr7%0qBne|hBEc5FQ3a z#H+k>k%2%s3nK#FQ?C`>p=kLAaF}oX_V?!dD%&tQG@LxQMM|oIP%*~M^IIZ8X2> zQ;sr#?suL%QFk22Q`tyn4^O&>)Rl>q+t%b}uGXuR zSLcWHT~Sg6>|2a8iYiko0Z(~EL6j`4MQ)ALoOU)m+%|yfyzfk`lQ~|BRwjjk^KlpN z-fEadOhYaXM)e)p@HPbA+y2resJJ}5$m3zg6F1^=soB;GG<3j@Z#Ysl8@?(YW=waW z_)1eD&wFbzlV|u=tON>gp}BZTTi2+4`~C*=ul%Fs&un7(KY&rpOw3rJD`v=&EFUul z6D<2LjlljLykb_Sc@vx}`*@;}MKX9QCr39S zXcA+K9S|#JY$OAAzX{z(7C>Ev6vqQf6NBRH^Kh|j6e)SGN?xfYgNXy+^kV4;n!N;d4;Ui-_1?Q*7yX{i*aY7%(hP|)Hja)j=G1_P(n zz$M{05Nn{mI_9}8q16j426p3lqH}O*#NdzabO3l@zntmXh#VbI0RTtY$%DfC2kAig zx7_FK=T4HeshtEA2~vC5Qtjy12pR08vzuv5$bKI8yDE6Ja3|0z#p&_<&| zwWoO_hpXCi8;zr~GFXfoPYgVaKSveN7kB@3c`goT+*X*F^}Y<3`MUgS1w zHIqkNBG6{)Qn@Adar(HpxB2xa*LAhczp6-fzU2Tf-8zmXR#2$<>IbtOaP>;Jw z!5ZCXaTiG_-&bh`+$aDK`_qNWI za$kH+&*o2Tk#cHNmu_|tY>a=FfJ01sZb_`_DRGRC`udwQ!Xk5hX~E@XNcK^=bp&Qi zv7B+_(5cOe`h)gwqU)|_yOGFNz@;--l z$|8GiGHCRTyhan{4C43HLrW1puh;@o?soQ+jGe9Zsm1P$Ussz*rDob&X5Ywr$q;5l z?l>=Jx~`Bozfo7{oXVa5Re-YY#N6Zjd)?T{-;4<;gYFC#yS-u`q01NJJm;}%9P7UN zQm{MVpFmfTr(540f_a-2Z8OZnd0Zvr6VP%%RHw#Y@Ch&7HErBkHFk=M^Y$L5}E%aV91hR<}&toRH>`H$+~P;MY+M9saZ*X)tb z*{Ls(=JZ>B2ulL>ZKo;kxMZC{+dT%+)lv1hDrOvJ%AR|z>A{rLOQ|r^mDfU{ttju_ zuxR-+Qmxim{`KZYb0mF`!JrX-qN0$Z`=7CAkOV2+zOEL&F13Z3PNthE?Yh_cFh;$& z998IGT?04sa#?5~f?g-9w8ZJ!R64j_GVnXmCakorTb_9$IctPLIMDs+bKJ?kq}+5e=+9u_`I$?0fcofZtwx8S@@7( z&=Yjvcy_$;^MI_bRsw+d6*FgjLaQh6yaSk&b%1K3u4ltlq)%}k{J6Ysc=JzVK9R)3*;pUW22|OgdqS!c6x|pn1(aL(2+t8zfV&YHS~eh7 zjM3RiaTQF>g;Urkq|u|j|EIwM{VsXZz*0&IpdG$Ps0@o z7COYI%#yuG@roU16UVU1-+vi>w;)y#?@|6!Boza~>7HpRc9TkWohBsPWaV7t%5->cmj)w)!%dP9_>oBIL9cn(O=LgkK z5k2B62nXzx*klVagoziS%hMw$LORkO45RuC_7Z-)Pc!Wj1lz|EXHbaDu+=lc^?wMD z**#Dk$KUfts4vZh5KOhpyzzI!$JFe<@QU;U)R4`e8Of7Ul9r-LqfO z8#`}7x)G*DW8w?TF4#rbFFQFHF@m-c?S|Yz3I|erF z^qaLR0Yq#Ib)< zC8_;__%hKfyQLH#HzCfnk65JYH8UO26uiIxFZ`1+YvUAVBz0<<-k9=9cV1=3UxRWgRa{e1i; z`4L5LBnUJ89QpI2&R{DE60_zplC%P$o|=rX=}$mbML<*vxcAWxRP0#m(Z44VseUo~ zKl-@R5s8c);BNb`m`!^rFtI6#G7g+Zs!Z}P*Hb@?^ivl~y}_wyd*nRva{Soz5dY?I za*M^rEtvKqkj}3hqc?je1AosJ5TD9g2%^LYLnA65(?%wM_k=EIDfR{)ixAtk*Bv+L zZ`Hqe6M=d=ouuwZF|P)-$y`YwfTOI-mba>06f#*s_@mISihb~V+IAiaf3}Wy?G2*m z#mrmNze*MA`g*->Bh2KM$JP2espp<4wW@!T#8?w7{Wo77V>pr<1QJi3$6b%%8Nvc_ zX$*gPsussG<~eWD##q(*lya(Mn17f`3Sxs#V%jb&?zni~vC1P>y(#C$A6MEZbxnLXkXM}XMTHgX$ zKl?&w(Z{G+VXd|HMZAx{@w0uhez%|Pk343(Z<4qFxPM)Xk%WM<8Io=Oe22z&w3<`P z#eO0#1yvXsd6{Z=%dL_Ip1hfC!8w|2iq2@vm%r349vr!L?&si=eul z{CbgSdW7jAUeCBkqfSX(NSUD*`jyLy9?V9|rBM+U@dZw;xg{x6OWNNAF5$;~FO7m4 zcca^1HdXD+E%Fyj%v{_b4qlCZp>f}8LLXCnWT#0mz<5Dl*;&}3B}htlM22s^n5$f~ z^9U!la|eTkX81nN^0`iYV(H|n5o`$ors{Mha(Y}`T@A^1pm?iByY>pP3GI)1h{y*a0x~Z*jd;bpZ&_bZN zyR=AxTT5|wmjVS6+}%o%2Dbu13&Gu;QfQDCcW9xwQ{1Ib&i8ko*Kq#GB$>&cWM=2y z_u6Y+*XO!mDRZ(e+|34h8?<&$y>!l77ih=*_RfN}j@NKXp$gZ4C9&GeLMB>sdM%#s zC)aWUD|iSZ@?4n{La8WLXWn)RBFhoe`T!mjhhbut5=#^z{1xV5F!i)L-~ zzmx#NSF)TBT>M-pjE43o?RILi>bThyU=#;PQq5t4^3VW!5ga%XDgr0~#t?`aC3^t{ zJM4?2=HgsJ9cg)fi0cB(AzE!kRQE*3w+Ll&1yHL^IIxFfY0c&+zT;@C?49F?+2*o` zVUEkp5bO6eCsdE|XlltYRrLl=DBU*^K=PqG?>E3x%MVwUk)DEaq?~-foO5^_?X$q` zeC8xbg-k&E9vuB}uW7Z~fq>Yt>IA`Zgaz9n|FIO-vM;+qzI3CnQttMfewLUMS~WLv zKp~nH0mPiy+8BHuiF{2p=B_l-S@(kDKsBAZVpbxx>R0p+0W}|&&Y@!SHIJ@9Jq=%m z>}uLF4Me^chu=3;aE@Z+K|a*Rg>ty}0>O(TK{5|ACiCIMaHr$8wcLx3A z>;PB3k6KKHICYiKfmc+f)lBAC_Uyh_6YFUlHqd0YTG zT%`X1xJb=s?D@2^3V7xE01HmuN)PvmSt?eRf>E=suS$%@ zE6!0<+sT%`q(MEv&mpIoG8zuq(`12tiudh)K0af|y_{pZiCu9Ct}d02{Ot&98ZC%t zU6ZXG9s#QdL(lAgjPZ=S9Ih-;wMM|pC-i^zr|JtJA!Nc)t2!{;^@Q0%Mj_=?#TlKm zz-crT1kb~tj*}&?i3IBCE?7OU!9$|+-wNSp{UCXCdFcP&sQBiBf)w)P)cr3>g%vlb z?SRGWzv^5mzrp_TTbhFZr$<@b1Gpy%DQSpL8&w32xN#|uv%sx@)2cafdQO@Fm@L%s zJyAJs!H|#BXktfGN$#kn(E?d0Vfv~2l4PzBy+l^x5`kHXBFtxs78lqIa4oLG#dSM% z&;q6|5I|2^d($1x-1m2vgMSf+w%^q28@J>lj!EqIrK}HV zPNmz>i!~aSp=xP6>(On;rL*s)0_8R9oGEj_C`o5+qZO*@xw(bk;!me{WTxORF^6~5 zLZhJMo2hM-bLvQwXy32woAk_~?U}p)2_>p5xLD8RCl*q@u2-@d2!=dz3m_#?FkMoT zYP!9m+MDSH4=FA}A9>oHJkC*ezXK)o49p9}C;l3Tp#?_&!8@Mlsb`NE>*nnE=NDv)XKz%Q`spi+_M!u(o`+ zVea||kfWNN34~peMi3;b^aWWTP&ln95|EBA_NC`ZLcVW%rE>PO z-L50YnK8vt(1Kxmk8E1PDAbLJtBdo+K|2e8!r<6ALp-6JG&t85pM-$} zyD^VS&lUd0=<>IRW7U?usg27DU-r*L4@JsNfgu@{dMU(`$z%ReEIvuKt;4gC1|HUG z(w!VyyY3>*uP04+BpKyqi^Y8j1RLx%Tx6c3yxvCJ={D``wwCMIjX@B}X+?&lXTP`( zyAlUFVyor)|17-`t>L?}XJ8`7iMd#)@mjQPd2?E^Nxr8sa&EAzsH8h2 z(NZce8g}8P9ChRzxrX_qT0|C_VbaTe9}!rXXDcu{e(x0QSl(dFG?T{8AM7Y>@=Btq zMJ-~bZPCllF_pEQMT)1+by?#?1WQ8$N~bb|;1NtroAU)XPmb?)f{uZvHTZ9DaB!#) zr@8MdD%4^oSnXIvbiM4&#eqEiW7#+e&`ys^@7;Snz_~$L zfa#=L!NDmu(zV)AxFn-Dn_KpZGbK_sj$d+~fKhdCxtj*T%g08#(q2N|}C z+;(z8g(V^Th`IcB<<*B-bQSW2){rzj{`(Auc;-onuN8&MC2b~71l)cUWV@5Rr(Jot zmMDEem~L5%oo?p!8|}JcTf1v=hiKuKESZ3H?+4tg;@`ejC&7Ck%Nck=^ePIrGB+@~ zRom7*P(geM+%9I^txvob4}i#6P&f`Xc4E<*3VqPK69w^-(cdg_giJdfYQFrfM-i5YWGZMsQa z{{7E|pZ@?sbE$hK;c3=CEbq75px+uDl*wmhj}2{Z3z6J=)QN#&iVxV;^2L@Y79SAowcTTut@+H>55P(#2wrI$Z2t=twJxaU~HvM&tX0ATJPCfA&`k2i+ydilOT*jJM?5Mc5tf1Q@`{U`O{@0t=53($R z*EuN~w?+ITlSB9&Ipk91!W(;UUU2DbBpbmqza^q<)a`DfRZ?nJ z$o~vn79Y?}vo5sdt&RSt6P6%JnN!36N=F*tr?t^v&xHTm>S)kG7yc+i_&q|CQaiz2 z;n4j+;rK@;uHT;a=gVRnSX|BoBdbr@PpfkkBR$(NPneYq<7FwD8a4tWZu&VR3ROfb z4*R4Tkgfm$JfO5lw7UKnz|$dwz*=|ta(UK8sn2T81V$u>bW_pH6g7a~b1rFe31ySP zgvNwv;8K>>mnE85$xzaImE=P$mLYA-nNg_;O?`vSqB+yVoX@h@lkzosE=Y0SK!`nu z3f|Z!1_(W=bF8T*y&fvS!a+%4FSj#Gr6OO2e8?P3Xj;{PNZ5wx73iS9)?iSvo}Ni^ zXd@-Y0onLsL?|gAX$%wOU4%JBTa#+4^mgYTk%cyJ|1AzYyM_868(&Sj22uARs=VHa zurnhe~~{Un}*XWgm4Zb8k+cx=mWLQTMO@xij5U zgRx-mY0#-F-s5?kb%P{bQTNOr=Uk8O5a>An@0(Q1<))^$mlx!FJ}vH$tG*R}^zh-D z3cV_un92#Sb46#2ADi5Tn}*~NTKG!C`=HF3Q+WNlxq8ixDvjsNk!bZYnFh5tJVn}v zeAbbc2(D5n+Q-?eJ(YB>5O@uWhU3uv>pjiIhlyfIIA?5W6<4AdF?xJG&8<^M>Z(w2rd+2RQc!;Xauy6wl*6v% zf%3S!MO&HhE4s?zAnBres7zU{_1hm@S2ZeeD>x#xzp5sAU8D_G=kxb_NM?8!%oo>{ z5+yuSZw*Tw-8K~jRuIjUXKBRpzyLdtGLHr zX_I3~#|k2G-;avXA?sb+yHdwPFymi!%g5)u^6R%xy?lX1^KxMs!M*X3&(W?^ZXa2&HI0L8s z4=-<1)Bx!}!zaiLST^-pS!wl$Vg@AU)DB<hfWLsT=Jy&fU#ZVV+s|{nyWha#Rj@Edu}+5F)BkroE*wGPuC8l1f6Aj5s7k;6e3v;svd{ zvf6pk)7_KTvmRUJEt^1B5fKbvua(@L|rLDofAV+g#QvBs+c#7HG@ND zD(UxE5B5%s)=;w|ifD6XUsr9g{u{Z*FNMZ-(HDX*Ll=SOz{y1V?e`dTj%`yJ?+a^W zMJu%Yq!)2rTYp~kR*N=?7P3%(Y@@5=Y#zEwHce5YQq*U?pJHivT!Xi@82rGtx4UN4 zizO=G7=3r6{eymvO;d;kUj;Q^5n{SEt*v$l&Ko(g<+}t1=k*3}+@U_PNR?+tVxw{H zxnR)17X|=Y{>V|tUjjdrZIL*|S&DvN#MPY8O<(aHnAZxfgjfs_9-8QSIuu1>>~boT z9Pnr5y^x*OJ4w7Xm}qMOm8=umgdeLTkklQ2Jq_>7(`5M?a&P}~Iiuo< zn0aEZ>i%N61m_KJ{b3yu+7(iBemP+OyOkL2I2^u{Wy$^F^(n$j{_%2#+&qoi(`KduVp(9eJ`{~R#?j#R=sSKB6-J&!O z9o+bG!7fEv&w|xoIbu?z?)!J#Ks?X(lw^)_)$%BF9)IEv&N_BE8%*Ln1R?W%$xSq$ z8zHZ2tRHBpr5nj-$|lPBl7Gmrna(){e}0~?t(o7~dNt8h!l^`iYMSadt`cMWyLMIH zdO!4e(>S+MQJ#*{;E(jQdWe(PRPSu+9Pe$RhMnh>?p5I`=7^T?SVa-$~7AK`)Q?6>Z~BJRqpRc zb^p=%?~mFp)Z`6n5pgNNCmv)MEW$SIaiBRNXA;IBpB8_`Q=AuD^lb%wN7#YGp9f zBi#?+m5qY`LQyCQ?Pl4TY-e3?Ic9WzmJD}em=B{c)1qa5b7N&ETSgBaioVqc;wt+; zul!lY0=|%U^)S7iVhB-Me2|=nw}!j2M84G5otLPro32(fu~-aaC8S2qXWJdW`hx2k zDu?v;i(5ima}p1D&Xrr)S9{%cC=m6&4sSb!ZOzz-ZFe~6JFN~_ZD?8(gd?q>!8Rzm zq1Our-(o9ht~Kg)fckxO)GWe&Ql32d-T#twsC#n#q%b7&J9Nup$Pbl}5So9Zit=)~ z|HtS~HH-k5E+yr76?wBzTk+@U;_Vdkq^fZMao>2V5AD4^P*%e!7dy~_eS+%WO<>IL zp%^)tSfZzKFj*;eF{Ki8u6;Bh;8c^cBwS-aQw95_yYf=nBbT6ivJxhHQj$E^W!d>$ zW>m9$atFd%T+hs{n8IDS!m>c^2+6={Uwi;As7Q2xOHeuu zT^_*MyPhL@phgQ1K~3;zuS#K7rDfL$jQMIMt}xyCJ*8()>IO3}BbzWIqF7)#ZSe&B z>+J`N)Z4CC@@mV;5a?S}h(Rl_rpZL)Tlc>%{9Jr|z2<|>ir&Jvm|QcbX8IhSJ@Eo9 z?%=J{^qzHkp3KwSGjj{RG+b(pO!6s5@f>=F$&tY5C0aKg_(@HwdzqzhksBW74tp-A z@F-MW-l%lVv|3Slj$&acH^sYV-hAfsz(|r$Cvm!uD>I{uFz4Ce3eufy_*D!z>;*d; z_z&IlZ9U)jUkUf@{_fS*yzn938udngauFpbZ{mVD)fM!jtSCFpLIRox>Y{%gcBYcx zn4EW$aE&yV0vwo|^em-lX@qRFEwQ?!aER+v5z(NEFBIS>20B6Y*e*d&Pb*D?A&?D5 z;!Apeq$oWX;9-hz${s|9N__^pEBFIP?sXzQaDhM`^g=jW;ITbK%I|r(4Vkr}8ecW@ z5jRIFn(wVl2k^*5s`4!}>R6YJgb($0VdD1Wyb485XbH`%9CQ#?A;mXr-fbwD`Y$HA zD=+E3E=3ehEa|tUw#5NDL;c_d`LI46=+Jt9I2UnMVp{sM^B1hS@{7?oq@tY&w*lV1 zm(lq@z^4GeG)4E+!DfHhika~;Z<30QtG317daPy367W~sRW1445%toA99yN_xs`yF zV@F&9^i#HpLd`^{S`yE15mXeJa+P|ZUUyfUs~9ZtZvy0MvY&jZNWgoL)g1<=5&LV0 zzJ$(9XLN2JG_>Vz$CutPE~?;MFgM~R=j;`O5Wg7J5>{AlFx@V<;iV-!mq#8h*7^e7 z%rm>{S>I#WA7~X1g#|Ff)0;)4aELh`e^Q!9-<<)Zx-14}xM@JfmiWLxbT4}7NnU}WX z>3tuh)ZIf~&3R|>Qk;*nPxh?ahw)UO++-Ntn7iXY3`mMFe5zs4Q|vg&NS`gFJy#bz zta3NF))}w*H7@koT9)d_B6UNVUY&R{x7CVd&%(ddVJZGc@p5;kq&7oVH1uzm(!r}} z=byx~=w;*O-&f)kN*WXY3{_quGUuntLZ6i-PolfbN}6+HOqIkI+m0>0PdhN!;Bd9z zF7&SCiSyuL_a3zIlw)ef&3OD`LjTHPUYDm;RLW7Jzo4ZOcbux4imG+@D2Un+A3V_ z+d1O;S@;@?APiKSx0vc^Dh#-)lxZ`uQh&|DsQY^K zrNc8sVzIrWZniTxixq$MZuTtXO)w7mde5u5OPL#Gww64Px&7}IXmL6qEvNl?lbp*; zxWepW6ajqQdUl@n^k$~tFf4cvfOsdaBmU<|Xz{Cw=8^DU_nUcE?`&<9S3DAQ;FG%p zyp8Kl8*78whLXR!s`Oemi@w^*f4BmMx-9+!jK5ROwD_TD`iKhL+E9Hg8@#DZd0KA# z2gvJ7y$={+xa`a459G>qpZPTh_vU!ICjSxY`hSNh{{!G*l|EbmJqZ?ubG2to?`J}x z(gGdrGB-+mGCinD^JCQb{3T-HF)pFX!LDPuj> zcrP0sHjr^I|LFLcp1nb;{$@J*laoZfV<#l+o#Bj1*CGJ?({7G+#VB55Ba1JC7LX^7o9Pldu`g4!$~X8! z_VmIwK7Q?ymm;w49`9RGGhyY%#hkZzv69i{mo>(+pxew=KH`_!D=Y*_kxJp!Dcs@a zi8`S#=eUX-Nc8*OK-QGk>r?C1EkK|wl%O|1Hgr@Pq?#69Z$9*-KWV`&UNqdh&OI9& zmphh^TnaGx2S6xD7=mek?9vp}Y#?9JcF5(GI{U|W9W{rGeye?17_`Ko8CJ<5&qZDG zT01MOf_*dZl1wx2g0sa(r9mO4t-n_4KmpPRZrrIP*)bc>kH!EO`|{rdd1;bfKSHM* zHY>Hq<(91EJ0=T<2!&xabN5aN?E$n}(di)F^2h|NPTgl4E-Q|8DR%}_#^>kc+fDjp zlFC;5x`Dfk+rB$85S%ibQ4gCB3zs$312-=z&y>MGNG@xn4odMa1xBo=m^0G1>%f}b z3@BTEL53(eyy9^eWxd+7n0@TuD*iuXz8%{Cvb57ac?d<(|LzkXDi<`#H&y^BUs?^x zHN&l8ZK@L1a0vxYH6a8sjaD43MjdxqDx^#7@T`5%38p26*a24XyQ|^h(CUTZqwIpg zyOe838dUpAph>tN5Z6r%%pI;Bu7jq8^MMnAo{^A7Xz2vg?972lr_mQpcQZaa6DxTh zuHibB=?=4Iak2qZDD0=52x+CB>pnvbnDHn}-PKVJw|C5`Fx^A0?mJIeY_1Yi;D-yg zXMSHe8p~Ap_%cE&KszT;3!}qLfvfkP+CjPk4OZ)Ix4(}<$pd7xHcMpgkS&B`j_ksNY{q^=dtH#0bTu*#fa;6fs_ltb*YOa3K zw75&o0Rz6>g;yM$x1!oUO&nmqXS$TTzPL0jltb%o?gmq2Qx^7I;hoK5p`aKM`HDmC z+25hFu!v`_nHlW(;!S<9rGDUIIA>|xydw+1r>qY)gG^3c$z93{pKpHYcl;VXFRee} zVq?08D+^N#{YUKnM}~wBC@k$Nsq_G%=vh6+#jw7Gqy8TpWLN-?gnKjFE6RssSQBFnKYYeZ0*gv@a5us%U8$55Fm?5 zW$NEjWAcGVZR}&Ot{rzCIX6r`CLZJ8;SaYOA)k&s48$Q>CR0zVdK6Z;x^&R(iq7f* zu`<3MqoP%Bq(}AG$M=rVkO4FL*R`NizIM2T|HnXB+c^E@UcfiI`u7-;SGD5vYz|c| zAK#7ZntqFl%xI20Tu(jhXH%3Xj}4{{lZ~I>b%atFdo8pI*>dhWGM|BWwq3u^?W_Gz zrX5`(df*B1#>9;mugbCvn*G_-|4hhuOG(Pnp~Xf>&5Xuz<9)X=)oY?elgcWS&ta!Y z&1JDb_*>5-Y<+729Z86{)2~EU!?zj`mW0-%e&&uiRA+suXGWvkA!b*rU==>dvuPpd zjaF~!`;IsbpOa{xM^0$siTa?G;tsp$-4#~}7BQ7TLR1?=!=IntKKLW`6s+Y^JoPu~ zl7;&YBqKHP`9Erk(?U;@p%fp}(l zJ*h}_a(ljn1qy?zFYA?jMi$tP?B09{v3=T~z(dg{`GZvE-t$sK9N~gbtZ_Cs%4I>0 zud>zy!*{onIx>kpVPv0P9H{f6eX+bQEGILxnSNmLBFFUKAfE^Ow?_T_=ut2paN*_7 z3hi&JE*Ph;n6YqIkxu(PwG+l8_xx9ayT+!j47c`R4K&Pb@-=hP1cvQ>^i)xc*hjsT ze}GEnFAe_y+BXwe5l6~!B3eQ%jP`y8=t(Huvpl{aZ!z%SUwyAhj-$pjnMt8>@gEf@DG zW8kK$4@6Tya-^5)kjZ*{iF`4k1GIdtd5K^Fk)#tYk-SrG3cwE`V&}xc{nYG!4HbMb zg^<)$XYycXxd4vkB>u?jL$t&x^JB-7y(gV{(Z~5Az2aJsbu>x9)D41uimQf>WwqSv z{MUpzK>J;}8EWHUF1sjM#egNt>rCjtKo@}$s<9DQb!sYtZtf=T_yR3sl6w!&*jwtC$lHsu(357T8gx1+($LBHlBf! zA*L^9hp-!6_^cbhIwY%{Dz#;1JRiu=NG@9H z%j)keC8sg2qFRoq)Tq?C5>vWo%0gdGf<8KOrOvE(yS{EEs^|=ykM}dbI?xKNt93s) z!9Hr+0dHA{uq+pA-{b76ZU{B1GogqZ)ByPobaDJcNjuZS1&%n_=G77EqQ;IgrTru? zV~VUpz)RW2i{<_OR@3CS8(Wn$xgGT}CUR~KBG291&LD4pdsjWy1X3sQW>#p6nJWwK zX6IeR^N-8vqYwY8HZ|woSCZVak~ieW5+g6k#uU$s1|L0P%`$eK{I>UdnMEiuA3bd2 z=4S;sHuR!-RPE0wSzmc`(n>-lMtMcv%;h1GXZJ25*KgtapfWa;sh<>^gmr$bhdtTu zH161CGiKqTcV4&FZ~Z{8>5Q+?FP0=T8Ma~5^!}&N`(G*Qjye^|qaS+5J~!~HR;;ML z$YA|mBTfp<$O_lZwn-?M3eH?_H&JZLO*Sr(PA5l2StbFZ%By&j(uOJrsr% zL@gXSO_5Z6UX>k=)~8ZDBAmY$-@zk1IRD7jHTQ84q?(zAvAZ9e&lR1kb6(X@hrFcq z8TER1VIK=u7^;2g=7^(D>F}RQ$Q;8e0={$kF8V*y*CYA+=pohr^XrHGPxa)Xs8u#J z|9@rC{QZ2AALa&9E41xDv9^AxITHX)GZ>0a^<2XS9@i2G$3$h?jsvr!0_@`AP{jF! z;0jqONW||M7$@Zk*Q&c3@WcTvlsXv_W{t22fB`&a(!Ob8tb_rny)i(gsJOE%`pl9i zP$}FMaIqcsZ1ry1ebB^zuo`qx@K&+-&2Q@5wmmHYGgP^RQ7!~Cfm{{H;g#IO+)K`< zivdhH-Jr10fs6y?i8IjxIgQs(Oe|CQ6xYvQJU`>An48E*!kDVdiT^^1jPKd#j-JY{u;fD!dZ01a zsxp7WP;x8#&_<_mXKryn)H-Z-QKj2Cv#Wws&f78QerCG4)edfc%%(#m8y67qSk+%t z$FnF$znNy8;Q;)2!6Fs^G93D{#&(7cGbO}q?nJ@UZbrMfxymg(3>863wywGeCOEYr z;mM&jR9&aj2mQjaQp|inGy4aK0&VBX1&jV9Lt!GY$0Af4%_TI9W`ah<%7-`eO#)jq zrLf*=iuIPnSlc&CfPQb4?X<0DCawEz&e(3}PS>i~0|D)Wz#@!xP(KoIs)iGhI)xx7 zP1Phil8wG9wWrm6J#M1qx1KZ@fzqC@XG%AnIABUJBQR|W$`V1Bw4O>f^~bN@?I~Xr zQxXhXT;RHRjsni7!W09{p7aEYKA$=eR*2QuYu>&T$T>9^i4_zW^)x8D-k?wa7++|S zHtPX}1n3buQa~d&4s_r8-RY_Rn3+6<%e}n|rS9V3Kovy<8jK6_Pe(zww(b?LpH6BE zKwoch-i9vLsFbP;O1+lx093@_eoWLz57c&U>7CW;|Di15TVqi&U{MkUX7eXHFna+j z_`Hrg#W{=?b%=s%yd`N64#nS`yXhUg#uK^c^#eB<^KO?0R*R^|^gFQ)?JBC2G$?z! z*ycT_2|zO^KN|U-K^e!es@q!=a<;BGW}2w7BzVSFgnf#Qx@~!>_l>ferqy{6yYYR9 zKe)+1&d#DC^%2`h{2J-tr*XF;as2X*@zfs2ZH$M$@2zQa*OsQqyok7;C;oTx>>lxX zHP@M)RKYF?g018$>y=TU@j}--vEGY{z?{8JXBV6|JPjGIJ0jjvr)6VhiqaU7%HR(u zv~=M73`)pELg9il-6tiFtEZF(97(b`d*&Q4(gXF=BC{iAF}x@5ksA-usxD=x({u(A zQSctavzN^NN50%)4=xW59Xz@t))Q83rv#&*Dr#c_K*%vicYx(5Nft?IvIIv&Bp<@B7{{lKwC=D8^t^568kgz zZ{j_~SwgvoPd{1SsJh}HqB>qhe%?0s|5L-_x@EQ#?^7CktiT`CFaIfareBmurAUxC zt^cQ|N*rbz5>0>C6_SC@)1(uSV_3eIa{D=UoViO)?bMv*gBwvmZB#Ah1V>vnqdyqM z0>7|dO4^QJ*=|w5XjIM7v1f)^p_pX54#1D+Q<=E`0A4c`_FLW;;CD}J6+ViBBT~2s ztR-T1xZGSC{S1-OmUn!BfQR$^h`|+kzPselXGsFmD4OlW%fH7#zw~u9%aNYqV--PC zg2qrWL-%xob9bdlo-|2|1~Z7Y`e68|J3rYL{z1)UW^VY=_jiR)fHUaASt zZ&WdcfIRB1V$AM!>{5rj8O{b!aC^FUMQI_E#Gq)gBiK9B@HvcIYRx~spQ2YCwyY|c z9#E{3k>M4Ne}Eo!dYjO3_W!(~tqMAQo_04$Sja*2Ti5s#N~(+su?&LS%Pfc9Z%%Dl z?|iE3n11_FvE7ueQqY)iDvL5jvs%7A{679x=Qd7eD?3Ebqux`V1c17JSa6ewCa${v z$T(s+WcU%w@2SuOfBovBQX6W3=X7;#VO=K)G@Ik=zE1gdMJn-uduX=GXj>ILJ~3&- zB>_M4i<(m(J)t3;$R<^VUdqpqVugn z+@+Cb*pL!>{(?`m%y^AUZGTo)2mtU%94#>&K#QKx9qwJC{+xXWNH~Lxv9b!h@BLC< zW3+u+wf_9-nQ2k9eeg~VmVI_LYE#3*{0FF4-Py%qjmW>|+NH3ovS4h6ot6?W@+71i zoZZnJoH7dxV^r(Cpr@BIz6%`}hf91V8R#wQ2|dW=!>);|Y~~7BkkoZkT0T(qcXwr* zmL&AachU=iqFtBMJxgXB6O?D;SEAkUmfUECs?$ABE-jGBsQiUG1w1QVg2lzJ4lK|L zY4__Gu8@HVsTIhQGQku<(cV#iqiWVfyN~b1H3Sr%YKz$`nR`dWlT&zDEKX)jBeQ>AN)ldeokD`P7$?HR{>tXimIDX=W}$=S)AyS01VQ8x2;S z4{femU4CbXGglt9-sI7K^cvK?wgEZ}p9l5MAX1HiDRg<_hH?nHCC7-R_K{O_?2n7h z$q?kejo})OzRd@2;np{z<(mX4+{_Ed8e1htU-XYC3Wb&79h<&jydW=7Hb`aD(VmL7 zyfpYT(*p=KGY*fxB-4<9=h@-Yzq!>;Tm`ntO7E7LY+}Ue63sXBv>3!RcG6)nc?4|2 zzGs`AA-D~TO&ey2mPiXLKfe{9&_EtT;j?`jB^507lCX4B$f)|^=*wa{oRw$h<7G9} zyP+kb*EO>X((A!I@!br2f29t-61AU;RZOO5+QYujZQxp6FF*3Q#TmTpL@g_sRm-Vv zzi!?j+b0%!7-tFN|5Acqe8TY%&mY?M=SR0!GVJUXI>Su`6Kab1H9cSwMVTfQ*Hs>T z{d&9@G=Xkwm!|7qiuMNtSc9k86)~73dnV*)VN}Qps9{KzuiAyta~({ls+&y@(s82w z)~&+=1w$64ZV?!fue6mfQ8rrl!~nHbT6{53z6rn;$_2qKVHPfo3dZ!qX^PY7T`^O~=RK2&{>}dOw%%c|oVq1vqlR0= zUwHp1M-1E_D=O#L;uxOEc53^)24)D$e7<(Oxo|JV4zaxJO<@1&-b7VO$zG=Kk+z?G z|MNYcua2EGD4PKMS9d3cfuNa)mMHK`rAV4HO{O$kNAR1wUka_FV#`eQ9}VslDYC7~ zl<;Fmt^IU0{fpb?TolK7$jz=$Q8zs=XU8A>W&cRHxtlA~3MGdJO6IYglJ;c@D1?gt z{nBbG;q^&^7&Vp=7vGy>a7Ydfdc>lWqI@jVw*-XwQ@I-uy@^Ax=Hy)rOCmXqQppJu63d*7rQt-Re!rhV7 zNo4*|p*huFsnxfMtt0xEXUenlm{UgESo{u2mvB}Q?S_Fto|6KO74yF-qmfW1=Z)Ul z)2@BPlc%&y7&rW&8g5`M^P^A_z-@H9x2Gd$suSAGh?0*PPKX;1WD$pU@a%L3)s*5f ztdJkWJw>j}a25>NbPKbDOFF9s;H8e|rnlyr(9V$TYS~e(n9O9OP`vH-jrPuk(hBrB zV#Hdc`%l6K3W?KH^RdPkcT~w@L)&eetce4iTBXX<1*tfQRhooJeXr#t9L{%fDFHTMPa6MB6Lf1$p3&WTBGTdmX z&!sf*-pv^UB+zJTIvpR`pZ8=6bOxh3guLn!_-zM>-jIObSoE&`xbi!uL#xj@Ev#| z<>k+|nEmf_vO{vtPG{OdDx910p+gY?5>T0DV8# z-d8Enu9*m<0NAF;4D3*#rHq!XF)F z?+nHM^H*PP)(`0s?@S=9B$Erh@h@ubxz*G?(97D^`+b@2R3=*R{APwCg^DkHR85ei zw%e7$YH(^=TsInQ{X!H0az9X{EU+5fLh3fG@2>{JS_1SXp30%ZC&*|A zEF8-^j;)S2T>WN^QZG{yd?-+<>>o{jGVDk4-{|~&@`E*j9p%QC406DxnzuJ5Vhe{T zdh$n=ArxtcNkx+BeexOpgu2EA>g|u2gHWdcGd>vy3PH_?s>BnRqo43k1}}p@zY0&VudEdtEf>o43+0Y6mWg?T_qWQhrAfpDp&cG~U6XHcGC8%O9M`^)4BIk+d`V_&N#cbC3z=L?v(A7C zlvdjg`8CAnCE0+vE;7rvc@v#M)#@{;{0k4XgMnd8(mOZbs;Yj3*fXY5h%x{s0AW^Z=H#!&N`JM^ydU|d?XvS@q5af7H&56{7;SW=nFvD9&`Rp8$HfZ|}>yc-AIezB+YMc@B+goqUa^Hbx%J84r(x zmzA3sKluTCYK)azZ3AX@IS0%`H<)0>0rzfCmm%u603M%n5_i z8Qg6k#g~2|Q=O{AVSk;RHl`1!STPtq%{iX4W)4iaRrZo&>@=%2qY@A)GM4Hhz1n#1i)i*G~9(|D@7=i%3FLB^Y-z(j47WAp_|Yw z`)T$TgM7P3x(==ycB(LXQLBh)1ODz;YkE(+T7d_UJcVbcMXWhBysY6{RH-*dP$N&9 zKf*QR>GAP92`a(L zPvu^vEwTWnU{$qI%G^+68c3D|u3i zjMvmU6>V*M?~r@KqhTkd#sCX=*La#X|7s2;nq4y^-%mkX?~dIF;`Wx3ev5IPOu=zl z%hldG+TxjNG@30tD7RD^-(As0gGbH{_8i)ac=?6BdcdzjyOrEpxL?oc;M3HN$Hw6` z@z1>H9l<;d+CHDJlqomsEANaJkdJzE=4+4lsQC$;JQ2Hz7w9xAmwhPr$59`%n#wvFGh=0_h`)GkDnqZo1zi=jJB`PY-hq$sDGlr5^G5ibO6E9@P-J-7da7`z`qsQyaB#M}IK z@EMFttAhqJz#OFD^%xW@pAOgG??XX}MprM{Kh+BcQeQ6A-RU=aK2?QspI*vzTUG}= zW-S+)GThn8r28+V1#9T?sT8|GC7 zq(m|2o;rIJO+091qgWCS8SpFTBSKOZoGNxRg=44WD$j+-7geLK>C=?fN#2Et>m^~| z<_GL_u$0%PpRyA5LGY8?wCNzpKYM>p$jk-iaIjoscG=fP<#m2uSFjlU^ejo8KpQmK z06)|e`X87leOpIurld?S+P~Fw3Gc+hUwLPVv9wnmY3=+#>6IznXYU_2vIH9ljKxdI>^Ds)KG^ zZQEh=-BA6q39@-u8rlI$D?Af%pq&t?7Z#v}fkaW81m+MJD@lW8<`br0nW~ zIlY-WrcV7TddWXL*;nk*@oUr)-OG7On$ufD;MQoNR1g@8e3a=8+eZSRA0I5(_r88vGG}}S**mfgfwwc;o&E2o_zMgYgl_Tcz)baU0fPBl=xT{Ix_q%#; zbMC>yhf?R);0F_mw9hT2!M|_MDZMK#XeMcxug$i^E%hz%#qkj4|>lp^#1^?P=-@=0YKsciFSy zc$WnjpefJcFWvDXVpQX6vIPGhac}w5R=7reLvbij3beQsiWZ6mcXtc!g%(KA;0?t} zf#O~uxVuB~7Fr-!kO09c?(Tlxoadcq=J^lKhfK0(GPC!GJ$v8xy4L!wW0(&p=b~^| zHuAOT%H#~zZvYircCJ#MV%}N`nckz4MCfP`A+C%V9WaERGwW3Qst=2m(JT;ZU{@?k zCQFJ2LJ1*3etGhcNp>MGifwKLB`#R6 zl>QhHxiRTOJcYRMCSG(~6>e*_^7cUFx=v?r zh{dT{W>;+a<*m>8TvXE@*auYSC& zx{ZA)7J$2ca5o~ev?w6uG%L+C--pJIxO5$65zvMW3taAS!)cbPE}3R;eIZuc9;e_S z!c7ZTZ-qy$WG;A=Qq@vGnhz%2$_a_Ke=6>UQ3m?1b!M?BVY!HIY#4t!Y0*P-hFQBeD8mdQ&0x;)CQ!?Y5;`zaema)|KMJ$Ch}W zeN>x-@m!e#yZc|5FOJ>x6Hh;Kr`@P%`0SlI!8KcFi5O*d3txW#_k198i0_FjO7qjV z#FZ!S)x;opdyNw(jUuAMvf+r)Yx2c53_0ae@7!QpZu)mi6vMtjXsaHKqGr2~(sG%< z@zigfw=+2jFsInpMb*bf4wlsd_V4+>ADNQo3C+9NT%D;{qYLHlo#0SA)uAi_X>CZK z-SUlyL7XphKL7UDkJNo0$7{zg`q%AC1wwa}tXojcnG^T>w-)|Lb)|q0$=QUPye|dp zcybW1OWJ*^e}C5&Ykcw!4=r@Uns(8prZ5M4MKQ5jl>}S`MrYe5jka$UZ4A;(uO`L4 z;9y5vwF7Pq>n7p$rs(mPs#Sd}Q<@q;f4SBME(QW46SA3d%8j1_=|_o;%U$nP zvea+|CyU8GHi6I~-^NfamgP8q)XqrY=b|y8j6TjS7^V)glA~{!js*PWp~yaOmoJY9 z1Njxyc2OvGE(?D?gLi7`nXmZoV#28t0g<6d^9@h!dTXYMO5CUmA`v%$=J9Z?#HHNO zf(fVNl`Q4SScJK>Bc({3g+gQhGMZWQcd2Y!lARRfc5pJHci2h`McWq@;~UU)X}kMC zuSvnUf}j8XwBU=THvrwIN&YQ6VM{IXM?O;Cp1I>CCZw5Z8w|s}sfn zWFzLX$96TRyZ_WDQa|m$@QhHjI6v^f(TF(`up6FmI<2#*ym=v$`pO0yX@lH=>Te^X zF@g;S`xHW#>eXeI3%bp)4GO6$nCf<>j`@FgDFxTfZWTyRWv0iQNxQj?rbf6^tZ-(y z$*CppYVt~_07Y`uEuW@v;88%mV}^?Y9dLp|g_jJE(K-KomGYdK=6ufjc?9}J|CH{# zjHqEB2<#P2S~+G59`6{rpsdQ7g4W)p%d)SvI?w%jYENVrN{KpU?pisv915 zsKu5Aid9!o(0a?m#-%|{;YFeQxetp_)3>dA#reaXam5i{KH{@ZsG>tJKY{eF@{{3ipn125 zvM>FAe|i=DOuvy~(?30RB?)AX9AtGbBzT?1DgJt-8uvik-*dc&GDBQz*QZ)D1!RqXYv9XRrf79#-D93r#MJXg64Yiu<(#+^o_E(Fhd6h z^=b^Zqba1jUrCbO7+5d)A4M;1+j_O(@Af$4%QHT+%5o>4dB0EZXsnMy5gs+~oA0wn z)D=mgk!q|KHXDPk&0?3Ffe5$kqO<9i!W(}kCd<)(pS!q5BUgWA8WV~S&dykrQ^qi} zSZCH>0($gI1skL+q#1?|T)L`gK4R)VyV)wURR84J*0`&`G-T+ZGvaUL+`@0xi_~1l zf_Z@~m%_Pzb8RZ7kr!uos2||sQTFOo3`#AGO55)g6ihdpHajJK@B09RcR4$XGpOc3 z&aMzpGBuU~Xh;1WZpho-lDiAC99aMg7vqES>q%rfUj><;9(vpSJs~-#>5u0EMFiUQ z2hqfgrz*oQr)6j+r@`i%)S*}dMMx3k$-&GVFN%+4F-3Q^@@k==p2H{%i^i+9nm;^SVRc|qPf-mD$@61&CF|+401I-&glcmPRYhBVv+`AHdDJ(Yu}z5iRMV& z%{1M3Xo4V~{qv_PGQZIEpba}FPk+PUc{OGuJ0;*TL{qRa{`Tl}-C~ggTSsPMw8*EU z=09%^e}D)!k{|ZDARR)P4Q#g0zr~@4XL!pw#L%X~kDo8!`fzR~rNx_pMCpwBF+f8L z1{)U?%c1+rjhFuQPWH1h{B-Ej;lk{xBg9eO5s9APgA&ljQ7>3kN*ko?X)$V+O%|!5 z-x6oyXPxd_3%mi_{60Y}rThm&_{E9SND1xqe)EkQB-=EL!6NN84(Ul6Expm^x4K>7&i6bS){7AP6c#SC0$BNE>1MBKb0k)l zur_>6E_;Rh>cekj{)CI}B4!8cRhdHzh@5+d0tOhHd(XG0MqkPPGE+QTPboHZKpCIT z7#jikVkRG`>r{S9Qp|H$nv@{AG~as5vlS+udQ};j`O1`t!{Us)YTU*=TB-YXKgv|T zmDQ^zd<@9#(!k%8h{|NTvL*$gSD5un{np6lkYm`H4&hC%QNxtoSFOnf37Z1|@>7Xkh|5Cbni=&m6)L>-_L8BB|pNV6R z2UzyA-NDy0JyYFk)k~PA{JnagOxL4!Y|3sg3>8+f(960k%MUo^yeb#85E{mz?9f_jEXIM^oeEopZNwt?X ztqe|SH{Uxt+0es^>gTA8^;b7Gc^5Sm^G8GTbFarRa>1K6OiTdR$7l2M0iLFf^>RX9 zg?i1d$x*4iwytr+pGRVPZtNLjO=35Qp6Y*#XA0(kSjKyYpk%ibTk*$)=#-xr{Gr+H zerNK>-Up=7gO;?B-ALTY09x~md@Z@w8d7HYUXAmwK^HwM)g5rtwq3&BG2M%jf#qqZ zM#(#~XL{zWT)E8$&+Z1;sANfRgWkBf2O5M^={z(trh5GCeT`M|l*)0+e@qnUWhLk3 zrHsNtkIehzQNr6*w)OBx<4&#HNqFQNDc$(~=z2%10D|V?t7esD3nFSb>MaQ^Din`-CV!;K$ClFKiv^#^s7W819=VG(!lcBmDL=4Fg)xj9 ziD9jZ^{gq}0!hPM@A)4pTjN%6Z|n7&(8X-PtB|43>we%zD3)F}mM+>?qXlJ5&zbrs zAbCM?o8Xb-<>ew9G>oMsuAL`#Mhw+E(>c-q_U%GXBLk0fi(TiJRUOP>t|skR(P=7% zfBmR-Q}fkHeUH*Z*_MKyWP|Fabr&_I)Nk&nqX#)`K2Y3V8Hp5kMD)?ewc=(wN97Su zh*kA!_`lWJ$I2mE*rg6W{W3ix(1I!~|3b{JDO%uCs7GH5RrugEk|h08f(XHc_A1^@ zs8MhVO=|CPe$(y2_bY)xipuNdZDaJ;z6vUZvxy?!zE@YcDE<(}uCAxVM~e^&)fS5F z-j$umt$e;b*1QLb!iVIFH7E?Y>mmEhO$VCE&yA< z=$n$xjp8^giZa!(>AY%=Bo;Dp908&a(@#%=CQ}jolk&e=I7i9NPAT}FVf(k$M9DJ) zL6Dc}kPvhMQ%Qwdb;dh$u??&#qw{5ILCT>QPen$;5Q*D-Lu#KEcG>AaKM+-=)KWM; zp>}0{=>mKMZ(5~X>8}pHZFu80Npe;R{rHMB8fJf11CYp?=3CO62|3oL2UBet?|{){ zR@6^@&5aZqIxbnRw_+<(QRb3fr5<=Bpt+*`U5#!kDNu~nT=6!2dFj5ofFtIt6ap=0 z?Jj3Ym0=RIX&=~TM>)~yG8f%VQr!_kO8C3;@H6qs%B;gyYz%r&4Hpw2vcYsw@&P-C zAzD;B9y-l@xRPryIr>J;9KXYarkW^m^fvwXsq(mOqyCZKAO&l$o25mMbJ&)9o)24_ zi%PHlQd>)%vQ&fk6yGi^uIA~}a6|qcLG?YoII2(4=hQ9jzSqD27R8$_rnTew)9iWU z5NoIXpjeOOj6*31GgW~@6`t1v@EFr3y5Bv`X|2>>eA)Aca%-yBa*ma*%fO_VOIfP;Sc zKHn~wVgBq73F2o>h$xuyJpTMwB7@a+Zj?Jn1u2{;HLzV*t4vnEp{=c>FGVW9tkk<_ zh{vo0-804%t~k`|rs$s4EyN(SSnqPO6CQk>)AT|`Y+vg+4lmeQ{h8w(l3Z1_f`bap z1r<#^*2}Ht#|H~Y?apn(?CK2P`Rl*%DjuUl**WnQg%P%F>c?6=qCl;`ju>W zRTNxWA5o5V0ggWDB~%2aSiG~u!z#;TG#hYH-=KRZQ>=J>4KK0@q_BAB`V}mfz@6c= za3)H~83`#r+ENX^1{)L6>)MdM!(jjijVV!%@*r04k@7(+hAfhb_NJw`&O~(zh@0mF6kVG`ZYaM)kv199cgKM+!#jvqvU2dxXU>MV3`%gLdl3waY2@%mG z`eh9StuMh>jSEme(9h04ZN3R4ok1OX)YCdIRS7Q2ok8?2mv?|)(|Bxkr?9w%cO5Nl zXod~Cgsu1!n-hf+$1S*Al&VrcH)X4W9}hMNOHzuVNhKixJT{~x7W@czUkf!qRGO>h)4AelwPlVAf=K@vy-9Gn8zI%i3q|`M>t06xV;?_DJ zf3F`|SBvvcacRiQq0r?VBu#C#+T03X{gdqDK$ujec5zLE^5k&QwKhxF^|3ax&{RsK zrN+jBAe~LrI(zb$(c5EFZRNU10v4)^lF(pn$DN#wNs}-OV?k&(ksQ@SDWz}seCX^= z#TycVKNW9|s4CjO{IffK&KvZL+vLS);ktAZ%8EMz$U@{3ym8(AtaD;4)h~7uc5NMl z(g!b-Pk5`s2VbtnPeq*!chdk8jCB+QcPs_gq%>BV_k^j}m6@Pkwa>!^D$&Lp$C;Wh zJVA#t_6GUuYt{Vd6q`Bn9qKq(E;08P0IGOa^;=i1ZH%2zNfi_NG7@TPPv3$c_@$#Nh1l9d>$O&#$tGWM! z0qZA)!w}I4fz8D}GHa%1GZ=ENHeUMmTCOe?eswO;hGfdmZ_ zN3danYB`P@lXXNeix}UMQ)Ne@X!O{bLwagCJeVF{%)E|_Ndi@)>j-Q3HCchCttCfA zSaEpOB0l2ex8vsMiXIbQ&cqIhK(7LjiW=>CiGz$8M*~qZ5271w(;fTo2qxqGQCbn= zc3Mv7x-b=Ic)!w$gRzsX*wXbPh^lINs_;#m!E0gTUgPz4G&AtcP11!oIy3(T#jb9a zV<3_J?51R0Mj(Eu#QK%M*~F84Ta~`vkhEQ;^=syR@~P;xj)28JrU$3QzPEIFMc&Yw zHV6L_aZa0?6>^IWp0SNwVOkyBLr z__fEb|5jEunCnXfEE=#ma8KpTxeGVrY%3n4#F;e%6|#lOnkek6se|}s`-+P5)}r}n z)n;H2I(<7-YB(E+;80@>qKxYIfi-KpwMZ4~`E{-qEQy+-o$KNu(PcdZao z@n3r%?0G2k%;67Sa$WR%!=?61r~Za5wy#5Hiv~v>zi0RUH9ou1Bkj=Igtroo{Fh>PO<%5p6xS6q_RhXPZd={Ru} zxXV&v-_eJy@UW^ce=QKrS^r__?FU2Mg~g8DRi+PKyyN=EQnqsOrnRybUp{oC{;{_( z@n^FT5kh&9)~I9D2MB#U=VrDYHm609hH|E7%L zGTXNX^b`DLAtcw;u{Amt_AP0t-ePGcj^_oLYYylzD+-?03;R`YkB+N_9C0rCNSM~F zwCE!Tf=RE!opOGkI)l|snSFMX@T+ztCCZk6-p??3k9wN_G$XDq5td~OIu@aPSx$8X zq7lp)*j{a%_8#;dQitcnKpys?!^(A&r(K$jP?v#+eHZ6qZ`xej|6uqO8#Fc27A1OK z)|jRDHbwqZ;7MuDFy-OpmBq#{JZzf2$^Tgw@1KBwB#v^~{$Bk7Tlw#^I^HjeX(WoO z$XrdD%|K+O#GwL7=V-U)b#KaBU0+EV-&No#+?s0hBz-=or3^gaUV<9GW_M!jMsd9~A8358 zw(^Tl%W21gPHjuJThU<=SzNzl(5MMn8VsR#)iZ!0s)48%_r`{a%-G9&p%5Bxo zU-`rdKkzKa#P>G|unu6MQbbDCquq;%kF^LIESFO{y7uUoFP5fEcuoE-XSU}r9jjWy zFj88&_*$eunY+d1QR~B4dLt0p08Szxt60n<=Q9UEZu`}nio@VV!$`l3r)DF4EW#gV z>_#@Cw#3h_yqpPW(#5Q}Uf)l%@Yd9Nlv3fHmgCm4oOBzxV(#{_E1-e_C{K<(B`MpN z0Y~5%(r$#K;);Ijfuy;tcpk$|k(1xuH*ABjNHL0UFk`!V8hGfR7~n7;9Z~=BO{~L^GI#@F+L#MVk6e>Zl@K`Gu5C653qCXwamdTVt;crPQjWf#=oSMof1(~U z3y87$*q52NVepfH24A?JbCC>{kP}eWyu!aM3px(HhXeGCl$JT46G6nRZ4= zXj&Dq1|J5xvar4x_sp#@RY$qHFocRSH^5;#SjpuX_5OVJ4eA$>v*8k}xg1<-zX#|% zek)5qI1_c`rStON&fOviI)TYSCb+O523Kxy6Hk?gVq>v|LdCYwHf*8L$Z9umfUF-GhQ{NcZFS(hO9kQD|d!YE`;35 zqi4Nd2rsAA0Pv)`NWwxDYWP8YP9~x1eTy0ko&3TqUitgb( zYi#ZaYTotWqzeWgJwT#Vv`!m>{D4q&Id9c7YHR9I&}M6;8SF6^=r^zetGXGe0kM1> zP5wJ0@evEK;IIMQlQ7QM^|Eqw-N>YePVMir5c(dqN= zBG@1oMYaN*v%DI~Xr$Lg_Y$X^#ko8sJhZ#&HwE!BT|47J?xvaSWd#E>_KnYu-3{qk zexaE|h|+cDzL_zexN{KDwEhGg98qhVByF}Iy*aSad1@%q>Cn@r`c26i7QHLK{w zaXdHz%<29@^)Cx4nvO66$~h$U{=u**$j}8!9!gj*q9R8*H=Zbo7#v@qgo0r}wS{6n zEHzXbZZbu%bv5HqTvK@PYe|1#NXeZpbR0Xge4(`r&MmtZ{MP8Y^qE>2<^`HXM($Iz zm7qT^#ES>zC^?tK2m5i6Ba6SU6~iVMGukM3eqp)Yqz<(mIgKtH&3sX|f08dKD~rv|mujxD91om;uXI0FFu}W^1_IMka~rme?Owvh zVku#ZD=ZGXau&jq*AaT=MlImG$k{oD)G&AW(@XB$YrOMnr%!cX7h{CI5C8rBFnhVy z6x2v|(cikPfr)Gkc5sE-w=kJ9wcx`y6FsB0N+XQLE7yt&y+#6r0qyB{qZFtp1Q_tC zah^}^$xuZrVIEwQ-pVIYNL8gqoqzay+#T+8|sN(+lR->OgWHwe#wAhPm;yr%V_SvQY1o?wC0 z$ThO~#-Q%s#m*%`EGEn7tz25r&FhO=`y6+nqU0&f)KK4|;9k8s5q|=c48-k!aI`VYm=A+(NhT{dEI4nLbXVH;}fa zuHjy*g`uGC!b$b$=pk7o1)k5+1+7#3AxN9&#gd@xL~C+#Sl$Ra7%v*~b$9gf|LP+3 zT&xKZq@Ez;IH|D5dG*Aa^LkEFGh(@&lo5f1Y$E*O51VyLrbWjufwJ@a@3{V=6c5`{R#S0h*@HmmVE~Q)+iW z=0?oqXBuY>dttkU#?dF5o^2Lf8HEZbQAS(J#Zg}>^0=AvPNIk`zWNnK+e!XS03 z^=7?NlrhXK)nRf%b235vcm1jxI8HIN(xtoYhGxvIdP2Z zBs_sn-S4Z@l=F&-;+)Wv6ma~L=pr&BtaXDk+n%=J04?X`Z~%V*&|jL zv69)>EqxM;7fk*LD`H9)0yMOO2cA9vfBuY9rvygz>(uKRPbbrc^tgG5#u>F&A?9bN2RPRZx|$a-TGmT>tzLSmex}EZp@ge2+}93h?dlsY-O+v z7A6-(;ff7|}3HPtBlq(DUsYzwBSl z>dvnzebyiS4QZ3lpBpqxh%^4kPk5N-VoZP_>u;(%kLeBV`a zf1NE!)T>9M^S6pWj5YJI=yZY&_cis-fstF$!Bw*#tjbrZUhI~?xr75Y-_Lis^>F`I zBH9hLxFpW=Qv44_VXJiNAI)dW!=cL^ZOXPm5DUs~7QFYb#r6Bq$XEk8;HrDEx2$U#RD2!t!4hFKPtzrY-^H#bDA>`O%o3bh}N_ znox3`zWEf9<+q)mFr4M6u%>AKHY%HkxpdRr0U1<2YsN)**0aLw7R80}7{dtHB^b$i z&p>zHH(K?*`9#o-t%mpXtYM$}&FO55v=nr^Cf4h}s9`3mVtyV&mHcWvvx~JkYo87P|??!R7qSTdj!VJ znYPCk9o*O6$Y#h`cM1ACo__FNHnzQz_judbcIrJKeXFaD5c!)O9Ae?wlEGm$y?En8 z@oFy{^H^T>%Sim6iG}68C#7B$cPY=P3#mx_`B1Fl&sm-&Y3tZt?#3*l4^GH0JzVdi z{8#`W>Mk|>6;E|WH^3`xB~E8Fo56w%e$&3-Jj_RRUB&m0qh_oZC4a2$A@*rI>U?&S z#E;c(xef-17Ag$lL1#LSo6O?{UbO9TBZy*4vlyZKU%34=XvxoP{E9tiTxCy; zP02U>+B@*n!q8=zE*;|w@B!;dapU8Z+i2zQZ+4>;eAftxyhgEv5r5>-hXp_fd*~Jx zC&weW@W%GgL$U{6UlL|-kLS9t(aKOz{WCN$8}~S`j3l>=9T)eZd=`JKzHHVLm4%u~ zJR5J>)JtZ%A5eOQNjNDFL$^}B3FRU~{>a1DXGqB(ClR0M(!vnLq9_zCeTe9yGQ)^R zbq$fRpaB4_kn+?3Re>jNqvcG}6`>_@hRCpOF)U z#=kH2HxVc3y?qGqDz>+gW7gU!3ak7#S10}Bn%CU-zQ1g-Jp6PDZGu5Xwm1SgYif+K zqIk*8DTRoCc^uLi(w-RirZFCoZW{@SEC@gewan&Cy*C|GvWIXuJ#}mgITQkLOUK@n zp)X*{qDnYZ`V`I>`!Q3k`lE7!3+si@qtD?=dxN2kfOw#ge#y$^o32l99UHn1J7df9 z70@w1^UNjjBMy6s(2KQL-KIdTS>Un0HQ1=3hpsrK6^`nVsupT?__1oFv&yw!QMS|T zVmIHI8m9u_E&qJAA5!-CJNSJfvuoAI6aTgUeL%X9o{}>pj6(1K6bs}055DQ~ zLW4GJBOd$Fo~(T<>y^p>U{KQipTv`Td%F38WYKyQ#zv=knNR~ymP?N)c=6;{*3TaW z@~!riL$mVpzkYW$=!!ruL{pTg40mw3)a5%q4Y0ygb<@Tu{&i|;5w4?itjg|ET(Zil z{VEEY^!%t4Iw08)_*5$&>{PZ;d!+Wbg-2D>FnUF-JP(8anii_v1N&TFB&M=D?BTKfP^K z%qc4M>wyux;K=|v{5Wx||B{$52RiXl8stmSa7P$3;He6q&&c^)Frck}#La(MmVQ1c zwC1Vz^K*&TY-YIsl$(HZ)o71Od6^q;L37J{7Mm-|VWPq2=mR`%!kp0j{JQ#ase!C7 zxxO=~3<`Tt>g(UoNcpna(2(vv7m&{yfOmMX2Gr=N*oE!n@2Ta@TGZLUcPdTQb%gP3_dbo(sd-`%gHJCDcvnhra8>pkT z?rF%8W25nm)oco);sx25S5{j zjdZg>Yf--mPfki^Jotl6tJuC;CszEX`idG%9#rUyc8Y2=|85WB;(f(}Ud!kJT*h-U z${3cFB?)=Ij>Nt3M3}M)tR?cWN~emoJ)pq~>V z7+$I%HTs4f;r!@Cmfra-Ne5L)G?Tt^QLcLm`!PG^OfE7o90xA0QYyZUfaV_aivfh* z>fTTNFtNqOVbf7}yv-CUntYMp@R^>AHj64wuG|l++Bo}+k65%zabi?GJsA%b6L_jD zOMPr~Ts@-Q5JXU{7_OWDol2^*Sc2tMB$^S$wk^*`N-^9eEfCg!5U;)qSYn&eLQA5R z&PQv;vnyBKh>w3E^u5^69q9MW1MogtpKK+6@%lM!%W?8&Ro#v~$8oykwI_FIyxGKw zQOTResf#TpZcZjf%jTFmghVHVcdZl#t(PKv{jE1Ryx`S&{`_L7L22CQnhe&r^04-h zH!&FCB=S#UJiP+ha3Vc~xC-My_w?;6&hdOn6adj^J{XSYR&C75a(E=0Do2fgvPH?y zReB8|K3D%1;lMby9LTOdDA3hm$tx-79rB!AT-+mHQjQslKnvWvKF^K%nU;K_wlApA z^hxRgp7)Cii}y3~zqx`{Rt*wgvoAuCuJl?;?P)@P);IKoc(ZK2a*rIlDE%mWhXVyb z^|NR;9`u~0r?aA%AXXWUA_PnBk0vsKwCmoXL1=dVX+xTNpMx|$alkr!vAW(!jVC6XEVUKza z$IB?_<&v`dUT$!C{;4Yb_(g7BP2hgD0;75+nI1ERu0?M#Z3 zj}-hRLNMbWTfOVw$jS3^QewpT}Qcs282zfn-X!A`ev z7SVpwE`)tspSRKvV`L<-Bo#*T5sK-D*@wgIs#-(l-BElYV^){L+RFG@nd3Ub%X^Ht z<3u;mkjTWW<)P7f2n{1Be*gzz0&63A1jjON^?Yb(1VF-7GSlxj4K~KBX>TAGrMw+3 z?3e?0ll`SwLBmQ9yXSQc9BQi_!11~VaN~^&-lE+tYHhLik=1%Mdn>L_OB!ObweVM; zv3;$;jbyQQ$;PSTCDyJEHp7KybjmudVyE`podHj&HTy#&`$^4--Hgy-g};5S0A;+C z@C-Q6F@964w-P0IYh3V{!@d{%s3f#|g}Bbw8H&!U-~RMyl#H;ttyOR#nLwM0k^&8B z{lNeIl}>#@arDjIR<+Y>TGH4KndxFlBuF?!eP1~ZRuawfDmmfKn9j=C2Iu1+gfe;H zFo}VcB_~A;I=Y7SG;GzxXT&O>Th7SCxlwiAiT9V%)5TIFPR_0%JaM2ukm_9dyJsoi zRgo(}Me0adm$H3v#IXV0R`Itrxyyo_wf---LJyYeQv2DbBIa&r(W~aiu4-E{R+ncW zJ2tJA%zSNH$r+KTpx1f6w@V!SrLHMU!e{@plxD|J!n<5+nKp~Yzw zu0*bx#ZTxYChNJn7KVh_zA{*HW8Azx5APLy7=Qc5bD-}Fzmgy9T^MMpG}0c{AA%{} zOi{xke>98nadIEax~n(HKIRNM0iiPM+L$lyF*zgC<~oXZ{y9z$-vZ!tN*mZsp;D`O zIPnWvQ9%2|$ikBDk170&9M#8dXCZw?Eg>%X_;@T|!72$j*OxT`a}5*3Fxx06v0NWd zoh11KHAw@_>1lkbQC}Lr>$`D+y8w>u)}n!GAO6-gK?Hw1J*VK9P}rFEv@zy?uTQlI zfgOjSE=g9);bAqL6Z*&#g;bPTii+|KzD@^dzj!F2MI8e?J!K8n}NrikyYR1dF zzb96nK<7Y7m>_OYrpAJs%t>n|WYjqNa+BiGDKAZ}J~|QGPl`J+Hpbt?n{sNt(PB>d zY`{2bDsf%SsS9IUC)rk%Yti)q>*sJP*ZKV6euyd^-j-y^Oda#tQqXLR{l$et=cT-vFzE0_s9JD zUENCi%jHAvn_&V9Z4@nK1%HGZs4*$Y>B`q~vgG-9^)~22wU{``BgHD~v&t$2u(k{b z)Mf<@aKd^hcXEhxUsN#^(VX|z)c)~xhE?&C$l(FP6rFIPS+)0Vc+GzAqwpRK8a=J{ znR{KK8^&RNmGLh|oH(kr!!HC({I?1do_m#Jj#0oFg}J?KdLvanAS|%M`nAFB9K^f8 z{9y-V=8H?q!sH|njqoCVvHiPsNZ{J~NJn$3if25hCJj-J6qrOHqEvR3HGC+F)|v43(aeKbkHSuHPm{Z5hx#PQD8 zVSKBlDf3bM<2^%pY5zp-t=m@FR z`wEZuqKtL(WX&;1i?yxU3Vylcq{u-Uu>%d-q;?mLSQj}x^-h(wLElpV_WKD0Rq=FD zU9FS66dJB8XAmGO=#{%fIAmAbh6KN;BYv>Mi=k>@-H?A& zxX+~6eNP0-a;35#!1cyfu`IZu8ZRJyMsr;5YA zoRk0)pQOsTD!xN9bn40CVjikZ7E4g1Be*d(VFsHfQHgG@X+|9K8kzF_H2}SP0&M#)%W~z#&Q%>Iw z+z)r0mX=MbxId$?@7_hWW~Qngv$B^-8V*}i;(XC@CCm{=X{JTLUFdXbHn}L+?5q5i zAn?-PXgieFwFVDaZ#f&+T)(o7XQjl_TE(>&uYmt}-qE?Xe^N$J3H@ecxruiDR=5f$ zk(!->t99CYI(l&T2(~hE1ZBU(rN+kfY$T5pIzd8${b4fd3QBWtNc<-wOSWRhndb_H z7SGYi#P0+p$#VOeY$5pl88Cv9BnjOFLbFWOsgZM3nPzJIu*v-RDzP(pYE`yfI>j9g ziZ<)=r;ryeB9jzsEF)+jP4C>h2R5zWsyl?0v(T8wu;pShI4(^B$kwuA!x_yCt{K=( zD2|I2+dffm+!=GO8Na_m6FL8bfozXHkB%wZY72TP*fJODMSFT@T&;NH>~WnDszhNd zxBb5mQ2y^ZX&GqRUbWXH#^L=~zo@RpU8-%yZ4C@`o?&-u9m<_Msc;IFjflAaR4lK#a z2Pd3)j9G-TAhaQms)U;a!7k;AmW*MtG7t)C%0LGuLi@dHuYc`Ae1dLUv8Ak{75WJ( zxJ5zf2};VS)rg?c{2vJy)N%-HEWOnUcX53;sXcYd;1W9Bk5qYdwNwSY-|;JjSI7;+ z{ikO!3=x_c5T$|FUPFa#yOz>Dlnr^b5EGc9ty&A;ic!@85qbE-ev%HbgySnPW}0B} z`Ki%cNiTrBG3!M+PpZXhDKPaS1}^wZD)xq$;usft(PSff6i>6-r z^#p#S0vtPp3Kwy=!NdvweDF)rkqGu;flV<(z47V#vsy|_>_LNX!vwh;_LaAxh&NU7 zmwpu`%-gR@n3LWkjBKgoG`W+J#d;x{A5Sl;(R9#+`Hjz_-GDJ}+xA*)v)lPl?Ij9` z$w(_h`Zkw`KibNBn(Tba`n78SvuUkUrGFr3mCY^XJbvHwuV? zI%;a0KBbnIn%_2-NpXvFoX2q&B3I@Z&QU*OG|h!dnasqmurQ1XB(PJ@1r@Ok zGNq7*?&_TR3S(5%e>K6WR-ICLwIw-C9Uq0{n0cqX7q-sBbTRhq8_&C3f6DP4ac5&+ zxht{Kh^O&rCYs3M-1WZD?;G&C7EqlR01n@ zx@XUmd1@foR`MbrY}6l~>SNbRrY;hSY_FtL<6Vmu3-}wg>9wFc!^w68v7~QK9a^g1 zz@rr#+%T%Z{Q}o2`{d0rSu$m2Ic@4nbEP9~@fr&|4v+FZB@bmA@4E7y4Va+d59^{7 z=g{IK`0d6SXfNPSw?9sy*ZtPme@tQ5HM8$o=4}*E2xO#>q+{+9KiS)P_mGRH8R(KQz%!PP{JI)dy&Aczri>H%)nLd`WtV3;=(<6k;}HL|cwgF@}X9N7(3wx-6t^ zNOTmzTC!-NP(s*)BNhEFe-vkoFETmCyJ(QYGYUhmk4HGgJ{Yr4;-m;({oV{iQ%`$A z2}7irV=Lt%j|M{%qRa_W!eF9EFGWI>`q5yQtt>pK@HjK)Uu^HZ7=5xsRoiVk`=YSA z**>N5tsjEt_TdJ;?>7?78OUsYF?|!Eep632NLjsF%3Y%v(C0Zdd%+jKEJbSsq&y)S z4?!3ieY!PqV<@Nshk6aDjbRn*Eh^a9cUE-ddWQObeOIM7F2> zmtj`WHu+FV-ndMqMO`+yEmp*yg{*_qZN;2xE#-o><<_Ec1_d=>_5r(U19@7Z0LA_+ zNYn?G#HmTPH3pR~5usON7=d0{F9ICpAQ3env19FRia+k4sEz0$lzoMuOD=RmSrnk6 zM_a80A|3%BsI4~sjjETq+p3VJb5>oeS^TKoZPcJ5B~nf%RG-{wn;x)ZG~Ye-*Hitj zyRs~aoqDY;i0o$|;=fTTZ<_d#Jr$ru%l9<5x!?b#&Z@t=iRtkl`CAahU3B*6e-sP< zuQ`O6{uOBx*u5Xu)2fuhi9#N*)4VPH0)F*i`d{zxg}VocB2pQ&ep(XcE<_Res>rID ziWS%+gz*sN{-*G`e-x$=ewq-u=5vszEc^-`bFpzoZZC(BEFCHzNdN_pm6b3g&>Rs# zEd+)r%-#_pl*B>R_TSnhX6G0~r-j7lw8|nhT2cK*ZQfnqm@X^G`j7M}w%M}`e0i;c zGLy~QrAmMN@{g(CA-10@(klf$Tad5792Kh+Gqiw3e6}jd%hC5k=y1DkihN*8>9_}q z3T2>QH%1eYG3no;KzWnsa>`&dp|zMT119@?3I%pz0L4u8;*@uMKj8fT+WXF^sFpCn zi=c=S3?Lw(5tOJP86>pmBTH5hkf3A`kSqu^K~NEBf`}qP$r%xlEC`ZAlaVADB9_`Kv7;?4>edu%`mtGaQtw`iLbj3u&P z(7a_2D-KDqrnRvSi!d+?h|*DZdtw>;{GNFT@7m$3>mU6k^4!ZhKQW1dvMyNy5?q;? z7t|g7G+$q36gk{vkr;A6OE_vMr=0YA68B*t1+M;_zsekApDU27B#c(%@dUd84nETk36_0C{jLqw~(J|o{-k*#L(9WEEFC81L zeuT%L*=Is@^wCiyuSV{}^p&%#vapaL)ka6X8{OpgsFIL@5KJ!-s{cz}!v?MFSQ@*Y zc(&l|`UA?_S|dMxm=9*XB^CD;!{N&B7ADS>~c=j=G z#?Jd+juP@x7EXP395Y$UGy2-ZC10Z~Sn|EA3#H)q%Dufdd6$KFVf{#pEM{jdWzy|K zMP!Vbl=pNv!|!BUAIqBA>zTf4*`Gg~lx0!Q?4)+nZ_sQwOxO_h#7h$08sYv>&^`_%Zjh}s zPkam;R#gu2>ItI)9n|<3Udik9k{S#w#72(?ce8~zTt3Rc`N85zedaFXj5?J~S`NQX z@<%zA46Xk3k;lE49Zyk?_Y}6Px*yW?NFCK$NfsgDwzsa?&X8k|V*+aJa4-98*OW}X zM`5<2^s_pK`*8iOKAQ=gvel(+p%&TO5JB{1M2cQa)Td7_eEIwny6K{!Lpge_Gb23A zw{I8R*s@dGOfH;@m8|tbSJe{^7|j$5K4xp_oXIjrgGYxND)+2X%QI=>EF)hhi7SBjs_0ZSZJ1`HE?K?Xr0dtfVq7ra`HR zJ=HSO+UzdAr(SkOb@)Q9vxr`kOugOqofKz~My6JHDbAh`MaMW-MN(2=|0YFRmrh@q zHS}2JqSkzGaITy9RU&j<=iHZ!IU;lmL@S#03wCBz&{bYRbTixz9HT!{C@nkea5R^1 ziV*2+P#8<2U6!KLE}pq~Rk~Nv*`^w5U7e8aYr!B1hWn~2uG2IiLWHb}H=k3oZAC%=Z1)nF-zgPG{g68kOQ4G&Lhl+0stB}8^;!;QP8aL}Doy*A)y&37tQ!8n zSR!{{5TT#zD&qJA_WmARHDo@sAYAVb?jk}90z@cs3?ENEk${-}{hh?wFIigGn+P34 z5t4||&uzh9UVn@_`QnaDeGiXaB|;N=h~D2|!YA$!p}z-*<`Pe<36xG&k>LbTxCZ!! z0TC*E=Oyq3h5iLJ^<2Cf@7I)sz5wZ2OMVT~RL?$Ct&SrR5^PTA5XY$haJ66)zt1L`2HlD{zC3&3Vgy;yDZ!2GWsH7S>+p?QvJxNsXcri zNMT`yqeVodV!X<*hNv;yKnlF};~W=A+}bBZtSl{}*A^fbfxS|ieVT`>0Mw_~O->Ai zZJ+%$1BtmsP6$B!BvD_Q8A_b1J3LW;3yHZ>nRfo^x~T@9*(nSk0`T45TGK@gPF4 z=Ljl*EMu6P@NE__SA)d&99;uCKWy?jjM>iGcR%6Q-@o zX|q)~aA5h29fC3uLc1icr2!hr02(3i@$_`aOYNMtz10(Hh~CFU2o$u$UV;BP;P-EQ zHLVq4ln$t6OGqBuqIszh>Y$ML0!?7~VgVd~M@%!QFOp z&Z=j)qs=JX`NUnIcZa!QhY$;(-b*u#FsK~LDxKUP7QJ+RTobklmYPNqp$G496ewI9 z;^%B$g-1U))>BrytDbpLG~(KRuK_kby*R0Xiy%VFFGa{B8f*JMMW0c&$XAAuf@OqZ z1SNpMmMZcuW9%}?hN$Xq`{=6Gj1morlpfNB!g-%`I~(PU9cev<0J68CvClFF<7unA zui^WHPd6X)pheITD;@&3B}K{F$f1FJP>enTwsjdX9Rpy@csp)1m52emY^Z|iT1)BQ zjJmnP=<5{>IIAK)lg<$=ZXkyDPm_l9Ero9g{XSdz(#$u>$wxbjItJ^PWw#fr*OK6W zV?#s3&)}{&?z~4MUSc15^_R;ZoWE|g%L`@6Ym-ky14Vbe=r((4FiK)mgt$#2RLuJU zLxKrJ0GJJhiGa9 z+z7{ieCb66h+({YVV|IACz!MbC#uD^8uK{F-*qb&h0)p%_u0l6GqJ%I|UUPC@7 zN0$tV6QQ0@ZHTFcq?>7bbY~+BRZ`|8^Utksm)B=gxVtVJUq#dcw$-TKJq{v@?)p@% znJmVPSvj2Wxay)&u!46F?hxTjX!tyIW@Ih!fv-{~Iae@R0Hc|>y^r9h0Nv>VHFoLn zwMa|C2m)*VAhW5x7wO#8>&weXJy(-&4j6|H7-_Cw{9%Qm3Hlet^P zN;{Kpw9jK5hzTHQ`>YCz;s?@$JAZSQQHx=~kYd?1TjV!7Cx+HihWwiveicmcwFt0r zHP&1|V7xPM2jO5(gi53lOWP?X{j*N7mL#WkA7&xdZRAn8o^Tv*7-Cwq5%2j+*fUZ1 zBY={+fE9DQ3tmVs6QMrw?$Tv>L^tz51uT#(6E^IPm>&SwbKVfhJvPpO0%tE6m(hT{ z$|E+7K`|6V*{Y7SVl`@yU*I6BL`)_ixjmrPJJ5OU5o6Oj9FC^h7Z^6nP`(`H5NFMz zI!V!GOSC7@;ljEE9Uvoi3S)&p3Sz4_fCvv;KU;rprpI1$D7%i6$vWRrWAIx#u3ZmQ zIY$s7yYxn^be0kW=Iuk2#s|PXCs=h-egv&dm^o};k20L5*S>hD#x>Myhk;=+>TXAbX#L3S z?6{=6uku{uKXFVor$#Jd2# z#Q>-c3~7Alo$-<=^%2`j7$sr>tg>$=!7A{7F{JXHOAoUi%H0v)&6RguD>5`-P%jAC!SW-}ou#r|pM>+sk?H0k{fxK4k$&phWCE=* z{>Cp|%Uwu@qO4>L?|IO1fo?ex2W=X_*P=`bBXF#_7<_Q2)oyGpYVPNdPdG`Gy*%N9 zM_erGmZa!vBmwo=0oR5B+)hIn)Itu9(Co&-fASDdO06q9TAD47rxKn22wwOBzA1v3 zfdl=bji|dqP2dKd7y&mu$dVkKU`S!F8YVC{Av*hr&`Tmj7zT!rat4SU;7;IGlO@m% z=aPP}8Xzz>64LT<=?L_YF~*V~oQC2z|DGp*G8-ehlDO7kye<0M|3+8}>;aCB-{)w* z3Da2p9XYHdqWAATln|C6N4M?o;Z;@!8rq~P6oIi7w)uOBE&#^dFEI9n1bSpL-Q$<< z2;|BIzV&+!aOUC>3!u}%{&DP5$e)_hMz35)yG;=k0Hi?1hu{8XDkvQQJyc&F01ITU>IM~?!!S)f@c}7|`z-R)%26V+f ziuPd>_;Yr{BNHx>g&msz#U9kOBe6ShjHSa~EaDds)oUHqe{a!ETBn@CVmpFbn*Y}= zNYO4|Ky*qr5#k|2_)mUmk7Bp7%e5LZ$+3M)rf82Ea1k7M|Ki8gPx!?4sy1gttwzPY z4%sgufbmp1934!vLapjY3%RsfzSx7}1_s$Zd7l~aY1~m*WBV^5__x6MXj~}3XeI83 zBBt|!J7MH~LsahpGPBkKqvBXJ=MV+@D|9esQsgTF&8!BzkZN2sknVZ-gbt$D;g@?? zx8Mq%^wt#-=viYT1cy@~B4z_W+f=0L=WZ_yzhaABMNDWrCoZFKfZ3K7`rod7ogWGY zCh)=TTg20)Qq?y~r6|ZK6 zT(<2gP9)*Xm39V>dU!Jtx*={!gjnh1WEqxE2V_sH$Ppo=JuuaN1DOiPq!Rc!gag%5 zcY)*GV$Xhc&cZs>k$mVv&x-C*g&7GHXT|1P$;GEw%atuqqIn-S1m{Y2pnWY~O z8*d@X6%kd2{92zvX2N)5baxZ1UNF;Jo#V2WeThvMd=z}xv`#@|(I}9sHg_XCudu|y z;o}^@VcM7%w|L115Up#sB>4V@cZ}p*{#Xu^cUXq0)ulNMd_#iVn0->=;$@FTtr5fA zs`e5EWm0=wb`|2ujk!zt0Oj_H_;_&w?LtENtOni_fp&cvul}rGB8SO6T4SFlX8CJw zV0~sErJc#wgpn5jhaPM;44A=E4kMLN{>!s{G^{`l1qp568g0tu+9oCmmEcZI<5Bb)A+0%Wm z?{x}$X$(ja1@(&0>Nl`;G4C>}R-j0^8td$UF9+1H%r!g~A7(XM`WFGd5A5`l*sHdE zh>07Cdo+M8!M&Esz$TaylEH%y7x12YFNzv0*-4KbnX*UxykSQT8*ck*ozxyHjyt}m zTiv>Lr{yhT;jHLir0?(<3^mY z170n07kCuQMTj~v@Ypm6wB0IU*dW1rd`q|TAHOO7Ih*9*@^4iAmqE*_XzRjlx4r5Y z^+8Dqb}6@6T^t3^xyO8Q$bh_s4dpd^iwxnnH`z~s!gOzAG?`m4%Ind07SG@6$cR(55w45>Ty9u?{%Q3+1>N-QGXN4^46 z>dRU~qVMVBmp<>rF?6Z+fnjj2J6{ItTfJv^-f6en>qhO5A|^eeZ!0$M`p+@DtXR=I zd5#m<#|(#<&igBdiBpwkHgd2KAy{`sOVDih&<31;;XBV%hg*~1(`j3MI=U;tPP$4R zRpQ!jgWVpituEWH?qW-cP<1-aiqQX=2qjh^v3rPys<(ubcqW3M7#u^LIH8E+*b~Pe zdVpACf!9{SmwDmMyQ~gqZ{s-}it*3ekbkUaJ6Jsd>#F{78u-D!^8{K%Ej$^~$=OJR zNP2MGgzjWqVmQLGkAP@fPyFMy|0o#9pHPq=08x8@iN9I%022q8`0v%#0Z$z8!~swI z&y4wjbR0;>fpi>5$G_+FALxk#J#nBX4)nxDWjxey)YjS48dHxGK8Dw?iqU$cx$Z ze4GhMM03q-ddQR(l2BT`sWRzvL5#mBd7iFuGuV%1VR*1SNXf+fUih^`M^nXKr63wB zumA8pyS_|XA5(rln^|CX=oM4$G#6~`G>&TvoqxM)+e$R|iq!DKg&ZaBsl#_3%Dp@M zB>u@M^?vi_Re!~;OkO_cmr;ar5YX^G_LbjrT4xQ02*ZGKNR+^~)kYgh-_nx6y%2ieLZN(abQugiMuZfOO`2fd zNX?(FM5EWoSb~O0LLM-_JfYxRdPu{_amZH+#O#6S9hoWc_oX6;{mS@a9+4Eq6hqGO zp1k^p?UT=#H&?z5Ri##ymQ!#T%5z(g+K)V73uEFUk27V+Te%*84MdOJh}x}!uEf4L z-?7Me>!!rTI_W8i2E~kY-AhwRjbF~z=3mIO>qTmsJvq6>Ht82{{10HYnXGFjt(vzs znh3?4WorpVzD4Csjb}Gj`db58nx~3g3G|6_tiqip-E2WpuTx{C-i%+%zJiZ$;^0b? zoBGB~?MsKc`5(r{`d8a^)5-0!Qr+Xy6rNIQJXL(9ln+aF8Mb)gL9fLgTmA#Knm(IWH{Ls9~Y=%5nC5G>tF+i%tpWWE7oei6v8T9&C zD|y0Si6i25^0;L}m7@B1o)t%B>Pd)tu)~v|nr0yO?LR~!t2h~vPJ;#UNXdsi>SLZu z8%ze-woB>v6b*auQ=UO@Dn%5=XN^N$lBUH25;D&9mu0U1a{+qy=kd&k7DMcQ3`)S% zZCgYt@Wx-tr}q+yStj+XzD5`;7YU6@es5_ys`-%i)A$kknJ*Hgef-1w(S^e_cn0f3 z=6-gP%~$OACs+=mV#m(sx~o4$h_kG3MJgw?9V-8$qYmpxkl2X0Pw^lM`eN&i*C5sDD?yBsO%I!rfLZ_@+aX{`a;T) zo{==H)U!0b$yOL>zRGjAY_DLN;7SGpsYSja2BJ}fr-vW7&=-cP2<%O95uQYU^-`od zzh|PUY&9oe!*%h-BWCyU^<~4{T9raYY30hKj~^|`GQUiX@$w{iC2mf*?t&ZXi&B19LDUM6Wo+ z33F?hk|_}}@d-ghL&{dpw29k8#(1hM&!8dBASh4HN$*?OoBPU*lQuTc%r=Tr;Cay~ zpSZyB~JrP|&^15LOk?gmoPG)5> zR$&t$`RHa=OU+@FcQThWR`+hdBSUhixZ(`H;d%=QrJPd3ii~Xn_Z_qb0|Am>HHD)p zF&>tV_pI$4T<%!~JWmz0w=S`3UJwkebS3RBA0IB}sd|qjLf1SU20>m;A{L3A6dy@bQtsIl1~J z7FX~nrIEGA9l=sxY0En~b4JgYJOSR%!`RsNIeNa`@?@|?kBg7-h?#Ugh9ELl2*P3E zJFuOv#yELW2^LtbXZzD&FJbq~n|4bs>$Dqh$XA9R)UYu&leXU?@3QSAweL+s2f^_a z^VJsr$~loo&p_WUwl!W{ak|qpz zMuQOB*t0aYC(`>TUYrKMvPX)Ka=qCZL|r1l0-=Wl-nE$LuI)~$!2D+9N{L)t90{|{hF5r@}Q-o zA%s+CRkU^W9AS!pc|nApy}K<`3Agl4!#q~_*lWINKjlX4{%T09>Du)6(9yft+uL$< z8OmOR7b2~p+L*=`8DHq;7A1F5Fm&+wzk>rlRu6txrg^(l8ihl0+{#9hM_=g_8(7us z>drE<&4p09<_5P{^rRX@J-)};>R;1J8}|KX9pofA^o^AA2uR79^c7lieI6JV%Mf{6 z%2@gn&1+7kTYgK|kuBv~O*tdME z^(R4QmA4rEc8=@X_jKkUr6rg8@a?E&`@2M_CPWW!ZBVz@6ZiUo@=g_kAbLmTmTcRN z^efdC@aGpAgIC|OAGft4H|2X{K-j%YgL~93)1RL)GOdbusJLUwegVYn`#9h{i)eye zqd;Tr2k} z%mZ&j!BEh8N+UBb9HV##zR>~9?;-Gn6{kvz2e!z#NPT;mOB4o@Y1V9HY8l|vtwK& zVh&m55HrEsl{F)3?yzyisglY|#{EigOaG|5qMRN8zo`cRY@`d{W2W`kTg8(Wt>S19 p1Y!BAs;!|o_mTpG+IxW$fB9QPNexn*kG|{urGf98%qDU0zX4s{toZ-{ literal 0 HcmV?d00001 diff --git a/paper/figures/CollDetCinderblock/ImpCtrlv5_E057_R05_impCtrl_K300_wall_nocolldet_collision_022.jpg b/paper/figures/CollDetCinderblock/ImpCtrlv5_E057_R05_impCtrl_K300_wall_nocolldet_collision_022.jpg new file mode 100644 index 0000000000000000000000000000000000000000..a6ade7370f6fb61a8421b6c2af665f1ca9506754 GIT binary patch literal 145064 zcmc$`dpwi>|37}soR7&Aawaw+V~QM_gqhQ9PA$o)vMCukO=@zema~x-8n&U(0i~j- z=FqE!kxG)&YZ^&1k)-cl-}n3T`P^>5zka{p=a2W?o_4$Da$S4ab={wj`{C)&yFU}a z7PPCoD*yrk07&!&{P_Sl1JaU`Qj!wVQc_YfGSag05CwTTIeGQ1DoPM74IOPQ4NXm5 zLvv$Y{apr{n$W$lT^4Wz0-tJJPZ*GOK{O2Gb85tRQIe9e&1vN`OO+Cy1&yPQy zfU>l>uGD@oNFNYW27#49e_jAOqW38Q`o9n0-w%)&SX@FD97p^y(TWi(Ok+fAd~*OY8jyZ4Vzkd;Wsc-P7Cmk~cK`X5{U=_oI_j(=&hb zXFm((mcB0wSAMLn{apX2E)W3zS6QO(|0?YNQJ1o)E-`U&u(;Geb%Df^L<6iWE};jP z-0I{j6-H9gw@jCY94M^1+a+UQh5e=)9ychv%@8rUbLpSb{%>Xf?+Ux{|Ese9F6@8m z8U^IRAkl{hRtEM1KR2mRhS>jNDE>8haU*Z!(+c+wP?GxAdg7_vA7Ccw{vV*}^v11E zQs_Y$N-b744S|$Tf-I$TjPbsn;S=W&Z7Vgm(HJYFtc1A)q-`o)5{6`QZBhrsR%%A` zS)%up-w3U#VuOS=IqL&%(`e|Hj7At@OB!q+4(KM3F-i~&C>P^w63I+ggg4Lq?>r~(VI<{DzTdNT)o@@Lh3J{D^(b8(G z3~{4t#_P?(+RBFl&+{uM1V}lh^+F$YA=`PAiTi~GHehazJJtHh045&2AMfq5n+$|h z5TO3m^H_S;Vcdt649jo?`UqL?sX=6wwFos}5Gd#n=EwjRv+j?u)SdwoRDqUa1OehON z9v4YZQ)f28=Z2TBS_T1-K66^S~@Q3;zz#%&C8{=`u z64qNM-ZXL|Ah)BXnXp&Ib3C&AyB#Uutkm&=D_7V%cC5KK&|TtO3X(tI+lN*@SKTi# zER)E#%AsZ)TGD>1Rq^m}=ihfJD&x)eK7G&KJ$DkH8W*{r^XTCbkI6U-%b?(! z(`#_L(4I_kwMc#)g~$y^&RxBbFmJ*A0W-`wzojW=O2(|bp>FWbob+wxb%VN(3;s=r zU#5Sb{St$_tX@uU z@4h9E`{j^g9y922eUz8=LpAYlCVm&o=``J=jRvS~C6~2T{rpZ_;In3hb%(BK?9%)0 z>E2nF7he>$h)${Q+*^zW5LgO{mwr*}(GbN!;CF&?OD5*%Z3sxL$s6D|x)FOM*8S#X z8574@ay@t?+(2fP_zeBh<)9?&{f3~*vh#+u$-ZL0ESs(S{FhZC4qDWL3lGi1L)dKh zt~nx&6W(P%V6(`vK8E8}tUh`ZG6n9(`)kHVy^iXHbV;dqA+Ec?HtH2&V@YbgwT%I# zgFzduglsQ$$Pm~ldb=j|=HNX|_g(?~Tx}Z#S>FIrPw6 zUptxE)4Efge{<^2QaKqL|Bjci=;qk+0zBrMPgKz4f%Z(%;1FM2sHP6$Av=PXN29Cn zG;`Icpl4@01m~4ldb;78tQK73M_Ap{yKiML`b>{BKaZ%YWxmkh4#{1$D)u((hWn3% z5-~4EViX`{HMcc!?za34D#6BDL2KBlZ(n^g`fL^F~d?8@lFsKv(!WfZdlS+NmZq`|KY8 zJ>sI)@cZay&>x`lDN82(nhOM{=Ia6h{zC)we#2a6>F|g1Z})EcFSbp!%S|S20Lxv0?>^gt2wm2oOCOo3Y@Ac%cUQg2i1#P~aZp6j&6%SVlv8 z5I}ei$pb0yR8yp3=}tnnZjC0E7f!iT0VDsYxd3+(aNy}vbT744qXO!|JJrSM!{_`? z@F-w+j${!<{udU@i$}`1K+dq?FqE*S)d(d(W-;g8I*dbTz{R|M!|^&F>BVBz*MA?; zD{|SaC#PF?>05+3<;fFGvjGAd>*L?dC0#${G%3xRKy1__pzxVF!`e_ zGh=i}OSUF<*_{gA(lX~AB|wGqW=Dz}p|7DpFO$WQq5_gpju-NV6diqqs1aB6R8IM#5 zC3#lJmwvDBhq?){X@q-4cWf70coFvRUX+e(-}d<;>13qv=Bpmhp}@a>Udz`bj;)5> z4%ljYviOj;ar>`*-FIpfI?z;Z-b{$m<*!~H&o-`M;Gb9tn=+IhwbyZO_~oqO(L)g` zy{|eR1lFy2I~hi|a``vJ4iQt;DXUl z4(z;_dEya+OVA-7uuOx(ylO7DuZ1y#i$)goZ9mJA==@ftto2Ow=#=U(K}c(_4P;B_ zjK;B>x9gXmR83Zd_vQVv4N{u&pSo+5hx%}`t~YIdZkvn=tq=?z)-EYYnXJ%XQ#Q*~ z-_LnK-xY`u;W8^WxsNp}Exb+WSo3F(Sy{J#cRl~eLL!cS_1QweaP#4^8K=3i;df^X zQmy)*l{nOy7I!sXzpY3tjl67TcpBGI=vO*ea_6&eM>j04Nbn>p!5f}OOkVga;g-8t z-E6T>&q=>~CkHit(REW>!qb^3%MR2 zfnQ7-?z6}N>GK@D*+y*1#R%OR*o^O^7G|!y0OL^SVCn)7s(15VF?jZp zsP8~*^2&l>k6%T+FjHr$@zaqqIlL`y&fe7}6y%G9T1m-bNLCsQVOMkx5$_wBQAzSv zI@ES|EZI<_@R;c$=7JO%-;~!%O@1o>UX730U9bjSa-X9!jwP|v=!_Y=F-AvvDgS=?8#cB+r1uBN zPgwV(0cSqLQkXR?0J_53uw~yS$1=jGX`;&)DGMX)(NDJwPh2@G*9 zvagG{&NGTEp_gCrwsr43Qj+jQ*v8M%oNWbkvJgeEF|4wuc#r1rcJAMVWt1JP{tuu* z{kpTQxzs+?vTz+6;Z_t?4HKHa&ViXxMK28d zzB-WKUVmBWZrZz)Q`}=MpJ>W4WWq`=+s;LgoK-a}z#HZpoN|yziG;VjCDmw}lixNF zZYz}J=tTmdSk=PM$~JV1&5tnhk{{yXmFLBS4^^u=ZP}SG*h0kD+H_aq3uCp_npUYi zvhOfPEJ?uGx!Vcl9R+Z-K7)Bz#YI!yBGtRL6815fUC0H%jgtA#F2Iorh>Sep7g@sm z0+R9zhnlMBvtbuRsg3W$oTIfzj2C1eWp{vix$gvCoSkA)ekJH$>cooVJ@fY6RpVcm z&#d|8FM+tx(;4&b8}_y+9#_5~eWr+LeVziicyKPU)Yk@X7Doi5B@ZM)6jqheGd?=;yhjoiI`R;OxQ z%&YpA&QyJrZFN6HeGY;l$H5mu3RAufqRdVt6u(b=Yn?jLNbDzV;~xYU)30us@i`uU zv67al_>h0Y(&2I0j2daQT3*_*)m;DYJC85bAb9T}+@JHPB4jZ`Fb*bRZCrRwS`4P)NGi4u0{UJGd^+j2`=He0eS zKHePWMC`65S_uNj-zoc7zNgK|vMf_jb&Fhypaf=rqdzAsb-)`2BM<0m+0J16v}y6K zP|#x%*Dg(cKVDkuz6gk^iiG5T2)EWA8(CjR((1E}7dY86#}v$oJC(qlm)d;DwU_!bM{lE>weHpNYj@Q=NvnUHcg~k8Zmvp} z#~tdNRMlla4Xl;_-o|uublI( zzfBKEaU-LhwcSLRjG?@&rkZ5`r!e@R^CsSq+dq@?UpTDs^A9k2Vk3XgzdGAAFy8EP zsDd3GDPe;%l!AP%ARuR1n#apHVidS5EH+;Bx)=fG0+*v&5Mp6akcgj4R*X=#=H19O z14DocnB6ZdzgXajOlB-QF&W@iV>C<=3OGa==;yW2fO4vH*Hp!t#%Z#+QCd`g2joT; zpf~R{ReGHZR%+BiJGNZoh=CTJI9dd04geEybnr+K-vT;suAV(eBxZk^8XFKFIN$Rq z&BS}S*YYiawv#o(BaNpcdwxTinn^58EXdW0 z1F5MT#sIM4!HgAFKZ4@xM)sWGQJuHv8@#YYAxZ#h!#MJwVPK=w`EAokuf6t z{^p`9@7oDUWEzZ8w&q}$P%eP6cZ(7^#6h5h4h18|WhRCmQ3>l9&>B{|rTqtU76GIY zY#?nMEt{zVh5k^J%G>cj?4*iqrd5+pJ19n9TRJxWfpqd_@B@~IhRsps%id)Tab1sE zNqe{PoHZUEP<^EF0pciuYcn4)gLF>P#Zu4oLye$YQ4W84uxU!%sq)ZXCt-Lm^pbllyA%Rz->#T;jq%b)kzf9sFd zDRmlcGiq7-Y_rnj;rb+~N!)Zbl|JvP?mEOlIE%q7T+Csn2M(_DmPT_hNQPv2<*@wF zqoHI5AV0Xyn;tJ-Vt|D;`P~IK@KAthbQRnxHHHDFV$&q-AT(fzcl`!2ZEuH|Mp~Ud zjTff??A&XB;Lq?dU=)Kw=81?4U_l|+fFa);>ZNB{@SMKSFvWPT-4fFwjUY|v`@yE5 zbeDU`Bptl}Jc^l|p9^uj{RGf_YkyRA_^iuO)59ODw9nTCkQ4J1?#NrvnVoROW)k();mNRC7J@3~x4%c5NCWYYu)83ib)W zja2VPTLmzmz4-g8s(RN9&Wdi89>CO#f?Q*Au?1VRxOPAy+f_osgt@b9PjF8VQFoIrSX+;ns!4jmJLXk-??$#Q3P!D|9)wO(6N%S4}< z*l6y7w6Pc6QFLkbT9VwN8y;9?>0ikqc>iSTW!Y=^_Tx*NwrlJdq5USHGdx3`>PcEX zTND6gFL^g&?AehR1MM9I0liuE9mdk6j$?h1<#CC7?2)S)q$WQ8knHPL;*MJH*6Wnk z-IsnVh_pA5_MuR{DNLtWKZD}~qCaJyxvb&S_u{Q_y1 z$msLmpKnV1HuW!8Tq$hWvuOMwNyw)B^&dyLr?MjX^}iubdu4g`+0&oer=HGV{{xt; zODjgZ+}(wNb@D*o0?&fl2)cwhAqQY-MX?|+o~yI?`DBdKJW{5QwLX}R-iHxOWX;Hi z(5^9nhz>Q5In0&|m*ecss}K;BAOJRAfOau9=m3oIXgplRC#WLqs$(F1v;=MaXz9Lg zf?{Bmh$=;l7k^_Ju45zVfE9PIJ&!KxbnKVi=?Qx%ioys)60?tSK*%(v;+?s`o?GKL zgb_Hqn@VNV<5lha;onfP)bndA`2wtBiPqDNR5ziju85frC_v6I!bYxsXR>tgKrEz# zuus-^9x3Mnq0F{|b=H>Lc*PF6W`G&gkv1;k9UNV)6=px;I91XNia4I<&V-ZD`*10> zU=9GSE~dhOr)WzzqAg~Xi@tX6c%Qb0{uZIHWmwePD8*%~@N>-FB= z!ztC-+qTQUZ0oU~dZfN#cji%2%!1~Ixm|d{Dx`-++&{V= zRG_+5bykYH3wzy0j&Lk1PI4!%*ZSS(^_OF=cY2XU4_oe*tUS&PhqtE}k33S?e_+q5 z*ojW%s~GO5jFrhC9?N*fnZFw~P;G#(Qv$XOSQQ*9aEH5VsZ9sIwRtFS8TC4^TR>Oj^>41VB*G!Kg-cPjcR?vdluCT#M zt$MGme7YQmhsviBl+%davz~q(SpvL4ZNo4;=Jdu z3>9|n8bgP8!Ic`TUfbX~TdNvl8fuG>uDffc87^w*_EQ^A`tq)-F_P5oW_^~}PxlP3 zpchKo)`sH9ynGx|j(W7a_$S693iSIYbJ4xHJh27=d=WVY;dE#pL+W_Of|s!-#tSe{ zX4={hw&6T*ZHgb$Jzo=Yrm8Ke=ACy8IlDzp(hz98D!O`~M(Z9^jmbK5a)4)2gOYWe zUF%uJ6(UN`77=4J3+d9YWMAm4G#NtLv?4kX{OcKB(kaAfiJ0LESo@nX@hGRyL@RYw zqttk`QXQLVx+QMkAkOmQ55&l&yz)1}2hX$*W>mTulL?m+2?PlvC0<#UjeU4ogaOO0 z(Bng+hf|!xD_ED{om8XVl{Rbpnzk=9@owZx*^sK=(R;V~_r>Qq)z>_X)FR&hk_TPj zdR!7(N3@HF4$tdX#s@K`Sq{gKEn=o5?-FCaXt2$5Ej_9sg}%LrzfS9F%{?BgTRimr zh?SrGmyd*?WAArM5&IvNy$p0{_870e+KQm$iJYP^7m@Yy9~x58-)?WZUH><8&IHqc zE=~siPX{M$deCFL$aRVL?n3kdFaolsd`RsCf`O50G`H;)Ns~erN0W|$Zo#H%geal0 zHVoiQ4UiVaFDP7LNNhwIQoYlxTr6ZgHE`}o2|dU;1V-!(kSqFcdmmD$VMATZYl00JCsD|!}79YhlxX@G`j1l?*8eXd2?bFdHMO9vvln=Iy} zZ?1j__@E_4Y^C3-QxcMaYwD$gdlY)2>J4_`%-bAky-vSOLYMEeW;?*!?T;7bUC7Y@ zq&jv(utG+7M&5AybRo)$3SxF&l*Ob89@^H*BBj(>^CJamgm@A1xf1qkh}1eMS(udv zU2-=XL$LBz=jbYRi#{?5frrR=+lK{3*{2a~jp@NR@RDi_VQ-D`Nbx*UR!J+$0D;vm z$AEg-#l_wWUR*%O7e(^cg4GrxB_-6w@`+H8B@9sKmzFbP42AjynzNUifXks^yWArK zUwET0ETIy&DxbFfI(@0V>E=b%chA-H#C->3CHH(i-Hi8upFD*NaX-xpUVF}Aef>xu z-SgQ^jY~GZQd_E}ntA?(Yjou|`_~U#Jj8a~H!+V^+unY7vcn9qy=eTUbtwWItGRUO z4(bXXOOjd6aW%{769p>@JN|TONkuUpV>A` zO=lXFZ3`iBkwYrJ2_jPn9jb2JVI;$XC=n&qSehE1+HXvrEsj#|?0Qv8ZB~8%TAGLzNArF12*TiXfP{RwA0=WB75%Kxxf;!Is zopP7z&9VkP0|x@LAl}u=70$akrSPc&nC{rQ+gk|4l6esE1O`8^T!YC8yY5ZK>NsOF zsImTG{rFqd7hsn7aaPohI)SgM=|}}9bgEpbV=rRD%B9mrpYErTWY7xM91wSrw%4$9 z^TnOWqm@ZD8gJ21!)o#`RMI|`X%jWkp63xyLuj4PdF6mnRn?_I(=#@8`0XKX=z9k; z%7^3`q><)<>ibIM?9-FCSQ^gHhPU5o(RX;hcw*h}z62UtUGVIGVTk{4%=CYLSMkGS zpyR&(;;5d1{pV%R&!qmdjXiI&zOCgzI4`dp;~;QD^n!k3a|U}x();*jJ!w&|p&WA? zwvjqR87WEAA&P4)d#o^5IWUG;K|T?W1}q6O!dk5MJ{-u(#oULr*Ombc#d|aDF}hqM zCrAQw1_MOx$NO}rBc%y43*NdSHV24YISm{~k5AbuVut1G7%}Y@We<@j0vLBKq>^ z3TA*gOvI!C^AyGj#045QLhBO(yoh9k7xaL+5SlEI2xVx5KtZV(=oC$x5Da#>i-rNL zMI?v28z1%hYdP-j8U|FJ$kHP0!#K83NK@%v#`KV3vF*CNQ0;80FE9O)q*9~WN{s;` zo1#c^Q)e*|0FDsvHjR{7Kqb$kqo%R}2V%$X-qs=h)kpQ5pvBPmrs^kQDv<^@H!Hr|(2=v(JA6+oikQR}x#K2DHwP3`s;a4HbNSXDac#nQ3Q8%xkU)*Xl zB#KtVqvE~oHJnE%8csck>~b%}3gbW`dloWHcNQ`LA^Qi5BT3PScjuM6L9)|Z5Ih}X zFcxD-db(BRT%J#B@=T1Z@N@L&IbEX#iGGIll=Qp);o)ZgyOA2c+yjQSQVo4OC9hhm z5fh_86Vyba1;I(33GQM^UMr+yqCm5wxx>$fk5de}=5rTQ*jG7#XHX*hY7e=IH{Eey zc`$TWdz%(g8zwgt?feyV}K;7vkz2REei`E7>K=1>a!OsD(=J!_-!- zd&V|g>)?EBT742~Oj`mJcjR+T4$gjL{}~OxOWI!cx>|K&4h^$rK5%neRb5TqROY+j zrXN*L7FGQhj(8CUL=vGI2VLo+#wC{dKK4&+eVw?3H@N^^n5D~pH+hbHnMRNgTJ&RY z)9-|kMwzg5QGOxNB2)gk0F4amWyo4Y@l~_coa0RPxZ z1!Q}cwq|YX{70fY54O&ja>{Q$-}wh%IR#qORZ}Bmq1BZC)UZ39wg0<=$bE+GFG*9# zGo8JWrSsq0N~0}@Wv+PS@Z!Bi)@!ePIK|58H8glgZ4SyYgUgJUroUxDMOxI22=|ez zMmZS^$c$Fwk*lJ zd*5MfIx0Ma3W8kYr;il$6w_^(YAlAt6ipKsCn3T|39bz;-n$+|7O{esYb^290eC8} zlFUqYKRB`#Rhw;Gmsq7lscR^CobAi#46^5A;QxDI}bnkAJiJ=NbNMVPn3DQMf z+~Er4m(P-BZ#V93g$GmTR7fXwAt&yY2j)B9I_G%J-WwS9DgNLWJ!WkhdB_XULts}J-$bn$2eIT)E}u}7gRzt9P~#foL%aY)&T0*V z)yaiOJ2`0!wV@nfuVirtY~BSxP@PB0N$x_1B;9*cSnE)?c?K97DM&9LdW7@RlO(j$ zN$kQ!q_h*e67~ncpGE^dWG^PKum_?oh3M|CR6q>Ti_#6~OE15E6F&V)|CW1kR~k3< zQ|?tq?W@0sLZtX5N$d1d;(akVN(QoIsnZTSQ1hF&Un5=Gu(qMPI_jP56+>-dX7IQY z`N(*QpGB?IYIP^Rzr%d4k)Jxq$4KM~vxEK5TMT>lj8JwVI{nNXiCev+IDpMV#2Bwq z!59zV55UpMkZ)OaYA-QziMNzLY?}|5zAw8EBLR6J3Zq1{tlX-ra)o0_c_NIIk7a-j zSe{!H%W7hLv|yyX;U?27R7@L!!moq{JGE$FY*=Cy55_AxLqo{8XA>A3#Mj?mfUE*^ z-qqoAHx#sSoO&FIh+)Eoyx5ewQS{|mf2}Cx&^~H}JGEx#Xx<9eV=5W40(NimJ5lJr zv%{sK=i0j!#Pi~j`aRiEjdOSF&klT4IHqV@E4BX_ak#93u-H`_!^OCNun7yODoz=F zctWUJ9e!7D>N-6>+gmG^XcXoLaJisdx5q{m1+X!fODvbz$l&RfM%t3$odX6ftq**D z+|3AnA2CX^wfEmT*kSZI@!ZOboHUuK3T@`S{7-en=Pr(+!L!!k$?{NjFHnSULt{*K z_^H}Y)LOI5fj!7EDU#oGdt{8M_a}dQ$r-XnsZguuL;d^ZNR8`!DXp6?a38#FJFN{y zCzA|fv`el8YQ1Evk8Hox`v-9C`E``{;F?8>Kt^o3A)O%pBT{VNFB__abb`P6z~djKRP6yqbFp8)_B;7p{OnY(Bzy!E@0#!kirKK zoTCA>j7Ga}>;aI-Z$!&fr^}2MH=2uNZ!Taw=`LjLM-wInfO9S5@!pGGHe3t&LHF^T zb&OuT8`0?o+GYVMg>NL2)ByjyG5W2uakpL*f+LqgU72LuGCj}!G05h3R6hi>Z$NB@$1g^RjyvyS zL_$N=Dqv2K%w-npP~KwH zZ#T5(;-dGhwPu!L-f_sYSF8~{p*qtnJ1jlKdE$!H+p~V=%)fnCHK|NQs&SSu`HYv? z=qQ}htC=5X8O=RsvX&ZIy{VQx^d^hEe8&F^19YfTmlrW|CS@XW?1T5GCfK_Zpl`J= zel5JdnqX{jDP4FQJDZ|)k^GbW@{mwzt9{U^AKy>fXqO1hbL*OFSk8NQ-mx?hA3VFl zbVwF>6bfAQq*EA!BN?8OR6E|_B1#<6lHe%3nBgg5m?WCz2v*2UL^*aKMMRQiM2x!s zBo+gXv*JqKMjt(kOA&FBB`5uyO+Sj~iQ9;aj1?%N8>Or33WNzB_sf3SJKAVEu zmBv&2u+72Egk5h`dskT9wk!vN2~c=E6kZ8C`y%Y+GDgUl9!cMN^YmvzLzWVPv(pD( zax82SbufkTpu<}}E&G#y}70o2HB5Nj*}8AXH#_6eBB@C(QZ0HD6xVbe3E$R zkkblc!bMCabcHqg>}rDf91^G${(jE8?gF5g8X?)$V-glGL43-t6H@7@R}RFQBUxI+ zhDR6jF49AzS|~|%+FzjdBYsz##$=mb_YV(-A|i)vr|SFS4eko-khMv*Vd-OI#jZ9C z++}Ur7dS0;-_YIS-uj69N&8KTky~>15@V%oeDSda@0l32Mzu3-(=$|aNl0Q*Z!!+Q ze(b?JqhHQ$?duu?s3NOp!&!S3%W+uMoa=&8e%wri!_6w+Jc&~sOwr%SI^c*+UO)>@ zPHnM^f9+8dmpJEmY=d}(tq^t1Oi>;-mz5pB5MZ6*-U`^rdoH^!8aLWDX=U$Vp=I0H zYF#()Tw2Pbt;`D+y}BeT$`xsGIdLyPe}ZwNM(2uLKPBgxT7et!4>H|<`q{kO6~n3H zSWXVB%m+C_mHETn7gWH!%WFVtyedp)y;_iDB|X4{sF!_ z9{yJYt4#g*X>$KYe(9%`mp*?VJxCqg%HintvvwoehYX#)7u-i^H~D9D_1+f%&n z4SbBv3JU^Er0~-@JE2T?a_t#5k5AE5FeiOLjAEkX@>pss%mp;uB|B?wA4a68^hC6= zW>%OY+5Mq54VzSZVzfYN(!+}dkq;5dLLq<#%xiBWAV$STiKY-2NeYYrjItW$u{CC1C zH)dlu?_3{y$7Ni!#hgn@`BmR}^3eF$D@LEubTO~PXt$Q&kz|GD7JPp!we3W{xG3Ik zNS52ny-PQE7qaV59YhA*84!iNX>Xc!EJFxzC=cE@=A=T-^oN4wlfK_=>~3T6^U9kE!gKfb60FWYK5GBb?fQKBzwloDmv>q{QwM!-NtstO>Vi~G zWZ+&7B@XDdvG^CHMZQ&}kQHG1ItrqUlF6LOFB5~gmHvMAo7e$m$VsZ?U*)g+9aMFI ziRW}Ecs~GT8-_U4DR28;%R)7ihjM(|et(FVBksu>dH@NM8Nqm=HMLied+cx{!Pq+* zz(g#;Y4v8bHToW(VkQP3p;^>{MboeDPI;@5ibvJr*hMkQ&T;5R|C~<0Q)i^eyCnLp zv;_IF!2BUzNF>Rh9vCrl1ysFCwR>~O{QZ-KfSHw=Q+5E`Eus%WiSJ_xkgti^Qra|m z-hwu}@~+hxQ3!{&z!cspc!&A}Jc~Y{wF@dCGI;~RT6%?#WFISDH7qabY^-aX%87ki z;b|l2te&!(`}z(&s0Hy4z`NRtEz>OFJU%dEA;1KBr4XB8D^2I3a$@}QOoQ$P zUEVX45imRx=`T-yQ?|1U5H=R>Dr@pW6@t5J6&m7Ngp;=pAP-5}8biLj)J@axW#}^= zc~Y;Lfh=!*?Ck;M(@gEKyUtekyj>3{dS1+{CoX;2lKOSCq)ANxC-FHE&sUp|* zKQq2Ms+{lrdFl@k%-r-BqHb3_5pDm9{`a;IdGMqMghwIlmp%IInm#T|UDQtJ3FWax z&@G{Z7wmYEyqWN_%&sp{qE!nnfciAcD48XaC{-FEvd&-jYXCCLX-Et0h5A&nWmB3onn)qut0A)9@y=Y%Eg=3~_d4ORaXx zwI2-eb&+<5jUy=84}jcV<6T|%Vf1VmQw2P#xa7@`e*mSChN5`?rbmrnBOTH?+EaA+ z??G?1MWkX+6D;0q`Zm!w?^*i0^IFU3eZO$=y`sDjFgd5NuS^N?Z~+z3ObzDKr63(J zc?|5?^>S56rJlu$Ar2X-NmFk=%QMOY>WXt=a_nSnqdJw@8 zPcJaSSaXR3yJEPI=Hrk1l8nV3#p#@XaJ}#ws9ahiSs~Bo582_Iy<>32X8F- zuKj>gOS5#8(m&9JyH!H2XlVx;i{DoL>#WVt%rCEz8eORroBg>!(qw>5k@W<$TSBUG zc&n9@p%NL8(%Sd-##x^cd5!RQ-QEI}W?(8wH~Zs^jkx^VtI?yG8ZGz6f)5{Le<)G^ zH4NgfJ|YvoT)KTVtW>Hs=dH)sltc}KVJz)j2e`#&I$BKO( zHR}Kc4?mF=82t(;{eJLe{ZDU)`R28UQSmRid=aci`(8a z{8fHWUaftAHJ`bv@FUe<{KnMn{f^cmc1wN6n{zL&>4T1XC2Dv-u6`bq{?+%mgR3h{ zrT-K+cfVJW>iDvwPX|G!>C|QvE79Pt^}%R-B&9HQOaHHk4dSt3Gqqze6N0W~2~)^T zm+O1*Z|<{i9BacA3$<6g=iWE6bZ1qskPBV~@SjD!S}HHfF=aidNN|83$&2*OW|my( zc=d{(L3f;1b*PUeaf7m_JB&n2nbPVzezNu8qj?pC^Ei~-BvPRZlEe~>6o@V)xJcG! zF;@}5sQ2*l5QHZI?1fxp!KPVyv-2X41OAU!`|Ozpp*D$WKOm1LuxuE@Ri>f;aQ1>p z*d|xBGAHh-U{z=F#_Z7pAz~+ubiTapU;Qf=J9EC}e1%aIl?mp+YeH7c;jW{vWE;0Q zm>6Z|l_WPJ>JZZXPy&m%>}s<83SBaw2Ejkl!W{d`cX4lP40#`F=S*dS0L$^YUMHpyB8bx!}q)Du7{^9 z9J-`A#OdjPSDj3>K0>P(P=Uuk@=W$Ty4hhjxaJ#bXmz*lFBRmX$9VcB*f2!}t=!BJ zrHIYYrC)kF4pUzg_oD;FDA=B=Tgs!&I*+2Ub_b7=?^Oj-pluM{Ay60jsTNJzMsr9o zF}w`YXZZF&+WJQdG!k95Zz<~uAtYDRsDZ#D$1YDertHDRf?oW>QbpqY+8{|T9WBkC zwFkRbbO?f_ia$g9Rprpz*Y5fs>+qX7TV zb^lrd^OwP3&MH)}kaCHXNc^_nt1QrK`?r88{X zHSrjcMRo6OQ`ERZ>5Sxe_YKpsHSXkcl?$T?KKr{y`27#iO&z9%e*7yV$(~JxHmQVG zQ=!0rXn@<+y#4?N3%7sA75@wzbeNw#o%!jz+@nkGLx$g z0Uokf<~@Y-UWPX!ka8`|6IZ@0*4lnt4~0qaiVfp9^`Uhjtp- z>TcJXs~mFAj9^+v%8rMizj;NBA7V~2!O^$p(Hw~x1@?hlOCWM)OFU+@PxI@c9&fnd z&=Bg&jsXJHNYr>aO_F z=y>#JvM+k--nL(;?D3I3?sD7J?S(g^VGkaBf7TrN?L%&eQ|QDr#;1xKv+1X&Nf)u=KOe-k`p+?2fsE46MOE$Jk>M^G4AWU8Y+t7`~Ew34Em-0Jcee3q^mD>zMowisXH9^QpM6`l4 zo^G5uQ+e20;oXSIY-OQKBDp`4(b^^>-g%-moICl8_V>AP2Z>{^uf)Pp{DL#Sc82pW1Q`_%Iv(SNa&l8h05D0x*k;bxFjCq@-o?7`50J;RR_Q zx+85xj|C$t)=5~Ct;wnZASpaJ{_vn;X!!8UMGusRzN$ zVnhT+39SDJcCFVXE6rrgVz(wv8D#HY)}tF3nFv2gw|9N675&yxGub*p!t225?B&=4 zH}K!BT@4G!@gWbt)pEWVY8;&ZUf8wTVB%LaU|?8Td*|@z;nAjd;eOiB+PD9p{{gNY z-W>k}{K!r15XBNBwqH-!cd)V{dNzMlCwQne``g^RBZhpPmY>&CPrU5;ZvE=($_Y2i zj{GgvR2bwxxdUMAC1#Wc$9W6$1U9JtYl*c2VplMC3; z2?(4IS{#PB{*W!w{-x8@*_*Z^<;;do^(mtkBYN!fplV;_v3ZrlgRW`07CN8kiLfh` zv((__kpd;IIe{{ zlv+Ekja^xe<$)%axmrGual%-lDBE1|w!@h0ivrhnXzj~zAHOO|ft;x^P+N5GNBb5E zsLtDp8`UBI{ELhaMj7u06h$FMxjxa#A}}Iy_C9nAIQS2cn~?t{U&-_H`4r<`skhY6 zNX;AQ@8@-nI^MdC7YxMM#HzauW2_=3*|fp;I|Ma)%)i}lBW-t~1pbIy;zNkGQ*L62 zuG^Mtxzp|ov%eHFS@6|s-U@nlmAQ>`rnN!MCuYMqDbv@?Gya126<2B968o$BD!$nz zx^Cm$gzDnq^~`EHeH>*AUB)ZtZEaAyg|qFEnyA_O+vdFDg?;(lB02I~->HwjhP+d! zN}e3Y^en0N;y+qfeNxAav#)6Ae{I%uPuoQzPspw;UewqHe*QXULHzpLHJVDu;mO~! zzg}n*^%{h2IoXn9b35?yTgfc8`E{b}O0d-sYR3tcsUwb`+}`lNTm6XWovm67<_ulQ zvP0>fX*4^1)LqVatChA-Nc4^SCCq}HP_i#+$M}w6E`vVm`^Z+x$Jz7Y=}&vv$(&>C zh=;F9+~C;5e31c_XmaELb@HVao8_UV1q#^|Hs7*8j5Hj!uyuJpqdZzXuxIBUcseC> z*zB0v{EqyyBm5Fl^%&pGz1DSeTh4@kqlfps3!h#$51Y-nPDeYU>iA}M<+q$#V>7_x zMLw2l55&C4M)}|PX+B-tEvs(4aNrZHAACw&ONomM^<7^2ONcSn4=f2N%&R_65&v-^$*YMtZ?X_M@Sp_c1^}a14U8G^0B^`2= z?Nn<|BKi>378r2$j$y0I@?d#VUrzX2L`f^ERvXQ-s>T`~wJR)mzbfKXHf#Yh?CKkz z<_$k4hC9yvu=?ySBv0qmHPe!-jRF^YGGR%O)wEC&0))DYr*cJ3nvmR}NqkX8KYM*zYilRVMSnk^4bwV0H0oIG zyg~by@ef07{Vz-5#%cGOONKH9uadUl+vH=}`;`onYuyU<+FO*Hz`N|V&{b43-AS;r z;FXyc9T(8aPHLYeqn%9An%+@&y4)vzU5S}?t|m!6H1y1c$*H93h+9ck&7ik#Q(JBk zm7+1S0xtD034OzTmZN*ZcBQKaHSkIHDPUG-za3>3D!sk+ zQ<5B0JUZ+;=DGVg0zb}s5ln>4Uil9Bx;#*huW66lPA(`mo?9rHq24RB!6B?m{0W1t z9GFXjZolxFC{YAUN3y(cyIx`@`4L`ONW1A08>9c>gJavTpZl*8$-ccmzCUo~-I+<( zwI1^%$6eO?S%5I!pBZ?j>k6!Ns8&)>w}e&%h|7xJ{tdP!HSgfEUvG-W2jyG%zNg*vJ?>CHPbrVvH<-INT8RpMCH_8^*{cX`Rn0HP1%+t0Sy?}pZW^o3j}2AYSg zkJK^`4JN;#_L1#=wv78 z;L_X8<8z=l;>5nfxXE#s6_^6-wzH&OTgw6ZXxYmDls5X`_dWdk|9Q*}UmP8m{?!@t zyV({vZ7lDGx9GEZ0xz5nwvgwwWC}Jza!~Ww&wtIy=!*Wh*I(`ucZRJ9O2Oe!eJoj_~ zV<^Jlc4mV6vW#$&kXyj#&h97hS`d)aOi2OcS6WXx{0Mi1Cx3xmLENOgx$eZB*`O-` z`!a==IRTzeZm!TWHH4($#GPsGFN4fgF@r!9eru=ThZ?}e7}OGYAh#2p?TS51YvnMK z$HtctZ@Iut4eo5pRa2R(QW5hm{^vA^BA5hn{JMjJoO+JnPNX~wh*&>SoEU#*jvB% z#%`~RD}dTMKifdZke^L#iWq+U50qHKO!KXEJ7-9He;-qg?Fq7-i!XMbC@oH4*fk{2 zKf9iNfBi;a#YCZKDi$o@@~b;`Z(6J&`N>L`&p<*H^}6MoBxGxkKE!-GAmzsLrAPns zBZ9hp$zfOXHXb7792=?!U0vQ^T<%CRn3Ulmeke+<^M*HFS_Dzl{r+lv=Pywkn3Kfz zJI%{(TarsnH=g}_Ws5J2W_NgQo!Nv521Vi~d>#*k!d~b@kwfnu*OJ*#plX-L#lD4E zABycxe9gMrTFl*-IkUGfgHrYeIb>IQwZRhNmPhQb>pJ!zZ<RVm3l@wa@aFl|Y-ay+{G6i7#QhYM;1t0{cEK z8(962$-BH;AdosFPfQ<+)aN0k9*Rh@Rsh#~hj07tJz*M}Hqw92FcyaRQc*1GqN>tk z0Ua;Ie%1X5QfmkrieyfHiY=<3YT?@GUWiZd$1eLiZ;ZJ`y1?_*5iTQ8hoR+IYv9jj?t9_B7yu;wXV z!}@89n(Z)h=mAUaZng$b<1_0!g-aRra!+BozCm*qAQ2Zf^HG}NnvQEzu>y_+`t`qP z%g~>PdLW0nAYyKRiINtEl#%Z?lTI!3r_}?n`{BrI0kp=rZTZCOcu1_J{Pk zN#s$<0G4_!=lTmJ!b69B%Ps8HWTw0IGY;=!V&XIkNcI@>u#2I^Po1Vk4P$%0Wzm^I z|7EzZ6Jp<^8?lWK!7$_oRgtD?oLN-arKUY8{||t`skfT1TTIGD#L-z7XxGIi!8zKN zGDDjzkz&bgV3n(ubaO=d-6Jr96 zn)oo24htng9xO*O*rOr*0yPs_+Oo)d51zqI`?%(ey?VFU(!JcntCNbu$OHCNX>z~L znOSBEt58PWPCM%S16g02zK7}kH43m_NFq;M2hFh9sCio`<*qP8u6Pm zHE_zs)7PQ`E<$JWKO{N-Cv^j|voRn$Z@2$1*?D?(@Wsh7GIO)rS!Fk;bo68FTK`|$ zY^zvIDN3*^yl_9(Jci0dD1&!|wnN9Cl?ilNy!62&wi5C^R554{X}1kR*`5jckc?<; zgEIp#?xmsF`Yee5O=%>QR0)Kf1iXADIfY1YAz*0)$xa68Y(QQ@NvFK-D5RJo9F@9f zO7%b?;=?OK&s`nOSpnfnbl)Vb3SZoa7)&0bpj=TYaQ6_1VB+&JvCTFgm{RHa@2i#( z$E=vegL{oN^pv3Fk>R)!mWl%-ri(JysGXEELyoy0XR`sBeAD=U!m3>fAC`7W7)nZ|;wBuFIQ!cr@&?l4%nuB72x{%qX~M?UtHlR;Ikz3^ zX)#cDxY0fEMEJLUK*xYe$ql8at2w=jomJzp z33o4+iM#~gLxpcnblW5KRELF$0pdVV4aee(UC(fnf z*ln(aXWrrOVOt;Ps+kCC@r8zupX6OjJPclsaBiioQVSw7tAZ~vWZ%#qh8{oJr+qBP z%RB-mO#H2evkvtq4L3I5vwyK@X7IH*ndP7*>HG`U=8^N7J~fH#pw;|u0Uq^5gules zG>Ah0q$RLBim&8j?!uMe&mQq}a*=E|p8>ox%8DL>-XzqpzHxBoYI;}fDRjw@w6ba0 zD@Zh;khOGRrjZXSlp(|4EG1Ifyx%lHpFnB!ilwpkNlRk)6u5vJEE4pxp`zqX{dDVh zEK_Bik$>g2_1!Xqwr1AXazDKFZf&#Hvy5IINPDInoS(5Z{D`*8W3lZ1ZoZ<+v{DmV z`odbln_;r??fn+MqLP5UC&o#>8#65fSoEYD0i{~S`XmRltFErLuo}AiiP_oM-A^i} zHkp9~n`me+$kb?SY5ukKnapSDQTbB4R&e{}Np3!Q{a5@Zg4`_*sMdH*Uv45#a$I6n zYj7YlS>yY9dAA=oKD{MaohQ|qC9Q0W&4!nwrDZjQ{p4vX!X*Am-Jc`xCp>8u*(K~q zdGV#5W%X~-f-!wFuk2yT#k!eSzI6A(nmNbc?yx%20Pc+D2@$#}QLk(Ugc7g$3B|b; zZgh;>RY8@g<+sxDsXmfX{);I3EZoQ8DJ4pgypitraG*?(L-TqmN3o?=@hz2-_OuS@ zFM~Cqz|#EO2P&j!LI_dmvv-hDe;p~@yPCEvNYZs~;verlYvLc1m6bwrjRim7{1spn z+2eINLj`I6g!+jVpjAlhTdNaY2vP?KY!-g#IN(}ZbVwT>A0Bj=bs&@uj(9Ssqji7R zzAIYB0J)fBp$hFAgvQi{5igK;h{`F#?(%2%aM7lir|SWJh~EIe1Yy8tj#s@hlNKlx zs3fQ)iH#-De(t(>e^YRA{@IgSC zfTCq?lHQAI_}Nxyl?ONiQcts9JMrK>%`kISRww}GaWPOQ@yjc5A@7m!>d2itmaX?^ ze1+D1E-Zmz9$8<=%NM@>ZsB^f5S}I{O4gy!eDLI6DgI};dUVySpTRH`nCBMiS z({Zxa{ZQvwhRmcSd}|b^jyENxNpmC&o2zhE*g=>pg;i0jZK6ctl68X_k0^zWTLv&O zwm)sd4-eGeJ7sG1=gd+{4nA6FZr@}EpZJ^qESfbidhiLD1XFV;6ZoszU)z?SF|EH8 z{xF%T+cMk9okxI@O7yKqz(!bKE&xXV6;70ylXJb@SKZ4^(9OIDmM0Q`(#3iHus@e8 z8!%QgF3!S=-^cPB#YkyC7GgZo_O9-~VIkclkNV3{QKSD_cBfrwk%8{(X6BP*yJgwy z>{7H!P}X|jLjb579x^jgp+{um%Q0W9T>9WuI7z*k`nJ2R0gF0?ohOsU zvxJTbv*!$jL~;k(6uR#?&f`dMHJQa{`rRchv1TAbE&*K`{}s5736)-Im=s^3Foj55 zd}fRuQ`-5&fZ0!T?G(+uK#MahTIV@pa!`D@Oehd0fSdF$3+5I&t=X?@bckyh6a{wKuhHDjw(nZGL4!mLk1t1T;A&lS5nFXy-eU7G-MJmbdWFQRZK%K}*yk96BLN5(T zg$8kP$EzWG=_{d}039Kt{y9-JiGRc_r4khKtEvcQjz_wKSnCm5?f3&tc?q26Jb+}5 znd+~q63-5zFd)4%0CxiS%40nia*BQp%G7R6a|bGfRGuJZk^E8g8S-XgBSa}%F7$Cx zJW(97sNpgKh$qued9(CLXvcq^*D%!0tQyyeo-uP7F~OnHYRsHD-uVPTYSv8&la)Kt zqmT)O0azstmg2sfx$r^R|6cq%uvtJ4P&BVooNX>4x zq#=Dz4PIZf{)9}52`r?H*fm{Gg2~*I7|4Wq!0n)5T1izZ`<)N%IHiMqme#6lR{u!} zLYU>@=(4T8BnLj?vpIl;M=I?q46DhrSK*Z|d)||MWCrjLF#5emw($|VmSAc-9wCJS}USU<31BGnz zpC>Vf^Uea-@Jbvf<6AGM#JZZ>nj$NX9$aUGn@`g{<<17=Kj+Ekj$M2kDPzq zd%K;XAVSM_>Tk@pU|&>R&3Cg9UtePw5iT`{bX(fwD8x0d6KM;yqxJ73i+^1D>;W(2 z?&x-+r)f!xc&M!&JEZMxuD`GdQFl(Yb6HK$o5;(2@BGVwVP;JuNy=7dyx8ECsr|#l z^Y+Em2k1P3Z0p9Ih$N2fF>vbKg29VU*#o`4z>B7>h1V(MmXAZ0%jVw&8K`6LG3{xv zktOzU$FQB5C=fDF$bDnb+kcu@V^FU+Fzhv$GBZG$dzZjMbp`jflcwhA01l<~?!TX1 zD~bv_dK`H-nsWf+6YVx7duZSA#!b39G;eyHZt*!P!aAWvL50-w+p{#rjt-HI!zWAC zj-6jt^nZDivZt@=UB^T3?k_$%;C&^3KJgeAV@x=ay!=5c9#81C$XKpz19NvCf0Q&j zryv=y+ia}6p3sx2d=PGWr_V)fZs$PS=ABN<4Jt;O5v=mC`cwj-PEcQU5uu3!o?#V) z6DHidO&?= zeRe~Y(qGaHqU_+6O`o_O`?BEuh-`yX6rBvyPS?0Q!5)0amzudy2Q2~VW8N}nYY5{^ zeU!8L5xQn`gdh$S%20f|VOjB0N%*TsFn(=raCViT5bfs9o%3oU3ND&*DegNpqw}}2 z^rGvZP+)$~uRpz2$!OsHbG@`D3tfUqr;tM%1X3gN2i)Bq;_{8Bq^arL%li@Ygp{^1 z_@^19r9IHmgEQBtJ*K11DZ*sbx`&aG$2}^S%1r26H-O%KXLDXltp_24O~-D!K!&;_ zEFz!2VCnXA{HXopO{9o;T7q#8Mc=A-PM4K;UJ7gWB>hpVjkf;Ye^xzC z6rA_#^mruZ&|-VWIpcR~dM&!2tle+4(%Vs<&XPHC$79;vG>7|RuC}54zWDgVbW|w6 z99{W@QlQQxusmP)=SoI}jTTAd-psjqcjt|+y*NsJg=c$q6-i1e{@yHtBUjJU2qC9v z(RfMt%y46G@n=)!MP1-tK1o6#hZ3P#7WZH!7_KgE-Xhwg#%Y%hJ+eSV(9SYv34Iyf zGL0!R%QVmk$n2|y#hY)|0nHT8Hi5*zoRHr@D_e9qI55N({xh{NC6T9 z{+W~0t1hk`jv8bh9s(@FRR|y`SBW3RdWEIz5&EjdObovRPCIugACygp=@D`Nsw#!O zvQsDW#QPM-y;Gd7VW=D*O#xiU|IU2_8VjTzo3utuC_`v9Sew@6FBm)T6)xL)kPEt zJF~2AZSCOv6m1`YednohuhPZ8JZ`{?%5aYvTk7x*)~Bg z!Tt9jg!G-bH#z`#W0T&M2K%Ncw9IuH|1W=j^aL1zrzAuks$)lt=J%I3PZ%31(-GP1 zF|pl?G;3qN8Vr)BN;t&L^3L&paCP^YV98A2h_4O%2Qrh7fA`Rw)#QTcttU*ovR*Uq zeLQvAT@LXhRhv(5_p3e+|4CcXqPnaE2pAJj?K--18aCS(6&KO_zecJ&&Au9aRxR6F zOg3i9+Ww+5mJP=rl#uu`f~JsHS=;qfs#EaHvR#mz?L_NtrY+mx+I@{A=Hh+7F9fc5 znO4|;!0XCsNH&>%7@PGNJS8=vZn_eL7@I9w!``f@tUY`2x#fdjkSM~(?{Mil>NWo5 z4uWQIMJ~35kz`|2K^IuP7Fb+w23N$Fw6}AkAB@HQK4>u%=A>U5tO0yC(pE$4YZy;ga2=(n9VPpSPL`9*)o4&M_I{aC-C!3T1OQ;hDK zY%ng5Z+J?n&ZAX_uU%lR@Yjpy6Yg7H?@onBPw6_LiL;WvN?xaB5AbSJ%XkB^T_Q_O zvF)_aFvckB)Wm0*PhPg=`nWjf=bJvnj{E~Xm^%Jz`P2maV|mH`@fOj3tc#CA;Vqx* zpnqHdqWHdjNDXgO>IlvI2l6Q<3%*6Q;JZsrp)W3L#&Bhx)$DRLQ$_M{(%`Km*KGJi zM|O~Nb(YQ$h`+WeYm+xC0PYIL2oMC+BVNW0RR?oNOBfoyEMJ4(SXiIwv7O8%gZT-N5bW@RCboh$2c z-aC-e$<9>bp|%^!MDC|+_L;rszdbur8)?sNA`8&rlm z*+Z{?I@$21XeJL$!xrmafMBz`7A<%mYA&(oe!S5hOJPUY7%oiD4H;jQtt^^voo2(*3 zYAZ2n3sG+ph>FP{KfT|1{`L!`oyo$!ol`HsEi-Hn!eDF{phW<08314&bzH#>zMIMM z!?-S!AZDhw3W2{I`Ve@~UMz~4r~ zY`<{sk|iQ(o*u^YHU?j2rBq6mP)XR2TSo=O?O1G;G4yC`A)h-QYPp%cjh|b_TTKtw zd=}cspcHGqVgMqmR8p&YKpqBsxJkKuzSOB_HqC^K6Rvh_);1_#;Z71>EI$1Ni%#=? zGl!m@eCgGoE;)ZPN0#fx`xD{urSoYvR33}Xi&vcM7V%9KepvJ-jWCnITS*zO*(!FzKC0oNg z=ju?Yl4|DqC4a#6IZtN%Pw`T;IwC_Q%o)XK^6A8UhsMEMN`=>awEJk6uz?K4@Hsmz&X~%O*UGUe$o7%da#7;eh+J5>* za=5?AEC}Nu+)ya`AarxNsHy3)iduCOB`CKqMCUyByjsa?<+)dXw(Vop?@%=$7|%Z9 zxni|Cyn~u*mogg9OR+5T4{y}Yo*q>{eOU{TRS&RlrWeL1vV3V8_WKunwfZ%QkA45< zHVO!OmwsZ(2sp40$;+3j?lc2D@h<-Vzd26KFr0n*{OX$X;j4rHP7_Ikc64;W9p5X2 z`?5;4pdua3zL%n^TvYtEjlzkSAVCM_IHsl^sZ9 z0^nH!*C%o;r>`eZ8mLUeUxh{94Ewx{s8u_{(R>)ZFa+u=BVezk1dvjD5ZS$jXcBFq zghsm{0s}vk7)y{Lp9>-=z(DatHU8L;yP5@hGm9sGS;clf@rbv45S(%WCQ;GT=!%j( zf)K%G@d9-mBP#%c4EP`DqZa=+J^7Hb=RA3=;oA38Z6e4mq;Fmpx0JY2=e~L}?-xB> zxt3vXu8_URU&23SIiWKI71P4!JJXIlBm%_Kq6?lhV=p4ThT>FN>WDdB{A`YMJXb*! zmu0{e_H{psfS=$LHPxfZj*;WcRWzL91xLM-1y^2Fk*aM%t4Zl^&6qYyhe}K24h+qz zRm7@63M@o|sJ|9vCJfDoW?(_^hT&Hu{OIH&?5`=92Err=;+&S#QaHhei@y66{ZKl; z8n{gCE~lim6xYe^=!e-^Z)kCG@*?$nCJ6(VcavhpM%aim%IV5^ z=-^iTPGKr*Q80hw!SbEwp#cwq5<{hNtSV9C_VKH(d?E%90&iPT!*YWQ~(OeZO2>r}O^NBbyR>%z*jPTHD1uvOHWdmmMU((S4r zj(rXlT2^2&#GBo_*X~!N!L02@)Wc|#t=-o0TL1e%zIc>6-SlGNUWwuxy_VC;cFI38 zxkSxBf2)POwP)Xm-(1V0Fse5_p_pt|$>;pJ?tuRYCB25n_{j8o+X+(f0t0IgwUlR@ z?VK@U!sDVQ~A}lxty8-^g4{A zbr$-Uay~@gR4OGBR?-XaTN0nL>#Sbem$&Tgc-QI5+f1vo4M}?XzWg7Egjr)G z;ghOLP^ekdm^!?p{|FRQqRZgxLPyty6gkfj%4Eo{J@8%Sb(?*Wts;I@~)mE(i(0&$?Fy8P^PnUh; zSQ?>)op{!}XQLnov}%sTxmqyB+}kEZc2m zo5@aV0RC`5B(cDG3;+{fe zzA~6?cZ1-6xNdH^&+JR|LzvFWiAvb97QaH=XDk50Q&j)rR1`=Y1dch%Q_5Rpj#{`@ zE4Sk1bX*%VC^h|@GzwTorQUPS4!@muOcSouyb?_Sh1PCl2iv-&Ru)Z1XK{n5N_)GU>-DshOK+-sjo_;(MKN{5C*kGS))bg zp24uBc^Y|avlTgh7$zhpaCw{l&Zd+TpCz~P121rf3&{0m78yg%w-4pwQ@0#>d#HJA z=wR?ut}g%J)Ptyne~`(^Dmh$n{&|$b1rGiBD!rP4z-4?R`WF(+qn;?sb~8H^Wc&rg zg}wGAT9-u*(Nro{rogc_?>hEuf9*Xgp`;YCZH^+6H&=Htj}oD>G;<%uwZqEa7Hi}& zvkNCl#QGHN|FvxY?a;H$Nhz%-rsfE_mNNHb~0t?ac_PNCqHv1``mcvE*{7Hh{J>U ziyRqP1)EWV;3^YKC@E8&yl?60QK-w+!s{VC?w~Y>l}Kaef8@`aHP*}~J#KD1xvkYzNICjH2gpA94RD1L?3<;AUYjUn=h zW_SwX@I}==n+vw!E5?%exPF&{^3K5ba18`#HxvGIT&!atlWN$~w&k(Vr0Q~HtAAD} zAe}XHiQ?7Auz4>o<@_?UZFzL5{ty$22&eGo>E4ZkdB6T3F@Ji>Ny4DryNBKqdE z`JN87zn`<>uT2+M;oP&oh`i@RF@7Uh(J}G*e-h2P`M*dWpZ;%>$KvF-|AGvy|C`Jy z!r+<5ukEQk=L{V7GO3K9a@CwDexazfbLSkO^(cx}wG1xi2|^CC3r^tErp>jOh>PnU z7MUT8&IzdD8c{;VMmdr6B)*cmvuN2_pmwWhmQNP5fRw9267wDy5FRXKA6JJ~{pF9Q zP!cyB651k5DOqbF(H?@vk_8Nkof&9E7GXUQX4=rskv&yl^B3AFFh+@!&Y5bj6+;7# zR4FEi*YaOe2(W(#@zT41Lk<9-zC!R$wA%2VD$o!iS6TKQ3fyg`yod-;`1#Cb{apQQLpp{Be*;o!mh zXU?K5bFG9k#nFr)QF>M_FkUPfnB(avMbZ{`Iu;Zy{rrLtc*~i-V7ouj67_e{A}Q+~ zUR4`p9C(MzDBCK*5TNt#B?_#N`Qy6!NpGRn#77O}rj=mmNC38mvFGH$dX!VE1M(!( zU@qhn6*M#u%8JyraYCg8UC+3W1VWmj)jDj?4HE7*y|O!_P$!NtD-wRKA3XT{FUQCB zc$0o^P)_;3_AOWy2j|606VbP zRj5kK1N{6349=x&o>4O`-plFdXQZ}K>hA{vJ{X)sR{;_W4z+~KJYC)jx zL_j3jc=L)45B@}PXO;WRVlqUERpF(!#r$|yRj7^-!6}+3{>h{M*(q9kZ5y_iW!rU? zHmePYuF$fZ)Rq%5l3#TJ>1eZgbff6Qjaf8mu1X+vR;X;q^nS7iVo@X6^0h9-R|Ps6 zXN{Db=k-BSi@y{Dp-mu48IhnEE8M5{>2bT@X)g)gcaf)%v_Zb082di}h&GAWAXKTS zI!>d=MDR>&W#q&mZBd%ER8;vC}KqZE^g+|VGq^!R6X%a75Np|1pvh7LR5 zuXWmN(_%VYSuQ$%JUjO;a8*lmkHcmAT^2ZcoHYvfG|7k7D`lz#Bu;3^b4&5GBxR0_ zNIf0pjCyZU9Lity|4wFRKHoxA0*d)o=!ns))sSPY3R<Ac$+rJOTeu;nVjkU|by zu&V4nRmLe*@6gN{G%@!mxdPyjK z?5>Ebr5*Q^@fb5o0bNTm8y?Q0^xkKFgO}e^vr>XiqBFOP=2)fEDuLZjS~HzAb?rQ= zoef? zvG38Vn!agG39FlEGrp*DhYOo{_v^aFaU&rI?lfq$h1Q;(bcW9syrBkhcYpO`aPj^1RLb9G@z4Pjy|yr@@q>t-S=W9_J2m41)0(|2RFMidTlE*BC@1>4xS zK}($Q8`d;GhV$1ok^2it%*Q{N>gH-wZVjEU&g`YQp0}x3fn`3n5)*dJRCk8nis2D6SAb1{+Z1@I)9{moz;`VURbLG&9zC^nL`y!c;P8a3z8Ra%!MPg{ z)aruk(jQK3JZ6+JlsKiZB;Lm8o!0_A3ePrOpB8Wqz0I7mGkH0|tvtWnCbzVLYYIsu z*Jf0~bl+ID+g0KS3f}$$tplf;poJ@2l+w8Tf1||b|JhOE(eHGiHv2y)n3nbAC(>72 zk^jeO@rVJEcOP67QjKsCwT^+eKt83@7Z7}e@-i_AfU62f0J1;sP0BeKVC4vr9+n7s z0yIu4qn1*Kmg)l?dY}(g5IG5ST!RGI_mqpUe*^)m#T~gp@YV?;0E1$4E{F#(7hA!o z%~k=991>^^l3ApL(#uRsLozl5kOe^hK($rW3UvBCHovRkr0g|#@oxYQ6O;f<3*N;d zbTK?dUxtK=($0a?(K5guSSbktI-z7rKO-Q-RnP&f%W)Mx+YQ$B22W3?hi#gh3Y(pF zzPX%{uAw?q+DLD9*jKhrrYfMOEhdkh)91bEt zu?vFOp-X*x5FwZuQ)RUp+yNjk>hMId5rt0x9aZP3z2yuHWdxc1FC_iXEBg3H94#BO zX~4BPjypN}NROC}LrDHPiut0Wk169u??X`~5X^J?+<<6zTm)qDv_~x_Bn3#`>C5x}p@T2lg_0@m`N7?bGJ9mImcB!iicRIuMe(GRv-8TED)V zkUJhHMrxW?jV;fo9WaY$X6maanNRi;PklGkf_vHP{JvzjTwUKqU2@XvT+q#tz!A75 z48bg0yDXo;%aOkGBnN>_4;)^WFu&+oU_-o_Dh0@JdX1 zLw%y_!>d-SAtu{T7AZt>C#Vl8r&Th8DwIL|YVy#JPs==`qK8Vq;Od~C$|dl&al>9n$(TW#1rxA5*i)MR;qE=O z?<<^}v+@h7!YHP{t?9?z#+euK2#fyyqMfD}ob_WHRE$cgxZHS+Z38L;0*67L@?|J2 zWC7(lwyhV}aY;WIJSBQ!o%})V5&Vcd#;PNpsVGj<;W<&PUnP=89WD|tonrr6)O+UwmLjp5WP%iT{56KlWu z7t1mdofrivpZnpz7yZrIxJOq%=6te#(wbCvnMoPzFn-Sd{PWE_>{b?FTrOsd8Osp= zT!dKvU|Hdy^nK2;wFvo5W{kNWHkGKTRrPrJCE{;Hh{&1fnu^`R^hch93>)!Izt+R= ztoWs3+7i*b5`)6hd~JoV)>7a}?{t_{%pFSqf$oav&h37Adlg9?Q}4@P-ZA^)E>7KL zX7{l|lLRk`zwz8m@MPlr&vdXo!Gs{&{GlJD`}ohs>l2CC4f{X}vrXnfeaJlc7fUa- z20481H${VTe$C6&l|LmKy-M|np_jEMrJ@^r#2NiWu|W%QGe>>7Ir67(C4>|fj1wMd z{mf*3m}hGD;TNve;B@CL=06>mY9S+S6JDXklPz0@b&nIK4oU+5x)D*`Me^ z9ta(-p?>z7??I4P^B?7LIc+Q}XJ|<7hYY+lud*kY`@^*t0xq?~$mex9B@D`cPJTW1 zR^sUPLM5N2fn-7;M|wM6NR5E$?Om7G>?NZ~ja3nu*!k&c`n6iujJ}p4Z(W(J>oGdYR<@A}yvvT&t>EqhNh3b-;qMA2={^2HlKc8GCt4qWiobzq%e5HAm# zRd=a$=p6L;Rs&kMY*pYS-0%55%C?Z0=PD91#g9x`_h6ed?N8uiBP(_hh}w!UbBu{_ zJSN^W)8LiC1AK!~(M2*+eBzkQZX&T`_@fG6=)E#_mn6oXeRgXj5sGH<3oNQSO_l39@_eYAS392 z)Z{5I>O{&QY}1i!vA1o~g!@y$Gc{mRd1JqBSv{n~U^L%>-_Wi$AweFobS4V3G%IAY zJk${Gm$Jlj>P3!f=1p%8KEp6sFlb{HY3$fu3vp*YY5W;)%#bVrT9rkAEx#=(d~0Rx zZ20(&mAFf$^+TLH1GP0DzK9ie<;UuBg+h#={XjiO=z=LPpSAu=>QhR>AifuehYl#B zAOn-|J;)zf6j5deQ={6mAPF&y;zDG{ZQc?LIH$Z)TyTFEwDrH5-v66Lf-fZi+XznP ze-v0+8e4j*^1pedj8ElX@cjd2-Yov@)csxmy$kSovcS%(hNBnRg$8B-9y(tdlNDj_ zNcH)F-YQgfP>dzKEW&I?l~jlRc`uR+VDCe;fX**4{G~qAxP1PG}ImZP;U--V?@9q)=xxv0i16Z;Cuve(cO zJ4lv0q%g#i6% zLpRC@s;%USr?ager7+WXS@{~qHqCXY^~jD$0YSt?-}49RuVA{6K|(|cjo3+T*%&0i zo3ittLUZl5DljAQXQPgm5kx|mMm91HyqM)86+56PjYW%cgr^87qU(V!ZNfn+ET%v- z^adzKHcf+iI&!0)ew4(fM3{{8ByIU^+`+Oa&SGY-Z;C?u%N6Giq^k0r$nVweJdxeH zcx!04zOT#^>T#E)-F&&*j}lX^Zn^x6x#6W`Q6y0c%$zCPn2Rw_YrN%GXqn|X$td;r?B3(bpIts>k8?j2V0d^h?qj@L+fy-) zVs9a_ga?vVe#k=P(ou$RgKQ1nq5Lj)fFYwuYuehy-IQC4JnH&yn)$@fwBil*T_CTm zD5mt*vZj7?={?~%pQ5qd`&DjOJ94pFv~c)YM&-u%A6fO3@9O?&N zGP1@q1=qG1dhPZjK0ME$+fE=%sHs_^Rkn+_X)iaEtqzj=yj$^GeFptOW8>fz15}v# zKGCsQ@q%}5U|DlP zug?uLs&L-$bmMQ)NB-kqXyoX+UY+7Q*sjVSuN@xwPq9+*mM(r0GI$u` z^efErqeNdzpm5CQaFig^?CKS60VQ3{o`!nX?B~Eh?(SO}^!3Fn7s~GSJ;d75gPB8rRd#vA*{gUvpZLZAsgg2M zf#^w*W#@Rw4IvgC6PDE`*9-BN#!XF~u=hk&pEMo|1$2|F?4jdcbt6=Di~U^etZIdXc%1Y-6O3#ce%6`+Nhj97|Fw;^2MV&ebnhS zpF!y)>Rs|1Fj(l-#-nM`;Ky655%_d8N`b_jlO5u0ZPsSCE9Clj8602Mw_W)Vj$O67 zMfsV1`@j{DCc=ry==a-6QHW9Z7WxQ ze^YaqS2>s74e2uwpk~UKwtTPuncU5M#$PKjWFtzav(3q0m@j-&MT}A@4m5(W&NH}n zv#|7Dik}!?vCQ*XT2Hr&zkdFB6X7h;Ors*SQ}UJ|$W-eY{TAZ=R+X$1;*QD$EoBQv zqESJYqh&rt`^%(Pp#FdV)>!EzIbicOTZbm)BpqattzZc0q?fj?026=Guozr`_ii5j zqVNnkON+iZYIG8^r)LYWF|9o2nvZi0-i}A?ErACmG zT8AF(ZFC_tZ!{-0=81m^`q2`Al*(W4n5At4IV>WC3iB8{|^ilWc&mVfycSs@7LS)dcCj=?u9ugGZT~Dvd{O8VyZ>aMiwpl$$ps5V}cZMKsj|K6kXO zO8PPp0(!=1pa~uUAl9?gPCIiLZPh;rz}E_yHbBsnYU$yIZr>ui&c3UGQ@X$%1E>oB zVqe|U%CFMO0B=!C<}#?%k@x(l2%!x0?h2;PQ~-QicE_oub`W4b>BNzwM!n0X)fiE% z99H{E0^Qf6kkZI9FyVHNzFr+}mR89=0q_`2Wk45|pdf%U5jYG69m&k4hB;?lD+Umu z5Kx60L6t;L8nvGH2Enktofo%~?wn0B>qRbVCPmxV78E0^p_WM4A|S|3%~0qsLa zWy)}Z6_njs(Jr=25QtfCeXWhk<)j!K_t9HaXNE&vKT(~CT3E#{8Ct7sJI?ctu%-)% z4&39;df0~92(cC}hG_+^Mwm~1E_d^e+RF8R_#<9YJ2jq(jBcOsMBksM0VYhOo@BtS zw?P;0MSMD}ZkM2#{y4EKKzK+D*S%9zx{TOOU;(R3A+tt;C88QGGoFHbI0Somu4xk2 zzS;lK1S)mmf_?*)76P_|li?=ccMJ_nviaGs4Y~d-G;7N_$fB&0T>UD2q{VeC^JMQ4KYmVt1;62K&IDSsf8@5hhWBJgC^ZV|6>!VC zsCl-2i%Jsm9D3QQLRM?^M@K@T%VQO#B2`v@m&gh zZu)WmLZR6xk49}C`h8o8B3l)X`N8Np09g3CifLsQUgfN*^HW@JvP+tY9WMPUDQpaw zheGlh{H^DHt;io5W&WZ%pin85!$Ak7FCU_qXRM3zo(KL>ZCbdXF=&Dw>D6UYFXgBq zNvR>W#@NT*$~<->Z-nRCCYtSypY!?iYRH$ZnIs88U*3hsmn=G}@?{13Mt|q==-YH9 zwiLb_C_7MgA5y2a8;A1<8Y0*uwvxr<4fcosvYx0d!I8OMH;l>Gpnp8yC(%g{pmkC> zg0juQRa1P{h!x2T@IBt2$U`~Ye$s<($t<@9#3MSdfWnrVz3yxgu{Vx4j3vf|Y+_#Z zt7b4yKZa+S%^V3xo766kCjNZTS-0c3YlX7^;iWKiH&Wp3>#2rFk2xw+U9HnkNnbn` z8`GL(@hKmX!hM1EW@`lGk9UjdZ(692+hQAi=!49zTsu26)Y}8X+<+!C+FXdg&^`T; zfIxV4GMC1;2;7ewB}i?)*DQB7Caoh&HXbpAyt_I5N#8K^L5K@G_j=3K!xOUmCyen` z(|9jo^x7v-s4EHa^$&yYEQ1-xl4c>r^3~Fn9-h>MN!G1IL?4DDVU`)Z|kI#FJ*}bF3th2!c+molyp5neekwOW17FrIU ztGocoz;0A}-3g7rh4OEpTf@Xho@j8V=FmSEd!|5PERBG*E#_`giZk-8>>awA1tWnI0Y%qC(h{Y+= zdh-`my-jY%51;%-CRO(iIa~9eT=#SQS=jZDUJ%SMI=^6a@98Wg;y%Ol+cwJ74S?*jUbh01Ycc-y0G6=TjGaO2Z zls#qf{GRr=pmJFEj|@c(8!oVmYA)`8-rwx!+~=rI^A5G&W9o)py*RJk968<){fiP= zBtP;xSxH?uw8}GYPQQAU&e#xJt-tCUUo83$D6qd$w9E{Jee~SLB`~KkbWM}QYpHdy z`zdSvh{!jtr!|ev9Iw|Sy>mt&0fYGxp{}kmrnS%6uTHNYA)W5XD#<@`&ig>gr(u7{ znVSo}T1~^->W=p9T4j-e{E%Kt>}37tY6!utcGeg{_NJAj2K{c?s?yo=h79CRh}mG&|&knIHHPHsv8p#0&N6}=3A}? z%JbU~6suVMwxTWmJDWq-NJx;cMOuP)M4ky8Rh4z}bv|*aMuqjLpe(#81vj_b?ql~j zINg_RSXT@Dw9F)`^FK_^fJJkC=YQb(ZP~yejBzNAKx$QwhK$k@_=GaV3T1gPYU&>(G=&IdbT-~2*bEN)8 z#g^sGS4!HpCRrOtFe?=5G09SDxKL|>E2x$=Omac;*X^RiSLaH%C?0D@I>8oe^Rc)a*s|`&jz~}<~hh8MhSO1=J{#R{ze>t)C?_TJ?EhaiZy>oWa z*YW~^7=1&1Vm=MV3#g{7`WL=UYBq-!V+z6zfy<+{e9;z$K>a^EGmHR+B;-e*S8Zo! z>3NXgX6|2oMrw)+{phw}y4uE|reGq`OlU-<>NJd$6M>`kg)Fc5nGGsDH0WL5K%eZ$2p-WgC4*gtil0_$(Mm`*d{ zKT;`mT0zEx2ucPZqb_QSm5YG(vzS$4Z%TSH$)Z+EaYq|uN>YpnBRUc{cy{UR-Le7Z z3!OuDuQq?R3nZFS4SY4tpo{b=rE)F?$ChAdZ*otk!8Hu^9Kk3~4dX*S3LKBzZ{ed`Xft^a_9=kg&U0CjqX@Fj5U9YMRAJLv4xO0?OWw7+>z)81w6el$dA<^NCP}y3+CT4BtG?jN zkC1rL-12(P@I@F;)C}e;A1Bxiu?C`B9DSA+yf7djki;zk)oG0$yls(il_CwzS#%r+a72%!(pORnu^ zBBm!oIbmS?dKY0Er9Wjo+OJ+2`o0#U7{NdNY5r|DkEGEKr9aGw?4O_I=B=Pz`l8S6 z6uXn$DAtiqIXwM!*~V)9cc7PkwKj=~5YIl#yLI+Q*K0OciIepe_gv1>yGTp9GNE6G z?73rAtoCa-szPu6u@0%ZDvJ&(d0&)qw`cN!Ywqsr{XAKN$TQxmdi{9(13_LRFWMcU zZQdNswU9ooV}l`E{Pk!p7tB(d%8XmhqV7}f$j6go2W=-&_vj3?!ni&!xvQ8bBeA!4*v?>Z`8+Q}`;hbS;6JK$fMWR&!m;S*j4kTrs+f{Gb|DyjWR9YS!k-9ClsYx`PVo%jwANY3D@g?QTEkdHH2L`M3Gb+a3L%)=6u* z4W5o@sABcTTzYaq)veNHP6XfI?ojen1kRL>Qdi4xyYm<}3_#rdUpo!29b38+A@x}W z4TAnh^bdK|5K1CN^OprLM4z40$m$f5yZ!@WLF4)2R%4xR;m=zDEnad~hd#hAiVun4 z3N!Py|L~TG>uI?=>?X))2ji0nFE3%Vgasq1NVn9Nh4nFOen z_nbNk_^p(9%x_&M`!iTSKYXr~53f~PU{E`F|Mv!0rKB4D!*ZRw}U}s45zhn$cz#lQL4Bj&-#$~~Bp5#Lwy&iJ=Dsxux z;>+^fpBZE$6LkMj#+ zP-Gol&)j-|ciPmh28xfuDmO`=Ei7)9igsv$oLS}*V! z9qU_v*|eRj5})E{S&aOWA6}~BjA!~-I|&&{J+EY1mEE)?@}ITBCg9GT{3)FbHuF|B zvz8>gEA`P`<8lU-ufi;4Gis4P1KCh!1h=J4Hu>@$35=G+m~Gx5%`fZeIo@*o_f&cr zrk$;Q+l7=2GJv!@L+`%wrdXlczMd=R`#0vI1Y2tCb$Itvxk$DgUVZ#Sh39W+ zQ%fIo1OJ$q=szco9p9Whb7m5R3Bjhz<6*2QbMuReZ%uF&?k6$7<{W^kd&wxiU3l8u ze@%6u+s$D3ZQuLquA=|PhWZ=N9g}BoPu1c7BW>J3PDvX5nu-Ac2_x;Y+CrG80E5zk zLDL1WV~aHB~Q9glrIV@et5wKNO;Ph~hr(6|_gaEtqwdGK}& zP-u~*3rVb$<|;u6Cm_X$?f?k>vCWrC2K+%~BRO3aCQNC3X+A<^}S&DlI zy>nduA(UD-d}<|aOCPPp0Ju=;MUmv}l*xPs#$je-`%oGTJ;$zwY9K2e6^}=S+SmPY z4-%BGfh<_=PzQMDmip$LEJnuzv^xwY;ce>z4kU4h+9Gm>#29on#%F)7;8RUCP~bs& zf^k4l+y*ILH{L&l0mSCs?(OuEXhu{p4@^fIF;M)>oc)UU4WU%Ye&xa58w#Y5GV?G{ zDah9O5hD9rP|Ctus8Xpr&55YZjUZAcKf=6?+S+X?v)L!PhC8PLUq`)gEP#rq>+|0*80pEmbCKV^foeRHd#E zPSw#4ok$4qd@)8uSRQa^qA=&FNobkVWD7Pls;ca}-c@BpgCJbCE)uJ+KfoyrWH%CESN zYiSO{jXM3SS-zTed3}xJa-O!~iPh$vsdRCCH^hcZk^LA=43=HHp-s@Y20xI0`yJCS z7pgZxGXG6tvQV=FJ+9<#)!imk;KHT(iRxay^>zM0(Js6Ry(g+MyD{au{qEr)T4$YV z=Dfyhxy|T@^1Zxzqb9yzU@8ve)`gn0k~el?sDt~Y*t7l96G*_f&AeZB$NKqq7r6XI zJ3K!Y(Qx&HP*!DnMUBNy1wN5+Y#do+v>?`Ty&pJBcSY_J4eK@m9-Da5*9s~#iv4xU zDMgqb1q@SW2*I#oCFSm-2hQ9mE*fB%r&O>26Y2THZ8*5u&9jC9>eUxqi!WqEr^3)X zZb9F1Db1^M7QuHIErRBY>7T-7!04SrE^&#Vsc)q=l5J`zDb2x*6HJ4S_}|GfOv8s* z1P^s|a)ihCY9?6(&VT5J*i(pGE?TR(fOVxh##of61`@3?7i)s&JzvXO%rE34O_O$Y z$HZQYVzJ@n4a3p{ujI*_^(7m8Gm6F6{bw<{hTnb|D|FX%OJt|^J{$)cqo|_Ky^M(( zejjU}plTgp!8=Xzb*k@Muk-viXHYROF`mKBR$$iB3}lW8Qfl!4R|_H?r=MovOArYI zWIuMC>U1+$3D{4XIEam)d|9y@i}?ve-+hxqf?F&;*APM-w5 zs}Nc#*6qCo(oOZ)E=EX$LCe@c+(dJ=4_N8E)P-SS4x(yDuvOA;%YptSa~Nm!c8&E-%xRv4 zXfynPAuJ9JxE1a&hh^8vr575^4BGyd=ukmJUU>F|t?k%#M|id@&sSaSc-;G08?bI( z;~y#Ou{eB7_{N0EyUszsQs?fsHwDhJis}8fNUu7T8bnz=ipKEU_OiwFsyenTDFn*| zLG})M2hAF6p!_(2`N18Y$EN^Mc(&aklzW!6<|<c@JtOo_a)0b&pj z=1`JnKDHEbbqGxnqe)jo-1OsL_BUTnyiTeFZ~Va=%gP%e=G>+H20&bkAlv-pI!I5f zZ9|28x64vkp5J*rM1Aj(z4frIPU)$y{jZ0R)|zFR;@EEa?OVUhIUaU3cxgxaq8HQY z<{T>GLDS3_ES9ry*KA{RnL_D7nyNE~$(;)Gilz?Bhiav%5)9ro{qVPDrm8He8#yVb zEcv_>A2J&o_kdb+nR_lt~|$!-|Za=pF{Hq_K;zH{q9Dw0r`p-3<><2)n%VE?zV^D!Gy zPv`y4MUF7#d1IZF`Qw%seX3aVxU3O_iV#u}M5+_p zHyctc{_9<9(>IxEc)^UBwohR^s~MEyKlI|6c=za%&+C5@o5zoouSEWj(vLlZ3)*&7 zK$fR49@*qm`em9$wL=8JK{JB_``Uc) zr^4$o)W%|bIbebaBixayniadA_X;m+oK0sk47diUd1{1uNl9hUS_Ga>z^6#2pJs24 z{ZW;%jHU!vnqf5N^6qV?lTaxV#8}`^%^ z2C8JmPRH}J`Wsh8Lb?Dr+0}^w1BIwVTPJT@f><>jtz$Kj{b;5_vFf7o^Ykus#GSV) zuTcp{f2adhJ=3FM4(7d=C_ff*HhA*2+o|(y z7TGkJ1dY1jZv4#Y1Xr|X2Nk5NK}9APopEI}-F=f99IgMycjr#nBJM`tRBo?rHuVS6Psb*IPqP1#VcODN>1x z79uhQLgI`Y#vAB|F!k$5nT6eho`h57;3oBGwxpKdMBXqBI9{5C_aZb-Z zt(twRFyV9BT5NfSMj|HdGL41>b(_n#B=V2RTSVq^3ML$pyK|~|@WHxy<7Z%%60xoPfBy4(Ai#Khpf`AvN_kQ@_X%W7W__2{{3n$6Mk9( z2D-BaqMgnZbY8K0p&ukc#ZJY)orKlwX(4FZcE}NPO}fSOMFbDK&hGj7nc(4B2hSKG zXMh7r?hZ(it%7w9S&%Dx`1i>3P2R2cTLr-mCI!EXmelry$B@N`qwZz9hgcO6WoCN#iuNHeXz*Q|O&>%Dt2OXtVE z+osJ&rDxtLR>6f-ouk3?r3^FZ<^e;)=#U|Dmr4--@8$E#9aXbeRVZ_Su|-p^O(ir} z`gg`qK+>;PxS0CTLX=9WG05;o`z*#L{toErgT1c^>mv{?}txnRGTwrLFt896S8Zl8WD=6 z9!BQ8;IM5VV)@aPxXRFW0C2|>&eD+HO4S=^BTf%;p%^TYd%7pEYGW=tA=PCVdi(Y5 z^=fX>g;0i>D^T2E(I+-{ZU>wz~)NSJeTdf3RZ zVqN4VU0uj6eQ9%S)WpY_qj|(VxG>&*#&RZB1HM|M!MhozZ$HZmk)c!G>{dm8h`Ipw zn5NOuau0|n^7ip>%q+ETv)siH3ViRvJOYQ@97e4jC`h#i9(SN8JGitTYYFV>&?6RG z6h$iqUq~|S;lsOLh_ZR5+LhKwMa>4V>Cr{&M2HX4|K7Sxgg02+HrI((&Qw9?b@G6@ zD)G``UKl5sfr+?04)iTgD3ktY;{Xa*X&wI^2e^;28UF_aWDCRpHxR%d zRDZuEjOYTi7x(Y#_**`wL&JK%5?Db+Ulnl^Y968hkPpBCyk)&kpr}o<-@!vLG-Eix z2dnFFUZg@~5hF2~DNz{3ca(;or}0FFD6yc3*AKFPn_ z1RxBkxDTZ|t57@B@lnL#1Q<}?al&rd#p~&3P%2`!3+oitd^0thE=aM0H`{R|Lj!== z?uh{`<_HfEIm)abx2$58>JMe$s}$?6iknaahwO>5zfAz^8fO=LuMqx@BTIaQj8vmy zW8XKX;t?Ym$THrCu{%T=*aKI}0HAnL?$RQ0E+%b)wIYUCcmdgiD*7nyYxr`?wXEsD zL?b;*PTXp|yeeMCyd~bzW9NZRKuGfc20xcS$<)SCDIWORzfG$2@*la|9nJu2Q_-24 zRz)8XSJdf$y6OA>UdLvgH)^dBo^>bmM%0ZLn5??&V@xzNb|l`lqWdW-T zi(S@-8@TiWwY97dG#;e2gdot}2XFD5@YPw`CvVOJ}-@1p&HJG40vaJc^ zL`yqG_%NSA7th=LA(>pYTKXGT3ZY)^b(h`GJjJ8hA4c~4iEmu^@Iu35FP^AvF@CRo z=X!;f&)utuVhWEvcw^g>^^Ts1^yW*QDPnFVE6berL-ay&z*G2m5h%TO-^R5!Q{t(l zzzE(=K-O?X_-M;M={UG++1dQwf36ay9{W)Ti?P@J-K=YnR6N}7 z_A(@W(`B($SO-5ki zLl6aWLAPCkW9F%U)w4SvGNS9z&53NZ=c^W}w<4sFCQUwR3ZK1y}y!gq~K?y^+)%UNICH{9@&4xD|VkBFj^O+tq7yV9;QwJ(!rEGhtG-vsgdBGE(!PaxmPRJI$bVvA~8U zi!zVf>=-&Y!s-}f_|u$4mvvCoKqEC|8>mk8g;Jves$xv4&Vi*5r&gA+8j8q_CRd>9 zl}}{nwixTL3fzU#j4KoUs6-(f6G$UdGT&iOB zUQ#&$agL#L^wm!rF3Hq|8=E+Qqw{&OL>JK*_`DuXrE$!a=jPmH?}xsNrJtp$U9XXzg6YuR|+U!wNd+G>+{z&2WCtdKWL6_Km zWV5MQXIgeA_`HfDWIa2XCO?w(gmo|E@=X<9MVyYJ#`(n6#ubV@iR4mJ?ioD zbB(?$gPAbBMdhDT}cIbtuy2HRU4le zJ7q2HuyjNNROqaFM1~$aqyE?^s|ORcP{OUgYnk*oO-?ijye~=^yAm&6$aeYoN6b3E znS@@3vnRhv2#pv9*9?}@Nh8?LG<3W^UH7%<3*o4d(s^`J-S?USkxn21_OC;mycY=I z!ft&SQ5(x|9!z%zw?2T5APL6QY!y$F1BUd*#>Q5OCTYS)9M#f0ke91{{+7`rD`lOv z7M{%MjPloOmP4vX*hiIyM1&$mM3#Lm(m#{neXaBw-(;0L<50X8_k1{ufvG&vG z`FP-f=ixe94x@Ffp8?=)ADhNC=v8l(oM86qe8pe{X!^J*;Sxyf`~J z_hK07^^=Md)*@wEG4^Lfe*uHk6?8Hy3iA}vyz)WAliyQ=12*zbWsZCItAr&AW ze;qLr9k~h8WVG=@#jYL|$b=Ye98t5ULi9~GCEd;w0*JlYWFrP3`&cEMDHRel!B5&ffK&xf>tcnN_wn zNITjJg^A}ij%4f)30J!$@5A+G?gx=hapeI&QoRQFF5E(_Z;ea{+==2`Z{K~}aplDJ zlJtGr#EwH5o##^oOInVQDLq)0*j2C|ao=|LX(pLE+xvyAKiRh&gIPsduiWeZyu5VM zy|n6fYj=9Ms0nPnR7V@^q_WSJe&^;Mj(J}cNp_jj)VA}x^k$em9Illa-Nv}KS!Rsy z<=*8&%~+sjzyeg5mK%DX`G;;z4h+Qu;+&2mVf_Ar( ze2h?dJ@ynikrXHptO`EO)`&^NKVGIky+M_ROkz6n^CQ`Zrg%BC3lJUWHG(-t*6gqN zYw3yA#WtNjJ84Xe%DH`4uGd?X(gc&pXtnU zw_p7ZisYf6p%X=>@c0DyYu$3B<*^gCa?^&nmM%C}E?t5Xwxl-{d~@#OBu%bb&rd5S z`^s}UjXPu45%*1kNM*PZ`*4_kfOGAM8S5KB^w7+aQ}^4T=Xb@_By73a6Wo=Hmi9$8I5gMs@oT>>6Q868-dot!5W3_};J;Y?q+gCC zz0hv&r+)>IBIk%2_1(-)H8qdm&MgPL>|LkAH-5jdnB+X5UHxrS@FLDps8f`E2z5Jo z{mcX%s6;2mtgxYvJ<-4&8d0b+v@LH`L)zlhz|q0uU#PZq^ZtV3BXD>^k5)?UuLP`h|BW)XNP0EI*O$LCrr&>KN}4nX2|2; z?{88G7T@$bcE|~jIS^()bZ`mew;M4*?bLWNy9#|+jzHROk~`8xAmT__MyN1JM!`N3 zsqUJ$GZp)H7OS*JfudZ>pdGYd-UHBBjh5R>SKT<{rPJ*~+T0f+m7w_g`?5KGmwH2P z;g{@Btnqz{>IUy4K~(~)H~0L{YqR6oCD08GHW?Q6-hA>}V%h%5ccAC>b05bGtoUim zUkaXdTFu|O^m*o-J~q$0Ub8|s>~CH4g4?a$nC1l~p2g|epS7U}>78UAH4kHf3x@>r z8Q*w~QOa45q_|!ZWv<8QSB@u+d|0$vN-|yuac^9b~ z>iG}I9{1PkT;14nC+c4a!2clV8Bo?QoNW^!u0-=`VJ#gGRSQHkr_I~!1|}eq`WfK%`~c|mfw)amkhVxf%{UDFZ?AajOeAYQ z1eC}@5Kw}Y44SxTY)6w}CsAeqEb4E?XFTWH2?u(+U-P)|W~`k+uuAr4_U`Dw_{;}I zI1W`Y!efyD3%#<+1^veTQl{{BC6Vq3^Ix}>bzZ*MmguVqCwnYC-6$n9Mn&0jhv&@~ zpHrT3hnG(d;>B7S;jf|~%S=l9w()1@jZJ1;hZ8`V#(I~pi`w8b9m1S+t5nKXJq@YSodF?cIc=J#aux-VGKKVbwA(F3MNE|&*@3& z4ICN?G-^GZb?es2G$$vf6|&hFhxI&jcTa!UOR3oKdm(&mOlhMXmRPHnIU+Xr5n6Lp zrpM)ayYo7h*w^(+(uR!{+QZBu$ER&STN85))ReqhVvtEa(7c=JX+81oS8nOr9GjK; zilY21qJ+*Z&lBeNHEN;1Y=K?^i(3iAY9Z<0uCQ5ib=}{W(C^_Pk>68@Vi2+ur84b| zlxwRQ3MKqa?T#4G(SKKbp0Mr^5$QrJR5Tc|I52Z(r`Sb!sC6+{S4+^PUB4#gP9OG< zcsY~+;c%nqG_yH=5MF*=cox`IBRUQ~+}e=UR8r)q@BZ6fDgLJfHtnRi`d)+1GhjYd zhyp#zqIO|*+Os_@pKSft>S?TY-? ze#OX(mH}GON{oUi9Pi6Z^tXO87T8zi0H#bAag*IV(bG22h9u9toLs4(%&{TO;|{3g zaA+I8KcE^^W9!J-Jb!3~b84H`3}c$tD_OexK|CS(JqcAO!Rre8E%QP4%oCSu*TkGz zttm^c!y4f_y+-v{`zyz7olnoLS_?>2?w;B8^Lm9M!v|g5x#>#aJ-GKv7&b)$BBVku ziV?}89oIfV#%-fScgWV4qntX6Po?3+q_jML;{@xTpBkRq@8e$2w5#gn?*h!d)(Rf> z(SvtTmh*+Fj}*u^fh8ju!tL*F<@*C;efjr)w(tExelMw6LAd_Owbq+hF%5x`EQGu@ zO@-Knm}sQ}E>)q|A?DMO`u%?c0r-(ra1?i5*t4*%K0*XZ1rmdp^n&%yXasH0t@3?< zuq@P%Xz3YK84)EUlQF0g|^RP!qC9>SCWTZaFT6w;`82V<%ah+JTLFgqZSac~a=_S7Cp5aii~41bLH zJ7BJcmxG#AXV?A#J&z08Zm#hnlZjzouZq!Gu{2j^E?%#+{h&iVvSV+q%!G^IU%^Ia zG6Gkbaoe56YAccuRn!cfXs@TGMk@Py~RuZiuAH|ccU-+S{9;A{~-B7A6WLdqarE<{^ zrU@O}HRz)Y`ens5(wfW8I=L-3%G#jep!mzeN+;5dK%Tqd_kozm^EK^gH30WyT1(vF z&wE3Yg3xM*s5*j{+k%65h9uDv#2Ndv8yO%x_ygsU zgL68q_b$Ju&i1kexr>&iB-1iSKH0&mHlkt->R(lcNk9J}A|mquwJ`b$0Qf{1%=I6m zN9W#dB?3t+v!uV*+0>KX1NYvK%9{U4h55^x?p0due=E#doR>TQ_3^)b##+4X<@33> zI7+7$F~aoH(nH)OH0nTw zJixO(2cRcAXd^zjksBH$D~2Q71_=;EmG%uHvlF73h`epyLUmJEAn8T+)#EC(;=H04 zBmj^Gj<7*hS;I1V znVbSxfh0S4kRrFaIjKMJJ$E8d=0F!dfnRBdmCi?vz#1paJB)@(%}fHuE6O+{D*s)> zj3qq8y`7uLevDV-^o~Gie8hWD?1Oi8wWw-GEq{<9qVD9a+ zIic>!;TnGneO;dT1c!eFpO$`4VekH1b*FJrG3_X(j}=ifh77}uKPS`e9X7!~+0}lX z>kph??kjaT?vWQ_`QS6tpFXs?@#f_C3*=rtzreGpc(oMk;prAEJ_;1Q-*hYZ({NuF zdQ;%7LFc4!P-S;ZgRRZSHz}H@_H>azzOi%C6dv+;t3c7II5KDWAzRmLw`526O4Lm> z?P3U=I%>9~@9uhM1gC)fI|-@x47M|nhXlKaES_I8Z*gh-9_~IA8u*U6?=tr2uK#S( zu9aivHFnkAWgQi_m&dPBUadT_36U{hd)UTzZ>-Ejl>Z9U=Dy&lQXiyenPhEO_el4R zrEcPSGb?qWPxnf$_4>T8Nn5ZjJ6T$|Wv}K=H8P5&G3Cut7&)!R7^B0}I?v2KmR3V* za})fn*DoR7J*^M2;(A;6ZP-hD*sA;39VA=~<39e`Ox$Xarc|r9mRRE{eXeqW7i&ExZM`NB|OZJQmNhsX>bNj_LGB& zQ|JxQqm6iHCEKLw!lpj8tI+T3h2UgG)mqTCU=X)etx{d)sa3=tQKaIf!fTpR{Tk2u zpw*;xuhl;i3lCr23$u}54U<8XQ;{9V5CR^kNt9EiIl!^isjtO~`KN_5S@}FPa+*rq zV(k!{u~rh|+)SQ(7tYE6G&e8Y=$o^Vaf@rAp{Z?;h}uLlBR0IY>*qIAlvZt@ZN% ztgBcl9j$EN&nQ&U6YwmXz1W&0Q%;zT?_qQqihTH`<*gz3s1c4lAkYB306*2z~e2kU>ipU94 z&k+f&fcQiEHbi^nW4MV~`T!Iu-8Ty+h&53)_uYp!DC`?z8QMxx6a%VAd9l0*+~0tW zoNei(JgrL>(bjk2ergM~9`ZxTUq) zwyWE$o$URTnGRfPt64#=#qD%;<@OT(#u+$qk_Pl`yE}ezORPAGC+2W&hU^BDf;qeZ zjR1wG)Ye%VTg^QG*@OAPon9GQ68hruqD&JZwEwBJxHPpY(eb$@9dN_1({c@{qunzm z8FJ`Qbfh6@Xb+Ezw^eF3Psk%pX=mNZ*oVw1{eEO+ck=`2v@D@i1g5;Rdt9-qW|X~7 z&b7;XgS0S*ir?}%)(`AMvtA(9LM34$smoq9EZqy9n2sTki93)^F=MU5D8OIjk*n7^ zYHm0GdjLqDc6;Spl1Ot!y#9#W5<)s1LThc} zhO}rtI#>RyaYU?gwOVZ`$~&LoE#W~k9QEYy6kmi{(=Qi4{vZzzHS%?lFAjB{{gN2l z^=uPz8Um@4(bI*z4r1G_bjfKxexN)TkEbYH=~R975wV*2O2kS%X$%#sjjy#fPvtD~j=E_ksZw%M_~i$yTPRZO2VVW$y#RogWl)K$eQM2rEs z03;!g`%KToQH%)y=bE#?NNMGgPxLWLBGC*odMM{uUp-@G3lc_FB0_Jy5E^}sBk+KM z&~kkAq0#5Fj8D5J>lKR%*Nv!X!EAcm+{E+kXb?8BJ44A-s_ersBx$#JX?0C%XkCuP3CO?_b%fYqwpvj5)22hXV8dr~hord-CZ z_NyQD4*8Q>W(~`#1SH6+!*gknu2-5f_a?s~rd)I1rQgeOvFtHn3^ATIijI+JwEbl* z(K++l{!Crwo&VKdaX0Z1l3q?mAc^{IrQ7Cr<=Ua^A-b>#6I;3W45O(B#TTj#;Tk7* zWN5SKYfNowHUwV@qy#Y1wD+rs<|sBa(d+Xiwt2o~dgyYfAY2aK^YO=6i{S7rlRv)< zW_W zkuGeOdib3*QhzH`lMQ!E7YZ|{ysP_#fh|cLo;BcG{r#fnqd(_pm*}2^8rx?6Z~-C6 zfoV#xW3CkQ-IW>zR)ZNjw=7**yd@q%JOn#DK4c6po^`gV^ePOTBI|v5Kfm><9mD?v zN;;AGgfCB(r3^7u+}C}v<7q+-Uy}7YQ&i-Amp-A=IdkV}Xs)L3JU49vrO6z&G-()c zI#d*AV@N#`*&AbrZ*f{CTWpWOcgj`l$yU05v(tWkDYJvtV?a%Hh0jXFBsy8+^Ftfe z_BduZV4h48HSgD}+n>E3Buhq3KM10meL*25aIL?tH#*1McGL3l@|(`a39b0HdbgPZ z&3F!Sbl-Htt*#lC8vlD9lbDv6GsoX%hj5!>pYwPczK2-RW2A zyR-dN-0^0&!85Zi!lb_F9)A8)dJ%IM{SlPyr*UC1g030<`)cd+Vzc5xDep5L4yk1uIAJEWWo|jXqYO1-+tmG^^s(&e8V;3b` zp0li~6xR%9O3XxpKPYvi3LZ4y=gD_~8rMMd*2hi*wffwUHC= z^|ot6lB8nQiEhfwZ2^b&CcfEi5q{>Dy3>8FCBvG2a(KhTC+6#Nk_E0 zT@c=~@0c8ApiE1-z^eC*O^yDRN{aNbhtlq1YLUmi^8CSZu$)dr4d5}Szd|thq64M> zLO?DnKuFU$uLKS#LXGrv)_(E8qNc z)W7!JwAz<>rx=;MO2deJn~F@CyxfhU?W8)kj0WoUnt=jOat4~R z7)PDxP1@ck3nT0e7dgJke0YZrr};^(;0Zx*;`A)p(pc9FMkXD|{sA^& zP`l+)hF94d*sgIGMYm~zIydCG^R35`&@XqvjYEZ8s4xrHT>KYtMR^I{3vy9mI_GMq zA&{1W7_#V1Ftd#-pFo`qw*e4%s^D^*$z-uyFMqDUgm^_9qh?=1JA*rcCf%0YFM6)B z+&?OHRJw4Km0c=G@2Yw`Y!kc?6&LHFrENC}-L=gAZMEN@v;W{T$#zFoA)uQWELg25l*8_MZxr9po9Hk0zb;nQv&|qT`ldd`;Sfs{!;vrP}Tib z5b#$>1TEGix%(e&jEjm_|NmD2w4OU9|K}sU^>b(5HcpxyK}>|dQ3k!JnemUR61+4^ z`fu}93zL~?5(a_7 zb67=gVh~3u$;>2K>$uDikbehyb^TPP(oiPh3@T5y9x2(V)TEVgZ(;P_t#wvc5 z)6Y~k142*qQp9xElf_gj3q2~o2(hYfA!F4ptp75G=6Txy`x=?5sR{!S2KoPpd&{S` z;x+m=6sNdDarYuYf=h9NyR|sMwYU{&NpUB*1P@lUKnpGI?oc#Xac^mRbMF1!xo7S_ za9(6GdnS{-+S$+dS!;b(V8t|{4lw7IBbolUN&dPOwSSL!*fLtKs_0?r1yMckkZ2Hl z1gQ&US;|~tW_}*1T!8xh=lgr>oXaBFnkzbFQKz87cL^t3XR$rZ^ zn}+Ak2#g3>xS-TUH&MT_d7EEbX$$j1Y;D)%UD1Mkf$Sz2;1Fz~G z(L)4j_Rx(&8Mi+LDlbg4HEofgc>ENCGf(t_?Rp7rGM`dhIYpG|iST1uzBsY*7t^E!pjX23SbOpM~z6LQY zs5j#>Fmm{LKn2w)7F;&jXOiFBd}>ww?XvZ_Ci_O=w%*(##@?3D_rz?pYwdYLQ+dDN z7sh!3e|jI*s`U}j6y~J2#a9wK_By>!al89~13F`;7{89vg_5*A#+M84$$xyP|GI|5 z`g}i9s0H~kVGm785R7V*&h+{tF(Bs*^bo4@`qt&nyckAnh|NhcK$04@`1va?{TMJT z+(0?zjiQj>_s#rEGVWdJxgYo9%}$GmwdSgjY&x#3;JJ?Rwc9JTgj7`jhm?++1^^od z_h!|RlJg0y|M=b9)yitHgTLc?fMd`PCjU`mu3i-P@8z)85_SOJYDEcKe%tOqFjWG- z5# zie|99s294x!93fY))^p`bB{uB4v#J_aN!F|Ehz6yBsYS=r{OYhX=XKG~=51ypuvwwa_&OAUVWCRpnjRh3ZBH?GqWf=YH>dTj}2T! zJnF=)A>nWH?{BO~2WFsG?7nneDdl20WLZG<-Wn zv9$L3!Kq)9Rx56Gi|97>CEHS3{$AW3A&=|x%H|F-rb)S&d0}%Ip1<3nG7_-|g{~sg z9a9v*LdNMQD>sKZq>vTnHcG_V5%nZrce!(Q=i~WMMuP!^m%7YC#6R){kg7zY+M7-c z#s}ZKn1>C<2jAVRCk3+9w3NIZqj5j>5whZpmsX&P#}Bvq9H%RM01{1lqpTP6JZiOC ztpDef_Jw$o`(_TKpB)91O({Q8WiT1b1tG-TQT~(KQ7DrZYNNPiAtISxHQaW2o7MTn@MtJx;;{T z9Sk4>=G+4-(y{4XBIUg|J0mDL-mLRh)rSl`|GWepbZnAXHp~(BhO$_zTh1YNAHBeu zB)UVb-dcwr76gc7xVP{R;9O%uGRjP#P}^n)O4|{eYdWK>1Upu_M5Fk&uQD<&yMo-` z9b@p{Q;VwnJPpqbHG00CYN)Q8b#&m zDu^B;sA`}&e6IKD%{4gfqhNZ6A&P<7@-mI*dr?*-i(7`MG9d@k!i7)8r+ zIxVpT|EhC4(#RLA>w1(p)-FLNK7_uvH6;0M7U3skw`D)m4y42VjsF1*VH0<3Ov!^K zIwVoaV)S3-T{6^=VkO3jUK=h-3CK@WujkgXg3xYO^dsCMLx0W1|6Hr`G77nDompba zWjan=5h`0+=`U)NYW;CZ{JA|f9Kmy3rWLPM6@C{yqspiuXMS@uI3!*0{YV~LHe)NW zjCHY<%V{2@Q@?Dx@fH#Z~3`m+Mbf(Ug*vXbaAt0unWuQDo&(qgndIKCF^wyW!T!1pr zk*bElY$O#+QpT#aOi;OyujW((u)z65JtJprF~d~LeMtmUDuU;7O)5qk`?Y*nerHZsOkpVquJv^ z>cUN`)vdFqPZnDMz@U(6IM@7k^9&MFj?<+!)#Eeh{t1pUjH9!c$tRLebfza5kucZ~ zZu0EkUX6L3;;!TFK}`v|KS-}+5{4{=$t0;a_p2G>zpde*fFzwMTeyD6yi;ZJKITr0 z<7~rp9v{}91xXBI8f8seSg|%tQbh5dt{Z2dyBvs`2XL6DmQ~Dm+cWJS7zlKoK5ye^$Q z<%=*_=6>S$kR?BFlsQ-ESS+?I}0 zE9b3FunTVA{7%tf7t+zWZjYgT8Q$e5PVxW-S~s+`eAtzY4+&+HWW#;(bqW3mYrbB~ zJ)PkMl?wc7tZIk@!D2dW@4Tyn=`d%mJ zZ~5w78w)6qra~L$s*B5+C3Z@s{VTu95WG?~S7vGXiRD`VVB1yi$kFk5Iq|j#pA4DX zb7D%@k(jLE*#p(OgQNJKJ$|n)_dCjth-QeRr*enr-EL28E3fFE9sEpm zMBw{3LeAdcOgM|UXn)Rf6oI&mDPTBFI2R4P&&R% zjCr*i;Nomd^8hgj?LY2hyjFYSsa$G;P=f| zk*ShmGU7srY(`}?Dj)@YF`LdQ4YS-u&_@hLl7T8<0oqUcPM5_PeS_SBV2N}v3Qd{Q zpA1Lwqfl^%0rL0JbHL(VI6wdei`f4>7f6oc_VGUNFQd$*=MDLaovblw*4# zN5=X>v~+m2FWh=-V?4EH<$->p#{N_0ZTa{{n$azeb!oX$I^_QVBE0Xoi>uj?Fk#ce z1wQ-XlLXtkZ&*V4M*fypJVs+;(-3mVP`e}Agv!H|hGt-!Zq@b$mEe>h-s_7C1L zTyrJ0zzQ`3u*4i#5D#*qFu^WJe0>U@sz%k{7Auk|xFtbQ&UsW|3>C%W@N(v4$%z4m z1A98lC5kcR%r#Io3yV=`N8mr)L-f@>&d^tPJ%qA896QV4*XVW`pRJ(Ua!s-lF_Ez7upa zi_uf&0HWEv0dAD=2E`HxS!Q>FYq~<~Ddo|p&?yBAcdBE^4 z18&b&Kk=35u*qyq*`4(INu`T3wyc#zQ9jg5t>#x)b02Z)Aoap{HptpFP9G^*_JaJS zDCX?VeHKy~zpNg3*@bi}O^;DiXq?hip^+45}_w(c%HE|aKJBOvn7be7aN zD!jy;m({!P)aEABNLg=LnxVwIdhe!?5A# zNOz8sC(Yw`+di<*vnqqe@P0l)Du+CaErwGu-F&=HO`epub5K26C|4eTQyvnPDI)c*`vo)98isE29O(tReqRdb7UoY# z<>eZ=CQxq(bou?Ahv9MeO+<(DozkyyjNd*X2H@4d{^d-O!NAKtA>jGPTm6{Z$FkRmqMx?^H1rDf?J={ zE!0+1O=0Y$Wi#AFH;9%>A4xS%0In78${y#489-&!W%;uV1b~+)TM;r_qMZ8akeEV6 zMU}>w8rl7RNBkYj+|XS`(beG4Jv8WGwI`%f4~D2R9jY+}yYswDkeCpjxjG!78ITb+ zi@+&;}5Z+SxJXZ%w{s0v>8k2e+N~&(JUWX6RI>@MSx1*+>zyARqE=#`s4L%Wey3l9cDC7)M^JI`vZ$&%3{7A9J{T* zTq6;2$NY^~m!`^}QSp~+cW6Umz(f$}O*|s8CX=jO|ts`&g}V{L{|v`kCtwegXZvQ7P2?h`%&NVzHJZ?)jYQC)m%L z>=M5CJ~->T6E-tB*HzF{#dMbtjrvdS1B!d`_Y=~*NKuwZxG%OP%-5U1O24cS1ZFV0 z2u+|9Zw1fVW~Ari+onan_{p8PSkC#Z?2R+=`$}?j%_MGYa!cDnhy=LCAecI=;~uGM9I7+>3T(nI1nw z39KH{@Uz3tH)uqAVIj(_D=$$;6Tq2_P3MR>eIdh>;8C-TY_WaJZsTUMR|AP^+=3y* zXu~yBxyvp;!Q*dVFiL&JOLZ9D^VU(@waYruc6HA28Yf!J=9)gtw@ZRFTh#55FdO`I zQ7bi_d!DX(i7&uy>OAx5!*>R8k9%OY+U!sxT`(+dA(}&K4!&g@=?I+8bEZ*P2Rl%I zz&L^jj#y1|3H9jo5=_EMC+#TqyE z5W2ZXY&kIh?xSXfLC}x%TB3But{Giy2%nmI@9J}Sa~o5x_3-q)0?Y5}e|a}ECru~> zFcD`?alj{M4C^htYtkv+jbEDsZt6~yu8rS&WGKWJkBm$>xSIYM`VY>%5>?po4>0y0 z%4r$ugf1CD`k&e1YVvDQBtqR}t0GCb2cF_&`^Cr0iK zcAtH!lJN5B$Dpl4O6skKdj?EO33Cu+j<1$2BSI`=4)Q@s4H7|XQ>^H_ni8#9$SsUY z$SdhCQz8qOWSBSHhtv zQys;DLpK*Zm&obC1t_0j)PSJ29^t4Odr(>RNHJi}i+hCy=Diw;&oG~7`pW>-Fh!0T zhXRTo!%v6dLv%!gDYwPw)Wuc6(&(aZQMi%V(sSNPzB+7v=rG71XX;4DYz)HrXjHCN z7p+J`+gF+Xkht3)8|Dmx?-rBip!o1~GrjNu3|&F$VnXNP@?IG(w0_&z95K=J zfwz*^BgA;$G4OWiKk<_CPRF<%dhcQ>)G;dO?Y*Y2I-h;;0k)23YpWE*9A2)UD^)60< z?Phap{lsR9#;Vw9puP!(U7*uNcMTB%qsFx-ey+#uK5Tnz*n&MVSSOzIhuz*!%(wV3 z=eQ}N*QpBz7NCKOq0Np$W(s)&5)Ok1coeFR*!n6Dy+PHS7&=a& zL-FcCH6l4UX@H^^D%XzCHwJz0>E>5|yJ37Wfj@$AmtIbje+#7>L-A|)L zx7Rlv+GvAplK0(qcE)31aYs$chu2m965rfjxX$?tgkF7sHwk&# z5c~AfzwBd3NSj3^W4JCwUxUb!-_*|@@Tn3uUicm4zCA$1#XT^w*?kC~;Fa=ViI4Pw zu-XAOaL&fJ_2G3bN3y^4J>@;obAjpU{@0KCPwJPnCnDv7wRK@JP@}Irhfl(yML2;G z6UjPlfpi|%Y?)p+AWW*h# zsk&>B&oK!Cr*$!@D#vCjK@HmT?&AiLM4-#U@Bj@1I05uVi+bV2r% zG$*eWAxkqZ!J*A?qG{k6eRNc`+C($e8(bdTftQx3 zcUxmJG$mJlM|L<3x&u*)Ooh=v|vD!E?u5+?nhm;o@FSj4fk}RHe57Qa8;G>|2 zn1Nqzk{h)#YOv7B(zx%h`98ONQ^maQ<%Atb|?_eO{G)(;XP@pok$0#Bzi=r9x!sSt0Als1R#M)oz+%UO;FIZ_XMN z*ZJoB{a@BAjidILnRMKo@L)3lestfS$)wnQ9Iif6q;>uPdiNjILvGDn_!HwMCpPTW zi-JR$V7<|+pfXMhm3R7%*=4Mo`ZzX)J&w$J9rt;fZE%LMcFDwP=fz2m-c0nK{eI2PL)@K6GP}+b zUUt`VtFcpoT(tj*aOg5CQ-t>?BhKcow&AqZ(BCSq3+eso$zPu(55nDpH|9Tn=)+zu znXQ;GX0g)SY2bZ@>%30#XMe!lN*fq20}jq#+@$T%cWhDNTmai_KD<==GSZg*bMI!g zhlhcIo`90&cYY;|f%s(51-`<;;#!vdjVkNdc-Em4{Zk`FY?axDIV;=6X@v5gv3{9* zBKe#!OA4v)FT>-`!$46p@`SU9p3i6nHTYRhiY0kt?MEJS(8imoyhmGxf> zQg4MO8lQ>_dBsFLP(MBB0@3yXtGZM6z6e*SW*^*z%8yc+3c>n(J4Xh2i}OP(I`1$> zS8i)w3F!&0wbKO~#zu>8Fq*rROe$2jy~8pgA0{CuOmLb0-D*ncg=zUbqjaA|44p#d zf+*wn!d1t8jmdh=9TN7264}6^vFP7)6m3q@rck36XW0FtW$T%%h+X>+yBmrIFIfY# zgC2Jb2Nrf^?Z|NQ6^s3y@DVI>YR~;gC2C$qhAfnwbS{-3+8V|*q{lE4mSaw z3K7#ur6$qR`~!-B{22@j<_Yd!GvH$mCWhPpdtmy{vIU|2_rETL7{A$8Ub6E1$6|5( zKebqR{+Fi$FW6-2^?xfIs=<=8 z7dqr51L%a&P%Ynd6{28kWdMiFV_Ayx+SIdb`a?9yOHIuwZ1NaJ4FCiXqR&_XS)MZ2 zvg=_YiLdx&yO%tH?t8=Pj=2mQ)-bvo9 zN%ecg^8t4q)67iGLF$_-fgMx$a!*&V@m&*?m#c3;$IbrTFY%45!iCr9GLRh=g((JP zv6Hy~Im;C3j>A#3!HbISt21QE+6MFXr^RN!+*QA|gjC~Ju4u@WM}hIH$9GZD>b0>y z{l%=Aeh{skt1LU?J= z&SWjqA)1j6)R$<$Gn2d9Yl`bLKC!Yc^I`aD&Q};Z6j_+rZ)Q2Z$>fZ9{bCIR`g08| zX*H^*?T|v0vxvejSq@wh#xvy71>o#g*b>U{zBXy?{Cc59TJuSgix0a}RCJ<6Tn~Bn zM(ldR4!oP|rv9ldK^?{RCNWpBZTx|@VtL%2w)Ti$-A=<=DO&m$b0OWjFX5xU@0WT= z1Q~POn$z-(gEW0j@%+WZ;(>9uMTk@oeqA69Hp8uU@htPDN@h7E%R8Rcz_%UA+T(4U zH4-Ew^m3TjX;6yqmZ{ka_xwlhyc15C&>FP5;#h3acoJW^+@k~N+vvpZOO^Wea3jE^ zE>tcRK4)sa&IeAg?Qr+L`Q1Tk;Y`EH7??HbN;!MCvuKpI`WC7T8q_A*Ruy5pMd*AZ z2#{L0blfqK0XwXRN;iKf>mDP2pH^;Up%dS(uZ&MN^ghvRB5I^YvOS(-p6%K`UqF&; zCv*AnWAg*U@T=j;FP@Hdhu!p|B~td+*q+&Nn*txCR0*H2kZ$-9Xu?f%w+Fmsim=5U z#C5=`7Nb&jSNaBvaanrtt?HLCoiYLr^05ptPG9f&`Q z-x1}<+azG8HB#y*&G)wEXRm7$x7NDM+0Yp$a`_cUr-a8U_-KLwyNIBf%ns*Hw~C54-g^I6lva>v1 zc#ScEcu&=`tdErG^!;gyi37@d$mtv-semJr2G!{iwZ+)cS5Sj_1A`3muZcosS(lsd z{SimX{A8h#ehpY(n>*(`65*?lK2^VaT#rQo)dcw@(94Doe{u7)yZ$b<5U_Vw9$3S5 z^nDdn$x4s0!98Ztc33T;N~m3c`zG7?KLCrsvtNrqlK6Orj6{Y-rb}oZ4oy3wGKJ&j z{w_5(&7n)Z_aL{(8n9ne(9w2c;#G}~%O^7K?Y;q3DK0maip1Uo*-dUVCl74$=|mKn zH~{5evZm@<^30MTu4CHYV`Vbp`Y@#X0!QK3lG#=Rar=9J)15B4!}NkW9R(}7_$Tr5 zqhHj}Mbn9SyL^9+?ite!?x^`}gGgn%Qg7J=V>1>r7N#=%cighANNfDdh83|R*hd>x z9MdIuSzT2#@3R;$W$*_r>l=m^@m87vkyrhkz|H7+{Tqh)T-gjj{y_x

x0q94zex z7P)W@a0X-As7vh4>$j0#>NiqP=yvCzwb0s&i0gJNzem>L=TaXaCoJZX8!`00hTn*l zF_vMQ$H;H;Gh|6SpL^u=HJ68;Zq6-ZBHszUG9g_XrN<>t)H~EFhbBAz=6pSaT=RGG^RXo74y32kR5pg&nQ)y=wgV8x_sDyIS$)iMt&x z%REwSIup^@=f}^RB3ORyA;<)MZNB@m*OlNWm~LjT zFs{@asXXX$kXO7ZjHMcEpY?mqn;KDIqMWD2@hUMvwl&UCHMGoWO>~UMSX>*KnfpR9 zI^Ed*ys%Y!QlyJLj%O{pNYBiCfcya4-DV_NsMg10SK`+q#kXWoXT=9wg6}1@fGq3I znhzZ^E~DHli+N0bp$slRL*WMWpjyG?tnzZ!qHook-qhz4mT!EGJVo{wn48Nn&W_9l zk<}LBRkck;g$SCaYq@$y&WfSP(Am!P}^qtK8gxC*v(jvZ8c zzH-{Ys!c_kx5k`B&)9K&UOo@5cdnODX5v;R6*b_at@7b>FV44}TCz!=u?wEg6PVv- zc?%$EA@l!eVh9E3*kZ(f@_*J{%gNh91`jitC^klp-~SY3-2UGyt^ePKt5z!ucw1K4 zL$5|&a2&(T0nz#(B7cxpR1u z8|6d_LRnR;TYS|dcd|L*&j|m{7jWIdPv!e3b%1y{^v=i>Z0em1y9$U$AX;CqzQq*&nxoP0f9 z<>y^7<^iyb69M#x@1gLdZBtC*E9oY1i5+ct!m4#lB5M&B-Tr1%l#i~XnU?sw zyRxGcNE*OC?^Jcv)%u!P-A7m2S(}izx)9hIr^fL+Nl^Z#fxPjO;%~-p1RKUdrd?nC z52c6qkPsFN7tMW3akR*9fBiq(TMjKfv0^3r-sOSbmeFO}rCVB;*LXZ<{F$`6=Yx()=&wxk<>rvn zOD+_V;Ow+H_Tq<|x0j5!y&V)pXd?+82QpuKVt^|5=N?>p`&|ItscC1p! zb%awhRMY_3<(UkH`L!|!3z8M4LmAy`C67~n494F>v81xkd~3s0@`v~chIrM_Fut^AnN>U&{7dX5$FnkB2T!ClS~m1|^Q-5R{@_y|_K3g{ ztzBpro5|;<-udJmHslNcx*$6e3T+RJ|MHmlL3BM($N1v-%dkJq6Y`idzfGq#h-mo$ z)1f1Am26CqX26+VcyLF^yUbEjlaY^ILM~RKGOX{@VHW486Q;)LuuLto$3vatQuO0*C}9iNn0BO#VxB*{BMg$BC|!fLUS^3$S%XuuM^O|dHC$0Ox&Df?b) z@Y_td#o?l>JKipOx|zgsR=U9DysodBGCel|GtPba2pm*CC^<{bknt_BG7LhSgI^9W zr=v9{SeB&}vz33=*;Turna`U5onP_0l`<2JcwsqCskx68 zmgCGZO_jAAGc9Rg2iJB6qc1b_vj!anyd-NUGwNQ`!`{)6t|t5bnA(O*1zA#KbWV${ zH$CBMbjmNek6r4W>>6;6`*z*SO_a({IOLi06K=3N4>ufQ)ar0pTSYmX%kiUuma3us zr+_Een)aRPKg|0L$Y|ck!Bx8od6e-3%ZJ&m14Vs^#TM9A=)sne z`MTy<_ccp)_m)PvxD&=5BOm7EN3)(_U-D_k+HI*9-!Ujm=;5b%C_89)4Yu0vyP~`j z6aF(MLb=*1m=l6@y4oT7gu(s|=CEc^ImWfFrQnePS*$2{gkReS1F!Q9ul0i1(CjCK zfnR1_8Njxq;+9VxFkr}vJTjpRZ3TCrO#1x&{ewjGyu4=r09kSuFOST>COWt>UJd;x z;S_v+uciBtnvI(5VEf3K@-RY%@w@o?xz| z1b#!I_<(b&po;d{oapr4iu6e$j&~3pj~g6!&Q^h-Vw7=LF`Rs}hdbzIf*D0cfrw0* zqZmRs=g>FgWpMKDok&9Gp&puY>S7GpRy?Ou>?4Ewn#=3A-&Z3!B_=q@D`38}QP|oU z?;FhJXqC>m0F36?J?Mq=ou^O$HaP>=iTd0o3f{S_f2lPx$?c2=QK-0sPXHu*6##mL z+~q~)^5|I63K9d%C~^R5MYye@v#S^Kjk+!Bj`HW_cjY$C_^ z_98`I+3!Y=)UR#-SK-Ji@6{a#dYl~Fh^ z{b_2KE3jXcJd!LOlMdwa!Q$1w*Inq=@ktr@qBgXy)JyR(HgOwc^xWgvtAX*)9na~P zXy3P8aMjgd>cMR*j_8a1q?KE{1mAsstS)|S;#GGw9|Mn$lQwvu}|p|K-NsnA&ZrI z^LAvT-${Bm4)=vS$IBVaWSurWz!FL#Usw}TPoOt1aUUqH>%~n~3%1)m#`{B}ek@Od4 z{EP|YUhTEF&94%=T3q`0B*XY#lpPfaw&KM<+f5#A#7OAoKGL6k=9gP$Go|s_lM*TP z0-w=*+%jrHy(0xvjZ(mEA4)v1gx%;;fu+My@z^Qgt6P-YNB~e1Y6lp6*|8@ja?^MB z13*8yy0weAZL}sUoG3>||JJx477`sV)ccEnsXHVxl>VZb?8v++FkJnXsF`Yo7r#E3 zaj;cx+u|W{x?61YX!)F+jZ&n=-D6kndM^emDBYFRr63ykYu%@*&uNMin)O?G{>G8z zZe^~imo41idf78H>KzDsHm5F(AMRnr@q>+|y=lUtm!5Y@mgWKKiVPDzQ~VjtT_n#t zJt>j~`G6vJQxBl`&~wpJae}C8XzP<55Nkm3#@frsejlDQp*g6*1aL5LDn6X%#}WJt zxDE#Fy$fQL=Z#BsjD>{7gASn0%c{NnMZ0_h6Ow^e_jyw70(VM!Z<>Cz&rE zfA{;zW`+|HpHN2fx0L`jq_`W@=EF(WM#t~O5meiR)#!s*vXAf+~>u*YQEtV3x>MaM31z01XABWtE6Br*V)Ctzr>q&b%UI&AywKxfV05WP@ME)lTUD)6ueY= z#nS_5amijZ4F9sdWl{yn)`_T8_2tqv^=(0-CT?QL-4a^)ve3M!$wl&qvc@leC%x6le3Q5S)u*a-8N`wYQ7MoYZIj9Z6R2miV z7m$8}E*gs1o#)Xa2gL{ojlM7AuF*L^DN+iOR02jRn?cEQGnAR-kdzqqx^ichXd!`3QOU)7SOLO zzX$<~A_1GL!ZLc-j=7uUTzhL4dU6xa?Jkwi^B~JAX%qM>f*KyKt-ETs7ASI3DB<9$ z+?9Gcv2y~FAw1L(S~&|VCh7)Nb=D}OS3GqaMf^l=SVXhE!NV|>p7Hsa6s{S>A{9Ib zZYl9m_T%?NwaA!9qlFt>uHDR%QPeu@*>3glHMj52BegW zc^u5aUzHo$2JVmMlso5DiGB=XxUY{k@lV%%YYjRw4R{^iPqz<*;~5r2g?prXX^ zWRM#7lLQ(EjvwahrlW20%(nxH>ZZMbe)446NbH_pZ_zl&Hwucgb7|s~o)=EufR*Eq ze*9xY;YWvZ$FZX5u&O=IX!%Cvjw3`Hb*{)iNM4&|wpUAXz8sJ799@U62JM4}$o0tv zm^tZP=b_D@!d*@`yy_INBnn!vSoVSP4KHm%d7>28U#o@S+P*8*But4>G#b(2oi(n^ z$TcH2y7@uf4FaGF-7TW*EdE%Y_oeConIA2{w4CNci_jug&)=_STWWzvEnF(I!p^18 zt^X}){&no@D;bN3C2qOQFf7-DAE--d6gHO=h0(>WRkU>~Y>9i<%aHM2wq+Rq8tgWk z3g*bc39N9;$e*QsLp{Moo+2brjP*!928g8oUB#B& zVkDu+aJjVpEMu@OW%6J;0u_am$B3RympD>zfk@vL+r{6PbJ9b~^KZ$?hRpfUKb>kL z%TCTUQACOG2uXb(?p)4x4RI$_e#A=%wZn{=B|~unwXrb8fid~Bq^NZzYNAZ{0_F}p zBPUZ+rUBAHF{q!aamuHd^a@vspJh1Brlh0bJNPLE5Om*n+|I!`UMMWA;-1A?n&d(z z{YlGGEOuZ7W6zL*A!fscS=XMyrDwS}Yx~z-{ij|@=VYDV zZe`hfwEOu<8Fl`R%6t7}t8je4fQo6Fk1`wAta==c`5<>2p)tSmwT~)8CJ03#2Iviu z<2!b7qq2{C0?xzOg&8qB>9Px*AD(tg26?j{64BQKeJBkHjYc@>v3M(MKEtcN%zD_^ z?3dSy{(91&qy^b@<6P{Z)psoj`T-CoY=B| zxSmIyo1F8T^H!6@J!=|tk>Z!!`L#P1Mg6Ps$lwi26jTiW9-8es$9}LdSUfk16r0)I z_Yo;_am+3;JJO4l^+_ta;Tv>EBEa?(ur1eZWBY3ve9+%D*lxg`&k2F-SMcdA{hfh3WHa;|K1LI_Gz4z_FYxVVZkl zFH8rYcIl~Cru}1lMcyj%xAo`W%_Rf#%rrlC^Ow`rr1yy)VEk;S_UtwO5!bTfFSQp5 zmR1XLG{XU)(9S+Z^1#%ZSXE`^ZF!cGth+_>@pdk#SynI=a7a-r&*NV`^gzM-ka2=xKXuevd++qQr- zMd9=qa?Grl+D9R+7hSNxmP)C>#dOeks-r+#VegfAzWGtJk!^*p&q)5Z$}Sl>xjvs> zJNkXhsyEoE_W6sGPD)-25PQmv(Yf-+J$p^Yvkya}GIeja!mq#ylC+0kx6v+@r!pog zCNS)MJ9#yJY&8FDOWAO6&zuK@CT#A3Rdrb&- zmA+h`lFaOt$Aev+SXN2Bx6V8Y=Y8&G*~eb>U;d0h5;(~ttm zD=s^`eBpGX`WE^CjRK6zyyb$nvsmxs$vj07w&+m1=eGzj>AoAh*P6)O;ZK>FazR3! z>V`}$y$22xYFZK%YvN~k_la{A^IKZwiOGJUR5=lnU?^dUv0`0aY=-&UFWN)qH)eXl z47YXmN-DB&NUfFSPo*}rC({$lGdNs`zlBjqN6$Lh*L`0R2S0)q=@}USVrfbHJe}^@ zxB6)lG6s43b_{1#WF7BFDCx;0tK7u+o_QxnCHH`(=ecSD@{=Bi`Vhg1nW%00%RN$v z$b;=9u%={6*yt_4uKUVb1pDN9Ags|(X13!L zC*ON*Ij3p`T0VKnx7!t)8M(2%#OmwLUS1)_sAMIUS;aoDU@zgtV=+d3P6c6~U~o-!U8(KHM>IVZ*6x%|X!?qCa^ zc8g>8KU}BUj7#8ekCJr5lhv!|^$2xwcTSAlq<63T;gWjfru5*lA?zTP(S?>xM!RO9S0&= zk{2jr0l|FhCF~q1u^$OCqKaj$SK%FG$gb8OxFRf5r%!F7%yIe4gwmJMGu4mFGD$KO zv$JZV*`BVNte`8KAl8fNUZTSXAt_p~H zYq97!x~$*nVW+XiE5Z>I)Y&B>9s*ex_i1TPtd74epL=7+vX=OrDpdM7|D}t-^|=D2UvbsurXXpjTB9AAsj%|=c0WBVz4|>h=gPL$Lk3}514L3v2bz& z6&ibD$%119{W-!bMt8Cf5{adQ@@aO#+y}2}Kf5}RfNOz;#m@!e2>7q}f<n z94z%aGnDS{`Iub=f9kMT;Xf{ayV(Mtj(y+Mfd{VylXtelQcT)(Ty--=Q^%T_cg1#9 z9}39|lyJodzKp#d3)$IK_YNYR;L-;VDn4Z_@G|&SL&yZ`AHdCUa8RFgdgi6Mt`>j2 z*7rMTNE(J;9*6tupx)Tqlc-mq_yk$zP_`K8xBgWA6Y+ZL9}pk?B1{V59lvidhB|W8 ziuTSsRggqm#)9U7A9^3jT0%dJ9KLLmmfa>LaA~Ki;(AMP8$6b7>EroKSyb3jt{xLW zYxG&~gkRv-t6U)!FN|e{Cn^_ZF~Lm~Mj8_hA_RJJXkR5fI*hPu3wMYyJTN}GkUDxV z_H0~%>%BMeRwcL=iOOe7dGNcBI@XElSWAYr?X_+|AGN{!QWRvco;G<^Bza-T{o2y> zW#J0C(Dj3{icKG@Fgggo4O!LXM=M-By5tX-AuE|fKZsZ|WmYtQTB5$gJ#$3q(j=%uSUhHC1tLCZ3(%(tl0Ut{d(atWG)7 zm?5w)#myE}=K~|T5UMR2@AhC=3ff}YW5#sy$wse%>9u-!Y=y}ZGgo>>j7|{;))3q* zG-AOii>9HT8_O)4df)SW=nfNbTgGxf?b?#P0PxV4EDH)~PQLK&SGM28ue((vn6*tH ztIli#`BBfk(L26`y)&x^bAdp=l|a`B$o`X8~)MXmr-_xpE0YPuGH1OE8jcv2MF)z>YMkWhXX;Kd92 z)a%mvN*KVR#$8UN6yF4l%ya_9M=dOTOrGm_@OZvCmJ!0DE1(&uVHi1SVqxQyqPbrG z5xbk1nW$&YFS>Z9)dmtB29Tg-RWE6rPO)M?uj-(gNLTm|L?BAzaVy+dNU2Opa;uHj z>|`2#+1MZw`0f28Mi2VGGs&_8(0>32{NBH6M}ww$1T{FnNgMZOC0bdDuwTzF)mpcF zbB4dqArd8$+4ai8%WgG=X|27?cF}UxNK!kZEt>w`d=Y1=4A&BHo>k=ZCgh|>%ni=V zvg*XzVj4aa5Y#)9e`rP#-!6jFZTx-T&8Vk~L>{Qjy->nz!?iK17iCK1sgB9c*@ctd8$IEBX^?~! z1|F!3&3}mx*2mLebAp2)Q;-$7yt#Iw2->)#<3uREktX`}%rCXexjDW8iuFNWh#&Q-LTZx0yDQYKznE7ntJ)zQXH);O@a@WR>I1+q@e z`N-DR-!-u#%S3R})1u!z@G+%K?K!oD)(>ZHV)Q9|Vp^QnSHO!4wk1LT^BlEy=s2F~ z&)oXuM+oeA5og8&i1_x#YTzB-rv;B=RjG;~sz^=z`6Y?`%O0z-${(G@G?80QJ6yY( z>K4rDHhblGfDmVyX=>#6QXJQI{3Fo(j&8 zAO=&v$XD94o~!Wtb2U)+*u1g!p{iX#`BU}{A;@&JUE1uqzNxE;b@Pi9{3&1svu*&B zsYs>Ze#)z_MM%sO+@WcW)fAz|)^uOaFNSvJSAWlYvOck6#9q7kB(_yzmBK75-Y8O4Zi zzXDm#kG(^8%crJ@Zu;eklYET`^8Xr_zh~J34ebkl?iI-@x!vtm5+)qQ{@W7wjds}8kUUX};Jp zYT?LqsgXRrlvZFFxglXd%pXuC9a`4|fJ3s|A-O2BCz_t*ULb*FS&BAMVKeUl@ppER z`825VXN}v}J)|0jdVt4A+P0m@^trU>lvwlb+Or$uz^_-6dhF`LuB9+{dmg)}u0zOl znMmkt3DE%hIRPqY^4DAMfjz|=Ot9TIKN~N2H9K=`>D?}RHp#$TSJY)PDCqH5$J<>& z&Vd0GHGp^{TNR|DQvE3i9#97hBPf~dq3(5|GEf2hw=TbS;(q`e zf&UViJZ{TYM$P~H1Nh~{BK5z&u!9?j?RfbYiaWtYM#TphVSa^D2s97nWSDE}WoV%a}{X4Bxc;=ZIZ`J2>-pWA!Xq_!ew#50iW zE1KXd!~jRizi7r{E}z1`P$HH(KwOq#uwlHHHWp;|@dmCOpON3j*R~sejMWEQ^EHnK z=}d-)ofh8W^NGR5;!_C?)kB;Y)vhsb$8Z*)IZynp~isNNh zj%A$m{Febo(9NZ6!8vB9$lv#)$c+Ang#+A;_BAgI@yU&8Q=kREcGAHHZ0oYF1@XWS z!g-K=^Pl)n63-bQ@oo@%n!9^xp?y_eZ`+4oY<(zd;4M5tOW;Hrpr4tHiBI&~$EiKz zSI+Xeb&0P#BY~TBSmd7mRP5Zk~?LZI)95;H(qWv#U7+@yu%y_=uCi>0^E#AyOjT!N0C)vjKM zpFft1#JQg&uCT0xfCA=EHI51*n&st2=uZ|*Doo-1dlb_aUY(xG?}Nx_>8q9*hF%Ow9Fw!dDqmQgk|N|9mhTE zvKB{MOFW%0a2h8ZuxsslyxxN-v|_oq_gfR~Lj~D?U?f4SM`Jd|lhmx!)cvuxED8ep z0;Vxf3UNZ+`?}@}tmBSVdkkkfa%?=yFOMlwff_Z!WotsgQTlVG-3wZ)04UgVW|k@d z=;QhpN-gyWg%lrP!m%#dytM=rw=%3joYyMPrivFy>7hsF2Iz%#>l|JL)n~__;ZMTVY^ZUg+q)SEVWSgw zhOF-AE@_pv$qxrJTLh8N-}gUXAM$MUn2eX()mIV0n0!&f7K8H?)B~U_hq2!UpGx!` zjc*<(cspAVzKQD&o-7oS#&oYr;NAn_T@!opxs}t0rXhUtQ3HP`c{CFt*cSJSF|tE! zUB<}0_~jPzwWh~gO9+1%gztP#@!-#-4w&E9(Bc!80!PhG+!Zds^C7D4g<1Lcg6z9f zA9A_Wp=>1!EiDvH8y9d3hTX0jCGiOkAO&cMNMK_Yyb|zukT+mgNmZEm1T?6U zD4cUaU$jo5Bd%s5CbYpSZv3*uyOYeab>uHPW$Qis{Po4>iYM& zez_!J8v*~X@H(c5YCo01jvZgzW4jT~+8)Z&uzT@GV%V&jk0i_a0C^i<(IV&sJ0v`r zPA9s?ys)k-BzC3Le!#N=2cv~_1CYtGSU^0uXi{JOKwU4$?oqBgm_Tn=T~~z;H-ds7 z2izq-#nZU2%XE=v2g9U9stO0>ZHvd)O6J{x!Gv4k4081#nJ}03n>0@wR`UW@>DqN{ z5jNC@E%)y0il9oO(oj3Q%M0Yjb_5#mcoD?Xw)4n481y!0vUM9pAdB7P)}^Qy$DF7; z<6y&X?tut-WsMFb?%`E|d>psNK2%vehYFryR zvb;!~?=YycB6dZgp9uq*PK?jsfI%M!sjx=zu%y4HCeWfNLA;IYf6nPXmD zBXQ(8dVD%VU83!jr5eMP;|ekPLBv?iNi2!B-5CQO454{QW`I2)joR@dMvmZ{;&WCC zEnZHvZ%2ipZjHU;R|w?UQ4+kR0tKkty9uimEgHeUpB`BhmeJ{?Et8{a(cgGq?lqNwNi8rw4ioPzf!caPIfiWLIAw! zM8cpTj1z7uCd3)1K5b1-kj;Kfs&CVLNypLkBty`a^?)hVSd>AEF*dS9=x0f$`t!sX zeKnM2o2p`DU4pIg@9O4HvimvO)6(gtISj+OEh(GlWhM;FZAgYU%kqtMs0_VP{lE@k zL#U>TWF|aF$=+Bu&3*4>QxSAorZ--!9lNwnt`8vCv;yAeuxiBrU7{PH?|Qp|V@0(z zj4YQ|fsz=%NqtEu7UcwCmZ<6+ z+C*1Nnqn)SJY_pJ1#UAmv?JHOjC=enR5AxUA}bJZ>MQS@;yVNYGcSQE`am5T#laiRcnWx2w zT5R@jM9f!${gSO*l;*c|T34qM@KxnjxOGK~{usW>bvRMBIkt|N9cWu1+eqr|BkuMs zJrIX>lrglFC}6(}I<`jiXd5M%l0?zFoH%Fp+b`Sczf()KJkPMyX#DR1zDty54K(n! zJPqk*9S2x?C%$v*h`8vWt`~{> z8S_yqq%Lx7m;$l6S7%D0e`^luZe0=JTiLbR&)p2ZJBJ&*JUe`v8U@bI{-KYjdoGh0 zYNL`=m+CRG-Yx34u4ow%#2$m(cRQ6A`qE@^bn6$D8nIn@l3ig>a=tYqC@Y>QXC5*X zcGIv;odT>~KKFcG%Cf-#n`xCJrVH9R1n9Z!VdV7^T`gRXcU)<^zn*m3+4*(J103Pp z9?H=*A)Ghwh6IR!^l#^gQ?B$X_}gRa4zxz?gV1|Ld3_ipy!$Eoqu=F7Em~O4YlHZp zo=oD-?KX4gRW)7jjB%fb`Ls|U*M;ycrJKXr8wxaH?-9Xls0q{K>848RYl*9_uc8_c z+@6-m2s7cBThmVg1u1(Duzq-UsA?w&hb?HP)>4J~CtXpjwFFZ%VCI#%i1VL#`V9^H z90EQLrjzNm%AY@^YiBs)FMFxIBqB1==-j=xF!2bh`F10y zM2UP}j+gc;I2M0vU_<_pDz$a&p?b_;Wn*}RWOk_wK-f8N91h^!f_f+?DUeKp{196y z*r(unEo1En7%%MyX!Z@qtbjs-Nqqouq9PN+uU3t>e{~C}Z;8^gtJYfHlWvu|Obe8N zYdX}>uo56R8DeU#Ws!c^5W3qTRq}XzOz39^sS~g=fB1V$45B70^qv$3-`r@GI6UEF zjG-^n;V^HmL{?t58ouUYM}YjYjOD8ZTcd{zVGBQWnZJh`$I;|NkSnNzf;EFlKlv#C zA=G?8m!^o-t7_}g<5@iUG`Y8W0x~xy4fWNT9J^0-dsO*#Xz1KGRv5m@eJg*1>doMb zSl2LO+0ETHHzzJT%Cz|uWKU%o%OFb0grln~uh})}?pHAuG>zEkpus~x{GU1HvaM2> zn?7a#a6c9b7`+=pM2BK>4+3>I-!D$wG*rTu{yYRj=fn&6V8z*G54 zLnK|yjJ=<4x^Uv$IR1@DO8iu%Y&k@oBFv>KDHTV>xPy@qA0L1kB{dJ6u~U*Pcieub zd_)O7sv{8rzb#i7I5ObIzT+POwj)4Ky0!#Qr|iGd?W%68%)fs8n(&4WaFNiWsQ*uj{kbz--Cc7+IA{<0)L(6QN#s;{IQg;paLb20F1#?KU>%3`{18` z8@X>tv+Ao)@=@G`s4^EmBv{OHdrO7OGMEf`jpt!70Hs3Dq%BO*q;Z&wdLsgK$-D0wihvm9lA zk4&9XC$}|BEE*P(NbXJ)PzH?9#b7CAMg_&&(J&S8Jgt{)5MR zy#4#oN_)bF`bPv#crCtV1bHl}z3j*oEgf+}EVla`xP%4ng)nUN85S?uq ztehkTg|!JHaGB4s9@hR<157xTPvM4tK|QHi7Coaf;YRr(EF(LphfJKTc$x02rJ8eI zst-I}AfPVuHdGzcb6PO+VN~{gf8|XYb<dmce=Mj|4p?4g7_2=;y~m9>;%tS8IuZkp%3?9W>1 z%6!Q8l>s4BrVahE3CT7kpSL5zF4@s*BkD(1e8�rNnVbYI zCt}OZRPE19-dD?K(fOcAvX1(D*z^ZR&3mVT;&mA?cbr}8sC@0OCRY+LZ!W9_*V>*@ zRF(LGdj6VUwW%%YvnLa-*!*{AS#6j6>Us4UZzX)(EK|dRKIW>fC+JC|zdv#xru|A} z!rz7tglMpF_2y;S!w=NNoV*;$xa$8)m0EF_fakEa^@NYf4U;gN-!@WCEb&VG{1y<_ly3<3!a?C zi15E0l8)dn!6t^|U0hv*hY}V$7*y_ewon>Ht%A8C^lCRo{X(0ynZpf91-47U6VKBg zYuSxyZ1#_Pum%QKR+pxLqu*S(zhId|m6gr<`kK(pwz38fSpJEbyqUcG!7}ZnKel_C z0HJ5aL`de1`Tl7I+8r;O%M^D-lO$PAm!X)Ib~m6@aT2Xl!D*cFB%eK&%%x{X{%r?b)BEm_1ltb3ka>5a~Qz|NF zA1|=g$uj-cMmgaZCnESor=ZE6!1%i}tTm!!612$!SHGaY6)SIXTia@7XJL zxVc;E9$(FpyH-sjnqyR3lE)~eyL&`tB(e2Na7Dn+n_khr&>3rm_tc5ZO{18yFI~oO zg9vT~Zj9o#TH2cjOXRse;#fvyg8h$toyP}+6WG)j*AvVyvhAd{Fh%OPN4%jYJpm!e zS|HTwwZ-n>3~4v5G0(*}bN1fCoNcY+Yx4n=mAR!-3Zb{Xqvb)xkbd0+P|BR0PlGbc z3AZ^c=DRm|*DE+!#$c4&8_~h>-KoZ^)~d8ukzmU(+4XS?OJJqNYYSHc*|Kg&6Pyos zhxKEJi+HA4mOUZz(Aj4%E&B=Ivt(?wF~wDvZgcsfY(Aw>b*JSu+W@dNnlj80&+P-;NFS!|~+!DqdSh8U*}ZFzm((XD|6aOLnpF zI{+u-4om*O_I^%vZ8YRS3if|A66Dxql(VhdB0Om36jgnV@v2Hde4-;IS3EDE9t_~@ zjzxig(lZ5~#Aj^GnC|i7P^_yEU=k_J0s77bZ3HM`_Fit_Q*oFa7}CQ=>ra)jmXb98 zHTRu9u1(PRG%Q#@q!@rbQ3m@L5KMn%%?1#R8G=K;8^rU4ub}Aj^aEG*ahc#MT&yTQ z$sX}LXS|ddyO!}vmc5>;nvm5XQ}(dpcPpM79`2q36ZNiMkRtU$cQ!BU7bWw9r~S#& z-#8)7Rp17Ydfwlt$VLSVwddgT)-}_=ZBsXiR%Z-J3dduVdjeZT&^|d#?O?_M9?ASiK6`y$B~*=u z2BL|I%+6=z$1zfJX$tRlrlSw zf$(9eo>vWmOsb9VeVIWTHJXt<2F_=ZXcfvQbGAKZJe(+-A%@S<58y5M%1$t270&5$ zMgHi{60QcX92X+F-LeOyZ;b<+sCxBD@vCS!yRS(R3NX@V&{5 zZRYyLZLvh7Vux?DyT*r^Z(nU8VVeSCMwuj447>S^HQd9^tieyfky4ih;%#N~h2`;l zao)l%q#wYiEK_vMJDKd1Kbu{C6yg}!_2U*%SQ^uVDUY@igdOvimQw<_oBQm-#6f|1 zlk|m){3*<_S7UEWZ%&;Ds67{T@R(A};C;8%|AUI3=m&nq&ba=E_gXRV4}d6z_0up` zGy7?l_Zt-O-?|RuX#N58pSWRn0apH){$Mzk|Nk0MY0lcx6MnEW-Bq7L@v-OwEU#?~ zhOu!>#|KAefeTL*(tmn}?jS{aWaCs{`}7!aYRE>3C;UvkG04H@4x}%*bFlZ6D{xQF zT?GoJt0J5Q@$m#rKiLve5vXn!9$ZZKpfeBu?jdW8cx#CBsEj^d7%}1>fC%UPrgcBH z7WgJmwqfjHQm&@-je&Z|bsnBnAu}XvJVn(LE13iTCC08gMQAJQifMC&U~}|_VZMbj6q$LuiZ%r1FmIQ=qW5lH>4Z{U5F0C$vUtDtYG{XyKnlxtXh+?&p##PIHY z*^y-&H0+(0SE*HnsXQ-GtJ~8m1Ef`@ot(wtgz)kA+g3lmtIwl@>l2|$UiFrv-#q+T zqa`@92*4r#_yd!EmFZPG4e(a%4OIk zVl9y*%NIe`^Fn5#lP=G8)Lc15Q;+GG_f||DKLkvXSHwD)xZb>#9vx3u;nW>@&#ljT zNpV(@W-V?JCvRZas_ZFj(TMW= zYAu8B++TY-*G$ULCZ^L`b&~sGJ33H#sXK$<`#IGj)IjQa?a#}=Cy;#;a}tqXyMioB zZ<~DY7VLTaUC>qV`T0#05byMZg1yBwJZ$dp%dXJJhHN!fziJP|*9ASk*$lyq*=M*G zO+W*UfXjB=HrGCLOWFnRI8H5=wLe-&hPd@A=j+U!qs8^=;FY25*+w?+1Bd)bNx^!cN<4VxATqCW3;S_ahHOm>=vRlLWk&PZF zr^_hj*Ao08Yf=f0&8-dJ!wajqN`s;+VQysZF5A`oKJ3Gj2HAwYp22bhr-j+-*f&Twbu4tJwj?*>Wxtz zhf_W7=FcmzGUSLujC$-hkM(CAxj$Piv>Fokg{V%6Br6j1NjP7{Jxa_G0j(VcXUz9~ zE9xEEZ}CeOBwxz!rE4uT8I1wDx-Q9CsWS7^Z6;EF8UU^bZK8iyt8$!zW#7z-tvXM2+D0AWiWA$T6$@HqVpr!{>kuoai={N z0$u!OjpU7v%sz49JKcxAK~Au`%dw{#DC4ZiK9oR3hr_k0zI4 zMFvy|tT~cH1q>{Uj^V3!(XU4Jj!WC0v_7RbnR;hy3>gmh7jGw0e55(M&WdRx0oBI; z1JHvL=-fnf6cR)PXj!DF%&?_~U>06G9arX08^NiP<&1k3E8+Dm+?e`|g1K6Ot5DhO`0fl#G7#oxzxwLQf$NoHy^m8f+Y{8%7M^BM%1U+N;a%ep2#M!%q?S%>%5m zWE8H;KBSZE1ryTc0mzAS6f4C}R${sa9Xizq1{~-swE%WyD`s8A^YyK>^h_@hjPXK! zkwgWJZ-l0WVe*@mO5k?~4sG8R2kZiYb1uu&$s>->?YFz7HOb{Q5w6etMmHDC)9kV6 z@Nb71E@~F^ARyp3C$Peo>dQ)KV4vpCoMqsZM1}vj5G0GQl1^xsz;HmKA$Js- zkfuHYprzZPmsSf~L_hMu2UXneD)~d-WuA8D1DWC#E|_UnW;m>?%(3=M@29K^Ib(gkO!apn;$5EIo*CjR za*)21+}@fh%iKY!5l{YMNfUbdt5P|iVTIG`>#0m9zxSfYe6NL^Yih}fsF@;Rl<;(# zj&0lw4m>mmtR&`01ezpFTY|JK`17$+GhDs<;K|uJlG}pm1g;8FrH)hJ%&g4(tN&T* zoqG>gMJG+cpsGJpq5$!!Ay;pG1ydK!;vdO!j)hp@u5F%!K`fRQ=B*-f#lI9Wq>jVhKY;&mCn~~zzODS9 z8VWY~->RSfeeUo3e`~0t|5HQxSK?h;VH;Cz|7lG9Sw;aU)s(Sj?w1>euVOpV>~iNt zSfwmeJVYA+k4vCha}jmsQd&Om-ENaS<-=m7yLr|XSk76}d!6y9I?Vk7@L6hD}{aAei0*VqGA{UUmSYD>hNQ|QI1ooNj`Hn{nT^ATV ze#NGI)<{=+PdBm5{`6q&36%o`lcGMM+g?#WH4-}dct>)(-sQT{;M7Ko(WZ3t^p`4` z6Ey_$=b4%cYh7>G3K2=<;Yjr(6=GEaVm@$7>_8E@*LipT{C71$%=a;iw$27H)YV`G4r=%DQzzx%(K0Wxd?14z>MEW@UrKa zrlTr$JnU1$h|q@hAee9k)T#B%NB z1hS)3lS=-0S*De@+e|pN$a+;#Ts2jEoFnE{0QH8&sy=e9~M+Ynkw+M2)FIGaJHO^%iQQ^N0$UFG>Fyd)q5vK1kk<$ zfr7pg58jGY>PrVJ4BICU ze znuv+5H+`HNqD*Sa{nEl3!!U)-#$N`n{>1;KWtxLKuETOGz&C*3Qqro2GoEMs`c*N( zl0F&vPp8s1E)B`Aj=wN6*_fueHms5Kd9Luu7-xpjXnDCYC_h>xClQS_b(okih~sJF zikugNqHAB%&70)1rbtxH@KG5wrfpVjBuj2pE~q`YIb_zVfx#G3tXtw2bQ>q0<%ulR z;@ho0>1Jsz_ZL;>z&d^`eM$u3d^8CmMOIpnz{gFN2MJ9Te20Z^CD!Gvy?V4DoJ)J5 z+Ham$NTLE{XiF^Bw!5RE)f9~iyh)o_c(FU~3ON}SFn-D@9z2CX@Ck`cCGtssO>aYD&jy{ zm7r%7%s-EyD!#p;<|oft_6Uqmo~KZ{zp{}m)&AngN+LM8tH(*|bSp4MNjfVlkaHZ8 zJ6lJXT4LgWU++t@Q+Fq=6`RFo(CgA2(AZ5lCG%=_533c_Ji5#Egz4guQs@edw5k+0 zAWC(lZkqq-1SR}LOKZ6SmS1QbtDWYNZ+^c4g-8`dWNnL+j^V(q!D6b;03Nt9ngDJ+ z*`e1PugWJiO4q}*T>&Nq@yS#4CKR!ni^T_H4})0yCFqc#o;!rX`~i1}3by&)9>@NG z!o`N3J0+2~a9;t3?y7LKo|#W1WmFR&g*=UMort(t5<~IJN z!Ol_LsiczL&Bln+>EywdPdrqoWo&GxWZt*We%BPot7<#uOLhXwig(eEMOBID56sBm z%TJmIK$)MppkmMZ3z{nxsv2o7onNjs-4RbNTE+AY*3T!T+RG46c773byPxyqct8rV zdMEP9=Jg-Rt8zDn39JKb2D(hoOGH;V%kk=|(W4f%62uvaQ+x=x{2u@}0O}pym**?eqgy!Dz;6>-QZx;T|J_Q zdaLOtvTLTXM%w%J9@?2Tn zVObsd>u2_PS)w$9&*vO9R&!!8$Am4k5+}W2yi0JAKxb+Hu%5CyLEg*e5{ZXf`2=K| z4wekxy;`WUlavk8Yuyga7L6JOe}Eu8D%K+`G-^*Z2sMhifG-)!7vZ}p)leE?q8=ak zI}S#>*$rrCZNhN2X@hI2$fs3fmb7i-FUWCK!JqDFrK|#xXiK=r7OQyz9ojB^&SHq_ zn}`YS4JhgosbMk1QumI&$86!euw&H4p6#?)WUZ)&j%vLrLnq3?W#vDWjh%IUTv^zE zT1CxaM9DumC7`?&%KHB$qu{?LL%iDmzo@x%?UbVp`@c0$8+Q1{bWfE#_*KRZ9sVO?MQ}XXyyT?HIr@SgV7IFlCZ16DCaBdo7Wi>erFZksj5r_F6VKQ1_FVv7J)ckUg`me105c?4HcyZ7Fyt? z@R2*ENRzLwL$2;Ev1E_%x-9Rbx>Uyqbv%S1eUV)_C5jGFfY%1#(ImP=Ao{3!U%(8Y zL~Bs(2c6hYC|@5!JPEsQtYVb2${7VXGtnreP5#Eb(lg(@*FT-=-UByfQ>CzOI(Th< zU-=ZqvE(ImFT6PYU6N?4o#mppA6*vk*|{@bYz8 z%kly4_BFz~YgKy?m3@5>SviRVnE5+Sl)ga9F?Rn6G3m(K>TW1+zW@4=Yhy-Jim@p# z1Og)UD2(pBrU+~O_s|I5p9g2;ByOuMvFc`X9r+h@8_$Vd|Yjvch0=x&-agjP`gl^>T2^5`x z2#-#3a_Z6AEvc(cSo%%=&cY&vfw}%0%Q>4~iJNKT8g)k%!Vaejfr1wGoUvDmXCl1> z;^j}Alh0mf{&qq0Evm`Ph}{+OWNEN%Tp{vs9e zT$#pe3Htde(GtLnrk9^i9@rCp^?o?2Fvasp(DBE~yK$w0O6w_?g-+?(-m?ddB5XsH zY-k4I$+qX+Zsq}~^AiC#E?kIJ!l(BJCC&`Kg_l=2u_}^&m(*L+G$+hTk~vQoYi!oq zXxFmqv*ehnjbh)A@@Zh}zPCnAY^HoWq0dg_VMm4ajmdPAC8QdhjV^on$Mf^Mao}Jv z4XJw$2=v!I`9S0Auafgr>#Umlt@bEj_Lf0)5?YU6S*mB6;G!Gsi&%-trkT3E%EMYvb#u0=y3wety?_v*;FFLNJ)^Wv-Gqs@3|VW~^>A zcz~J)i2auYT>rs;64w{Y{We_2Pt&t4mgPdrcuuPw-yl%#qWdUY+BS5+5}Su(a$41eh8EKOY*^ZTQI z-WlPaOy+%UNMwYz(rFNeGI|ZRv0cx6U5LA#gSCQW`4vC`(&Gn;f5&rVu|icU`!?|# zOiIUAI36ZB63tu;D7@%-j!7KD_2!l02$$96#Tv}Su&>XFVE?=a`)X2%ZF*!%KUR{4 z5?`0X&jL%cq~e&I+A^%N=(%)#&;8KbP>GVmWPp^R8y99=5!!B9=VjW124YWBMl!NC z&U%zR7wpA%rc&)?C5t^C!)baoE|C`x8R=elQ}-JV6d%;9HriD71Ic>twmsPr%#rIK zT!{>uCv?kVrwWr6Rq55)F3UsIGzGtYBK=D|TKgkdLs)~?wfMu^rjMe+Tg?bs+Wa~C zURQ&8vZT7&<^40DYj<>Dnnc3S+Fuz{-R`=}Q{%gSzl;X^cHtP{U$Gn?#wkXcezsa8 z-6_e`w5>A5vt*KDR&x`&ckXn5r-IdMpF07^s+)xOAR29I%jj1|4_VvrP72@g-t2@l z8jL_MA-`o2c)QxqTT(FJMEUNY_94L}5hE9Jb0wEahb)63u^NVB_eP}(_Z*@1#NvU1 z&1&nql-(BBSd~frrzyTmLDk_>jXsp899P?ybt5)0H~jBIH#J|jheGw37`EKmpKQ)4 zdYH$E4{kU^X(RP*i_JMT{K*&0NIjS-)z-E3F}3w5%1KEkwDG5ds^h z8SkA}Y8H1U>X$4dVt?{*o!V^3KAvC8Q}MwW2n19djDUk)-|aciK6()ptj-*eS0Hi3 zSW4|xw~brWqP;pLMJ08}i~Fimihw)+hlkKJ7_N(RBJTzT%5g=jZO|#gD&583QOp4^ zWuTxQKSlD;bq))C;_8)JrzR}wpOY+9%)*(jE@6vBAXIKTdcWfm>AJqugK=pkp`EK= zO2f~P7t$QCp`;8l<=zZQ6@HY#8>=Z3LO0#bi$c?{~Q}STK-Sy=smW#^XC8c zcFtYKaP|*0;BPc-IpAEnw}!8`;g)|Hz!?G;7FG&It>~VeqdOw^B3wV9{!LIANo=s*8oirfq^?y zhi~PFwSg%24Mebi)6Umkt0d`Q{zxn_#jrsV=wi3Ydw{%sitwI^2Clb03vBRz6J>e#O zjq-s{aJO;YlBQqD&brXen^a~M|=<@bCIF?Xx9($Hx z?${o}^!Ed&97tk_!ln7wfrJ%ApH__2qUUDgB_nLV!ZvU(ot8*uK%{DtF1Qnl%RkL|U9wv%$0rzpCgyJf9BK^oLN{dxhF z{ZYSogWM(5c|=beOAe?3L_f|?#5WY0A3OPM<$xzCG_;?Bi z=HDk*7p-wlm6v4$wc(oh9z2Gd(x)kXriMvLuy&?nQRQpHK}cfF!7@g1(fHi!`PX zes##!6R>FdS3o06J=2#K13!wKirxu8V&vErNUY{^Q9FR$Q&Kp1KjdDtQ>xpVy` zGW?kEAE%soS&x6y1nK}$PF-wt1Sqe2(eZaazGw5k#4BA;rh>`h#nU&B-nGv-rndyX zIu@BOeI`;Q@V|&V%ceHNHChLkBBekJ6l2PPnW`P zRyC2i&n(?4NvEpA5gROsK~PeyuZbcsy#~Y^I=hJ?Z<;wKkbN)1-S0J2k1{+Q4$y&p zQ!5OOlq#ElkiYVLYf*mYzCk7|TUjSUN91Lxe=6U3h6_O(^zUXkLF~4_c7S>NsTM2| z)P{8kWUWb(DcfBVb+)erF)T34o&UdkhW_#@U za+p3>P1|iaT_2D}^9+<9yVk5o zkkv_<5JT$LC@O~!svf1JOZT(#mi!DVP1?Lp3*=`7 zKb;g{mB?!fRFe|;+vmln?|AAYFDR&Ki!o&Oh^bGPhvn}&A+^s^{%ifc$F&Fo-n#K@ zi}@+k&_JL2iBcuy73r`Sni}4nZs1FYz^_?z_0C>J<;~!UYPC`YA2GxvqL7bTB?ad#R#o8HEAdR0N*Y-oSs&c z9qZ>JusVH)9(4?BxCD+!$o1day~ zMdaqXYMDAicu+o2j6t+&iGp`|3M;x%+1E_8T^+X~%<2}>*!JnhsF+khurc@tcsvif zxl9&d+Q_g)2>EW z|4;C)%FLPLpelYVRQW#by5#ygoFdJ(?t}E3K)WV4UaNS@E0#6)qOHXd9>&{fcgD#A zb7-YT|6HMC{`!kvn?|&Omj$mI87!v6+-CT7|vy zeWexL#UOJmgS}Q=uYkX$bls-DORGO}JZDPWOH=*r3ssOzu4wXHLV4s?c-h{0p(;wf z^kWrdxI%finyUy*ZRnbQV;NBY|2dtV)P%~!jsD*q_un^Pl20jXHRWAl|I?0|)UJPk zTbjdvfc=br0JiJ0b5p#N?k7dx!2gnw+BT=@3C;%!cCwRV{s^N=UsQKaOXNb`3rN+N z$@;d7uoHonDqaOJi|17s!TksTs$a7fH=a}lykrqis@8D~lLfHO<>Tc>aKCheZ5KY&2#+o}A3hjG^QLJf=-MQ zsXS?VF-Rdoy9z=@o1dezFL^zrlKWKFoC&oPhORd!=W9lE(xV0CU3Al@6|&|a;fiIC z9+wPp28SyNE`aX@|Qz~h8RE*j{)uTNvy0I(}Da!W*PteA4|Tj?6O%^(v*Eitl&@} zH3>3wCN09YP3Qw{?I`OMe%Fbw*7a5X2#c5{8JQ@5UIli>jTSU1TqKo$B6uZ> z{HgI7=ezXVws=kNhM3k?CkHa=tg173Ev%zG!ra=qeA36%~x=-hEg(lRmaW+ zVZ?4V8;$6)x`P#`jHBAHycK9+>#49pntbX^(Pk8_`#G_=S9zB8gyRDjm9cSH5~oLt zdpY`X4^LDL==rcMo6AhI6PRyucAYRTsE)b%W#Y0T>rnN8=%YQ2nO;PXsMEL@+U+8{ zQ-yeSO=1t)F&8HT5e|mfBy-RrcibqddzJE{j6*j)k(0a5 ze)P^@`|iREk?{AZ0yA+G^-h6DadO~mwx*Wyg@zc&~d$r z@MOoj$TVxu4?ZplgcK|9A`Y?{o1 zu_ADb8-w55_$@ctB~Dtm_2pS1BrjYwaydvqNh|8N!(HswOwrY~Ym7n}z*-4(8Tu__4~S<)O$7<3hQk{Lr;kc{^aP>@FMm>;ESqaU#)*nF5Z9BC-D zh1H%s{-F5%TyOewOJ#5h03z1KE20;c61{fjx{zQhI%4wPhdIpsnIzY}i3-c1fc4>9 zvl`o|)z^`h9DGE+!I0t5>)6B_{n9;C;uF6Z-MX0I#nH0RKmPy(pq|DGZL_2J zY>8lE0ccs00kT;7?D8O(Zwj`P#!=oEi4d4K|1Vjfn6?z_COJce@hp4AUqpCw10_ZZ zdNb6{*7TdTx~5Lhxt-Mtt|?C^+4bvic2A>mIjxLRQ?j$)1|?FMw6(+YpXk-pwY3!~ z-t&qgH`TL_j*s>f6D;vno%8`@ z>m9_&okg0FXm1)`))3xf~}i%Np3#5R{i z)B&b3u`^|D3K^0|Q$oS0<-gZ6EC@D$C3mdXly`FV+BumSjkhiE9H5t z%?w@KnJM$vd(v5e8*QJ0DU~itCTJy2iW8Q&J1L5{teG4+{i;;*w)h8fcnGQ|lgBYe z1h937_a`7fM@hU&8;&xRv8!QU`sZe*itC5>c;UktgC#vWW!0iIMSa0vT~|F;WG~1M z#={bNg`d;ns09BeowBINpplOFZHbzOf~ErJ4NGbH_v7xjYhhNsKU+y|zhlwt+f%eA zKZDrh{M-vM=~vHrxL9WP?jwChXtK7A5K{xE8=>xr-uyqnF|6=0qWCtLcKO#aY(gV} zNI8821!BlfE_R6v&{98MHa#bC081w6TM87&gl+xfqy^fgyI$h=`TKe+wu(bcu zSU2*4rhJLy%2zQ#-MI;VFlRsfMg{kxbO9P$v`ZL$?-9M%SVHF;uZRqL`I0_!yGr2e zEy}QlN~||=uUFRn|2yNWM+@)#6dX}##=hYH5ti{kI7l4Jll~_~hyROaY+Hhz#Dz+b4bhYB>vmdEYGREX8vh1UbO+4;*oqqUNfuXp?$guQIx5tkw-X zlh?|7N)(dE(M64B61L}I&r7z2I3(N;U%WZ`vBEwx)Af5uMr?Zx%|PP$M21G|y>V_b zj@XRf?+;O}Ql&3y*r{#l-0&~OMY?D>$EB%)`SQpCXP8Y?=?eubavtZ-Xr~gYqcg zIOy@4vGeQS(;~nqM7e5?;Ro&Kf7Gzkh!H~6*-1fOOwfqXUV7oR7%eLw4a}fBWbxtZ z3QPq2vG;AnII-BIG^0Cz?l?wd?ivxxn2$^#n-tCrREQ~2OzY*5ou%+EvP+6G2XwzK zLPxKh8#OHR-NTIUeA(>THdP#BG1GqMdYn9oy*kU6>rL||v?5dEXZDR2KGTuH`~)?i zkvrR&7B{q@!(d}z#jD-R^1XLhIMnNvi2_k!>#ml_^q?J@(%+VmD@#Ybya4YV@&l16 z^Pf;bjUivEZGk{sjvi$u7`YR%ju`8MgNhbj-spB+_SI%DHBu>h)}>&$)TUj|Zj5Km z1-47t?NgsZ`!Nhc?~{ajdS73n9M|gZbohQ#AGd#LJFg<+x@R-ax3`nE6z-z;y-;N$ zRrwBpKYKxiqnQ{pa1f;V)46Sk(I~=|0T_IBuB}CFjK3? z*~CE|C1NpLyT8!zKuo+M!HuaghDSTjls*5HIOI?aXxCgGEFv&K*BYG0y0M6G>ogwx z>z!OejnebvqEvsRd6xBu_|lIr8>wT2#?)G2+`#J0g>{Bq2`buDca_Osfh(rp$<==g z?Sj=5uXK{vY8P#yB^m>_dV7LD4)ua31=`ApMY|mM1HGko4OmpRU{(E=>l|zj8I)aS zMlt-HQcFDFrH+lqB47@V*5%e{s){#_CD~-vZQ1&5lnpu*d~S?BV8iRzriU7Y6HQxj z+J;5kTD%WHF9Aoh!?@uf$DINka##X%k6pi4&}G*%*Rm;$SLOX(4c0ao;`;{K?(W5_ zYYh{_lyGkM&XgP+eNZR(=Z{r+*^?1$Z)Oyf-RNaya zk&Cp%CBYcm8y>cnD*|Vh8cb9UQD}2L{JIhVRp!zl%rH zpNM&K;~i|ATFB=jEOMH_(0KCV`JN$g(cX za{j$HPCI*92CyM3m8*d^Y2NK4i1?M7B%1L#oc*s4f9Zt7imhO?c>M=OO24aK?!Pb3 z1c6m!eh813wA8eAB&N!@__ z{d~lOZ?2@u1&ybIA9Y=~HuFIww21%%xahvmQT0TgPJ9 zHH9_n!SbHOHzW49h4%_u+-}yb1GW?>VoP-(wXJ)p-=NuySZrBZoPC@qb)nr9QtKdai#cSmy1Go zOS1m}fmo7dy*M?Q^+JDgjW;%{QO8xZQj(jm8VsKE>(5Luv)LvsDIJRb0kFx_y-#se zg2;_hnCEP2vN=3OSpTqnJgCWOPQ4ciWb$(EInmME3J<^g_SVh{7*WKWU>dm2^=i?~ zB-57)RJeony#<0 z&2}All>Q;5{zuzwndi+9gc6u0)8HDcZ1b$xY|bn7ByTEj{7d`}<|EL6$}}^xu2t?X z!IX!qhwg<6o>E>6oid?jAek3zbL*H!a@j{~m;@m~+ba>#>Yo8rtCEt))u!4|4)PoO z@+;Yk09M|_ZeC{;H>^?L(4hG$RV#DN7Kc2s|3lR*Ep>TaqGI_?qVD+9u*#s5(Hvyt zWTp*&v-fQ^Q7+YaG}p6L`_g8bYOZ@n$nwc(ggbn7kopJUf)F;iZZq0wt+U%(tSn0Q z#JXBg>>B-Cn8vGuAJ_60#hL%HL1A$(^9S(N@I3nRnU~bAzDjFGjqs@ft^)N03lLf9 z9#9pC3jKfmjk<(Z{ucn?Gq{p)er8-#g^K;_G2pZO4EkT)M2W)#&qV(JpqW1#=Esi` zoYsp)WqjuS;r7v34k%FYx9}8H< za$ezY55GEeoRChU28hn;uLBJUUn@%rog0|zHKJ06yQB^xKc<{I=Uxl*|Lr?i$Vck2 zd70j8Ow>&U8Iqs7pfGkszlzJV3Tw+&Tg^L4k&BBA(J4`~GOZHgrDJu^(pzQA%j}ec zjp}?z^b|A1KUsF&DNh}*>a>_Fs%?#U5`bgeO0H6V+uFyYK+D?&C`%>(kxef{%vHe- z&ELNuULX%X4u7kbO(H*TfTC0F!LUxd$G$BVgyHzw*; zDw1zIh@Ecn%-hOslu(uN=nJxHyPac()1pmKH179I6JFWQ6q=XD^UQiR_R7<(>MUS6 ziMKe=c~CU}8~bx{_V!GuVZ!^}1)7!IVM~*eHe~_VZJvCo3HYfVLp&CvNK)TiPXjtP zj;h|f0gt3Ai=J8eQ4iT2r&PBHPq8?|HpYpMFY-0MebrR0gb-BaU`}qDt-Q$OvL96i z0kp933X-o2&D%iVJ|L8ff4~PEx3Sdtj8bOxMN9@;Yg)hK#l1{b0t?;t7JyLwXkk7Z_ms* zRG6Swn`M8vZ9pZ@;w5ajAYj$NTO-bS{HG3D2p8xJt;opA3v^`!{TUI z__AfE`l`hwU74%# zvZWAT^iG5f+Cb7YpeA}>tq?2&qA{|d%**^S{5gCI-9b0jCLgoB&f1KA& zns-K0VTxtDC~iper;D>tpo7Oy;f=1fHGB=g9((*vSn(>zL(@M6SoMprS2QlUE!N|g zIgiO&90Eh*OG0z&j`}HPfX1gmoco@cW(UDAS^r!#nS@vsZIO*4%bVgtP05vVjs1EI z1QKHV!02Of*{br(4r*r2hj^NhT!B*scXsR3`+bB5jxA^fb^-ID4GxO6(gy|Z{{Rbg zhnkN+)lXrYI8hfBx3`9pe^`;h{{V5xWWI7-)_mnp;}|zZPvaX1SILv4UCHx{+Q6<) z@ZezHgngintd7;SNOzGh^078Bpb2ArneWM$gZbfIv+Z@nj^?4ji#&$Pd#|TU^z--J zOS9B|<^^a|0d7$n9HJi5bXmeW<47`-5iXJyzG28x@TW@kYw2BBv1i$$y(=;5WY72u zg5)-B$^xoOYxxyAItE~}eW1lMc(rlg*BJR=Vo7G{Jhq`lOoehfEF9~=)mm+O zbUpYWA6vwME}?xePxt-}B{5Lp%bmiR+N;Rla|4F~ORrG7C_5jXaw)HVWrjzKih9uM zNgC>{%?FBz=lW98d|d=j$8s$^;+3m<{g&?-8N#?MtcY=wynU2btR=Q&D0$`e*X|x9 zz7I2d^;h!zkw)ClBsXyE!3`Wyl`s)q^YJP%n}|J|mgD3^Y)|v4_H_N2@OtX!quo{T zfz{W?{2fuKyPW;*aw(D4Y5c&EW;Bnmly@4WNooBBEH zgm@q2vi-JPdIU^-s=J^76@4G?GBtD9G@l2KIXFhqxn#cY@ik(kT$Iz54ZXj#v)17u zQu%0Ekhrdpzjo_^@pNBO?R9J#Z*IYwqfl1n_sB{UM4s0R%sTml`mcOt)GNV|D%9eJ zUD{qzp~StAnUk!0-jRPVRph=sl9&AX&y}LmLgreOJ07mMJ*mykqt(GQ+h`Mv6aB_%lgAk_5LY4)6Q z(ZY&cCfAVBY5Cqb#E?!nq;EQNA)%@0lWfs0txu3axx90NDrVekTAc)wu?SAA{_u4I z?|I01n|%8SVu@aiG{Mva_~~MfD%OY{2>uUlt3S?+?b6-<}vOZTIKe_CO2G|Qp& zRP|V*q+}=9Sg^LSjl7)J^fa3(BbGd%&ngtsIU{jlhU$PeLb?eAml5#)=h}2Huth?p z;LzM#za`{8}+J!7rw|zL)dd9 zkUz(VB0Cdb8kvS8yRSw&H7;D}nJe3LtcLQ2Ygegaq2gg_WD{BdRsfnhhWKu)cH??* z5FAeCM#BooY6JaDfvK^e5rI|3CToEFJv>3^c})2Nl(`s11*9XKAlw3s*EG8Tnpjqb z#sbn^X?m}M9R~3thN+2#V4QW9fxSRBHDAqv14$}?v(TE><~odZiV$D85SrAfPQyYQ z8YW~5vwNGcxj@9mc)(xI3sNaYFS?x{IEE!>cz`wEt575w*D)=Kuy$)2eD+(u)A`^N zBO;%uc0iD}roGb$#T~BZ#?5QV^{me5$Qj^T6@c1_N2Y&tcIOnIw}RV}p( zz1)8(;wR#fLzB+{Ao6$ke&hY)mSm*Zn2DOEG)IQLY?=$%HLARH9s}7gBqxRCX9)kI z+E-Ya=f77Nu0HAUDE8yXd-jY(Y)G{*6V@?)@NV{Ukn7!Gu$p&;lm`IQ7>io(x+&C= z&~|A)e}tb$%bR*4$M6LTQ`}Ou$nUf~MJ3~vzp3#CJi^ruYLiD56iP*4jMWLz`j>F~ zvo65^9-zfvXsTpQJ7j=|`|X@W*yp!NblM|tpxas5K~HWS;C<8_9S!3axy~0m%^6A* z%EcOC7B9xjb7w^tJ|^3gW6ws$-Px@40^KCoa0W5;h4VwW!ULNfC|}D>HPYCZJnq%G z3<#);%@9lzfq^6gTLg}=h1+);K2)%|^Zo!rSr*ubkqdhFfeM{koP&hG7E`@6qq)G9 z3WLcf2ZOkKfiaC4EOA}s`VraBf_>kJ?6(Wg4Yx}d{fbErVVx?&e^qw4$_<|VX6@4u z8pR{u+%@OA3hg;f_t?zJ)UVwevWOZ0gwC{X{jr+;c<{N5SY@wJ(3Zuxw;|k%AnafX zA|+933jQdPT! zX^`X)WA?nDk~TbBdPE?&;M;EzKLur??twjak8VvUC05fLgY3&OgMo?Vg2^B?!Y@m6 z3Y;%DKS&XigVJkh-!y!T48r$>dg}9iQRNLDFWxt49ZIdYkwT@H$ld7@JbsVz88Pr# zYE9|gtA{g6w#q)T=iWF5V&@=|Thldh_ojyfZP|9ik9a>4x#+br3m&>+@S;Eays2eJ zQn&8!am7Wl*X)#i`q7fVWnex#h^TIKuwrFV>V1+7gZQweWR?%Ks&L-$W{BgougYXm z7>DK@a`yH4JfgnF1^S_6b`eMx%RR^G*`n z!MTI19lC50c^74j@Be7B+d_T+E(hzJs75$r?m+%9ihlkI_YsJZ4xp|L!wzs#y3@mP z6_f^mLvMNH4(NZmG ziP2kRa2b8{({2L3zWqZ%Z5~_!)F+ku&UK2vkls&^s$vK327kPn`35~!P$tVFq+t!( z0luOx@FFpJ@DNHDXA zP;>f3kp#;qbK1Y#RsxveFyttUo{oi^1hA zam1~n&`V|Fo2Mzr&sA=YJi_kRFJpHEE(b?pbIM1!4K9&XDKJfirRM4@#s;H0YW4IF za5puHgBnkFvIg&r120P)`IIIrYIn;CUU07r;m5T=9NR-JuBy2qGWvN$$)L3AmI~CP zLl*WWuIV1_$^FOzw^lYJFIWEo5ZX&1L&t&yvM~p~mPV{8zn_Ihgrsf;;nIx++gT5T z>>Lf>Xn0dRffq2?$&CyzhT+nWYgp~Y;J4$7lPU~GA2YL`Jk^m1lfQ=cdoMxM+HZ&d7>G-k{he7b>2Z8c zzXMUNwcHo1_wa%A+NDJW)AJ0Ln3K}E+3srZZPqGW^qHT#*<^ibu4#3 zz72nUBFPpvPW9}0V_C+RzcDXndQv#`uHO1`3+!nyXSslar!emHle#=mueri_g8OWN zbkgogcV|5%qAesjVcC>9`A0oBcMh_(q$9Q6eEUOOWRo*3-t_RbxYN)5dwtEH&Lv&_=;*H`vPw-?pRGiTWygU z?szcK%NARGw)Db9E9!r;a$_pWz*g zElnfNNW*0Y^9cSq%l4Wk=+S)FP=ruv^wu=BS2Jnp%Q!ggI+?h-#N}q-D<^vS`Ub_v z&4>WLV>R_iWI@&@5cH;bG3bw1`HMSL)6>n0X_Lp_+-v|M%Lt+VfjBrz*d!WMY_eb! zxt<)dQ2>jlP_2RdGaOd91hy2{Nu!9@jDi+ zF&KzICnjUhQsP3Su`8m{9{Wm3KrbZaJ5UZh)hyxPRu&kpNNZj~w|2Vr>9Ti3jB)0B z_*10?y|@_kunbxQ0EZm>^=s{J;E}_AkTIh^;Zsc$dG~(K=~=`=%g32zYZ{m4vvq^L zzeZ{6{oN_)3H0ktkDvV}{oJ{sa8C-OtzCT<2T2#KokN3y>LEjEg&_f|fr>=3an)u0}S_ zI-iTP!+)S1sN$R}8_qg4p-y8*Vafj|K^`?;9r^#KkQ$m)2*-F06!$Og%b3!5gS(yv z>OtBwCd|Fsl%wZf8C` zNn`Dtmtl*{f~+GG3TO2BPHXeO&#}_-3ueK zN&ci*G8~t4-IP8sBwT+Lh{$Avsjx$-bC?Mj+T4P-=Z=uaK)S|0p5L zt>R1&4Klut@~Rhbd8~vv2FF-MFmFJF`oOYOJbp4Q@%Yad()E>e!$PQwP zP+Cox%^}++fpduqhg@}Mp?p+rQiu9P-LNx*ez}j$H-JxrWdr_^q|aVK>DyyDL-ysq z&&Tai$!muJS&MBhgil|5{{c@X>YLP@&x_QI>yG8R^*jCs`HzfeZY!1^9f(5)quPeZ1v5Km`vm$9 zP=m{@zAk@r=9we4U@Gt64|UQHLX0*=pbr*{I*~g;8@IC+3#hkF>}2WXR4eNH!b?KV z`WFIxHxsdjUa$e2I)3TwS{40;c(nFA+_5J^gqXUo8k9{tORm-v$?#m4@!@yxUI zv5Jm_XOOZ&yD`cB9{}eeGRo3X%r5`#Gi+^EO>jbiYn)AT+5NVZ`S*BTaTCE;$?p4Z z^0J?}9o?8>=f;HXB50=lC->SZzW(a6O<;~v`Lu}^cY#g5p3gH*7Jtdd$deYTX65Za z@+M+f(y&iXfVIq1dEmaSZ}66`+$`= z3}VxchB!_2JyLwchC5r?_cC=3rD^&@IG9Ip*Y8bv#Y;;oAWssdErrSP*_eXAN87UV zQ1uOygKVLyCIz{enh$htv+uw^_FR|5ds`iZBW0e=ZXEso){DEQ% zB55S`FrLH{pYGrXn~sM+>1i(-X+}OA80PMO`E@RS#MrhBB~x@X-B0Ge+tF3HWs{Uq;Xt*y5$d7_U&eVJOhcivg$^zv+=fHge|tZ z2CibKS)&|=TBwWEn)t^u`L{vb?H8*kHD-)e@;DK=0?ztQe1n%aKOmm}sm7rsU+JY* z2NYH5HfwX_7ov1s^5s^nZ}T6Z8MHX9;DO3=22C8yRiIlL<0r`L8HI`KqD0tu7e6nI2@va}6>3=wUN?$Be?hCi9V zulW9k-s&ebSehdKL^mEH9N~#?WMbm^78-d(Y1@eo?R>DSFo1A=huGmp@?oyvg2@Z7 z3bFNJ1(n2JWyDP#COb{JcL!mNMXB<7tQt`GJ>!;+r;l;chIdGtc_SBQ@qKDqcD;-7i#$sIpT?)-nyCGWTOKMvdC>A^Kg2;_ zhS5Y&T@zW2&9`eP!iVOUCm#Do^z|$Ja4mdD`HbBIl(_Cw(`&eR$#WGg6huOF!)f3Bmij&vvIN^iI+rgHC7&dZ9ZhWzC_mr`2(I zcnfp-p7+6CR0k}m6{BhS4Ei!oAT2I(&;N+PJ#x6e&UebP zrxU0_=HrOLR2xTm=i1n}N90|b?@lRc8_RUn{f{LW5nMsY8R!c*zj;fWgDsO+!u6#azMJpW(LT8JALR8BGW*MH&Yb3m`u z?zmfO6r$?Cd4j8Moo|>(oA_-QE2Jwi2ab{3`5(vnG_KdhC}^2mp4+_;W0ZyBG;t=I z5AwON!n8KXd7u#Tbzcodks>RU45PMzVxyG0(-F+m&iu8DT}5dryu^k0(^Z%Vl9uIp zM4_R1zpUE8{!E$+Gzlxb0RthUUZ>=JtokZ;1a8- zCDB;|k5#2n1B38({3bPWXG#MdN+?7NN-rcpQZm_blDmS^3wUpXiUg7sj5S^o@DhP= zhb}vg>@nlzdTl8*SDJp2dL<`I^cJ2ooZyzTe$*}@d2^~5MNrL|Uhsg5O|$E_ivF2y zc=mq7z1!!iz{|Glba&?0!mIud-(4|0P~~&IDLLOV1k8c^)byZ?$9-^1Gke_rkq{v7&mVYsJeuR0KhQYn7Wj39%~F6#SO?V zq^eh#dK=*`8TFuAe;Rt_H7fMid*3wF)`2$1CSDmMM^C#Pqo@sj^E_?$KbJ^-qTKUK@gLuqaB zI#~Y5BzBXpJGzbyCE$!*yGI{U>_8+LLKm<1S-a8YlQ1vx%`}sAaapO8F5nN}OiKIS%fO5V>a6?iXl?)r9x*(G^ye%ZeKI9WM$>r(X)*D zoY^xOtCE?YFpMLh?@3iolY2s2C2(%O>qy6%*fyOh)n4lDeWvAN%1We@mwh78?#OE+bJ6?8B*lMht{ii|0?qO+K)>qMu3bM{vu!L*FY&l} zl}e{6_44nXX2L=uGAl?kNRd2Z!~NWknOi)K4p~1~7DxW@^s0$A^C|iL3{1>ds-ADT z+@-I-aQ9j9s~%X;F8xE%wpG?xisDJ! zP>AF_U9yX1uSm$H`9FZ)ymIuyN=!V-)N}7z3f@8 zff21LTOj@pP7Lloxsca{Bt&v1&aUHcU`^TJHdgMg2gl4Z@N-2hN6k5tBvrDXt@UbL zUz}Z6U+2WdHiaMrL=;v)ck5<0TBF}5;(b4gv!PWHUEBQ+z@dL$P=XE5`*X;BS!Xty z+5QSi0k->j!CApVBVn(OUxRAe84JQG@($+CGUNSWOduR*Aev zDebNEHT7+z-J61ug^lFf`i6AMDZjit;3=`(+#m3FIUe}j!37+*@g*D1hMnnt0|N}( zG~%WDz*DtiNBC>JBqhK?8Gu@!j9Po@y0lD@?MgwdX(XPaQ+vd`NL1cwm3_%D*@>nZ z_FM3eGhQh;N+VXiR-Y1nM^#{T@Hq3(KXWEdjZfp{=c6>?|p{X1pkl>Kuj5?SW;9cx%XYih`X?@f>6#zfJslk!;f_$^upVAB%oH3)&jQc^^prb{rj= z^hXIxB)*>rv_Y|xs7m%U1+Ylnx*nmYcZc6;pvSoFD*3qQ?JIfZV&=iQ$X0OFXM&z@ zXQ&A=6c^C?Xg}}P{9u@LQIvsdNL~OjYVC-#=1-y(WF#ym%4%5!@DEa{sbi3R(@F#~ z1>=p{aqQn|sPnH}bT|ta+T?A(S()j$48xJEZ$4VBfmKR+)&iK3d2$SlISB9y!zoK; z6ynS1ZcYqjvsmz}8ugg8nC?2uq4vSc#uSeY_E9!Tf*aqV(ZaxUVM=^oT{8kN?-jE{ zLfQ8Ro`C6j>QOm6?$F9|o1+VHHaBle?-!kP3)ZAUU0lmFrNm}!AFd~M<2N@S<`BQ{ z8xQzr5+XHYxSGn$2p2-ErjKrLwqKW)CyCTR+rC!E`YvXCCAMQz>d@_q(<>*HuFWu= zUbxzjFmOUE*!O{tLEKlXjY6;7z7Y7#dcx=A3k~v>as`FUlc0j1J{SGaK7s;@DCi6m z1~o)<-ur`9WtDps6SG0RVG2NA15yPLuiY3Kpm1NwWnT%13X%b|iW%U1V#rYF1sc7R zcVQ?j%4a*94~8j8PYVJkDv5xV)cM0Dg?3dav{~gb-i=XfHtvwE!dZ5q7l4P2M*c3v zFWV5ctXTS26?HgMNQ_ZJ%05t#tHTE)VTiyrf;w|XqK5fShv%+5(6H|d5;srKuRXk^ zPdzQjcA|+fgqS}LvUnu)tvCdA6 zzN;a1S+aTs|B3(J`yfzvqSRaM#ETNck+qu1teSJ~j?(CXt8(?8S%ptC&%J0IgkQ!y z_bk8K%18t<0APVMiuPX$@y2{QYji}o>P+T-(5jZJXH7F6JQoNeh-;*{HO z=XgG5xa_!AWjF3Q*!yNZ)2`!_s)CR2R5H$tgVI}IbdxE)SKur`bOPUQ+tBy5G58FT>78@-7Fh86T$?~& z%N1gYri@V`km|CLCD~n#$c6?L)2qKhNox+3r_)=7QDRs`dFb&Tq31-tGraYE7x_nC zTP3Nw>sdY?YxqtnA2A0D_n5E05q#F?k5frkq87B@PIYp+6pFu_en+ER-rdpcnd9nY zWtQYt67sgTEKa6cldx8k_z(F`J6nz5!lV!#yZ+DT7}ltI$G((~x#*Y|-N;%8*-_UP zp-NOC5}Cf73Fd;LIOyseZ;gPLxJ{^J^EtM^15T5kIB|C>(?|c9ZlU%1e#3RK53ZK! zXy%Z^#pBN?8=*}%bAzGTjuPIeBAmRM(HJEx0v|v=_yBjEZ^U)O{z|37C4;?_S0fl4 zFI4H(0 z1qwV2aX$V#g1I_0fmVgjGIi1iH+A&Z9EC?d24}Nof}aN;D}d(mC>A5P^Ia4Ds4k0TsRtqF82YAGMKQIK8GdlcPI z&io(Z-us*F|BwHU-BMIhqgGLhQX{cv)fRizs#POOMNnebZ0uQLli0fyMN5qswF$NN zti5NiyuaV;T<7`^K0my2PR_|W`5~|K%H#RC-|x435cjW?EihU5a%RCA3M1o)uX#A} zlRzy|?( D*G2w zjPBwi!e{`KWX~l&=<6%=ZL}JJ>=*V%9XAV4x!x}~?>~^erKaBmyK$pGT2jB?{3|yN zYJY3H>Atbg_(B9}m{*eD(&RW)6Y=Y_l3}{?&2ssJt1%|KadP&DIQccmS3em~yR@-M zIqVcI!Ff)z?R18E%)v3P=TVe->-5u9$wU*TvZS>Oo|#1|R@(y8ifp3w&j}N-K^^yeN`$TrZ zG7wHfVzErr`}9@Imv#Q<5I=~yRIS4e*pDw zxhr|4l93W|vi|_1t=}EmZ6<&80d2ske?ARsb4anDo2f2#m^@SJ{WKw94@JC^_na4RBJK$rr&(cRjnA1rxhJ#c7g zn=cZ;XQ`r==myCtx>Nrj9z*@tKkP! zHHb(6Ln?(_y-`^9Avu!5w&@zG%OdSJ$6g%|d0%jw<=S=eYJnw#4Wo(5NEtl9iw8W~5wNryHM zx_4(Atn)g}0+R~Ls@m3ea#)>-9^&r%G11B^I+1|rbaG5bRo%Jk_!iNCu%p$#|+NKOkm@LcFKS) z{CODk)NP@T?C=eCr^jSHf-l+%AW0gD%vW;QK))VB>N$nt*7u`IIGt}@Ho0S0KJ>=1 zm)S{VNB!Ov4hgIk0*t7jrvWtWtLP8gBsCQ0;%xfMnLHtgkDQ0{6og~7;&&eH8pFc` z7~pms@MhJPCR_@*=sSkj#lwwz3QTSD+~>|7pG{I72Q)FunQC4!N}fpTF@VEMZC%5sU8m&VT&tYFINph89)l!1IYD+ z>J7qH@I8sMVnW1zP=GbIyaSuksU#e~b6TZ7tR`tnF;yj=Q(UERa8qzCp>hoxz%5d| zd_+yZNm4*^$16DNNPllH9=tj!dlY}R$Co(nDjnrRD|`N-;vH>C8T`q@jM2Fliv8PN zC{>q3@OZX};VyN5gTibyvgWi(Ia*6HS^)$10*fJpRSu0!B}{IPwa9mnk<K9dvitTcFl7u&jX|Eo!^?lIowxJYIu#e~GK zPipIBIcX;Yu!fTSR~q-6mHCHg`+OFxTIXe)YtwAVe@ygj8~p>ca?{pvzK+wm2+T9N z_(lGD?onbF;2p2zvAIik>qivi{BgDVA$UCA#;lV!d$>&4&=4kBiN+1kVAY0V&Hb@8Z0? zH^i%O_uta^4<^mGL^SAYbEaf0e2(5)U{$&nVqxIyUXYCw|qOhL>RZb!kAx zW0#$l?LMjBg6Z+C?3>dVOL_-O0^*xk=kZzICF3BTF8cBE)u%E#Z!) zp2!JK22R9Lv%`Ji9QX-8@nSETN;Wl`%1({(R%$e^f?IbIDPnOiIFM8qm*h~}QNgBB z+z`nt&=H=2#8z|#Zx?gzGHuyl>LSr&D(IKuxd~eSrIn>(jt#a1w{PwYZSnKR0g~Wh zoNDB7sb@bdO=G3ab^`dlP?$82cvI_$cE{K|lGN#h@2$$i08 z;=%90I@Y~_=XCUg)hk+YW zfeTzo+;=|JH_z9sfTIr6nP#lN0(r$krelo=B(swb$e**v%r7Tt-cMeF$}_F!%}OEN zJ}Bq^CZk_YGeFv}-2NTim#quZPnZr8nNFs|C|r&l!zl-Y8nZSFV1XXGxa5w9J`R*a zLs6H3K|i;~1+`5{xDn=Y>Y8zA0KfMAwl3qI^OB_VCaHa5bQ01~K3xm4x%=G~OgB;P#*){fB-+uq`Y)$c5=mV6e~$chm{J7%(*=R8ARBA)_<|{7 ziC|j&M=4};&o<_QLddVR1+U9)$2SlfL^6MuQfS3HC^BDLkNUF;oBViE1xdxU+scZ* z(^aCa>7>zB0{pKoPZmIe&7nEP23gI|6kplJ{zj${OYX&if=)rYt@?;9%aR9)W{=pV zhFP*8&-A(v3Vz1~xr-oi?Ob17JY4)$4vlR8?5?KswrK7JUkXwE%GaN8{c@wi=TaA}lFv z%PHLgGCcC9`)b%Phg<54{LiKJeAlDTXzuCx<1o3)iC@qFZY*;4yhxuMh|j_+3cRvq z1jLkb0k;?o)og=zbR+bdES)0B1;?5Ogm86fSn09*B(W#uPOV#oxPIhJdt@g8HerGL zf%so1(Nyb&`S9NN=40H6Qr^+E)vuWno#l+Mf9ukQvX{_*bC;X$Q&cQxWO8j*;H?eG z%aKL^6QCifT?1xa)R0mC2#wxXZsvwD9Iu@HsE%jFjAUY*wipQ?7yQK{xa7LrTKW8K z5be@+7Nb|!lR2hEBEzT8b#y12aiwmDh!m#m3k!+Nn zD@Gka0Sy@q@v%Q!W)ZOOlnO$MMwdRL@z z-7g%4j(8npy`Z7N*WaUl>a>u~zo1o<5i)Uqc+`wHj->`gF^KwoH2{cno|V;pdw6JY zeBH3zlwNDg7V|nRLf>dw{xNL6_bxErZuG@)f+ao7~`!U4_`AOJ&XlLa0E zwunj@7iit*2uD@EWL1CV6sQZ{$I#ZqH_4{aob*WitexsnxQuKoi60r< zKL6=DZV`Mt?N_kP8!Ww^qA;zx=k7$Z&;?V==(^7*Frf?ntQNpSzZZXPFkA)iP32q> zw>(WRe#6K8gAY8o1>4e@6*wI*eRptV`U z+^_2RU6!SK7CvFbD<}yEU0QS*OEBpPH>LWFDpD&nk7b2_9CeShBwUWwW>0Ky-S_0OY`4C2_u-d{*(VWu$x>C@WBq;+PvF>u#vYxk>n)}WCO_-3 zyL>W@xsFNC%<$#4+j-XR(f@h<+Sc!d^~yON86)qyEe()teTeb#sFg(Kw*OLUOH zx^?Cb#@U0D)YOpy&cv`lwC&p%WDD-Z&FH}f3hUj+9GB13{Gp#?jypr+c0?s5kJste z>_`r)1RHHADLM{|%vwUBe7Hot@)uw%BwqFOS&CeXoTS%*zntW;5U>oVO}xFk0-m-u zYB%!*aFs~Vv&5_JDT%p%)NvjnF7cMsxE%jnv5?!A9AL1|CPP4Vrl2VWJ6BmV7e6Gw zVBMknPp$b9^dLTvlm_)!N~Sn4IFOfd9$#+a<(hfqp;FrpOCTOj1$o=TeNwt%ZHsbN z)xP=qwlCjBcH+lrWBI#7oAa=rLV9sDZSYDtM$3_~sDXm5{SGtSIO5PTtsmIm$QmR6 zgX=5zx|JMbx}Q=}_E+u=?P<~u%CM6{oNV*90@T7$m>q?vL!Kcqx9|YZcOYM4))!ls zV}|(MQWwGlKX!JDXWAd;G{fS4eSbF2PkHmrG~IPK16AsD{ra&4*MZPbzYpfRp5Xw5 zIhb>}Be1}^Om51_)yq{E?c*FjVetK^;FQ$V7y3`yk!jaWa$#_32a*IMF#+*{>DNZm zxfl8-`kfCTq6h1BKaaK-vfv~4=hKX&Pl~+5;y5L_DqCGl(>yA`63+Hr@Vg%E1HEz~ zhdrK~=jRG6qS!CJ=M~5T9=D=2lK|RX<#}o>P6zs-q>PQXz10jn??Layun3rH9X71# z%{(#*vFy3>N6hr{DYD?>#v|jz{^wtGG5|ympuy_uqLMrnO8XWOpE88{_~I+8+PTk@ zUS954dV1#VT3Hl&Xi=LC#0(mdxB?`TB}rE3#L0l z?UknIYc25kgaPv{kAh|}%P+J{1Uy7(0}SF>Me4oQwGrB=bZm2+_0?lSP&XE7xC=$i zO5FF(R=67}2Y8aT~_Xyhr7BWe*3&(C}BFxzKEjY3729n)WK8gRbc5@UKh{Rc({YXsw{5trXXaWODrrxXhiuZM@`m8_8rL^(V%7N=qqC*0gmvQzhXL1Bj^dAS8BCC z&FM6&o1AOTg$+8pnnf53SrqV5gd(~JxjmN*Av)ihWf>;voY%WyvD#$We8V9soX#)a zGm0|k@%^qZ4n2!`l36K?@&c7Cw)(`R)izma2J#+H*Tv|QHo9Uwc-qd2ZPGcJ1WOLH zLk=s(_n_k9dra`LV40H4SRo`FX&1YL&6I?Jxq*!U&jBewo$si9vVDAnUXH7ipuZAv zaHJMbVe<8u_8Rz};%GkTskFWz7@#~Gs|=wI5{fn`7n;w9*wCvMCaG(Y0NbGB4qHm? z(Y8s!YT-lb?~gF}bcwHVzjqhRv?!XrL7z7A_?h&(?*TMPjj`drkuDE=MM{Hjw^uzs z(5bnBzhyAkZ^erku#cU_Jyhq+LW+N0r4F`G&dN90%6R>pGtHCJK6yRA9$2I{unC(s z4l8O+wuDqJviN=D22Goqyi8^POz0N(p0PSUb1yBuJ z!&x5nJ-m!1i@_(8?vA#S%y6R8^Ua-&p7cShh|-GcIbNlmlY=XQLcU^-OhI6I`_!BH zaVw+FnsmvyOTtB9N5-6MWqjy1&3R=H06_~d*aQ@A+@n&ag6lSZ+%lV92gi0(aNGQ&qywQ1~Zf~aBykw(A{`Fl`J_T+1Q`s~6W>bx$3gtpQM-C#T38C>_s z4(!JJ#<4Y+y&DG_gNJG|*@)_&f|!!DGIxo;2%6MVIJt|wd09Hg^J|8+ayokZdxW#@ zMM?gW?fb>6u`ef;e%q26ai>C6<9ZmMl8w{`g1O>GlTBd}>=(GhJ_2Lb++vNc!#$r$ zG-et^%&mWJW#~K>CBy4s&-dLiiQ5;T(#F<;2kI<1v$~WUQiZ91j2fTw$eUnY?Auku zgmSv`W!c7pZFJ|4zN#h-NfOOMhoKRA7_RZ7R!MO%i5%G48TlrW2rQ zXKR@KJn2@`E9UO>)mSZb^-mmBo-yI#Gj7}Z#fQi|N{5>2NRZ|9x0*X(!|@-$Jy#4G zcj+Q{#R#5yBt_O7yc%DW^oB3q%?F35>*zF5;|u(0l>AV9$NV^f49tRn*3OGzy;}R~oYteD7#x-D)Db(Yuk;dr!d@rA zDHS_zm(4?BDpATw3_GcWnKwO}y%)h|tN{FhJ6er4UalTU*BLjsjw7dAcM;Bg?uefwu*GHb|np?%+UrdgT zmdoOMuq7)T(bzOrPhMo(O}sa^6BfZfCAi+Iy&N2Vy%d`OedM?G+=wmktEJNiYJvF5 zK9#2YUwrKXp7%KBBAjS=WN>`7$&(7@O>@y4c&S~~+Jg|lWTeQ~x!3yP6oUQ|RmKO0 zjj79GsfHg3QU_s5(KAv6@v0b>lUcj-242oW^+} zA;`5G3kdV$RZnKH18(+nN8x`Y(3?@UZPYg$4ksY=9Z&B-{KCFti9yZ!d<*hys{qU| zH&v0(hJgg7sbp2#Z47+z&~#AY=*KD3wP+<2s-E=Am3a-GFZ>KgK-yg-JSnUt~uV< z=>2|p_p_eWk@s#9z@5sX9nEi>O82@;xo0UWSk)DAR9!=kcwrSZJ>lvo^{Zn|qP{p& z&Ee-LwgD#J5zGqMR-SA?%mpYaIc%4U7u5Ayo>@eD0cj0_K z{NWK4SP^)=o!LM~fEuN|pek09WAe=JQA%$8ZkhCdG@e>y>q(%O{f%1rfvb4mVBEMwyRZCZ%uAAaB{`)^y9c^STJ5k3 zZ6;0GlQ&nSS<>FQF~f3;L{JZ#D5AkrX&={slSct5)_zdigftYZ9^YW&011r=rF!Gx zyRf;?_=3MLq>#s}@5Cq!Hj)Mm*x&}KE0k)RE?TBvoXZYG$;Ufpt|oc;3J;`gb>e*k zO;;;QWumFiV+(aZtDd81E-$i5r4dIEe(i60YCHXIWRFq^z>C=jqN z5=Y~--Zgp~e&f{B7rTOofxElG^+gtFYBGNUOPYn2>x26(A6WL`WUk=Ke}Mk~%pb;T z#X&E#n+AOU-^r;JA;n4(hZ~e|uG>xN;s2%kqv+s14tLQ;a{lDfxN6`7(I~yEEk%|@ z725&jO^gmMhO*Gt8cN|57AHG#vXbvS{3GXSXwL$lM|;KF-R3lUrHVg3kt)>B1t1$y zCqAAs;=QgS(sIJLPV>yz+==&(Mo;2Ih3XSp8&S&$edyF6a=!139V?cRe5w|yY0O*2 z6;OnSqD=u5hj_fAZ6O z4YFO=i(-(4&AIB2(9hCSIiJe?cLsqm5Ptz3;aAxc)zck2@H%$wRL-pd+vk0fSqWK^ zNRbJCPkL9Ekt5y6RhztwPR4h28PAf#PrK}uWNJQBsfyEDx^QUWPHPtUH8LVPH5M4@ z=5$MLHJ6g9xd&aIR6{l^pbxp5GBIw(mK3!!>u&-JG+RE^S1k3<>CMFymZjU0tfs^% zm|>{s#+S1xP?F5D{v`@>!6*vW+cyt>tS9r3JZY>*9+N;5Hz?L948b*F2p#cuSKdnP zV*MxcUjR(FuAfmR3iqNJ;NAo4A&50MHYHtIL-P5#^_vFxe1_e9vDdYLH~BzV7X{etL|?v(f#`}_Xg<5m`~1)&bCc`;_+tO2HdZ5Vs@9f zp3n%(X{LZuD8o(%)Izp}YY7JbZh%I%<{yuh%X7`SK4a~iHBc|NZ9+K?`ZCqI?N~m` zc*Mu)(~Wy3){i*dJ+2-T9IMI^yn7@}vdrgi>)%X3s5_zrD*QA>%~34dRH>den4prU z!tai?HIi@uXBg2(fD3cz8@|3$Svc*|{bC#{u*AE2I$%Gv93#rYq1>2p-K@p;<-DF@ zp2WMh{fnkyR)1I7u%-VcrViSkEGztq}_dkPP>APz96 z2*G*3F*wDiR@s>O*yFF`+@K7Pn0A#6oJV9|ItmT>^ih?NKNiA}NbQ+CY$nTuPgIPn3a6AlsiLFwd zOR1>D0H|uuR(#&X7ip7JN2SyAUmJ`C*m9LZS9?WE@;Aylh*f>a5`L)L8$<~V`Y~B( zsZlQ|{ME0A-gkn23YSGw9yfQQ_VH>9#C&IkJ1adFW|NmGfo+W@;clm?zd~x{82s#a z=_>skq}FVnD1pMLu<%|Es$=!;5>42k8ZAVb5Nd!L1k>SBPwDp%dN33|rCAwLQ0fHY zWsBzuY#G>Q;$X}brlYwc^K=|*3JJPAGzkr)gbljU`n~P=A^o=1=ypT?SR$)GjtEam z20~T|_%_VYB1^ zqf0vWUZrQa0&U5X)zfSpU#zG>sPQ4PyzbT+2}1~=Hgvxp#9Efk+>~lAeDXUGqFV@K6>mVOIv=N zeVjXzmyZ}A3Nvd@@1^te3-4cM{ykO_%NJdHIGJ0HZ*}~;B)olb(r4v_>r+!lfS$~d66>t^WeDjG}`uxiRh-Nd9E=5&zvwX(@=uIsktb;$wVTb zv?RU8Shg2gI#kCl?5$#ohwC}EE-WeDkEeTQ&JjNaD>L36{tR9m&Xy4!5P0*2;JFfc z7fn{5(f8MkL%%wR1_l~aMOqE|nzk%`mz`h!t-$Rc@~0 zR>ogR)A^Fq*XHFB4%6BsXz@g_#f0^>Y~jwI7z68l^CKgma`$KGnr4vR#?- z+SHGk6p}n~(59r_ooC`zEYGjky>!8CXp$}6J?=PlFK5q^w0{6?b?1kwt0TBJx-Crs zX)8)oQx|5(CoGcsL6@vsVCm&dagr_hrKV*|jwha5{{ZtK)2XA5=_>DXm&x_32{Ln$ zmFcezek|eOsmnNQe#17zw^}h?Vm&`tl`Hg}VUlYB&3gjv zu^wa_!|Yf9EN3hHsjdfkYy%c#9N5xLMZZ4>j*SLAKx$r(ZcHc5$KP}8hL7SJ$_XMg z^~1?UGW9;G(BQq?($Eb*Eh5gnufl=U?NTO}W&{L)1)Oq6hXv6CV$vtL4s?KLLF{rW zQmv4UE9b-cRu)9nJD@JRu>#8jibPZ#L&ABeaU;8AM~2G z5~8tlH{T8ksn}zo?WF-ceo@>6)pv#yFG>Yt_MpQtPTmX?K1U%J|)R=Jiu0zbr4-Jnf=!X~(HREfp8;6EvI zfffywE>ob>P0-|VBTT?sBRzQEa?O_cSzTk6cD)CMT9?gEu3uqGv7gFUvn7EG?{zv_ z$lDf3LV`?XP6!ZoiFmshQYe-qtdZlwG0joVu+znLU zIt@%cmYwL|S++wMEVzZ?uzEC+P| z-y9eQm4Dd#RE?N2Af?ayi^iCX&isA9^dWJQ3XjPK-9N7JV4QJpIO5*oM2I_Z7dX{P9WK58ch)Om#^M zrFdD1i&y$sP5zOxPA@uS2X87H_Q;u5Cu-EuenD2*=4Dg}OJJ>HJH#c>cirQ**9}4m zTXk5=?s6~teyWJ<)mm_|c<0BbII@2ZsIrO6Yr9Y8n_+mvcs_1BPRV_pAN=en8iWct zK+QSE{jqi!?@z^;@ibhkQs3<=l7}~@&-s}LHk$?bt?Zl0NbQQ?>;}X)IIeBQRG@yx zk0Sn$dCp&6`1MEF$wbg*-_f_M(xc?`Eilurl&toN!OxbqaCzuRnhDeWyq6>q7Fv&9 zQqIlv{*V&2kus_?mSqdZSF){Fxn}?F|0PyvHTj%9`OPfrPhq?*#E9g6US^4P!T9=5 z98b38i3+BQW@5rmUhDDW-ZR?q3Y2rd-AWbkl=LUmfD&q^9CMm5#Cs6e=DzUmka_6$ zXc}%qY@dNEPs=*Rg^?ym8mFC0?YYH)!&5t5W}!B*Z)_lHd$6q~vS-#Cs_zIIIqe(% z0-O1O`15nPLx@ikT1l!&f>v%GoV#4@vhXUus*H7`TdS=tVbZZn@8|6uhnxpY`-r1X zS>jnncD?blSZ7m@JqJCbDcxwlT!Kv=`8^&%q0HsjteqNVj0oLNpnZ~TUHS%ECu~bq z4YdLcjUHy>#wJEz>8s_wLdt`m_R{Fnqmb%~Y8Rtq6gNB-=U^^ecrR0jm~&QZLTe>a zqRTwfX6dWJUfge92GtZnnvWpDietmb!)mCmsxVxSfu4ieDJIs*cf|?C3++L5gD7!X zn!Z00gEFPG;=6hU4$*pyT=V|VXZ?B7IV#vBa0SyZ$OWrSotap8%3C+_Gz=)Soi>=a zMKKT?_F0&o-R_nu32-kN@5zG@vuRbTH;*y=T~?|A)`*!J8#aP^TQ0|h+$MevKKB|= zk|fobS)Fuydrn^?I)N^yx97{xwlvuy*b5RO<{anm(v2L|%Ri_akJM%5R@8CHmWS zs9sHn9z7}(vE|_%pWj0Q`pr^5>Fq->O?%_a^EjsQc(OxkuK*DjtiAA)yVDe>N99GY$%-Sf0?u3AHT(x=2+Y{OGKeOd3Gl)LDey&AruBNq;@1jxf%lD%gBzKo8z zhmHghJcA{Y{O4%5i`NoD5(5@T+!&-YY`L+eubQkn&(TdEgnl7DUNs)?suE{RRqWw; zbyE^oZZodjX1$58#oIACo>RRSw|xiV-oddefk0WgdEXbKxoLyOx3nq> zdOxrcjYGR&Zz18FeadQO@PHZ^)dx1-J*Iv0VPJo11BHzpK;+dQCXcd)d5&?=Oq8<} z#yCu{(U1(IUg7NQ&hPL&^|8h3%|%WaqCigS_4$ z_)ZJ(&OYwZ-rxk&{19(4dw={c)@V|VN5mICx)bBc*Vdm13an8|GkDi1sOKE>|5(WfV z5BQ8~RtgQOFgxGx9DVVF)tZpSxqjHyU3B9Uk69OA z_`TqplpVs)C8A;aNYnkbAwIAy?(ULiR2jrP#O?%}P(?j@=~ZQzq*@o)$`tqsfqohB zp0%9&02Ht_RI|b2_;)#36-N%5?OnXSFS{)+w{JkwhP@DfA-Aafg?CRX(;Ie*9=evO zjQv2+pEGCv{A#`AXUKj5H#N@hRrM#Fi^jd0L#P@!S}vvEvV>!kq-#US5t;_s zHtR8c<3ZMhr1HGx+!Zf-rw{-{uwLXu$-L?b@GqhKu^xdshxu5j6-%87fbk>H#j^X0 z(`kM?v{3@xCBP%-^Z;*wa5MujKJ3vRLX@ly5;UXkT&e>Dg!vnjHM$OKFCZPjbd=CdMj81w;@-dn9Zy9Eyx zp6@Nb&teVt^_>Vm&wk_$Oo7J=JU`lMG}yE+mxnxPlx9I;t3D40I!ssZ-q9xi0fRd} zf@&)HH1b~cpyDx?25O*-`7FnTDB@PhJlVK9&Hlr?^I^ z=N&qp%78!WCqJ6VmeKOMdlCiQ@h=3Ttd^@e-WM^KX|3OJRtqY9(ni~1jxhV?^waUq z%J8OlJjWJgkCGBht`>i*`|rHHa27FTs2ggmqL8CHnFs(JEL~0+WiI*@f#Q}rqCWB2 zY~1>kWk{5`8o$p$18^7_1#JG43@nz|zC1l$yWaf=2f#n$j_8)Jdg9A7a(9+ztcN?e z?8aTnj*jdTVasDd$9%-L^#2rlRP^7>C-{GNf5DQIaTjF&DgHNcH)U8?ZZlu8^jINH zikBEuRNS{du4@blZT;fFvls7QSN?3VMy~GiFPI;Sz9kmCnJj!=#-u%be z$(8XSP}B#+K!hy+B^p~7Zo>MUzC@m+Qc#)vHIcMOA;;&*#l~Tf!GsIV<&&S@Bxo;q z0NSPOjS>vf-hkIklDDt%LTApbh3;MjwVR?bD|D&C_|JKRC*=hA4)`uJHekfc4B~ z4l^>2a3_4A;prYhcyoSSk59-vMrtLSknCG4`)2CHl=vui$r5h6Zc1hPajzw6g-p73 zvQ8gqs_!<7`>Qvf?;t;Dj@St}eSFx2!7-Ojw@|@XfZqHwsA;1F(WKG&^~AQSTv%sg}0-Ug-N+wdNYw zr5>)ZZvmnoZHEoTlfD{Lqu*E75-&_W%_Vsx$Ww&oU=+bX2)P^=N2zzzE_Coi)R2nU z*yr@EB~3Us43iGq5SrwfHbgU60}1HNVfWfMsQhuTUS)CU1~m{k4A$vWD*ikrn?l%@ zTGZZYwO)|WgwknKAI5ML7e3O^uN4}Nrz(4pIbNy^)3GDaGA4y06W)1q^EgDKjp#*VJ`!h86=0z%PHLSG$|M{;`3fcLp&ZI6O=RK6QBzW;d3o zF5{@bOU;)yQjHOX7G>#F! zmWx7dI1HiyfFY2pu-EaMnDkL-00oh@2rLH@YuMHOSO1xfLF{@7E%PX0h%b*7nN=f|D)*r5a3#ifB{CW3$ zgUaDHPpLWak_nFO4nwz>SgO&~ru3{3f48w28PqiXDBgQgQa9tX@k7;$uO(YV!_%Sm z$b`nfTRNvg!-4M)B=sooNyCFXPa{H4Wb~JZPIA^+uNwD=iQJEQF%Rz!Ds#H^zk;&b zu4~x{Db|~=TOVJT@sFpOWaJJ3O&EyEQKBc^OIwx^OIh$IWgg#}l0O?**-d7fb=OoX z;3%bp0-VavZxv`&Q+@BR%qJn%aNQY>d&#DAz4aKpwA0EWM@v{doJvzM!m=*?vZ*i; zHbY~d_9&iHS+U1T$)^zQe8#M0;stFUZDlrd+A;r$s0gum*2b&?qK@fT0oran1DlVc zu0fk@550UA{qx$^c8|qC4`B;^5{GP%xjhZ$P^A83Uug2_fM>n;n zQc8~O3d8y(2=`B4;>9KMf3XPdXzPg?1cu2-Sa%VWZKrjEUH#8_pS`Ks@}-Td6QsKjOc=FuD63Zbz}@5mNdAo z(U=v(oL_=*O;2yY9!{_iPcPr;UyKJAxJLiX(ktd;^84{H`L9={5`MtrU-qr1j#UFv#=7bRV;To(qrHC5?2tIe*qy_^M<+r1?v$p9B#(Bae~}N( z${BJ9($Xf}{@hoab3w}#WEV!WW-g}w{f>U3K)g*((ePPq%h!0auo?a5&2%Is;?hQ6 zA~G0fxo3@RR;)OX%?01)OdnCmLRO3GWX!oc;g)%K^_116g+)I&FIA??k}SdRO3tRZ z_i}Sb5)`(~d-hU)b>l%#E9TVgzSV!_KX>CJWtZ;iT>&{*v>?`>cysjfMI%qEJy*10 zZJ4DZW1GF&d^4gH5`cZ_)&tW;R$X1S;@&gXuQYn1D$j`m9qRME5F`N zSe}W%u25eY=c#yvG9=>epC8=JW8`B>xuXL>Rj)w=jl*OAHl~4 z1aJ8gJ=fTkzcGZ7a3J+?)g}S>@eSBoSkmmoD?YpDay+Gy`FmeKR9GDUcLHJ2oSjC$w%BoJgn{FQ@_z^qjx3neuVnq!={yh4>W7qTo2av4WIp*+H%Hwp*;XlCN`t4y~R;u(WpUhJlT?>ck|CNXTzwh;! zC%|>bSrhcdqfr~k5 z3>|(>lgj%^(OQRB=Q^>oFdZqFmW|q3@eu8#dR8<0+fDOe=KeSiyr~1oZGTz z;I=O>e5eT2xY-k4Gn}KCHjqznG<5{Px*H6Dwyh^cXX+;>w&@WuIN{N9&4`s;*iS%@PuRfItUp=R};M)K$t#+t>f1w<&)J$%6HejKW_Zyji1uylSUR)SZ;0+xkCTm4(r(;mhqbe z#59A7l*+V=Ce0Pq`D{ZzU)I}ikh<}BCuBN3aS&z@RJifTvrOH+0Esj8`W+hO$*~o= zDW$c`IOmO^`Pg4k&a+L*+#j$Q6L{m<_|O9sJ%Z9!)l-043N5D$MXn9_vMq`#Ye`PV zTokW#3S*sNuHlNo&B2=S#mv0&YWq69{Z>ZBy>X%cjnXX@M{)4dpa(YPN~zK(G`*aL zf53^NJ-kj9Q9bx4v|{oSxg@VeF~|NZ8iNoH+<&qg&*FLz(*}JpVD_>|b=GBwD>Dj1 zGfMq#M@rvg5O7Ijq#5+$h}+8f>lnXMW$d6bryI=teSt`$Y`yE_*CmwlqEOwrqV)Ij zCCS$EG?Q$~ZKH|~qJ6#bMZ{GX_FI2Xr;u;c-voiQ>;(Qov%P5== z;Vk(zdLq3TkP#P-(r_P;D4UY!VtaOcS6$33(q%WT^h0US7aP;n9(t+Pc9#FE>3OIU zY>n!eB37butRsL8=@Zc9hS%2S?o+727ybT8wIUeTP%6V+M34hl|1@ua z%i9@|Ad(w4!1ufYdGjjTxX03h`zB_uM%AVJov3SQ)M(N-@*=cW5YWF)lkt~yv1u3( zgIfV|Em2fOd+9o>i156!I9q{vXRt0yNvXRXhZ7^X&ldAF2~jM}`I%V7)FWcGaDyvh zsNXFAg*0`Y8_x>uBmWU?LY>E)#F;UPylno5+R7aiH^Ug_A>c)*+_Fu0le6MoeE9dF z$O1Zu{CX3a{^ymeagp!Yzjg@d_)p5;$$?yV}nu!ag{V&ge^9LX0I*`HXp=k_Bm-!wg05# zi(adCv-`?nDaz(k)4qBKklO60*4Ji#@SC{K$(nzF`cqI$8)^e+LV;wZpUuTv*1tgh zq>RDQH$TS}I!Ccxjp|x8ZBku~c14mm2DX9UMs!I!$NdPTvb3S3@yu_BVVAJ)%^e2c zc24a0D^Cpd3kNQ|YB7H#l{1Knb>g_L>^RK->(Jz1`lv;{=#Zv_w>GJTY72Sjcq+9S z{&*?OG^$e)^_uoO`B=6c!0$Bx2+WW-LdvkEJ=(Ul85t+ zZ|PNQA)lz)EbG3_OObBd;kc2Yq_XYQ>F|63jwi?C`s)Isnx!sh_{J%~UFqHN#T8bN z(`~wa-7)`6ys-Z0SC`B{C&fnhC$wQo9&mamUkutJv*Z3*>4f{9^t4%ugcPIzzaYWV z(9ZuGUJ(uVl14Lo0ap-g*Swh}iMf48oz{oVvoJ|RYZVyuz#&sN(;lHHA38`bu>C{1vFR01;>wd>xJ%TJK<_w)fi4tLnXQNC&iU?o^`mEQh362y3p-doFT|@ zu&|p80WIeDXjs@$sC)~S0zJE$)b*dxu6N-`luDk89(Q1N`t8(Ip7>SL;UKQ1@sA^b z(4Pp(!i}qPeD@4`{ttj_Ynqi1ojR%H>-;@%W`QZZ2}s#mI#=nokAmgoBlzkLJ|Ujx z;{T5>^8I@j{Mn6Mwn6OBE2HxWD}QYh-!BaP4xld6FVvNTMTpb5`zB;A;_Ai^ex;c# z0G^UcLA5XyY)oSjG~qIk4@Yf3ISjsQV$}6q`&_nn8RKs3@WC5cB{E} z83Y>JKK3!v9uzSjL<(E z7{GL;4<^|G58ywJKiN_>jYk6Xd`CTHoP^~VMY;eyTi6h_Y#}h`@M9J&o@57vtK-AJ z%OPxry^H!}24W=VT)_phcS>(UhzVKh^^6x-6qeD`MQlgp#)-Y=H|U_N@!ABS^L1rY zUIZ;c-M8L)Wur6!lYGwf4OQq-L8e&0R%%1aHiDsR=Vgb{N?i{9 z_i#@7#W?jkf_HB-&?b>K(t5HKBxq>?YW8s9uErkVtzgLVb7Egc1ik^E?Y&(#7_ zh4fx=0#t@FR$@@edm%cFJ2Df#+=>t+CV}H7WX2L%PHDK2?(Ae zCxir4s{Fn>i&t~koT8rb2=bZ%La0q@WjAJTn^jO!L|rdA4!s%uAX9=TD_u=@h?a&; zr^&*azMr7tcbRlTnWU1oOhq5x`E3ie?HI6I;>kFpMslgT?KqOml=;)YL3-NEgmEFW zXk#+o<*nl#iw<09x)Ic6PTrt>TESJv#ZE9ny@Srs~e0hp( zOn|Jh@06fIBM3G`OV(GaN@)L`J=)GomMO)Pm15TEBaA&=c9CPgu~l!RuI&69eo?yPD@`ZqIv#u{r_q2yQ7+HzI8(pkRpPhpg<515KuvS4HkL{h|)o&NE2y- zR6`R5fk+iX6{Ls)(m_B(q?gc<-U+=ENWN7l-lcV^x_ z&+OUr%$q%XE7!;Ea_4eT)!F}G7uUWmmZ?kC>DedkI46Hj^ed;Dm*ZMe!zXo)lAys; z%A-R$DkpDt*WBv7)A-fn+1csN{-n&fp``B(S+l0SLiz=%2GWQOO`-GK83~7CE0My* zXF>+;-^f4ieH^BQPR^{5uB>y&SqqSO$7r6~ouAp|%2@QpxwGchf=RZ8>p0!W%Xj%Q z@=xZ%Jx&>k{+vhSGMPnfIVv(DJ+WEDL;3%e0(}o-0q)gyh-OCn&@|;E;^@;$nh*>C9cqUdEZ>(LY^$#zZeD?9-ozl0oqk*{(uXjIW0F6bFxtdpaRm|lVRq8tWWpH`}S zQg>6V-kRp$`5K{olRv)n2x6KdvD956Y8|iK8W7U*qQEgps<+gwN5Ibf9Q4Hl3??tY zaPBcqPtM&_*_Dnrqg~{TnjvS<%{i0?Syah6E@36@{x{U!P}{4-U1Oo1T_F!x!3~?8 z43G-RJejw4O@Vnuo&v;zWmxS^QH4;5#EIawdrBbU;g^Nv8zMTavsRc=iFt|2 zGwLO-Fr|{>ZRDqXd5L`~wG(&J{NyPmWLSFA?F&x{p$)A}d3B{fTu-m4VQf-Pu;$^+ z7BwYnct`TIbtn6sv(~9TF86cV4-kx&;_v1k_Gf*tWp6aMt}P?3&dJkvyc@GD%jXqD zZ*z7Sd81y3D<3lORv#xova5p6o`Le)%SA^Hw^Qs-gGjXG59C0|fHhhFiOA5pQIKBGPwZYP(ep7KQn1j|+wt>25o zEZ3~V7EIokdzl-<#H zKylsavNGknj%55T-jsLUlUYZ?!tfvae#DD3C|{n6JEfs~f`sLSa(N~tLet-ujYeAZ ztdnLtM49HQtxPwFY)j^E<5!){^DFg}i+cNoY@&TI24CJ_`h6J+GJ!^NucdZ!9cF1OvSi&;@BL;fD` zc~De0P&Oj;(mE$a0xyeR25MLgsBepID$D9Tlk1^6}ytDqoG zGCD3Q;5azxWpgcbn_{wIdi0dAGF|*g=P6lho;i_tbgr6!Q|%(3N@xX9jZ&QBr|d5T;#`v}5CQN37FY}HO0(itJsv#aos z+m1oShNJN`k7Sl?x6qpQt9U&oMv{iHzILu*sk7fzq-Hj4i`1!}WfdDIPN6JV*yRpjF`MhPeOOp+w_{ZPn8w}$vNT${>>Xf*se&=-Kft-(V59M9b zx?P##X8U-y{5@%lf=FlywNt%-JBh4q+N%iLeoldwfQ`HyF1p(}viuhm%b0DDlSW2c zLth?*CNLtK>V6Jf0QoGT$ep~}uhUlDD|!lg#2fHw&IluoX`@b*E7a`AcSzsJwV-ta$Zt#*2!P@_f;!);uWj#ZONA1DT4B z)3W@*8&|R-a@Mp1Z5wP*nU<~++qtZ4n3hUYul^?|Io|t)x`6lbhTnE%xv@77q$M~{ z*tPX$M}(6(+g1BJiTN(V+0Rc9wF*I8MRRPw-`dpQyzEHsqJGNfva_tP{B`)-0+9+? zRCOb?fEi11j{Sm@Lnswk!BmuW@HB_?_x>0mWd zGK4r`(-XU&E~(N$u9cAFato`;H?s9=*Ms0rZd0+o5~yEOV!d!A}l*k-6L{Q7KzpJjpgnIT>;4_N{;oI>vJ)(|ECo0KZs>!t^vy2x{12-4N z!utY=4wf8c`aHce$#VQ=;SHQGxIDW{Dqn?$?UH*|a8^A$%@H;&bGP)H3In!qQ;;jJbqY;+

BkO13EI)V&alhn>1-~WFZpOz|m*wp*K9CR038>fT~ zrFgzwTlP`82AkyGD)krh33%eNHg_K6(U~*~#o+XgAmIEhj_<1QOPxkWUI)V!^19Hc zeTdEbN07oS+Lu6=;_?YN>kFCP+L#`XB@`Qv=?PXhLbhD=r~8{w?@x zB)gpDfk^6x$y+@C+TR60$Z8To8e$*(Q&E^U;pE%Bn%7D=O?wc01eu{Fv_uh3gF83= z)xfILaQ0}jUE#lKT|0sdYRM2G_x}`s?brBZJ6)3T=Mm&P(Gf%&hW7&{w1Mj=Idt<3 z$dn2_j5$Zwu$md0hbAx{K@M*pLH_DXI)QQb?~5!)iCn_=NJMv~!=B#w4#N?o89``4 z?&*ynnm~TN--wXYawVMO+AtV%x~k?g);I6sEiO!rurnu&*5LR8@q#VWICD_81}7CO z;=Y4kD|wKWX_u`qOiA>u-j!mV@{|9;r+!rgg%->w^x9)x|#wdT#oVq z{cjgc#_{~x$bBlrOc?+Zz)U$zNE_e30!rOe5V@>YP`jnFr|140D?Mpc+a9F<7BPxDtFL0;GZKpgO~zeWN^14xL_pNqL0=IG!|dj3vi9m^4uzrTlDoRyhR>`^nTX21)e zHLRdm@DJHwH{yHF5hNQ;Pz5UT)a9Z<^0UMqI9uQR_&WG~QS=BBS#y}ggXhaX2t&-| zA3>~?u2TtjIQv-345TBze*kp{e%DP|&w>4`JWG=RTC(G^Gu(6AVecMn2Xz0BIDdZ! z;#ej6KQC^Ol(p+dOx^{U*a1usIH_Cf>9V5v_!t1g{M^kVnVu{i?KY)YyPld!or5LB zK0gq<2Rg~@+K8Qlt@MC52I=vq+BRj98c~{deXvP&mlQBc_$W|+0Wk?8c=mb$mI@|` zRBUIrRjhe`l;2pj4uN6dP^o4UXiHH#fdPbsOWh@?01RBknP)Ag$58U3V2Z70)-1{b z2oQ%!;sl09*d`Qo1V-oxB9F;q^!xbcw1?;dbUhQc2>V?~1NxojHF9MHSn4bQmA>i~ zRD%keB|r5>$VX0>q3XMMRy4lx_fxYICcduiBf%_60Ywd@T$XKCI6Ndt%laeD7$E%p z=O#+W_v2u{BrMgTt-aC+TYm!zgL(QmeGvY+qHD%r8ucQ<#jH9IPYYIy*PxR%I7>yj z6O%(40_Wd8(m42#HJpADoki^EH4#ed!RkfCivt-{o_I%D}H` zx#={@^Mg^C)L_Bj5J)&MC)lUc>n{Arm1V^6uf7@b=`3G;>XG)eQCs6}P`(yC@WMIh zaK$c;2i#O1Coe;^J%eHwz_9jtNm9kLX*DFjoXyvQk-2~=@UM|ns;#0%I3WH43qIK7 zJ-@~15Ivwa(N*37JHI$EvD$@P8OKM1L0^I^?AaY6Im@s$C?<30qhTQJ`QSTI^LIX+ zVW)39;ekY6sjA$N!?VRPu94SzG>B506XJl>_ga_6$%c);7$9HCq{3bf+)3|miabfBLmj3989sx`!7iNKC2rQn>7AS*HXMQ_c;@9;$47L+St zSgR$D2=F2S(H&vLTSpM# zKjWsoE=*2PgyADW!_n2zmE^_2Gh9ivwjojYUslf18CW49@EJbej*0cr9}T zfn7Y%gChRgc;tiLyfCSS4nzMkWc><_wbzQ(Er3aX`NYfTH4Jwr(-y~g&b%?&(UuC! zF)q6NaUJ%npFop<23~jYGqY|1xF{eIpD`d!kuD3!E{2j(?RH-^v*vgum8HcL{b8-?<%jJ!eUrR#@5}wJhXjbgMWHj~i zU8RFFu3W*vf|}SaecQ&7gWhKkV7({@*?0i1w1mOCH)foq>d _g9NG51r5}f)3)# z?lXWsnL-Z>-ysI45%_iq;Qk0YYoFzmEPqMyMKna?Zm?C^rEeExg-!d;EpK*-DTUO~ zE+0V%!@3tHPCrBkKd+gG9TxftH|FM^ddCq+&Qs#{#lkM_#;klr`NLLEJ)bQ6Sra)i zx~0LWz5C1VK=6DcJg;Esf@qE4F3hr#fYzMXwW6|qkaW5iT~lPIbwea>(Px~DsW+)Mbq9;sLCnO(IX;{0g-3{eE&wfgYbdL7~v zVvI=~$V>6N9R>EeJogWNDR1=no;FP=;=3AX81%Cs+K6v{YTGVp$h+VSUbHQS#2vkH z9_w{2fYvHyFS~38fsTb?GjtvN65>+!ln)Z8m+v1IqFytiq4Vw;+|}NA>g^3S*h(uf zUfN()6inF%Gi*}{T;AiN-emF9BsHsc^rnVx3;muP?}5slJA&vy2`UI|%Xx;UR-vZO zG4f8Pv)8^MM9c~F>WE=rD<5aWCR1t_L0^6i^_?E6cX#;R+}qJY$P7!V$hqoGxbKMp z=z0{GpfF$yYl@o4Q_f%rlYmGR2F77@X&<>OY4*D2KZ6yur0mDnY~K21UE#~C((dWd zU0_C6VytIkvjR~zOQ>CQoD_!eCgZcIZ~Y+QDZ>Q^$0q^4BJE3 zI}kfy*`1XJl69Vy5uDED_5|lr>m_fq?TL04kROtYCX$<#2#PYywLUwkLJX^_RSmc;QmSoXsCpfRo$5tKcgm7F*p& zU>+u9{=pW$XLbKRAaS#>UwtNjdC1%D_3ALG0GPu+&*s4k15shW(I=YxIhTOHw~AQr z7~c{3Q>_aKyVQZ0bGM0A#yzmj^2`~ULHCAA`YXeJIB)BS! zHj=)4FVOVU_d?9~jk4}ER$c*_1ClB5E3K7o+_o2(27*Y*?cH*Ft5$^@ZX zTkD7!kD~Ku=3+R>Kh%R-YM>Ta*a4na%5wB{d^K3isAS_H3@4R6$(K95&y1F?^@%6Y z;=`|L_gM6#h3H<0SlFzhL))MBeZFy$yBe;we%CW7w$$F8vG;-63}$=OKxMr%_@Y(c zu7|B2LG}xVKyDgyo)1PZ6RK!`GT-ffJf=sz^A@`=LZyJH=zT{)r>up zIZoP@(6eh;2SP^*PaOlQdu+@^&-wdo5%zf%qS~ZIOYIg~zg&DxZA+$qYKV8hTZcZ> zCG_6w@9mR6ET!d>JlJB!Vc*N!6h-<M%iIP&#=!!ai8#4 z)7JSVd%_)aY-TrGe&kGxOtYWe4G*-u`Cz~WfS393Z2blq`Jo4xDX!=6eB!k_`7`2U zP>UsysIXU3vtPN(Y`t(VYY(<5Gk0*?Ij_cjCkGeaW10Xe2l&Fuq!2y75WTSnOW6hFXYVV}p8guW z5BA|!2@kJrfFVS3%U-vY*-F&QL3{_2X8-1#PhU>_O-8fbZL7ojo%~BGKyFilQk>#* z9b+U&egxKoZ%2>}uLC^G5CviEHxDfoh515~)4K_1wwnB2YGam9tR zw$14&zXDG3{tP;9#n%uT(zrBnzlTzMzb>g@dwKhX+@?X88FF1y6oB1cEuusC#+j$Gqh&4 z%P^dj(yr~cqw`XhE7etJ4E&7{OLV7cF%;Z&`-(~ zl+fkPJ|$sl=r@C@N(G~0YVitRD~rWcNRcd0E;#9gD@qe!8P8&9+A~UKo}2Vl=`<#; zM3B%n^%wK;xiZY;MI?DX$q;8)9-JH>8W`W&1&bX5zSnh_>jN0_Gw3d`;bC6lc+Lay zL*mDXbynDSRQ#{Y0{u%A+G9!nF+Rtb z{LeajjL9)3{}tPItS85Ma;zuEYwBKqCj1a@2%Q!vzY@1lm_xy}Aa%SlcH<>>2dj{R1fZfuP^UL^} zz?N*!V03#p;$FOJnMtkR2rW+{26YxBw#om|yuN+zV*VBTYt&+HQc-E|3UWxIV1Xfc=_r{wMu=&16W(z{lBX1s+f;l-jLF_CyqC|g$uf}a z2@6I*^SOER5-Oyp&eJk<=}Mt-!@brQIE(u0n(!7QR(J-nkLJA{g{lqRD4(Zg1ckK1Rx8`Wm60kXE_*IUo^gNA-tDJQqcF1p87yRFNtb+@1~UmK1Ceo9+oFx)m`FK1RpV=4iC%H}}3ID~vFcSvc= zPljESjG|Wh%T`Z@?%S!`RQX)C!G|$hm*YNMSFY9fPw#vKA$3XIkPmOrpYs>yl#;X_4F2q0q+D-4L4zb~IUTga zOS%VBP)kGi47p;M3gsehr+R1?XR2V zo0;b?5Lc$WG3Mlrb_D72FOQSs);zeqCR<(gtnp##H}eZ*mZWrvtB|OH zM7PvazHI*Z1U}62fVYaqu{>IwD`N?Zvxiw40@@*WRT=iET&{k#k z9WJ{-!5P$Ci(zWuuY7~idV}cUA~?vO%1mn({?c&o-YF_Uv_ywc#Ny??R`>aWb;Zvg zo9z-@IeVEelKN0cq+03yQ_{OZLyi*QxRgvGEZ2M0nk+v_g_Pz%IQ2_f3Nz<6UOgo zV$<**RR`5o5|*os4YHKT$xNE$!G8*Nk4d0V^+h40$+b4m7cLARS>37sdy{{tvA7bjPWlT6)LIm_H*MjySg zH0QW<@zpB1jDfrpFcc?AR{^Av}F|~jb)m7bGk1@98 z5D`uN71s`0;|+CMt$$X3F*;?X1o<+3!Bb3=ya%-zcJ&CNxBjF;E-P2bJvQHoORw9W zx=iy~VIeUC%ZV%HL@)LoH6c4{z@bkQhOGmq&d$rnKQPi%5>}+miiPiF{Il^%8I$zA z3{n0=vpO9obNZ8anAYA0N8BTu;3P43X0DLIFt#bUP9fQ9rSqF;$S#!ae&jW~d^d%QbudiE{tee!U@ znD@~3f`(xO)`g~Oc-+R3Qjj{;S2a>lzG-2Rx3pUXCn?h;Flpe`qIdQACl6TC4H!O5 z47xK5d@bMA8nK>Op1$*%P~Hr#E;&Kz>Qq2JY>MLMb)o4U zct3rLujO-e-)#x8O5wrpnLGzhQX5Z+zPmsB7V2hfTbZs&;R}s##3}75ea7?-yc=qy z`9wE7{3GIK0Ocz|NDjd}Woy!PAFMs~UD)84qXp$?`*tR1I&@Z^-jJo9=g{r#5#*L_ z^1IUDcfR~@jAPw6GxZ~#_E0EaNgtOwswsPM)%L-%P4*$gvl>TN<6S1$wVLh(9)FR6 zffsv}SK@>sJ2SQ8W1`=mx;7&Z(^4%Xxvt#?RcrTiW_X<^AV(zJ{`yGEVC4! zspV4O?+gFh$DGw{%cdjX+)N$#FvNV0ZNi_Iq|IouG*6k$C!Ufx0Q0$tgt;-+si*%7 z`ox~|R^7Or_???$&J8&n&Oa%QXCl*agrtwDIDzpkz&=5=HH9O{k2@C(lxx41bCwee z9lU5KE?`YRf@EIa!NCb(jBPj8u^lvgb3aGouUZaqmRr~K@fCh1av8U7M$7dLh$brX zPHS}SBb?rB)=cm9JZ~2V4rC*UaXQ2X1NF?B9Gk(2zM+xPD3c-kl#RL(%6{0{Gt}IH zRen3KTx>e0Q8UH_e|k~^JGB@a z>*P^Jws=l|_r%EQA2Y`z zBF#=M>o+=N?^SEYS1Zs%A$a}}V%s`jqH_IFjezN8p~m9T@kS?y^DX5S3bA^%801cf zqSMy33{Mw>A774+4GIc(`%y2tp^{L9Vo(T=Z}%g?hA2X4s2W zMnNX?2Cj5ikb=xve(T15HTK2ly6vLd=iIW21G0-Gh7X3aIF4hW2h<)VL+UfJG~lk8w3e1f8J z@tg?JKXnB|;9Woa&UH%vNwE`ySdpWKj1cG3S*R;Qub&Sigg zX7m;Zkqo`MnTMvc5|p2MljQUXPxq2&YN{n)X<|;;2jlKTl*2yQjDh609DpYBGKS{U z4vyP=W$XG>!t6aOV{0fbSOFLe9XlH(oft$+q z0-TRbuuD+XT_=8y72_0nkH%d1r=c;EpRYb;oaA2DXFe~x6wokBn*T&8<1VVOfNyd4 zit(7?pwgU)aUC(jQ;!m6*qTsp=t+WgE&n1{aQo&FWL)FLp&hHY_=m=ekRXNw>KQu)2vt>>fXs8|u zh(0HZbp5y}E=fN=LU;JHDHyRa4xInla!DqWz^S^{3$%D@1VL0gg>s3UV4#nf07iHt zXC}Mg&hRb&oJP34tbof(iSZYXkIDI=1z-ZQAq@Q$1)P6GE!w@8qwA-|7lB{DfgRTL z-MWcU<0HrkB;iC2h~$+=87H8=tGAzQZ(MUu+%11gNnmGTj1I({HANH1!D3(H+*o_Q zf^Y$frveg~aL3r^*?2w{Q?tx!;zYMOBwBH$?1N-PvwNz=wiOx%M)>f=e3JXLCLL*o zC1oaEow`8&O_867ffzL5*r9oPT?v`#DLSRVg5a|*mr8}g%r5mJMKHlH= z&pPMX_r!hn-Os*juX7mRLuEO*Ir(rH`wnCCaQH!7Ajgk3IPc!QRWf(5bh82pJX_S? z%39mGnY)1A%G#N_nM2LZ9O35T;yA8uF6O58IG-{?TYkmxD_3XjJn4*YNB_|GLcD7P zprc-N)5Ye{$4y{j)&5|WuCMfcsn(($K;!Tm<*7caLR#Bg8w!WQH{1LYNAJ}BN<3Y+ z`958?J@j3kRz95=Uv3yb0j$RtcW#R8%SXp0{@p)a&OSY=dc~go*tubE@&D-(aG`OL zGNeHL>S@*ZXhUL2@u|LTaL1^n`|f6Sb>wclaskud|3MWqsrt zd+MSYKl{z5^mP7eNKJkvhRWQx;>tU5U{UR$Y?P`}F149%dT=G%tc50N^QfrR*cdh7 z-|02+;}+>w<<4j=dz^2`zsvI-ZKJ0{QzbCfS2Ds^Z~QCD*~udCcr$ zb)9&+M04rqI@of3Iq1kO!GY(BgtZG^iN+%lJ5rLJ^a>ZoA2BX-#ihrsjJ4n=(fV6V zFW=MHVw<~$Gr`8?1j04dDmoQ)Lej+$b23#wz}c!bt9Pmw5^>7+)#Qp}M4!ce?rhDyovVPF};)NL~4C zdmR7j80>%is8{GX9V7qSMqPR4Z~4R04sii?ME3m>?pfmr8zobX7P3W|AnY|(dqYSm zJF3_YqjVedThV<>J$>k?o4j%Bp3%tMrRSP@ z!4K`_PHk0U5F*0h$lmv@`^)WL;_A~^f2NUnn8`-ymC4p>d+C0mn*u%k4}W(ZXiCg5 zzDF?V&o-*NawJ&r;LUK&#bbDu?RCZtX~2~d;@FG)#}tz>6>AyNuH6NV`h4XK}Y5D+%Q7!f1CVamp*i!;*`9i01QdOf*Z|4tvReUdLU)URj!&B$Aa_}Rf&c;A#uZHzkZyTwJ} z{ZhZ>r#gqx81xus+p0m!QIv!CP; zClblPGW&LX>=#^y7hEcLM^E;gNrsx*x62ec3iO6bi2TDnz}OU{X~MSlx0svLh(meO($ zdWCmV5p~m1@C6cQv;LN&+NWSREv>G{NI>%KsdPS1OFqN=lu@nz$5r{YCRdzb zQ+Jd4(+j_taMwjV4BYio`=Cd0hXRATl31x#7?!J|Cm5v+e_%xsZzP}*C znPr*2=A>9=3aOb@1V85|omo9k(0dP(1G_ktd9|2BbD*9iXnNC0MYGP$U}>OPNjuI4 zoNyVR33t8o9+=WAR*@``zv+A(beN-z)MbcmVzxqWG2nH^8o-0Z2oN>Zdx zBu#pm`L@2efZp4A`F!>9D+cxA9veZfcdSi+yXE2ciF?Q($HE(<2LZHf1_{3AMr&|Q z?Wfk4)k0w$S%1Q_tYOK%Esy_tE7>xXcQ;XxjBXLV=x}C6Y;UbT14<=%7kLS$vqF;5 zMM?M%BXyZhGF!^|g{q!N?pmeI_pI~@RGVY*?J)SNB&jRFWk3mR=pCVtwJJl3jkI!Q-?ecNfcwlJzsKuOR#?r6W7I7 z%eVW}j_~5bH`Uva%~93~E0k(j6yJxR_8~t>qKXwoFlUc&*+LX|RZ!>UcdgKJZz+%Z znb45{+nFTL>w#b=lyT8x836)B_Y|XF8Z6G^_q1PTTIe7Vw7N~lYhhpB-F;x}B(rVL z7!^rzr0n;CC&5k3(xz0=YCX{D3Lxb}0u3(qyw!o&#B=*8$#=q(#j>C)Mvav|5r@`N zFK`hndyGG=Ar~t5aWXhO@or*0@%(ttc9^PE6bUr@L-tK4mQAp(A+-8}NJMv^e>A2) z-W(0Aw~)e49hcNMR*jk}ziWz$blcS@V@0GlZ>^y2$y*_VZ}_uS#ddzz`))>}vC406 zn&IPyD_YG3!Wuf)Dqqn04>{djzwQ)%frYOQ5zsfWDEuGV5zDC9qErKb>KshzC%5J`b%%hbr~#8 z3uB$Ge0C;S@rORq8Jhb76WHk+IhZ~Vk@Dgg`n8%#k*pF@OER- zb}@h5lhmI3M+|!wW70>AKf226^4GiWD5o!a!Gi(pXm^?@1s%ybHfc(IEZNhuaTl~Q zvUso|X$lemGEy4d<$}bpzq|*^Cwl2O`94RIEQ>sUDvfGN z|0XmVG`G#cED4f@1UV0=NFBU@=Fv(5aPI9Z?S40wuq0CRd{@n zn4uAAoVN0mp%WEjt_A^AfxbWJPF4nfRf&C6({+;HVvF3rcWQ!-<3&AL_a{Iw`6I-7m)j z9E{@ojh2xwkv49kySRDumgdn`s67i9Ly)Uck7~uTsXV6(0%Gq?2sq-mRztW<0e&y7 zz`FLnIuK2-l)PWvNJE7S*jNbUh{M~vRZ?sv1?uIc*bT%v90enST3i2XByU6}P27!T zUA)v*fUrDzqa4Dy^W5V<>joP{#p#MyrR!Yo0UX4xP(Up)MsA%~Ns8lnKmyiPcZb(w)rFeQy4S{>pnZ2mu%NsQe zP4s}e(fCm`K+)Hq40t=iRzRr-YoNB`i+-bl%J`O=nl_qd3?${xs1~|0Q7V_7YLq)g zvx-lhb+7n89F~TBE^m$Tbsw9eaL|`W7(44J^UM1txx_{Y z2d%)nStmse(u%cY0^#NT3C6;5@!e?~qA6ZBzFL%25=pitO{U}1di^Fl=Zd&$0J5W+ z1{(uOX5jIcK$!oAoAJjW148l-Pa_j3h~^BWhmJY zW5xvDr_0hxVtKeTC$p5_V@Ip}*C}+VOrAe`&qZS`b)SFvj>2^n z?3&gesiz$R;xV&|idSOf54zw&_ISxFf};`y$|I)!R8LUzPyczNP7ZQu>JX@4;(>FH zf2u5|NYO}!36zJUVUFX+mTcb@jCv(gkT8VR^{GDPPHW>!d(zqE}Z!V z4=gzMTVoR~y{r77ScKbH(BuPgyHY0wJC=R_c>4M$(A^(G%s9iVwJ)RwEhqt=>#I6-aFnUaZ7VF*k5DtFIU;Rw}+5al?7DfvheFgK@xWiYx&Q; zSsHGTO-O2SDiHmTru&uMpPzoxj!_YK8L1`MYA6enuuUZ}u5*FS{?OH)+h0QH)!yNJ zXE`2ITpDymARozu?7|g)UAw~)hW*Sy1u{AGcYoW(r9x*$+yEmGikuq}8`FG|%;7=a z!O`XE&LV;LZ;`-AoA6n;R(!+*(?1=_?$fgxCl>tqL)2 zMTKIYN!_oV=mhgM%$9Hd@gW=kginYc-^AV?{DErJB`jGs0j zzBzZ=L|cfLB&#J%$Riv}H(unCNCqyitj*M#0R`~(*XMV+C@!8~%)b$@p+?@Xg=zx5 z)INtqfpA8jd1qk%C)z9$dhvGbiVM_Ww2Rz!j5cL5%Z4uJ?w~NWL{Lh9D^1r*#aa>< z=q%R&Tw{r+U(u!36%-I!sZq}YrmT?x4TdKqb(Kp7cNJUw2`FWpvf%uAz2Ym|+e7q{=kiGu)3bTzV| zG4)>f!N*h!V}hnEz^>;+^$zn(P`(jJBrrQWC|Vi%HyOJo7IMMgZmo9ccb=O%O?Wf zHa1udK}~0!)Cbxxns3FY+CMFv z>c4lgz|@SjDVhI}6wR!V0I!fUxS^&X?8U>Jc(Ep$@C>-{#iI2bXo5#n%LK3OE#`|7 zL^H*I79^C+Qt0{>RD>%d9V-ubz<4LV)>!y}wZjyQ_c(K~P>k{V%v~6ly1UYLZY7%J z94pD%Ak>`W;p$yLs=IX#tYvb)gF6!@Kk9vW`G=@W+m|Squ6J#D1xY z21%?WAs7l|`9rLgb|LhV8X`d8`!op!P_zbo@nfcsNk}6hPIk!K%y%LJV`(Xnw3Q<_ znsrON&MTdb*lpKtXNBHo?QvI@ME17_9kktu#Me4K9@H~%B=p<}PY$D3O33MXs$d|Z z&-~AnIjFb3F1iz^dOzw`bsUY#bw@j;TLGpg8^RacZbhmC|7;ZI&e95@A|)C{odDnf z7f*pT6Pr!4Tr<b^0rqw(y-ZaR&;)mH4GsuvH0UG&G_>Ygrzbm@sHNebx+oty3>7 zK}q;W-$Mj|a5?=$KJK2ZEXVMkj`;3%6TUA>>VC@mc;!&^q5@<%B~vxceH;TCQn8UO zpPP^4MUke+q?FVaa?Oi$DjN=FEo0wV#y>VSnX+z2PKo zPdr@a4a*4X*P72{Kml+3@FC+OB+f}|g)^$<*RnC9K!Ro*`o_8^-jq}--tmmX^Ys6Y zreRyQ43PnlU8TReyF>4@!TE|eXjcB?j1O)8-y8wMLQNZw#Hgr)yoo#tdC(5Uk6*2N z$ID+@T=J&{2#YMzrlTOQOGV=)DDmdN`f#r|GtWP(SziyNurj4B9?u z5bkOn+=krR6{{gjpBev-U}5WUa;mxg*0M%~fE)pY?|XYm;5$X5{%!WUdG!bZ{eKB` z{_)m&f#f}>q3@x*$bpr^^XGJzTcq|Q;m7ygUP#{bEJ-0|TzZ3YRNk>VTdi>^Y(TV*UcKK<1RNyIzZI=n7ErZfH8#HHn0ZHNsoa{87A^umk`H8n0b zx}h#{(P@vjY5K4Pb-cmpFD0Z`NrUI=uoydC`4e!SXSg+eo>zwbz)Oh*Qu0u6VT+>Y zHymLAO5@;Tb_uew2t0w{8^x5@ai&wiDK5~}L(6|{@JQkrF9{&WgCnWCpdPRGwfA@` zYSh#Hu0fi-!xi`PA(c_E@QbOCqJj=VLP}~!)zsn7$5E`s%Kl+(>nPsFZScX#RrHY3{w zoRTKI35z(DhvmJRGJFs+KtsGIt(gtf^B~lD5hh9E5>}0qfPOrA6ld#hah@-lUB4h8 z`Z}T42FK>cvmgR$4xi9fmZU8vP*coHWhox%VPI-DJiJbG@y-`0Q?UXdqbO=$e~!p7 z(w*wV?fNc9xUN8$kk!G#6~Aj+N^m=}cE%3k5nWrxGcMpKW}I)t>CV?rI&!VxMq~}h zl%i~&Nlk|{xOi!auJ82k3fa74C-y=%0w$mqmhM8HF`A!Q_QsUpxAGYs>7(PH_wg5@ z+%qE8+#1~4B#yh7$IRw5sQtat_?U*~^ESn-(}Yc9XhI&i;Dj2HPol*tHaPALr`8*} z3sOY$pQd|nW?vnqLz`*}^22T0?iH$0{w%&?s{R8U!!ed4qiKHpSysAy@mvR#nAL+? ze;M$icn>CCxIMi@aw~6ISFrA_{aY1R%*)Ch0gk)5S@<@KgkeDiEZqsl;q7&iFisE? zWIQX32*ToIL$!*9ZFRw)o`8kzgsG-6^LpFQmn|YJ74S3s>Ak}0m-UQLr zyxo7({SsJya4G@<`!|q`sM~`e59bklL~|!22G_frp9YZ|ImC1iYX|+wh80qn@eoXl zAEPu-ObdAp@9zt2yy-P|JEU77fPOXui#m%%C)Sa|RJLg&=N1XzyjKsuI|Od_(Y|fO zMX&n91Z%ZHGG6zvum>u6`pm^2M^x5xLlO#(iexlUxem<*I&xW^<|4!C5BaM6D-QKZ z*1{-q{lNY)wyU_&Oq)s}V@#;FMTDJ7jVBJ-4oXAsG&T06t+$*P)ZYA?rJEu%tNWwNr@E8PajQAynSuyL zfXlyI5c7)SDW1kg;H9Y7L{uniyR!a!SD}oVS9#PRpf~*e22{-x_4>I6(=%NY)5lkB zMUR>^*p|oF&DaKjC%+2~n`iw7o=^Cou(q!UJAu>#oo=_eM~BVf?MV`D(E$^CYB5nQ z!^AEzLH!*sD#g$-VSs&+K&~7yY|sJf5VC$0=@uSK_b=K-GuWQ)fFA|hv#k5G6ABU- znjl_)$Uk#-qt2%u(?uVv606|F1glOu7yock2b^aqcGrKDWez&ooa2WH=J2Doi*hvY z(19<;1K&#|ZRA;iE=+>{h8Xr}bwjoVOb>}e1z+R_1F#JX2O`iXO0kC{;-khTtyBX4 zhG3Zft;s+hIVTYV>kHX7@ZpTPv*_?$kr_V_A=8vAs6y=OIl#th(ANb%zf%M`d~-Jz zM%w>8Mw>U4qDF)7i)fJ1WARUXM5Z#X3#f32VC>0L5OVZMdH&EGA!F?e9jr8Yyy40H zg1UZX_xyB?95+v)zmHH3Xd@B#l}YZ~NX(AbS6ijA&cIXExCN!62OMz=qXrRw{LWZ1 z20maq6Dvqj$AJh`+7v_4&y^#Cl{2F`D~GD)S~7%4+Q3WHYP6tfZ`;LWYhG&Yi&n z@zBy(P#gx6Bh+<+RbH*Uy;7DUChi_~rTkGH8?aAphFA=}Vnn3%y~&jhO&|o4*_k+B zGPr#S8XEzaE=XV;3j-(6K%0IyCk&s-X zAtz*8v}OSDok2<}y3}>iHM3CMq?5#|g`X#^Z?n&T0y&JtGZVu3h*^h@h;%@GIoNg_ z0vzneRy-w+j2tf<-!b-GofU?GFc|wh7-7J>T*x+0ZU7pbAvXwH>cy;-uf=mo{<8Ue z?Vw03(}FlC4eg}4X^s*cg)HW%#-~U`jr$kq*_vL&k5!=N@*}hW+kOD7VHjEmKkfYU zd@$zkEyjO%T&|qTeLCyJ69@^PO9MfhN7P@j&nH%C%Av2qr{ldGMKc2 zQXtnJTOEJbfK|7-G@(Gb)v$(NW287f%2P65fm@m$|B^qq?Ng8T(#+)?)VOf?HP z_w|78(=OePrm^S>vF36-SP54O6-gMTq4;n&V!etX!ZwVPhYRlbNTsb0;P}YDBZ8>% z^g=t)fX=Q0`0O5m8V5D09G#Tx&9*#tDsZ1rbFe??`&W zACLY!%Xd>vGC07I+Mz%!?rL%Y>z#+}0bqH`ie$jLfCwpGxBWYuh~S1VV+#*Qf*wB& zYReKAVeh`f^f(1krFKXVA3~tIIB`iXK0>r*pRf<8IFkT5z3rx}eyM4FTzoI`w((LF zSlOzDm91qNFn{v^;^t&$crp4T?UYCV;nw%go1i!-kEW2$r^PKdfTW;R@h{eR7l$Tf(^ zz;&FZe+I?P=DKr&9Un3)qdR#=Vk_GPnF0FtgH3I%3g$kKW>H1g!j&kJ(2#RkoCyH% z4>3a~4Cv(Xo{br!PFOHkR}t5%EC&8J+F?w&ZTL_PSeaJ7FrOhVFqBdjlqU6Yi$VEp zuU6Q$Nkw6RKL^BPRLFZdqx4;5aw)4=^LwR}98SevFeWZX;lFmgp%>@V)d%C0)K&La zQnbU;jf_ntq7H7lSE-hp>348BeFdB^r%1iKSQ&pjOJ<8jg$c3i(4n0wT1YYhgumv{ z3FBHczKJ)VBzzSaq`4Puw^~j9*_b@SwL_s|1syprV(;C>Iqtaw{PUqgRJ-5+r_3EL zGIEjFZYLrxKeMQyC1UPXc?9J``Ah_X;|%|-QL7E>WGA-?h9zuE4P$I*u6}(T2$J3y zC4|J4pYCA&3FhaRU$c7&ES}iI0wL^j_s&qFYJ<}dOpS|LeS=DhKEKLv5EhM#=30YF z8tJa|#&R>*7Vk5zM@Wv+izUz}+A~_+3FWVjmiBoj4XZUWRpd}4m-J##DvnCbKs>v3 zr7=kcPS{{S5k&#Zc|u;rI?H)uL0VMwT#~-CK{HU8h>8F+>AuiB&5lk;Gy{)sj=(fT zhZb%8r%R#iFh(+{nz(OZyP;dR1E8p%(e|umsFchjnS_^Mm=iu1vZ+N8eS6cOG+Vmo zIeVDuMO|yX?gnmnQ16qf4?P$|#KxcQcfU}wQ77EF%}utbq%aB`?qQl>AmVY^B{!of z3D_$(MA$$MUk=Iw8~9Csx#yo#(;2qllusEK2`ezKz*Yqfe!H!Ix$t|%tP^sxEYwJq zPu*}`AT#Ogz>k1VI#2)LnYi>baL0pF_dC$O*57b>UTs)gmI#5qH9rUg$hW^I4AkFv z_RhqBUxvP+tVpA3$)xGzeZvwCihfO0X-rTRKS)XDg{iH;2Ci19v`>m=QDZw1)ach5 zgBUPXyz9~gvKd8L*Xn6~TkI9Z@oeI{=?cY`2jw2PiJHldUR{hfC#6pw2~mqZV=XmD zIIBc{NVBkX!18Gzbq}jaBVpB6+QJ-5m1?tPE!CVus2C-wOpPeUY+s45Y!A z9y^w{w_hvoq*?TJWw^X9(3Euo30)@7e>5C1LMzF@x zsHC87f!uLI&T0TijCy2nahUpJ@DxLJq?P|#;kx=-**l>1l#_YYaz>t^3n?SwaQ3hE zmtTz*l(1Pn&JUPiwXtSeCPX)BFkYh7TJt-g#haumu2n3aF_!Sjvb27t$i!^~k0vp` z2bA*WDC~7IC=xw<$S;V6h^DSn65jcF5-OnH!z!6)=_7lkHF||77u^Yu8^^7j zuifP#gixCMtBv^8c!mQjWs1DprjiF*yi0QGCxRX~JMmWzhhb>I!y?#ooEG>IVD&Y7 zd{5DN;~2f*{?GV*?2_;<*`cd^3w-KzYUj@)(5b8uWo|{zsBTA#cR@~rjlVQ%C1r`8 z*MsS;WR~EAO{WdNm4)Iu1oglBk~oQ=7}KXQ0=xu2Dd?*F?~EiL)0r{w0z-fHBY$Gtq{>oEGnIR&NAvgyDVS^U)^ zs-nuf!MX;290bGb6)JNzPfeoG0VPHqzTkd}p2%K%@Qy)+)slgbD0C_Vb~M+bGfGfs zkdhTIlHr4y=S;2Ai0SO3F6P0kcmlheqfJ3a3NQRW7M907TQu0^O8UgB#Z05BV(nDt z=#B`Kj$w~;a&?w0?%2;!PD%=_x13`*yh^d##TC(O5?caAZo0_f5I3$r_o+X`PM|1K z6h<_&FH`>shRJyRYLJ8vyH#2~t2)akFL46W8@?=hsfyX3{MAl@AkWnZEed z@%=J0EojShjK8>)Pu4bhfqDvE-v=Q1zdx5IBxThJvMb;#J1XFULw^2h#zw?{YmRn~ zEm$f#juuDp`p_h}h>8qLP$ZLtueqHt)`urlN)oZ?mxz9Q37xU>baHvA!_2naArIVx zp}XVfgMEf)KDjCZ>w6n#K@Q3#{YDbRFllg>QXHktaWz)? zbynVEM2TD%C`>ur%diCw1f>ew4;M3ls^K{?G9?_T2I&ojw(&vzQt6zn>Mr){Su0Xh z&$W>9?fXW)(*wafruUJWHK+tTbdT=Ctbslv>AyBV$^gw_{DmmNEKBH%P-PDp9-wv0 zUL+jEgDiNCHYkzx=yoTg{y&4@WXMS4HiI3IlZ<^hO!3N%QxMBA$)|}%(R#(zUX|H3 zgbRYQF1Xvt=u;qWZ|yWXRoK`kf)%ED-do_~9kmyH`K1q9U{XU(1KqRJU8P_;3*(pL z6jZeIAjDSxtnEvi3ggwXQS6Ax3Bt_PP=O?}PG`6P@^D2r;FU_2wj)BQY9*RAv((Vz zpky+^{px-CiFKojJ^;9*${-elA?Wwm_V+z%Q?xHaZ8~G ze1ub}p?Rj?#qBHP0pP_K8hD2DS_6=h=V?pYG|>H@^C$S=t}0<^r`IqL_WF7wNWHM! zDG)2`SrY!mDxM!rFyS&{ji4x|KE}h}i2%|)leN4nl zQIf~?)k_h0EA!&L6*(?FJ{+IF61u8%B?RUPtY@oE+)mnkW^?H^?;%38Rw`2S2x`8B zAIh591>XlS5B+`0bxA9@Pw zl#u709A$D#G8_>Kq<0Vx4_#f2$j2phN3y-JRoG3|Gsh+$y+Q zhWo4@UONEAWjoz`Y?Xk+g4Yv};ur@&QBBD~T%gl3bYS?0B;Wh}!Ry*1h4K+iRHSa% zi01qf+#>QO%hE?e4d#p#)6-D@vjL7+o5 zvff0|L5QRG-!QyTLsQ{$q2FBNNdZQf=3&dalM(^Lm`b~H3P0gi#pBXT@^us$UHC`V zqoA$rctzHsur(48L4;AXZa<@>nP`5mN3rr({+?keSMwgiK5J1GTZ!$-DT3LMi3LK5xswT1Umbwy#u0yVij4J;O2x_#j9of zb^*T3DSBfxOpqrpb86!OTq*g)EgHD(-^g*^@lj43div1=*a&ka-tKD2@hasIb}I4g zLszrZIyuIW5=P1Ml5rM0?;_thc%Ph=#%kN+<3!78b*V?Q3`)~=Nr9CO&@ass=UJ(QOHklF_Q$^BVb{ZO) zqBBq#97+B&q+jgAVUF;0x>+zDnpaKKgdPgXpSQ2?k3SKpHK$A$uTT?r`*}W_lGh3? zgjzz`m>#9BCqurIh$~i?nA7Py8<0T7r`H>HgBs=Zv=T=EIh4vjUOyJKV@k^Z(O)c+ zsIumdYvv$DY?H|N$N{Vr)C?jY+Bs(-E^_>Jx_A&Ate^~3h4UC7l zMlNAeLR}-*#kf@z#q{iELi)#8c@9wdzO$%kykl{z@kky|09H8Je22i4p7fJ(u|enWFkoV{nx2tr15AUe{751-kaI zu)=SWAU&MwX+gsUB6u-d)72Fqm5*8S7>JJLE@I$$?G{&Yz4DzyGHugvcE$*_aEpqr z4T2#b!e*=22GiHr{r%dWYf(3r{t3Cot#z@V#up|b$@KkWR>uoG#0*oWhF-QiF!u

5O73a9(Q8NGQF+DTNb^&y(;=T$FUPIPx#evmYPZHf`$r6(>5ttLLRc^C6_Ep$ z6nrvJleAzrz0_R%4oI4&DN84T`iww_zA)DgM(~>4jdA7Pe}7L977wGORC*BY zi9ZvMbP6^r3KU0bcCVTN$hs>z!5}H+V;-zI8*?+n!( zmqCWXKyuQT#g?_8NueunOU)Zpk!FkK?@995(4i5ZW&At|zj}dY6%YL;Ay^szMVdM^h-6hE z)wYj%E5c17PRh&xuI_LBfx)F@q?$q&J$Iko&riB%3`MGUe~i-;bCO-t%NN*^>pbH1+GSxn`ily^Xa%?2f;8kwLw0Z~Y#d#nfWoCx@(^&0o4nL zt1NU_8uP;*VeY6{AMfAuL3l8x*CT4|ZjNJ^^U!a=c`N5YZy^k~oyf(SoD-=h8EC3VVl@8=weCihYSBn`zeS{mV z%bEM5O2R{aays@?Gb;*gxE@6Q^t@~)#KFgBE&8trW~L1 zwi(-`09DC4b@(fBdz?OsF~;W+5!G|4Y|Z28!Iv)kvI6Ff8*XuPiOUP=2QYE_qoFX) zcWEV#M?>z(9*@8vI@HuO+mCDaGkVgPtJ)rOYXxP?p&q^JUrY$oB8Ggh)s$XlYMTGm zTYAO$wwQ@Uy)$U9&>{&C$RS)^%SMjqi(X$vk^VNff5x8VPLhiZQiW8mTWN5{G0E+Y z7Z`w&!{pLkPBr4$-z_BK8mGhg-{}38G12qWRZm?t8<5UXmt-%Aty^8!Vb^l``ACM4 zy;ZxKGrdt^c5muu!GoiB9KUN)8V`A8-zG!IbF}%;(<=Yx3FU{o|JOM{)dOd+1Fu4% zb(L^TV&BU=d`?L_y^mDm?#mUeoo?Oa4nz)LyCGK}wGu-Ye~fhdGy8K6=cpVv4SG?O z@%8Jp;mvHLeiiQ%ac$%yN68A4`ha<$c0rx5`0kZ`KgPrZ)gNIEF@r9)b|}#IcL+Jma@ ztZ%m|*iqCnt->foBJxWB#Mc}q^LFX-Cegx*U7Nt0a!@ju>t1@ywhCy?z!p;jq>=}rPBagL- z0t&QdDZF~snK?=z3B|m3Lh`C!MBwkS42R#Xy^`qtM`Z4l0KDzgv8g5t z0;IzH!Xg$ogM$u2t{*U16s0ULVeK(#R|ppAkem+$C13er#k|;}HgmhLg~9XdvabXR z&He7veJoeOcB7y2D_qP8W`iYA~x-3`j&Zs#F`EDcOYff zM>gj#pi9i9n^#}&#E;DLkDS7_jgxH+V|3Qj+wVH7jRPVT9?&Rvgb#KHP4^~ZWK{w- zT{iZ8+62lj!rCKY8Y>!Z_Vn=#Uw=8~> z`{{)l;V<|FX<=(XSrx@#?&`Q-bk)B-qALa)+#V6h02P1u(_dF)9jwVb=z~ewRWAjglrKpbS;F(ypK<*?r8gW*y5db3fa^5#LQ)TjuE9FxYcyoM zB6?32RLfsG1Q<25MiB{Rw_9r`XJP9A$JNNP-i5#ASyiv;!s`p zFuKsGO<-_SdNZIh?b(1|HiA>3Td-<-&9K|*Y=^Mn2p>7yeaSiX?f!Qp%MGWbI$;=} zHK)OhccRP~M?uwc3W2r1U`!ug8T)iJi(x5q1IPV-xb1I}{gFa}uiUc~;>*1IG-9DX)~N z6d%v5)XSs3{c@8)FCkXUtm#OKQ=30W%8n8Q69k8TZYWs2`OER%bSe0`-sXB z&GG6!ywf4_=z6%&!4UL)9am_?#>*C=CEEP=fupTLI}GPWkwz=?PiW=y36{PIPJSL$ zlcP;BJt=lp zz{6RP3R>FZ{_)in_Wrdz(5`K@M*$Udiyk%ok%DiSInE~foMHxn<`%z${dITrk8K^( z*|vQh1HC%O68R8$Na79y9#NTky_<1armum+2%MRCG6X!2%i`0Je^fWQYH`u6!^ zfP^azmfYmlF498%zMB*d5RUUcUta#Zb(Hr{f0X8<>i|2fCQ-+0fcVWAMBO^9^YdTV zqmqBF9g<0150Es-o9=mm0W21mKAPGi+qrOhlK-l4q?1MLBzzJVaIK%bKP z-gB%a_ZNS>LW}idv*o_-7oVPEDT?vah4{X`oVxJ}{hl>3Q^mlp76Ca;j zgY^=aud+!_Y#r@L1`t_E7({ni!#YUt6Zcctm&QDmSI^GKGm4yIRsw-wNkt1&pkh@O zE#^zPY#MFvk9E=d0bkYR)&;`=OW_P!>(=|_s zvVZ1vZ|<@Ov|ynr1;so3_PpZwKLE@?Grux)Y2~V9{dOh~S!^OWK#<-VrWlc=5w9}z z%t0E@F>FsJudu*9Z|?2bvT{CCnXJ1G%gK>g)*?2blhUj|T*SwesJ@acHK$l4Qasm3 zNgid1aYN;kWQwGcJW`}lA030x070sl!!&IsY*|Sn1yCnh#bDD0c3w>-$*mqHiS<19 zhZrRFIRv(<_mv}2mRJ;rQMAcL6RD8|#%h$*lh|aVimYsoRB3U>jyCw%Bvz9kMzJmDkJ6xjvGhr%)kl*tycagV)eVD)rwD5NcJbV$_a5O{R7Q6Pa-DbfL>CGov$j3iKJS^7X5 z0^y{cPAY5~1fNP*^>z~-BE|Xj8+{AF4(geHqkWAkiFGN6EvWPYm2An@Fnd&nIUPc69-ola72s5Z0{8QH+8aii@~OpdPnJe3q_&umd` z+!rF{AzRmZ9&6L&>GS8Yw(dSswQ|eCPO|+uXrn_W^sbep>#UXcI=a_LRm5E%7l~sm z+;vjN*ptQGD}%(IEN*!zVxym1XQDk$Db;?PjlkNoaPP$0K+sXcB-y*PSdgdx=w^ZHUiicaQidgY*r&c}0^Podr5kC())D@4Nz@249 z_Ii$i{n;~NRh!s~cpPA@_$Kg&-=r9OCa`LoT^-_2xUs+#L3s{=Vbe3CRr>&U631^q zpc=E*gf<~ods7#|-!D*nCo0D7vTytiqozLw0ykeKSejLFf969nt;z*yE&<^Hc!#RLMCW$P!8Y+qp`L>nHLuOI=kS{R@FUMCwX%be5*BUw<%s zczvt?N@g5@47JhIzDgZQlC}oav4FKoKhjMl=NlkPm+^c91UGM)$#sQ4OXG1liKS3* z86ZhZfDUZuQD7m($eqG#65PCPrx(R)9>MmC`@>MS)an z8rb&&Ry3Ft91_n=K+u8sNb@qvK5P5YX_)!J=Npn3OslOd9-6W)A1R;o@$1wOFQE#D5eEd#J?6NG)2 zsnnND^UqUUWmsgLC78B(1hIDlu!jBFBwlUgpgA=w0WOIHRzMf{E@D-&_O;Ypl&eTD+$jZA1y(%qJz)7IiTF>kzkfpQoGA!y#VD&wR-dF#5bS0p*{#X}N z31}$eV(Vfm1&y^MN0K2@UH<4d`xep7N?uxNX{|jo{Kf?nthbio-pVW`lILwO zBbOxK2J4`5(QEdFa?zR#e_g<;Pz3olSh^L&StuZ|h)^>|fzY~&e%dBM+M3#%HpyaD z6_B(^7W2?hK}N4{(dR+n8!uM-;xgX(9K*h=8Sksh>a?bwUM%U(#lTi7OKE7Bdd!`K z+O$4Cf+cNQ)4N`mwP}5((~H6L_G5}6Kp|gT9$G6uZ-V=wfjEu`(g_@f1E4y~^m&pk z^1KOFFb7G;!cs0;E2-I+vbm8rmapPSB9_O3SxQA~PeLQe6iE|iv4kZTk^5C37*ItN znFSdH_ICqdS`Je3vwLUw?6CA;ljJNC%NiDm<9Q&E(e*s*(o#Ce(^U60@#ACRdQI~oeYZdz$EAV6TyW)k+&dTfY&)JyBJo{m&$ z)kYa6&}P+(5(t)ld&Yj0%3asvDml`mHCHK+44oCvA+ULn8tNxFQlxcxfi6j?!5$w+ zdK86<{A!N$DCFi-$1C*NZt3h}`zwI2*W~zr9V2&h1ATKK=TIb_V*8Z;` zGOoVPR04!UK!od0k592FVMvs4j@Zqag6W)W;ZYMd{pi zWbyzAruH@0Vvw-&M!p*mwa=zXLwtb1)+s=!!9A}lHCji8g`4)^CXuNC()A2B+d!s{ zvDpT4)M6)1HI=_W6_u0iQ%ZOB8V>^KGL(55J}GE&fYhD@_D;=Zh9uCWH5Y=AK$C*x zSxQ7hd8mA>p}vYVW&CcpSuS>aV^~uczSt2{%;8ADgDijiSR=2ksxVf|)()Rps4Sl8D52 ztIG7QPfjn0PI6QT0A3il;-^ny23zgv(g0xp_2&&%77StC9{CwSj-J9cVyo7qPaZJH z&@CB-EtOvKSD!VQNeJsa31emd-5@on!|A08Al}ys*`2OG~m< ztJ9X=E)bYPH4SP2j-BT4Q-gF_1d%UYNozG1d6G;u*h!2{rRG4M7r5wzsjkyVF!Tua zD}ZcW=6Qcxc84qU65t{=4J-gE)0%z;5KQB1P48H%N?PM~50PZ(ESsMoy!T^>H&sLg zvH1zYo~juH0$CysP4m{8`l)8Z2uP^GetWIS z?0J?4wbo@J)-+H-y55%GUh8@9(i~Ly#lA&o36*rjwPqDt(uxIP=aqEkfNY(Wue2$d zt$OtlK^JgxCJ2S}v;GK#rqE;Kw`O%(GByH2eOf-B-&>8bP1~BX)9dNd!TF~L_lF3tqJHN)-s-%PMs90L>aHb!!Cr;v8a)Ym4n&DPt+N(Bi01?# z-9&~52)e19e3_0Z0JwKM2gjk@oJrt*0m)lc7#^tGW^L9vqh&3&ouKOw3;ixdT29)* zAV=rev(kFcTibQkR4JUKtt4B-_FqFxp^3DUB-CJ=#vqGCzi^YC=@1RUyZw>H=1ic) zux8En1cC_yc@3p(c?p8qe95T@ z0K4tUd~dBo~r^9W$6mS?ikLiyh1 zS)JBGnQ9<@<)KV96xPdIajWjb#gaWq*Aw)7Y^8jIl!qJ*ozieS%n7hH}19!_QV;DCfJ(pO>zjZ!8M6-4{ywF3)N?kgcfuTh3G9K%8C=t9o z>-|93cjK{cwLKZhTuF}3%K5=iDtLLOQy@^5Tqx}83|bq?5F${XHD(Dm*@v>jP~p(_ z++bNs65De_3Jb|dHi(B3#LBZUp$#dh@+<%Zp^}Q9$2#hoToTx@B1tDX@&?j%lEbSY z)KQVKxHgqVU7lrwAVbHb#m)s~BJwD<+45e_<^=J*9Ipd0ux6fCN|9dPHkJKVekMkC z%A-_kK18SKP;xzDgHK)$-trlg{8gS6iXh9xcHkW9h-c9vNY|6+YoAP{Msdf}62NpQ zKa;1aL~4+HD#f`=&(I*q(si~kqvWsBpQ*sKX6lbEJ6UC##QI`#)5a`pOQJk#5Zg9$ z%Y5iLIhf3&#_!?ASPk``o;orgx((j1KiId(60kivt(u;Nmu*=!^$bil?c03HvlJ7A zz1N@4vRfWiENvFUEw8h(vsU%Z9ldN^@c-d5zy{sGuWK>=3m$~^0CwKb9F4UPNYW%; zU7gpmt5A1g3D`znA+zGCcK|{w=Vuvw015UVA!gF^$@F zIPXs-QJ0^I-J0sBXEiCv6nVO3avofsWi4$f`3uE6J^t2`4e?C%mK9S=Z+crwq6YEs zTgv?^&te#mWn$}fsl6p1=%||-tMi!9hNwUNq{T?3e)@~w%A+nn)5C4WRMR5{vUF1R z(^evNd6v_F@aE6rSCA=UPc+EUSvkGgO{(B24FN)h`>c=!fybiMblSJAgt3y7N|b-n z@0{@Lu8yjn@O=HjzD16nD^2;WJZe_k-bseuMox>i@~BJA6z#SZ;RY!^N$Ay4`RUIsMP4$D0746} z{Pd^wq_@%`I65gOSX-;ZOL=AmTZz==Ss4tnM4W@sRBMmKs{IsoU&-JD$kao`bJEc> zSbLnB_s$vZQ64qCu6|6o<#mz+6zwRF8g*j#Lws+CEI^j7<5aqKdcLllOTaJxk)_=Y zhAxxcd3yF$PTh|3s7uK(ImnfAC>nnraJ!1YD&{a_j3iq#pv_om-sbyZrD&3TqjYbR z*pfWlZD5~gNi>LV<^Dy9)FWVf{xD$-#P$`+vl_U=4`(MN`P@vSW@-GL&dhg)FYhq5 zn#5xpj(J@vXD;x}Hxg&sw!=hfl6)CRq$a5Od+H(V4(^4k!$~wP=MdUuF}vX3KM`FoaH_EF6ipKof9IE zAy8(5wMaZFx(aEN%!hOzqiHD!yKm>H068Z4Dn{Pi;{s#^$;?-Q#2u0D*ToX(BxNKC zU1#LGz(yJb*}w^#m8AIQOMUgMXa^ZO%l>PSttN-t$DOBgiwBd?`|A1DxB6=T42z?_ zdX~n6bP-Q^L8hL;UT=`CCVLj#$kc21 zL>c7ZAy$UBdS&`Gi7Si!X5S*Ciuf_O6$LlW@Mlx0VthG9ebVm%z|MP?B6bGiM5-Hyc`HedC2hDu5)YYrYERQa z)V>^Cm0Jst^oN9=+VgghwcZK$H3P}>Wa+<7;?_7XiP?XCsvGE6#}5^85Fzx`h$Ioupj0#Bpcm|B>6_U`^G*`fe8@b-Wfa~ zTaC_93LpC)#Qk80KxghViTzC-es&YTXZYC#TK;z5I86>@tHn7;k*KZ~I}aGdee*(S z*UWU@^xm?!?7RVScfF8l;uqho8D~0pIy~(JIgq!F4PfOCQ~-d8wr!xNv7K45OMEIT{Y6( z1kyipnPaDlPO>Cjsedustjw?kbV5KiId3yU!l89-NMocyz(zu7}8P zCYnsp7t&?dJnN`I+-_+x{v+@_sP5l~0UGfx`0b!Rs9$kb8Z%P%n1VEZgV)R_FdN60jJBcbNmR|fJ63@NHe=NZV1 z--JD#6?VScj-`@-AYF)~aiKX$s$r43^mZ%6CiuNlPNv$R72{l4JlH5o%QSIr~cmZ zA(u>pETGiqmL2d4!bezK&7Cj!A=WMNh@yG&1;3D~zO@e<pq4g3mI%&n2{@P*Kpiu|=+ zeoei+ryLas)$kjk8t$17)R(088=%_lk0@N0(QkwbwWpW3uOrLmhwP$v`4r9oS?|D7 zx99R@kY0Zi-|6|i&-)Qgn&{_{rq}WV`g0$T-yND*K3SF8MzsdM@ zohdQ=a?FwdeIYxWV^JOSn!b>)KiD@&lNxwAuSpF&*ADHf_IAwCSNBH7c|YqJm3a*O zD8Iq4lj<|Vo@2TU+&AJc>p3fAEhhQ;gW*x(s(3$bNSZuvI_l2B`a=3^F9%!$zd@|m z!4j=xlV8Yu8>-Q&Ebuon>gxcH*7DnbA?x+aiPmMRz7c-|`T#>adcOmYcYnpv#xGd_ z(%%F~XutC}GGzumVh3ccce3)kvG@Y%Z$dA$^ZXmxDIqL7LH4UO{rZEUhue{f`*PmV zD~$X#-+rC>D&eCSnYM4lHjy<&a25AEscH0D;RKhfzmq1X*rT{WY$jQ`ft+{H)BLiI z1hM(`LVPRh-{|pZ?H^(T%z7NeM&(0>B*SA5fQ=&ydP-f%&0#?{IO+fsPZM_8Q zi~K?Sj%@;g_#N9!ioPXE-$+p*y(gAv5N z@Iuy`;TcioRCyy^k6;5fSoY}S$La+*@1T9!l$PZTF#aI6XJu{&ro}(MzkZQ#{q_j4 z5f3uo41EyWw<#?no(aQzh#T`lY}I*c5|}4{yv%U`Y>d5-rIS(=#z-@7<;$Bk*gPo% zu)+31+;f(5v9jZKKEkpE_e$Jxo<&CN>^RRoLAprFu-It^pLmXO&w1h-Aw4nj$9Vm* zJni-y7)5iNXW9*7--@T^AoioA1Yw2BkC!QaVBQ?RiTx;c41m~=VsAo>mTs^V2AD~I zytpX<>;` z*nbqPsr#F36OXAe(+QRzQ4l`^COR+ZxP)+ zzX@#Qqvvw!YpkBZ2%Fp3S4a<$U%;}Wd}3W7M;CU4ELLRP$a%LQLr;<8eOXbykdY(f z2fT;xKy+P4_yCS#q$OYb)JSjWA_Zo=iuHwJIn88 z_g^vj*pV@L$L&EJl+S^@Bm2tH{@5e?${7J54$9|9-XnwZ&e{iYU+sLVnNfM?B7kH9 zgR>mo(YJuQ#yK;wS9YJXB|tLABD;7!ITn2+aYBsqFk*Y6n5h~7Ls=m?Zm}Ed$4kOT z>?67OB!z%D9VUnEc7XOtE{RhgIsOc#*MhH?KM z&mA*`CXT0$J2S07oDAc<8xSYMO6+Bds2R*~_Uk_wRHGiw#(C_&bF$?@Do;HMgol?ecL7TEnWWj5MVxw!6u%^PTL znk@)76Frqz4dOgtXKF@MrNwtjFG$SKv|o@)1lA`U?Ir>{^E;aKIo=7y(QYE}^u<+Z z@n$6hjP{wh45AyhTx>MeS$tL5bI>=F)es!fL zjjMNxJ4h&%-nwcadwgcf2Q+oQlIuaHlk0bZH9j-)gCayC3V=j^v|ILO_Jf4?1GwjO zm5F-q2Z-LZA*z)a5Qz6nRL`M&)#rYMfG(DQvkQ#*-ok*t^J|j>$k#rI=+aXLamS(P znf6ooqw18odT+Ui?hQ4qmJUEhes0tNNjpGciY z;v9Fg34pgnR4+mF{&UMpbpKiRwzS*w?s5SM?ZJ8OPj-Ipl!>l#i_eu(0GaW*;|64D z56I2tVyJY~d$$?LGMT<~s;z2^8i2Q` zISL7Kv|Fz_!C)oD_wG1=sqK1RIsjSPn&q67(Tse19&&5f()I>)O^lHTK;mmKZZw&NC~F76l%Na&zys~FmIc2%_^R4Ng~{WMf6@wwt$Al|tib#ax0 zdTv$P2n%dP#Q{M=yW1V&1KB#ys;j5`l^fFrncfrc`A?{P;(OnG#H!8gyI$C;&Fs#k z2hpW&Yf0|$y^TL&%WKGYYi+gG6;1Ohs0f{b<_OC#_9HSZPvCwTDzf-oB{z^G z#R7YZsUnL2o|oif=>dn#0KU`{BAeRpDlC8u{l;+wkkmssjsS9W!wz*tcDXTE?g1o3 zsgrc!!{H_nNoaVYmy)P@ zD`i`*6>u|%QDnhX`N*2+zZ^Kw*<7$V1gl^a|9}wN2 zH}XYF^6@Q70y0Eu>YS_xb)`-4_tE{{b~)OJyWXvEN{OW=!B`T|6F4#xSQ7Y>Vga$z zO0~jzN{YpU{gOsaIiRblm2SWfB&;0c`Pouw#kaalELDWM0yF>?(W#m0>c3QLV%eTv zWgC!Tt(z)l_>29BSXjq9BSFrW)J`mmZ0y@GYnF~q#WdEGx3llWbA`N}D%cKS9i4T5 zVHur@PAnCKdafvGtgLI_W>7^ah7PjG*0WbLEVbRabHQcFk5d^fAStD#iXto<)OXx! zsqn>f-Y;Io6`xz}9%SpN`{E_~2$?5O;+9GeU*RW!B~hoE?Qa!Ve9K3H4BfIfK!c=i zr>64zQCnT5s@S%uC1wRMb;s7b0$I9auW-KFP)&7pvp~j|wiZZU?JfLeEitd}2Nnb7 zr+ycRh0JVB_b45+nkQ|QR(uPEfqZF+0i;yGD!j5~OR*Kw9ROuvNrYVeIFk5K zn8V-ee2UP;K3A5`(~_-Hi|rkm*r!DNYF@IBn(k`i#ZfgV=;pckkMuy^N_rssLwqkz zD+xcZkAh4SzvCk_%FU*iSU|Ae@#!TXSTl^HvWjm3L6B`pK{v#))MLBz2`mPf_&Lvz z2wlI^hoicRSMm^GNCVNOyg;PC*v%Bnt9Y5(ODwVxu4_ z;uRqf-SW+3`9?ngvaWBXQxGeydXkin%quI3rO1$g@l{#{8G0^HiSkjsMJTp5KgCpg zU8N!ri{N^C10rGCI&Y}8uAVH2HE?_0-z>?;-uGpx+M~A~o)iFBi`c$rHVJ%CkhK*F>nUpz03vB*dzy(c;GYi-=4_Jpc1-B4zVg!`Q!3UDW`mSyb@)|;q-^v3x>OSC zt%eN}61KK{0mznO_VhtEjah|GvPs3U-I^~T%fzkMtb?5Y*0$wu^dm6zSdI;Xq;AmR zVUT0Z@!<#EYQC#W4x)>nYERq7Rjzk7OCzsx__9gHv90&}vTaG( zsSQX-THWuft5PC>e5LFv2=!Ke2QhH#b=8Avx5N<0kvRPFSy(8M8Ud?7=m{JZ1=%{L zUX3IBSMMHRS`xqRWvK0Tt%78qCF^g`7sRsuPM!uyiTK;|1vysnch~Mwy8a&SdRW$f zt_v*d@7QIcx{pNs9jXKwszczF2N28pultju6MLSJ-5SWdTv(7$9fDKMV$-O8-&G^= zT|)sx)f${@3ZS|R_NKC{4Ai?=L-tceAKY8JZQ`x@0J2p(!b>YIJE2pHh&r!oE%xi+gQO~iSivk=_D~f<>L}G!?AMiDi$0y4jf zntwVBUpS4kPq>3Be`Y9l>K1-~CY!x-RFGq&+U8*IAM3CR*TtHads8u8^hcqRz zb!PS=L&S+;Ao*EbCWlmz`<1y)l)4kCj-lF$z1edFaCIDejyY9Z5u=X1is@2N?fN+L zsq#4X6G6`Stg@3>BIuu$ctB!)R_jSG5!`}4IcZAY6@PL{2pLs@+WpBAuuC|{XIY^{ zk-Pm_dI%(Rh-2nCT?MKf=$x|(36*;@Ramj#5|bcHH+x@0s03BFJ}1CX*&|0!K~hh2 zs#^Uo_9LPaRL-}_nN^gkT%MU#l&W3enpEX2&s9aKoI49L^0NdL2rKp7GF2chN)>fx z*MJ%oU;v5utcV4&Rcq_M9;r~mWMnTgL>zAhS+3Bf*AtKa@;Smapyu`cLQ2SxVsXR7 zQ}x4qyWt{Gv!v5NrVg^CEy!{iGQWsWxwCo;;ev{{mKjK@23h$nArlJo=C=?k0d=dU z0ZiSC1Bf6?Wz*^z3#pTCYq7#0-=Mf5D2nG93sh3 z38=Tj8>u$BrRqRZ#p}u=3D;AMilk;N)t`DhxFNO4cjY{gEmGcD>|2u0E=ahZVioBF zSSliTAN;8P)UEXgGXD7}2MECWQ@3Ow$W{?S`5S-!V)*LvQBA5_R2gKdj9@)`N*%f1 z;xn02NA7RWG;fu~a=%jL1t5vLNx{?4#r*-f!(-!nrrv!Dr06 z4kt*cR%fqw=i-U`x=HEciMvu=K&Gm9meo&}O58Pm=T;Nka-$%r;-X$6134-#>IJdP zqpFs-v?++rd+Ic*lz7UwSyEu;_RCphs1B@?JV1`>z?R>#nrffk0?6>CA zOM1(2NFBvk$^--14r%^kKO!koGiU_!b*B5I$`2dQ`$?HOw~}1 z>Mhh; zs%XcS=JLB%ILMiw<-~IPbq%HpA1-4?O6KgtmsZ#U<(x}UQ4r>Us- zyw)BeeLPp((94kx1hF+b$`Tv5<}C;dct@GNqcVu7VIG&T_2L?cqlIy7?5@Az!r*Vu z;E$>xqEv|o=_Ac$rhVPtY#mi|K<*_axeukI> z*+o!03i5O7{svwP=F&3w>ruKHw%GSsWa=Syok!``s0WiiYN)k#SquH3AS%dskDg8H69kEP@c*>}B3pQ{FYm&LWtF&u;S$u=Nwi-B(kt z86rjZYSryq;GCXLZ@sd0m%<5e0RfJhpdbnjw~^+0tV0M8u~H9 zBNBvf7=gRLSt4EwScnkl>Na#B@LlIs+W<-ZX4MN+MJH%?gzs?G)tv|q!nTSE*n+?V znOAFKbyjpjDXMyO*;K^;p8FHHKl6$?tgd|Rd1V<^SGw7Z_hTvDY+kPf#22r}!kmo2 zpW{$LL;%~Bp=2|g2M&K(MtTj_azcR7HhRdE&MTY?!bYks_iOO;11K9kR0Le0e%ciK|!YjLNt z$Utl`CWV+m$}~-z%DZ`VO_mNu@YnAYhJwKHIsiBpP>Hb-oXX0ccWWjH8=^K@0;GX$ z%v2s3^kwR1lt(ttzjbM)kue2*7TLNzkKa>iWb;(!1qdt^v($SLI5lzi5rUu@qIM0g zN$nSavO-g45~=Ou{ss;yWMS)WsDKGl#&s$s8~N|`CS)c->cN#t7H^kfDkU3{@S5uV zVm~5DP*!NlbjIEHwx-Nv++A)UK~Pp`YP}p4;OuHlnaQ|2&p?LBE`Z=0BzfW<1Va_A zqKqqKC8K!}8z6L$S873YcaAZxp#Ip2x5p4lC1ald{SAy{bjQU3cnJZHu24cY)&-OX3c}XwwW$q+t=I3ABa}%NckdAhTWZua7$i;B{mmgL zyBW$Qi@RwEWQsV-2m+5Ls_NH^C?h-W{vQx{q;a?VfTTz{1EFlPxJr8~luZ`n{SZpY zt{2L5?6{I|E0jnUS9J|!h};KIB3WD!GZ41ad_RE79>&}7hl)$ZRqFzQHxpM>Yo!*= z^{d0ZJBkVW9{JGERMc`cx$|8W&%KtczV2}JZ?q-Ldv{^N$Ph6~6PDLbCZGmERV zvQl|wQI#(M;0(swjAK2Zk(5oudVmh9sdZ|(Jg&S52tTqb6avDJ%pxFdtw$|&Ptmv{63@`3^P0;vNo*38Z3|`>wOb0;E$+taTsvn$hgNy}(ynDsh zX6jeo@_Ybr+VXBX20<7z?_S}Bko_WYz!U_&dwSO|{$4t!B5qsD)_Hg9f(#u~c4AW? z1;hz4%K`hmxxs6*fN$O{vjDLBd3VTy@J-#_uWPe@1&H^$g6O<)|Ay0+Z^O2=Y@K(H z>e>uLg4kC;#6AgX2;Ew>&iTGyty<@N->_D#bG~m_%hr%r^NE%Hm3J#Ah>odQgk$r0 ztFnT?Kg+w}avg4n0P)v-v_PGA>m&%KSb29!E(GT{NkzPl7O3;?c?5xjmRF7t1WRyv zw=XUP=XKOAFY}B2i0Ja(n+O1h5eCAspfl=*YTQ3m8w06v|In7@m7xQGyPtP=;6lWH zlGKoSWXtky>H~o-W5HG*rKRhK1bFp@4mVPK|1~B)IkZmkGik! zOh-%Ec{jwZqowS;^{hb)m21g5q3^%^ zj51|exsfDr7qR%Sm=ws;g`M575t)A-weG&At^L9v9;^4GmF{)T3&!7H= z(Mqe5761Ijend8by{+w7J!=ijB16A%%w%(;+?0*Xkuh0DvIW zy0#4j-DX|ewwuf-wpX@MWauc{ip@P0Bwkto;l=M(l--p6g<{6D7hy{c8;jj!MzKqC z_{5S%S$CHS2roX%Sb*^2cMr*itFUh7+;)(D-R&YEyz=yH0ATAJ4r1&kE6Tl}QDo{M zuTgC!ZG)UTiXvlY-K;kd1gTJI+2c`@63VJw9RNqbmTY&faj(1U9)JxMcf{&i<6gBv zVB>is1wjhf`QKd&-`MxM{iIs>Ug-sE060PG?tcJ*6SVGbhuvjG;T%6v zWa=pI1O$N-w5}=JT?^mqnlg|_17b&xF?2>Z_6sIa@tXx$ttiJWz}BmgWCd-bn* zgPLiV{|GWf-0!60>{n) z;4pH(w67#Xy6?VI5QIPWO@9YL15#tv7uTxy?(aL+s`tK0THCRF>agm}j^$(K=QB@M zrULO&G>9%$=E9-;UCHZvYSA0{T^={5Y$@v6__LW(SlM?Q=bl>h#-45uLWt#yl*O1@ z^xikSYEK!{J<4Jrmfs1=Vob@5?VC>yqPr=BF}3KuZvr_8n`&0*9t7?xwvX3yYSDY& z)TuqS=#35K9&)AxR`yK?2iZExyZrW)G2M5&DjX!0#a{MzImK?<8d! zrWU;S&Ef{xI?A)0J(WbZqnz9+TZ)-Ca#6M}&=+ z6|M$h+#IN{JrY0;9nKQ1>x&k*DDV#cJG@w4T7NAzWee(;I1M-VEcgRwvHr|UaHO}Fo?A!JAqX7G?0QdZeFCwhlgyZ5feWDxj42t|053R%*gYTU8ShXA z**+Cg0tp>e(-_C{cjYthlsQG(q6fQFboJcqWf1fd1WWu72&pv^M~FcNfjeJHt_<;% z_c2>%aiCzQ^2g3|X9cMh?sIdHLEwCxn}fVlE8OR~(}L6r_i5hc1dsx)(xiW}9}zU) zdE2VwqW8Hu$N)j$q$B{0&!^p)Lu%0*0Uz6s)S@@kmlaOfsRS|*kBF&7Z`Aqnn3Gah zL72#+9YZQF(ksFM0&nQ_N=w?QRc{avL&+2}#F6&>3A`aFJ=c5JqW9_7fltYmottzF z;)~zMl3dxjNyi&u1D&TVNV0$xNDa`K^y`*wQ!t;$X>QIj2)vPE~$>4n;i_|tJiE`$uORq9lSToY?15&@M_M@4hGo-71P+Vizh1tvy}+O z3K+An6}Y^8y*zQiuFb&vz(dozn3q#kLr3>SzOEkJbb3WQ<6 zMui2xsLdcaNX>V)mbWQMGK#RB){Tp8Wr4A#!7jopuUa$(flosr6JJ{E+bk;(MTU+l zo42*T%|PoY!e)Bg>8$bYlnQok4)8w81v{rq>5(YPxjDcfG>SKQ2X*Qm9VFxW=P&jn;v4dctZE^W)J%)D z^GKZR%o=P%#7^K*GT6C!!K`uB{%Oxc?JN@7MUr;O%Vv`Jt2$I26FEhWkFtH$!T^aU z^M|TqBpxYPF-4^A2VaNDDe~%QBvlUeI`ndk=U}cHh_s+;$Z2I zq@IcLDkL_FRD~B&=RbOHBzh*vnv3X}s2ko*PLbpDXl$eGwZOh$`j*cqvPdvb7NJ!n zX_pNDMvp~V;S}jvL>K4IUJ_bGlG%!ce=~QHZ4y2YGsZ~r5}#&`0_oe?emm4xAvvwc zFxUmuSmR#>vM9Q_MVe2XZY)Ha4b)bQ(3mWfdZ^{L8uy`?7eP|nVSlk7ksKm9>bTQI zmcahE{@w*bpxP6$F_CJ|J;H20s66%}S%0dT(s4n{^N_Slbm6@1wA@a4 zABnl_hW{ipWxu)BXb<|D5M|nuZ`hb8(#2)wJZX7HRbdh?7Q2Xus2;pm= z`wWTqO;XPQ)hLmE$@Wnm0Xr2|NaiKFI9I$))PAR|RcFc=$+~3tsC9~{ttcH}a!fpo zbKm!iw8yi1?&;nlb-OwU&$uY5o9ZVV{S(ii?@jY`d zF-R+eie&^m{PG`k1M}k6#7K^;S{pU~W0620FGwG> zE;+s(kCyY1=h{Zy^0Y;T5!yx6g4Z(7CeO8%*gbcT4Uut)T5#6bIJ^9zHtUwLN+6II zr~zl)@?;rIlDg#~f2du%JBJ*i7Bz^>A?LM)9eZw3GO1ghZmn80=0+l)XI?_*r(G*M zsaZynvxrZ;E}-*D5kHZ1W5s>Tsm98C$2O}i?;WQbD{BauOTKHnW_2!^wwCvfm;9f0 z%_{eeh~y<|tSrA^a(R=RY2fez&kF*aPF`;BARz|-@_6a-lXu0{fI1| z$z27@0wH2^6E>`E)q9U752#(68O^PAZ6;O%0Ir3M?zXuWGHf&3wU9wsGLch6jdLwz z3^&g9jE_m}CUFVf;8ttLOd>bgm&_^RIYP)pwo<2NZZ~g`BKRaJ7pGNfE_1M#NWX+8 zvK>$8m^|&HJfVx_i*rfaWcfTckqG?zJh_VuA7yhB+eYftNEll#VLP6uGHV!*4neq4 zBm}A@4m}DcYT)mD)H3~A%zV@`{i%maCZdt}q4JSOA>Boirj~)yTY)gJNy;W?RM{RR zT}{=m3C%8Nv_JI`rwwFp^-S5-R{dJl9CBxRO}?3~x<&dWdx?0wPn*boC*L{cj`lLN z%n%juQ`tcFR-bzD@>_dZ>Mv-)VFFHDIC-E zu*V0=Y4LmS#M8%b}ch#X{EkSQ&SJUL`3iKavBXq^X*}4yW|;2x25AIxKGEs zHW8}ovHpBR!TVijiQQG{e$QF5hH9pW{Q2&uL4eB2lA%m;`2BIZeV#5cow;Xt9g3?l zk`|%R`^Vw_v@rUwwRN3#8ntJn&f@pwt3;~-$i4AeESVD)c%rPNYP+=}OG#%hG0Z)B zXGY#;vfP&lSue1`03Ppva|Qczfh=Ch07H#Yn2FsjClNEfpnVBbOLfc_D76{cwAzD0 zn%dn)+gvR4h-q*4IAGpf1o312e_M__8Xq`ZLOjxtkwXGa;jeIUJI%lDjAVRcYKm0c5+x&pe_bO zl#=Cncal{mv~|br6h6t<19$Um<*(gMH9zxfFM3@X1e`s$EMEF8es1~w?fh2(OK*n4 zGQ*Xh3i&uo_rTwM_O%}2A)1BCz8$MG;k#&*%&kI}Q-jKTWkO-mqLs3iQ{|NBxx>qg zFbZzY+#gL0T_H4h@;E1JXtt$-Q!X#FjK4&K`MyhkJ^iY2340rZYe=CiluXb$#2itV z;MgE0&6ytZ#!fG`M*JMMa4wVUMC9VQZqAAf8y0;FrtX5}6Bg{}J>wN1wtq`vl#4_Q$WmuXlTIZ@NkqeL)q`Hs*< z=4ZPe0DEPdP>1M@)*>f;vV>ej_R5VQS5e?)w{f}|QTS~** zj8TKn1#w;GWZLozclgXXR>iy422Qt&x9+@l;A#&@INoZ4TvstfxwRB#2>y<`l$pM^ z_)`&YWWeIyI?WF~&LY2W)4E<3xF)?5#;bx1slM3Vs&ec<-Bt0Xw^7C`1$99zU>AEet{c6Tu5bV~C1AAzRNfIP=kS(5iZqaZ2m9C2xzZ@rIwQL0V zK~WEOxWa>%w)?$YaNn=s4SXxkM?xY`wAW8iJ=r+s-dQTy__Zzv5rtixE+ivAAOQzH zLYpC%o5f|VIO1yRwYn#he6V$~HvM0Hv9#rWMkcs@xe;7!uT?}gqUuX#|B)wTVEw`7 zH99X=GQM-bCr)!E6*9R=A8*~n3+w5N#BX5s*|OU5UiMkiaR7D#0+^X91(&lhG#pNE z4b9%%ET1zQluwpu4?G`_SM`P+y*ar2Igfn~tnltU^PYx$`40Jot}i-G5kWiXPGf^e zmZs>}zV@EBo$9xlPv%#;kn=5Z3Zf{p;=2SI4u8HFgQSb7h1k#d)^(l$cPq~j9w2fC z)`VJ?d5#L1I;$H$b~aE{4qp8yD|QO* z%|;}~QzGk+FKt=@{vgV%wrQ3RSaJu8FAA3q?YFi6=lPT4S8dh|s z^n6Mm|9yOemEE(_-7rPzowx8xZ~UB}oZ*_$Rrup_k-IYjaVOG9R#%OPlX2Z-<8Jst z$t86PC#%tv0*y z^=%l?4b8exYrWga9AP!%YmMC@&gY5v_isyjLm7IbSAiVBB=7w+A`?P( zDy3Bwgxp<&*;;w!Nm~Y_0WH8{S0@AnUz8baT&&(M5gLOQ_acUfQaQpt$1k5m$w5>p z@e9j3p10W^-TN}X2~ z>Zg7&8phB?2|4{eAc51Ltdu>u{}J4C_`62s=ucQ->~>7gfF;{}%>k$KJNb;RKv4ZtS}Wp8Xz%1ufHz-DOTG?e7r@+irdQ3`wh8BB`~t&G zur_%&@dhV5VezkZ&?nr}c>ZuAX-YOmUBi)NQJcrp^o3&kxz-cS$a~Q4rhk(*py&(> zEnOr_>zpLcu|L=cr|cSf^IQ4V?vzUNH@Bp4$f9Z-I1&A)|iss3gT_W62oaWW8B}*E7lzAPl z;o4>bFg9WjQ}m1^$NC6d;)U3w^0;0nqxkbQzAGSK;Yg`JFyU6&&4(~;xIcyN?Qm#q z^zJaS7hGuO&nL38#~0D!$_8PAq?+aY-Fp6{d0KspC~g-t@Vi}Cxx}>vcU%3glq(K_ zWq_Ut=3PAP@hoaO0@lWxzN}V2#?RfXI!Pr8T$!jMA7P&)+_m2sR(q%Wy^cG~-0-$6 zvK8Tlp_NQJ4!KIQ@cNp=`bXS3DfSCPTgdRR=>hFR#|{m0lLHB#JDFj2@g-;;3zf7@ zIT`!Uz|wdZ>vNjEQ4Hjg=!Ex8?T|tFUz>JbvWMC2Z`)c*xCD#xr{xP93>4ep%q3{~ z_4n55X3omYh=iz-Lk7^ItY(XrTyRom~tM54VFgO=3JdrA3Z_XkVV@klv4EW=A; znO|Y0rOYtL5nWAIfZ#kL(Jj%H=*XOr=s3sv$VgoZ+amEp+PM6m26T^p^7%Q9g*Lfa z?=B%p&dz#fdnp(GA4DVT^9cI+<2Og7>dw+dA=O5ZDSv)D1YO$vL*st28$VX_v&t@> z2{$zCfVq`++ODl#-Y$D_>Nn9yiw~XAhUJLvVKHdz#dXWEF+BD4m2Y6)8mH!utc6jq@ATbj9BFdV~46==ynaGZP5Px#pp&*t)J}-{n*pe9(=5R zto;hT9r~9jxl9F?k1!peDXpq4qn?Z`ZX2$Y!h7MmyzCO+XTR90(Vu@_eE1MrdSdJF zf$pc4RMHyoH0!MR9gf{tPe%~hvh7E5C8q!;GkaOtgWIAVy(YdNTC;A z)^BD18DUz*vWFKy8+xZTKZCuV8;Hg(M%yd*R2!=rUog6Npj7&L;tNZ|x5p-Gn-rO_ z!bZh*s7%S;=|}I6FGznV0|#|z8qL8sR2%*2uu1dg-I9}e!_s9e^v=ouk|w zI-L6WJHyn zym9Kc8_$5@Nn|#*fwaOj@iCmh3N#SUoy!uuAnmdhxW{>lsGgcrlS;bOJxsh?^?}Tm z*Sk!yV>e9lJ+9jAUK>m)5?RyqJPtP`62T)T5>&lD^z+Yi6^uUB={FPzCGxA*&3*QGaaSq07W5jN$hkoK-!!+rgBBLCNbRz*V5SUd=4ZRZw00WF7+!0~ojDLN9D= zNQ5RSo4I~*0u&;mjPIec$rt_m@%j1A17I4f*PD3a)bg**d{&}Dh~r{x84u+IkSjxE z$Gb{I5>ofwq_v z{aYyH6e~CqeL&sCG)QucZxv7MHUfRheVDY$yBPC$Vc^0vRRE7aPsG3|`*{n$f;S#i z6$1z#z7EfI2lB7}M6JAG08r_}?F5_#cx;d$XTo@L_%^o@v_9Y>0k&`|EfR z%ErSs3zv*JedT}uNLDcx^xx3#Z=J$PSfTcaZ!B`nia{uQfJv$Aq4(%eVO1W!U`0~3 z>RKfD7clK(Dwm&=tZy9cni?5MQ>#OLr&37?v?MFfNG|+!4_o6M<0tV9v>wh+ruQ-+ z;*cM_&XE!tiJipefg19-_p|_6^!ISXXh^W?QSN`2PT0qX*2_l5$<_~%QSSooIJh*Q za*vc7VlTxn7@BQquJD3~P87CQ zhT~QRdL}kKiT4_qk<$;9k4vS6vu>t6kl609y_ z=sq)I^`@Co_j$3Crnx+QJo8t6Vn_)z zDnIQ%b=Im|%A^$so&?tgiAw9HzL>?#ioRx$@=|QswusgMZ5j&-g!46Im*;bVH(|<% zS0&yaN45()=w;`BSFMePcg3aRZ(JP#ih0}mY4Ky$Jzr1Wl@Hs-9k3x#Wez@Of1BqQ zo|O}|;0SB7vBcDdF3Tj!Nfo5_W8sCr%6T(!Wu+m$tz`jB9YSFW=qApl%?K40yA#EWcH&axX!%QsD~d3LxMhOves5EIlLSLab*}$ zlYska2+|4Cd>=LZL%O3SGa|9|#FYIJuCZcwk8Z;Lr~6n}Fc;)jlJmy3fG;?&*>>}% zA~UXJI=2OEhlc*2oGZT?C*6}BjoCU@=%+~~k0^5M_Qnz3G^w6oR~*ZWv{FJH`aL-* z^j#3Q418PGq=ih^x;=gonD&@QN!>S2mF&Tz`EmQr7~L*MnMVN8wt;6X(lPCRxw*+fz4j^p24QYVu?&Y#yxIs;?4FFo5{p~nAuZ+!dpRKw)Y#XZhc-oSq5_r0;! z9|M*wxT!N!L3kw9_iqf8lIn4gh`3nN(>v~_n8&m~C?Ynb1G@0rE5d&YV=Y%b)N0@81=>&TmUnUx@p2A1AcQ4<6@TwYOLL?b+{r zx6?$uXW+oo=kynEH+sPipX| zBFkQi|2)zDXW7Wlr|1*hA6DPi25T*4IHGT%{w-GD8W7-n{|m+5ujam3aW5mY=+pjm zN7Zyy$B`&UcDaq;!KfIYJ2+$#XaCP zgttA9nYWhWubH35iKi3Mw}n@^`l?P7`xE#yW^o3-MJQ1zC8f0WjSXDLiKgSQ`z2Ip zZ$AW%DYvo+_W@Wg{p16lyi$gHvMGw&p=CZkgH)}WUdQ-rut92JMEVLC8?QFPIU(vP zV|M@iy+~@;BYG&tgK!X1+BSd9z|q{wPO0dP(wC8Pi8#y^}0Z)->aE&M^L;b_F==tHjI8K#q&yR4jq)-!`{)l#k3OS27Y zV;SR`?f4~>=(~GjKz2pcICaUrSGuc2m4nVnW8Zes-I0|5FVBhEuYn1IsK*kRfkr-f z9_J-9{_+!v|1cCK9_Gane5VRorJ5Q}DdO#8v41FzSAGY6A{}xI>n^!y@sPj-1$?Wp za3rxbRn`28RtmK*#Q054%6tcSO)3cIFYLc<&HD_PoS^dZT|G4rG4-NSG_HFDgHRy?+d%Zu?*gE zV}Xi%)xx^M3zduk+A}ad1^r6nz*ds6cO~r}(x6j@{M8qSu2)bv{ik*XFKW~p?yY4H zE0fohmWV;S+IiPPN-u|6-iucM`|VGBO@x^&J47>JOA;(rGI1P<>5$$B|?IHCTtG$_D8dDHl)XCHv-OoDK)RynvopxP{5NJ(1>9bstRi{A#jJwBKTeOfTswy+(1A;7Pmitj+E9zq zW`JHG$s2Y2GDGxLh-7QHx($p5vd3>Yfu?JC<%+Kn${Q};!(P;6&HQvb5`x6cCq~Dg zq$$n0yEKKvz+G|u3>4dI5BPz(tqkoO?VqsOvN-u`{yD*QW%Ky_-{PPleuXsMz}~h}jKk+<+f(tt*xO?xi=02y>TT;Z zlR{%@k(p|Yd+~3dUQK>@e%xmh;f}hn$zL2~-cD0eJ|Ax6GpN4fFE)L;pV9T)O68$p zYtQ4($eedx`O2E~@c$z;vJ8N0s>0W4k>$;Q>o4@4Q687it7_#C)n3_plRkW~O5Bm| z&sWcplWH$nh%8^9X*_)!_LFzRFsE*KMz=S*@p}_Jw`}0C(o27NQ^o12we`UNOXc~V zP2l|bahn&?{*d#0oV}g>{472q{=6-oszCdBIgSwyV2=qWB4U*Hv?oY(rpqxv?m)1P zD>;%9HNQ(0q9ss}y60i~v3`DG8mx&-7(6VGjEw0_kUtdnUJVm1Mo&5z*Wws3nq2tOgq?7^>qznG&YK-Zs54$`+G){&i7bnXL16o?-c3Iy?VGhdMJr57q+azHm)yM!-} zj0tQ-312MEa>@S`+X2ZCT?&ANkLZbnlqO}l7fBE;lwuLYvIO}{FkDefuFGh!QqaZt zR#~H2@T3S4FZ!0wkZcq4oAn)@6Jf>o+W;qZ+c(Q}FIf2&%9C(m#Um7gqm*Fjie)!r z-I|{$`Ss?reRvlxFCmiF)P!L1Q$~4S3*RcSq7U zYUBT6dNz5n$&XEkyEV>FSV_QlCsjJ=PWq!T#`EUA}^FJX1sl=u^1s;vCJxzGP0 zp>l?eK5gzw`?_qy+hp+k~_6>9>mhLgxoYxZsT zwrww}pgXb2y?A&BMOz|<0Lduj|GONtCAP5){<7r$)I%MzIV2(Qw_~wn>}|<#EY>)! zOgeUpQD3q#*JX7Jugz#MKs+9-f-Y~z=T)10XpF3st%HeI$Vq%t(tpG|GmJb}SA-DS zdKEIgbZYgWF-x&_ep9kzfpo(;_q$;)Jovks{DWM_9Rg&{WXqVT-W{9xRG2OU>KTs! zg!i-;{ADBzhI`pf(It)9lu=tbQOm8#j=xqS@>8Gv+ZU9p>+e;axyAEA$9vfIdOhni zO@6Gk)mJ4TYUEPsp1&1p3lACHm|P7x8}J|aEr7#{L0>6lyn|vk>HenMIp()Z3OE@% z*WEkxj6y)C@$Bu-j2{g9sUhBao+qYum+ZM64k_ri$ ztEL*UwQ6K=H{|&C^MVmDw&?Vr^fd~me#t;b_fY6T;`iDnX^9zSVHe&3WEl4ho2`(0 zTDQ50I)N9X-TZ9x6JK~##r0@{rOs@`TtacGrpRBOofkJ!*)!3`=}JWp8HW7)u<;R4gxQG`TQ#}I ze`Zv-APs&}NW!NWtRDkXGmfY0g z6rt$6N|W!4kMD0p&Vm899=`OvxUa0wm?ELCmCw@UxnVYQ>Cvn>*5jtCi*DmqW<8>^e(1o_^Rc z&m09SbpX$3&4kYBO_|_~vKWifhvM6DnVTs^L}$ndF^1_KPn}Q#J#Q?6$(eJw!!|eH z{Jdc2DzJN9-@g;$w5HoEm%z)b9x`Sb*U^FVNqzyeD=jYj_-eyZNZoCc!N&SdWK3zp zUu@Y67pQRi%lrVGBYP(mD~b}gOWerw!rY#vMG|x^r4dFuXEw$D3MksD=>b3=Ml8w# zhKg)AP3I&D=K3vcR54)Bw>nTqc;G)Ga;w}h_&jl-?Pe|2)VDaQ`{7z%&D4>G=UrJA z>D$?-ks>zwn5jqVmh4zw70H*pIiP6q2lgZ5WGMd?LA3)CcA9qkJrGgUq1=3ZS}s4R8=r9T z=F?i397j>y4ehwU66r}M`(dCM|7^w=4u)OQrzFf$ylmj=JKHDyp0jXkC|B}Gxy7uz zO=%)CbTQqcnZF*MJmTt*+qfdL=n*42+&l3&H^3*gWs|{#wh6CH*bDPL*%jY}i!@9C z;NM~u<^mB-OWHW}T7@7CEu6)|8Y>QlM>0irrzcYaOdz%38{1rtE(8UBg?8?IY{xy{tT zYcZm})bf9;!~=Sg2{B>=>!mQjnQqp9QMh8$sF`fvch5y+NS;`b`3UAZdKt*j1kFJT z`GOCZIx+-c+LGH6!Hm*$R5#FrBcvAjo8!J@{=yASMYlgb+GWF4DOB* zUosEbPao``9$hk4PZhM3ckZbrfg+d05Ieqp5|W$%%-mIc!kbhe#S=jgjVvf~v?~lGL|nU%mnT>)=r7WPI3+E(Q1*FNUcLiPGvXmN)q&A{7SSSmgT89 zr$M9jA(Va0QVQ}xL=Bu$XG`rS5?`Ia-H`MF6&@is>$pd8pj7l8K606#o3vjYCmlfi z!n)7nWY!pnXN;5V=GY@;qR(k`b25b(;qW}@uuYsJk1tT@`9@?9G+R+<()sBK5cN%! zpfDy^9~<}%4LS0{OOKEV6DA_V)BKC=6#UCS^#CZn9^%pb%`piB6nXQ_`7siklrWlj z$W)$brBA9+*TdiIBU7tJU0tWf&%ZK(kPa{nU?Z5(R3o9%UMX(T2OwhChFxSfw zExF9g1tT_tXNOL`KEgEU#HpVN-~kWs$f>#yXpHttRuHO3>kcqCn+C+Rnz|SsFEqkY z6Yr&aZ*8OY<3hejSd$lElSxQ^Boz8-r+@45DK7j^Vwky7)>R`hm zj;>#za7lQittgoMBXnwaO}9~GZ;iJkM9;vTaK(A9|A*T^{8UlAHgf2YgdU+6uke0y z*UGeei3NesPe6-59lxV&>!t=EwEwFNgwsQbHia)EZs-1+@zPbj@4z?>{n#~TN%y8r zJy7^%SO(ZEU@w`yB5awN*@6QA3J!U;tGR4^L7`Cv2SV{oC~kc5x*;6|1h*w@zPrRP z>*On|7Hd-I0sYs1Kr>FY?E+|~s%-!zgR@lQdMm&J%M!9|#?i=182H|Hy1{Kqa$`v% zM7f>(%KobQ!<-psqfPuv%*PKcK-qQ8MvLZwuSZ;gEs9$lsEGa)X)s0{UK-Hk{cex6 z!-&L37mqpXi@)pAuA6o5e(jG;dQ5B7nZUQqporK%jiQekZ14+o{aZiha(S38Sl)br zP?z8~LnnY4c>b$ZLihubOV2mc4QbbJC+_p@+!OL4VnvF37`CQ%6~hFFgdi=h8{!p?0F{j|n7X8g?yv;fhpn`qt! z*)QZ-lDG*Kg+KJwm)ga4Qj=VRThJJeV@D<;5ZParc`!OV%mo{;|CG}Z_%{W~g;KL# zZU!U7JO0@HNume@?C2F+4J3RZ@Jbj+s4;#(SePJiLTJfKGb3=(MdRrEN6Lo%NRT8; z52s%$7dR-vBN1yAy2q}}AJOAwHnPiiQ<@L5%5^#GahKCCKNnmnt)(>AW6UR8=mR3v zM|k%Ns4>No2LQqEB|e@m0MAsWi&MNw@=(SUWN_PVMGlGpXACoO=lDPeXWc-y>NoX% z)aj}JfGJf^Bx89#5$JyuX%+5*UD>As*-*cWC9|3aAw+ej-@FR>m!ZNPfk^wpQHk0q zqe>to3vgygK}`taHPpMB+OP}^>EHnPG^TGc1QGnci`iBOoGEKfsNw*R(d-MMd>aW- z=0FQ)t5tjn6Ee>-3@&fP*-V+vVx|N>RKFcyZlir>!U1)gJ< z4`iiQyfYB7-5613xd>V6=*yt@qS1cd=_CdyB^3qxuYw&5Fu?4?@BN5#GBAM0pjH7) zASQjIe&%L@Z&t~6VjyoH6Hu0mR2&3Lz1dz&;vOH|c3Hufs=Vv;Txj{2x6 z&?bCHMCL-bz+(|JvaaBTJ)g}Wii!fGOXK)Um{)GroJxc^kyJtcUNRnO3CKXz)MEmv zs)e4$YP8ZLHSr>HxZ_;XhI8>I|E+r@8@@+XyP&H`#EzfP9tVT~TJJI}gg*%6^6kx& zL4iK$wr>1YvFK|Tl&o=s%Ss#ig%bu6BoD?i2FR6xD2S7vCyIAGTq4q&Z{;AKALsfh zo#RkUyoZHdZZgP+%?l9$go1p#O-caes$*-*IV5n5lF%)$4(G&nNj3siN#^ovVu>PS zbI)vyhS@bgcS9#6QI$bp@skR$MIduLJNoqDQZdrcdasCQcb=wuSFxe9ZK}WAdArc(KRu!;z@G-yaP5Rdn4H zxRYW2*`hPGTdt zaGMWsCV5`6pdg$hhslvUc6e$e&l>WuYTEgQ_RaL@lHfHtDAJN0(+gn*jAc+>T53S0 zC_1Vfgk(0iRA}{)ejva9>(h%O!w1R7F8-^>-ZixNV~H!zt4p;h50m zC4x1x1)$uDZ-pUv*}_u>2Ykd>q;{j;X2G^X&G*$Q(U|L3c&>WEAa3rCMxtO1f~}7& z*HhNh9u>I4oxDQ*^%`cHOfb`B{+R;q zxo7SSHVZ6)hYgv$xN>p7dV0uo*JzV-z{sJ0%2Wh)&~pj26=UJMAoJ z6oI{X3{j>|0%U|C*kS;9{DoApUU~cPa`M+2K_P7p=%q+?Sj4>1fn>0@C^kB%Svs*5GOQXZLNwS*CE330=Hl*u< zh9-ww_&j|UiKZk2SuCu*lpw**h|xx;ld%-CbO;Hj?Ag8WC8$X5=--`RcumJ6f}8r> z&Z%xcL;+_Wl|(qiw@40pnt4> z4ZEa-1Ty@EW%3x22H1$F8k{Kn&qfQ%y7pqS*JQjl5-Y>n=I9~@bGQ9~Gdx1&Z7g0J z@QO4nS{GGl{fQR%o(e5vI0^L>pQrnX%g$xKW_ftr8C#rC(56--pd4|6nnCLP6;{uj z`|TGuEP!>b+l;|TzKbHV?K?EIzSTOiVTMN{@s{q;gs=%P(X#y2;XY!b>=uAyW30Z# z2dfg0t>0*<5(xW-cRy>IL2A^A!z|k@SjrqrXY9S+o7P|4P+TaYtZ6^dx6^@h%$#eo zE+7-B`R+Cq>lc4^uZ6w)o1$q}q=r~E^{>%}rXe;(flN2Ntsn5fY2vkC<%7yt_=?-||dKP{XEBSexnt1ETyovPfQ^xjW|96y{|^hG6+%wgb2 z3~?bV{!9a&DG-JQ_)-Y^v+ekUH&TGFv&CX<|CAJ1$a%g))KV`~V*p3I1+L$LITi${ zA-bb}k(O~Xl>Rp&6cEC&W3kxz>)EhxHY z;IiQ^$sFI%mdk3gY__d7@Yi%E4S_HAVuT?U+On^I1l_qYlY(rT?s-PI)Y_?;BhlC~ zD@oJ<1$U@wR-41dtp}s8gHUh$IK!?nhMtDuZSXQ_tSGi}VEj{;s4C;-w13SA{>G#w@H+z=9J7+@Z@{+V558#r#Tm9e zW^aL1VOP5R0a3lq|GP47(U0dPMz6pUkJEs0ppk|!$ZE!6_Hsmvb=dUAuEtwfWn$m% z`}rkJv@*}RUp$YNiKXw z=gf2R>w{l78|r+?DZ&`l64`ZjM5TL$SJl%E;KTkYRu)6p=Nx6HIy)QM?vlSly&<`A zs!tg6TyNQ)^)A3-|WHauw~mxcDh-g#+$jv{Y9n{=RpY zEI(-Yk?7P4RSCaYJzSE6@!<7TAVSVP%o<)K)okGO1kt=A@Vo%_1Kg{Gz9E2D^d7Y2 z*4aRtRHo_4l*R85h$#4?@A}Zu&dL@dezo3gdKF$QD1LJE69)?PU3zCEu~F|vMmA(Z zNI;O~se>AlwA&b-%-(VyE3r|x%6?k0zK~9m`T747U8E1w zl#uA*QDb`(PrCFn_f;M;3-KLxvzoe=0CzItybD*5CeCI3She9YPWsflNh*tE5@=K zx#kk;@vQs2H{S0P69JNIH6@Qd)14_-S=j7y*=CGr&+?LUZ)7Mz*gr3e3XbcelflLpRzq8WS6b9Jq1LM@JbcSe8TunrY@KB=Y z90&!=)Z%T1`ek??YXEecia?#KwNSIy% z-0?>f#jM|}%Irg!n!OKP`6J-|6&S}%`!kfBeF9f=>Fe};=rq|D)WkB`dV<5cZ{UKj zcxvI*0Mt>X#D?iTOmFIAKZI?}HlM{hsOvyKfu3$wmdaONhOcAyt~6MD=R?~XuUj$1Z>P_7K&#> zw4q(d6!5|&cmOY`=K>X(@TRSBUt$bCb|urVtx7s*Msuzw@Hu8szi!MNSxJ}r-FMcn zlpiRPHZ4*h!GUgIY@0pvI0bh;FAPzPgalcB3Yrye{WZ^){ZbFFZEC1t^ZF`M#Lo1z zCxM`oQcWCq4gx}JLz8yQOOs*~o^)H=MTi7kD~dPW%9NilMI^2=KAX6`6q;4{sk z(?1IEvdN(crkV(f@Q9nag5S#k2igwD1h=kRbylPT_7V^o!fnZS8>OVHMQd-$v;4t4 z7%#Y#^Bd@(F4H}qla;lEVJj64eK2^8?qHsQ zX}>VN16XHYZ}Cn7#@d|}8ZOe)8*JOe9)_L^3(()q6IGT(KCKUHpP|yrDz{re!jUsx zXb3`q$0n&uko@wd3>!8GSC3sE1#sENHo!I;24#IR9pV?bXaHQ&3*I__yDuK(jlBaf z0L~YamU?OzVaH1yUUpr^rI~ngsU6>2Juc}M+{N{Wcu39#U9Rp`13=4km=jS0(DKRr zi;Kj*_nH8?+Lc3Lgni5G$FV7*DX5f*L?!T#Zh` zElcp%GzM>0eIe!C@!jw%9c(sTOh2flh$O(5k}#UFSK%+9EsO@IK7|1H3Y#$Li82>g4tsUE1U7i&j|CCd_5v90J8vR~s$`Vt_h zO$_q;zE z=)a)tDD_k$naNK~NGLX{=!jE9&)3y+TA;BH#)&QQeC@WU5`G9ZHDX%0!E?$b^W*DI z0GgaFv3-WG^$Z6V*;~m_!wE&{;F2Pb{OXwwc6aao8;LQd$(D0ciE_%|Kd zMzM$2!592^OsugRo6F@d>esu`sgY87F;!1N`+sL zuLSfheF>m+u-bRhe>v;+#nUc!&N!*0b#Dskbr(GI$? zFE>CR4-FS9_j_P$?Y3B`HHh*HfgYhF6TkLY$U59(aZr*Paj&`air6vNd3=D5_5?W! zqJjCpL5YQbaxQHai~2nJU~`XW%{St7zQw}Aqr@5_hdPAbRif27L=v{ruKAFkO-lH3 zY8@cu{MBD-`i##%ls2m5Ypt>;^)th0Zn*gemzVIqyHpzm^hK}n_1V^jhVv6OKa5Z5 zEjP+b#o_C7YS*&Cr7i(JxISf3TBa>#-1q%N~GtTwpQ zq19vB`LY;T86F#-QqPc=++hjcaSzoLmMBCPl|fn>{s)Pd@c0I8N}nZM`Flytw{o%s z_$sF8$`4I-DGt1*WUwzkeMSh?f?C|DB9;Hr{i40vcwp3O63&0z8-NYS64CP^N%B}l zb881FqOwFF*$>54VytaNJr`Cv*@SA;AG6etn&h0*ORzFP(KZjQ6w&BWB*MZkNM!@F zOahpZ_+SXmgEQA_Kq4TI^f_%mRYkVrD80b8A8YWC)C}=FR?5~%VGHA1=^cApT z>*oDob*W(6zb31gTK%A3g2VQgKQgv(sd$6`yGLKUQY_d&%Mrtss`0c>uic16eJPS# zuZMDaZ8=(2!WLNdKln`DB1ieglf==+9Y;0O_lGI_NhS|t@L8toG;DQGSa_%jP8F1C zAytL}%^+3_#~L!}to=yPxZOvK*?k!Fb92Q$`sEaA3U-FbzM1`HU2mFj+k`6^8AyLoSGV2QjGTL1OUD`egIZ#mP}SvMX(efwGCn5X z#is0-=KlNXf)^o{&1(4FLhWI7{w;x;i?MXkSI0Jy-xl__`G?iTw?wBCVT;ZZ53UM> z=bNkUId|?_CTPk|eGmY4_eN63_m)=u$xuowT1arAqkT1j1 z?zc>B=Q<=RgAz0RCMZdH>786Mf1!2{2~OL)YpouFwO87#lp$LUnrpU<&39MwE|pX7 zLOA!tR0{vAqVBsz-B6E^t%eu(_IE=s=y!oTnMs`1^keRTN$v{s#`e&dz^R*Fi!h`& z1;CRLh_HqGHDIg_&p!#JiZ6LkV~m5HN}UuvnXc%$PARt!ZyJ=^0OR0B7Jnp1EjrxO zw{pfuNj-|>9TJPFR+r`$grUs-ck*2O?@5+b&Kh-hOVeW4e^UXP5lxjyiK={-(}~%KXhIKQD6^r#o70NQkJh zC#_OU_ASb&6V0CruZFaP)#*jVz|xYM+;EOlUSh`f{KSoEKQnQfB7ti0f)|c2 zSEMp1uW>T*iZksv7Hg`!h3z{}YS3Pm_SI|(Xo{FeLc_HeR&K@IS}$wPe| zluebBDj}|=oTvIl*K;L~3QtImI}WEdGyC@aTz2-xv_MmDqr2Yv1~tHbsII38e#S+% zMtEAJ(~wv3Hrk|P^R?Sw%ZCFU+_fuPs?oq-qVBDCTFJ{6Gpq!Sy}RWSkS>2%1grV_ zwyW057_0U14L=ZmKd=5!mGm-9E?&~ZA_lhYw&&{Kg0&7TUflVb0*L$4tzss0{RXfr zIdJb5^Kun!`C-FhvkKqVTSoK!+h5EAWw8;bjVDKv1tPM({}V?gmrE|ATH@q#5@h7U zGVpHW9Z%&*p(Y42dDZ8P0wIV#$m)p_nLla=xb7g238aGjulzId$TBU!w{Ge(H-t~&&t ze(?{zE2ivtY2whJlyAc!%oS*h$M=GAER~#xUe8wLbFs)0dkQG`68VSp)yI4-ZvqBx zLnR@!CWrFGyXhr9*gyjpA-+O0 zIXP!1SxJs;dwc?AL(&tLO^d)Qq zp!$3z{jcJCvxpM!*w7O3d@HGCHv!~$843{BBteV!U96NX$ZbZhddr!7WFdQCVkfU& zsq&phx6R?q^z~A|5%)@~L!?Nd;W>0XvijmGLehc9or-(z$+MM4H{k!(bl>f{w^VV7 z%?g36<3v@CaC#IrvM8j&f#nP(L6ZTE<2{UCD0sGj{&Ydofe zsM2=M85`o;j&t0Rp7dmraBu6u-X?WOVb#~l#$HM|NblCPY*!8CUE|4Ls1_*0w|A%# z(l{O$*|CxAwm^OOZk~k<>muulmWAd2Z&sSWR#x^}33kONyM0hXjnvZWYY_P(!?I|C zg&agOw}BCsJNIrSXL)4fs~kv8DSY}SPomaVwfAmTe1_voa1fSh@8oaNk9YR@{fHuS zzVE7_(^u%?drv?b$pv^@bgj~od4$Seh^r^J?^{%w!vWk4rh)8hI4~V$N+}$>8g^%3^Be>fpsO@edwM56O~4Prgr~ES%^I3%T*7s?WxjT z(Uo1$)(sHP#c%M8DYcs~sTHBn>V)hLKj+P;gz08o_P!RpzmfXL9q-JQbp@27!7VXZ zmWtkr+`$YQXWNO~iE;F|e;>j7XP+Pppm6NtjPw@A69x8K`4g^G34bqLD|=(<27^@s zhY!>*(tnYD3LKGW6bNtQI%0Q9bU^=%&+5&?h@^U~Dn8SanS2i_CP1_Y^fJb{%O zEFvm%5$FN{c>DCd{+1q#`?v3|x!YN|96lf+O1alki#4=ojbK2y?WA|GAJT)44kK)e z*|eFECKdIs1)sw&NP=Yduo(sszHI zty+sWp%W+Lp{U;*GT9aS469Xd-Il||3uW9tV|6ROosr_HPtA@Me?>z7Kv`CH($|Z? z!$m^d15Z46+K=6_^5Z-I9?TL?V1b?rjWJo?1TT0+xgo~CjXGeRmQuspy%>|qfNuUd zIXS2NmHzx5cJs=l1A+dPy1X_Q9_Q)4FvTKCct$ z#kiLw=EVlf5qtUXPMwB@cv1vNWq(rwXrBnf*UV|2Tx67sJ$WLNT61`PmYv9??ssFe zj&vJZDu{w*dzX|yBj@wJ8}O_q7O}Z*KIDoVn2IgX)}F%vq!+Yd_ov@9j<+jYst}ewMZ~mQj(w>wbZ*`v1{-$rDVwwMqRF@>v92O0B@p3P=RD>tk;d?>fTg_=+@-)m);?<@NWzKRUhjYZ}7}^^& z0%Z&Kl|OpKaq9(rQ5B3&EUUxHN1S9&#Q^O4M5a%F(;Oy+*bpe5t$Zo+<%-;b-VCjZ zTpKLRwd0z74Zh<^ zZDQwO8BF_pC9UnZsf#(=^iS8QGwOLW!AtQlU?;KNDWrGzi{y_I_)j$^(KFr)(-SU& z%OlP|g$+RX50{i7by`B!>oS_ z>85yIIJ`onA$uLgiz&XQF(sm_whAcmq9JeEtZ25mr9;J`zigw8yIfDsRiG##Y&i-} zE{|N1AJOyoT>p~m^D|HbP2Xa|?7pi`)%zQ3Gaxz5x3W*C-gkqX-`nVR>rR>_{!`Ir zc+{IaJ^ZBz%5a?zONTU?b~~L}UpN1lm_-*aMDKW`l1XS50$*D3{q2!kLFmu4jJfG# zX2Tsh7*#a}T4LbQ&pdT8eWl9zL&{JiH5ml=&tPnOFoW2|2BS=V%wxiM3wa3LVcf&K z=rEcIa{aGGgm}o8+~4FV*!g}E>TfQk{R$4>DI|vQHwA?Y3fIQvf_+9@oFwpugnk65 zXBB#~M~;u^vyyX;+x);jRG#QZ?@k&ySVc5YCyQ}AF1dEU~Bsg zCz9|!w(<~04hZH08CCRV9EoJ6_dI$~BdJaT<07W)RtkAgeFMJ~z?fS=ON>09^E_GQ zc7-lNg1!{|&I$ucMfi;AGC~?vzqrFaBSDjyOVo%`LSZ|Nv!Ep=9t!j>m7?^nzA2IL zamNlXV${ixL198ljjG>W_~kk}OhA0FpRKK2B9YhVV==c62K9J-RG;@f$&2?)zZ?GC z)qKcXqmP)sIj4I)1LYtjV-pkV7fJieB;J+Eu>lMN-49(Y-RmBrOi}`@Ok<;z3%fH_ zoa}BS07kT4qBt*EJZMr{!xM5L5NMHN-u%3Q4|-??O{6>s8vl4n8IjO`@7%k9(f?~mh$@2I_zc*^2L5Ib z6fw(3Je%+eF>={1iW_96UqS`}PSdkibO|x%JgSj%tA2x)kbU_iUj@T}l{KwW8xc;@ zwRURHTB7sUAJ-dVP$Kz&xrRJOF<`|{l#!K5xhm-5&?47Ql!4a>xrpD5W5AE(0PK9) zvkCOSkVaftrdd?t;Opp#L%zt+jS{zqCUS*<@i(u7^VtOEO~?+<6XO9RXbIK#IukLT z>7rqNAOt;!;3aV$Eo46Cd&=;7I_8EVa9pOZ&-4Yzfns-39S`XU}e59!SkV^mCJE zZI4Z7?Fe@yA7U%}8x#4wnHS$4 zwEW|q5?L!isn_X{6|m6BGRT0fgp-E%DO_FsZbXbk9ws~nsa>D#gHQPs4=)(?Iw(3p5PvKn0zR^yQ2>d`9fVFK*A9I{YCW)k_1gqM1tzh3M zVA$ji;zHa+v9~}+n7mmgiEGY_?9o9vxBBwa;E&T})Tgl4E)N1sO|2Fku*`*R1v_+;c4fWSFK3?P1-!^rw-Cy#)viO3v5BT%(^ZrshtD5bXGrmR|6Datj1h5PR zHcJG_ZqXP!+6U*&rv1$H)=2#EqnsLUS;n9vc)81mW-y~6_2+qS6=dXuSAfAbfeN4@ zQrNYSg9aW^pZRvWnr>^WsTgE~Lpf9iOze~aRBYiQ;tLeyTnX`xIdEkM{IjgAlz?4%e$Z zsxRFctG3dVOQe%`I7D)>*DGl)Bb@*zif*(Zo519-Dp#IH1V!?IPp$le!`0lU@o>uR zXMg9KP1|`NN#4FGNB8@OGVqkS?+9;@G&m+4{`bdZ4n=4&el^d5{g=s4IupZu=))f( z#>~#acmf7a{Zq1o^d@@)Yj9KU4WW^#Uwpl3mp2oYZa zLpZ3&_2-|Qb(JPWap9l2%JHpe3fu#8_?XB9{&(hOj0CbCFM9MjWIlG%1Tua1E5X7?3Nce{j+U8frHdK+o4p~O1>I+6 z+vNJOPFNxO4qdof_EOs7Bpv)2=^vtdfZE&KA1JpgS|lt%i zWaVf#YOS8XbN#bR7zxt~|0SI-5?mQW^MLZY1h%AR8`%L(MuRb}7$&2ofU0g8GNnfi zNMiw1%$zb-`brC`RM=7U5$nZ->@UL8#s}r8uAVkPHbW50_9I#wx@q=J`1f4Aw_YA-_g2f>YN%S-khj%1T~gx$)HJ;9S4OuI8%U06P~S^T*!$(II6-fF4;WqmVRL zcxn^9|KNDhOvP@~a6Lm?EP$<{AT`{QwOQRmF|nvJ>9ZE8ZgO+MD5>rhtG99&3n!J- zfCMMZzjwH4Yw1G>d-1Y(aGSjZ=<0#%8$V@UYoIh?tX}I`zG#Et6XaPf(PV2tUxavB zv!lsq*pL7+-mp}Zd&zC`Y;t<j#Qn2%G^N z-fd^_Z~J(_sf%~v;NZrUHxdbbF|euQ?kZOa`b5Y_`BpJ^g6;%gdW7p7YG2nHH&dP~ z^;fKgVav{i{cOO_Ky@beQxu;vSr~JhO|1aanp(oMy($qC9E8IK%XObp73^t;_$eyl@${Zyy*)s1u7SxQ@ zK&7~u6@OgY_NOvFGMeaJwNGR@op#8d7&G8?W|c6$w~B22_-G!o^*D-cc+;Z?bv2B_ zFjj+$vUl!m2I@e(9lbcee(Ydh%7@x-e-o>}s-_LxdGIVr-=VV9@)phV08@^IU+LTS zKk!@4Xlfym1q<-M7Qk;-691^Vht=QaV3LCx+;YZ0AuUo=cJ7X*ojetJHy5BtB z@O3a!`XoSgbu`kUg@&&c{GhbjSO?+X8?_SjiIW0uNp2LglIQt?9zAxqNBbzUZad4t38exRx4R zDA;`}hVDHs5BC+Dlg3%v;|BfHA8U4_OHKpN(|U5#hsp>WvEO{+Z(6dl9ViI2Wr_J@ z?V8LxDl)6^jYNVFt$WrtEB}(}TcJ;%S~soL9ghOVtTo+Y*7pxTyzlt*DXx;E^Hvx^ zB|XIdOjcx`z#|3dLI*6m_4`cno2Cu>ZAe@lS?2l@Fx7?{!GntbhaqEgxr5UCD3Dx5 zo%;GKG@TRX{t1Pjs=?H?m2k%jd4l~aA}L{!OIN|KYbg6U$_u`PjoRx6`K5Oe;`|`h z3tSN-s*3>Ppp@X=Q6r=f=$f8QtQ3`5dgmNDiScgU9`mmfWBvVPvWj@9pSCC)W%U}( z2OqO+HNT!-$Hm=X5PgXDHV4lQG{7$nn_%5r{DWfba~8`O5(Wj1zf63=GV42goWzGf zXq~VOg`2#J$bTq0`AMGO&b3h_c(e+RIgV$rzS7e(d6aW!QXQ6N; z`v6$K^Q0ryHK7O0rL9OaiB^kfeTz z99Gv`^2pn(EZ2YCNuXCWM@9ChfP|_CDO5Ez86Tgtiw<&Id z=mkkH{6aC(pu>|%+l(yWSr{YANHc~hVj8C%q#P%5diZLV7!?4okz3h~kWiRj_eFPn^ zqv|U|O@!q7GQwW@OtR)rTm-hhQi7?wn;d??!3ZNayFv;pL5(S^3(e*v3YTlL+dq0L z2fR2wSV@Imn|82Ml4)v~>2uG|(;`3HdvgIjp^+Iuj@Y`Ran6 zK*bI@0o6_IZEPejYs%52W^bIe5`|lRws|LrchCh5$>+d{D?+Cdt$Q(DvfL4TI!IcJ z-qDOuThfesubHr)a3mbXbg{3M&QJ#;ifox-WbW@;>UN+*7jRcb*XfZTtMf_=s}+fL#dc2RM@`Onc+=D@X!F#SBDJN{UE?;R z%VL(qJ9p{I;mJBezlmQ8Z`_?BqCcu2CZw?$*~lkbhQ-Xqd$N~{Qbs-^YecJbr{~0= zeO#f*`P#YPt|C-e>iIqLkwP=X5$2h@`zuVh$i(nPQsqw-D-%@=?gSz7xl*C1KrD^sHOHvIs+2!?|Re^kyrIwgZ{2BbwtU(WGQ*Og_5Sfct9=Za( zBU+_&ELq`E8FiJWgaU6Ak%guT_ia-=2TI+aKVm%bKMnoeojC`$fe)A7929dI@za%i zjwZqsewd@20oENE>c)Eor(^nPKI<$b^Jdajm%#ZY7nF=E30P}aWd|xNaw0uGSDq;0 z*@@Hrl+%0Kii8H1Qwq>vazP@t3^_9SWAcpSYpT854hqfFdJnI(r%2426Q!1Lb{vrE z_Jf(VEWQ!x?z`D)P@t2z2XVX^ZM~Wjz3F+s*13oed+yvA*Z#G0l;q_wS zru!B&X`^_^XEuD!%PVeoI-czbCK_W>C-AGCrLfMKiAmu+bib~ z7c?zGQG-YpN6LSHQ3eeih3cBcc)Bw;EgwcRfLjmB)qmLB{jTH3|}ZLt8MFDce}h?VZuFBU0q`$59gPzz z6&1$yR!e|NOx$NTjbDw_MVhQh8&bTjHD8!VO3d2z(0r_u&03q=+ zGJ#73Q)BFVhJ;#jO4+1Hw$E&yY&ua3=W_>cjFTo`Nrwo&HF)p})Kt^@q7Zs>{d&V; z64aiqiUH=*HbRe-8_gVvYQ6cxZ+vec&;khTFSyb1hkVz$e16z`6~PQsrg5k;Vjxpe zW&lk(^LI7@gjcSI8XBMubL7DNJ3W%*&VhT&YE;Ijhcp@NTH(aW_km-nZb^>o>lC#Ji379{Fp6_?^+kJb^sTUGsOi-9BEeuB%f7F*gZ z_whAaFV-tmch*-m15fcaBnf$*CX)>sg~+vuT?fzR_;(e-6s^`lz6`I~SL(3HTdl8N z$+kjuPthu0ev-UIZ1j;7L|D~9>VHvDXtWq-AJu*bz~wj$qRXyrW(1r++t+9u^)@bp z=g{JWoAk0L0&NLZdV4PozD8XWIMRU=v%?@aO+NHJsxjR7>wW=pT=>;eg&rc>n{})8 zP(v@PCjCDf^1{KMHokOJ`V@PC-*cC$P93*Pw#%*QVR5o|Tr%)U%{v^At^GTkRDZqW zk0?Eq6Wt9q8m*N`d5Lh!Kbxt_K>RSC_c>{)==yRUY~A{+uA8ZVU^Wk-qGID#tER+O zrxx%1nXN#Pu6U@k!M)Y{SbyZ&Ol5S*k0S9>cG|1_1Aq13wL8yPGlcuYN`yXtE|YMp z$<`x!!%uJ4^dt|duWdi6obra_uH!#!jbfRoKJJZi7*S5m-Y0&qTEoFhR&r2?!MR>;m5S4JbRfcR9va)D?%a#=W{vZ9 z@hfWYBay1Zm5S(?-M}zX@R$e7pgi97+}AJ2UPz+wJgu7l+0WexoM5X~fdjjh`TzbId3|3hH+C`s?DvIM^_WBGKs?M&B2gVtEf==pT+H0tm2># z?N)C2^QOt9zrE3FrEC!pgMtb*p;8W)+twm$gn*+WN^^WTN!>Wg`OKzo)yLC!1Z2;G z4svFzMGa>(dWqf*Nv_tyz@t`uX`Mjw&JeS5|H!QLNtC!CdTQMRTL)*$kKtK<5+-uy zrQRaB0J8jTsR zUi02jijvD)`Z2zT-&&K!_3kg^vzb_E;d2!M4D0(8qWn51230t8LT=pn9C~AF_4yLs zsbbm>^&6<^ZNmp3IDTDShx*NPVv-EKWcS(8k@KFl@!0rU;gqja`<@}r7%S9KazVR@ zC4}5?cDjc;d1pj$ZhK4S>I!V#6L0GNN5A-^zA}F6cmHM;s+Oz3e=5bx88s2hn_kg+#7v^=!_~Z zVNLc{nO==w#)FOgO@(a1d|!iYgKF5@yj@r_4HxajS^33_DU+F2wr8(q_idBnD2t&Dzy${Il`a~ z6n8FSF^>8gyg%W)d*d@aNY-c5e0--U*enrSJq)H|r9?`2F9>GpR;TgI5*9Ich1X$% zpPXmamEX&)M=W2X(wLMyh;A*=P1CdNz@`Dw?4gUTI zrG(4kB?W_2;GzpJY&7>ZV`;je+5&ebp64Koe&}0f0LuXAw@`Pq-hsOEglvJOg@Puf zY=^v(mj^ZA9}?vFkziqlAu#}9R5)tiN6!1nvZCp(D=|z|uI-*A+!t6e4p6W8{WP>Y zg||qTTpYTkjk*q!tTEvbg;i`Cj^#+AS}BZ80h z+^;&F%FrmPr!mvPT$*Q{5gMnDs@h(xK!s?FbRP4`{c^*B!o(VX7gx=cL5n;d7dZdaMjypHz$Am5c4HAmBQyk9tLwH+5x~KK-J9 z=W~!S>Np!mS7+49=HhL;^rW+M`Syv~3v=^_60D+PMKE&!p>ni>p2MZjyOBab(XZ3; zY5$=7yaYf-?_VYvS5`yL3Ruvra@7mn&eSo=%B!{(7(>~ZqT=}KUz`-86~kfsSD{Z3 zZ2MQeZ@GuNh`e!$KZ|brdp|mMsK~6DFruoB@2{x|EtMvF` zc!!{K8c>%5n(jF!AagGs(_ck(M-!%_ZT>ZnD<=LO#^+sLAk9Vw^Jf^!wtDR+H^VB28V_Wwzxdk09%oSPXnuV(3^nn8+ zv1@LI6JoLH5$e_v#UrNguVvg?8i+;MU7+?RegVg6Tl>+ksiO6q<=G%R$)xP(d&QNq z*n8{v4nZ-LGtO3LwrA!P!mZMwYo=rE2|1NtACzHUp4;ZzE0grvV7&*CXD#>lfV4J; zEh2TVr&h(H{dbaMq;*vXYQTiXz^YuRnNbR%oV^Xf2VH#V%jLMsKiQBn95Gf_?Aif{ws6?XWSYId)*~-yoa3A^nH))eB3G2A66?73R4nN&-O{N;#@~gECb8=XOKX=D?vScWO0`WKTaz zR<3!;JeL|4L9gv=7h$^6*FYBT6cpdRsM1hqOtLWe}sF$^GMr#$n z!f$Z_1n& zTQrR%_H{7QYt_Y(5aGn*RPTdg=ufaNeU-n<6^3Xj<`K~W%UrxZ!mxU)T&62bM3x{ebuo&GAZfMnU8vrWp(3kk@|yKwyxPi!c! zyk~aC%tc!Gz3Cr&nv-<@ z%h{0w#Co^nr)EgbkSk`*+;5ChfUb33G9|3y50pA2Y#HoucDbni?Z@-w>WDXw$p)W* zv}^odC4>|s8VUTIKi2h>NFL`GgID@krRkLk@#SY8+1;^)73O9^K*vEH1$;hi=b!mr5`WG3Kif>S7&UQ>84natAU)>-}F~ zEKcfLjX%*i@oOp~X)pYQO$QP?(xYsFd3sz525}`hd}4E=1*`z?NPl zI+|VWT=@phwVrrg?V=tm5XHtG&xLDeeJMY(#xw?{}v&sWF#Y9eoKY$0Xzkho`-MLIU_( z=cBdc4)1?#DqyNm9P4c4m?Zyl76-d@cp6%akWq6Gn}0DTJm zLn4OmkPT!-lW#ouc7Jl|y5z}4AT4fnN?VuIeLCwcomPDJXrImf$&z^7)KQv>QXdtW z*W!%jaxNstd!l*0PDYT$W{`43rOAv!k``XOPT))Yiik+!g*c(5vvq}WEk(AhR&Pc;IOpQ+El$I=O^Nonj^+b?gCnho1R64Ozvs3^heTFPu zVK!z=$Sxf<^*!MNIiSM~wYCILLm?&k&jg6E)6)vE%P6|bg<%Fw3%jl%a?a9~`q}aJ z_pHa`zkdmB?ud*haZQ^W0?B~<0SyJ-Y_LIs`g*yq4TY}PeN9214v&fkbLlLK&o5&e zibgN9r~*GpTu)t1q;RQkkb*QUy=fu`>%LYZ=KmC4Kr;H0tf=2d^=}wHWsZkPMxVpJ zE1xY_h}v`UO+;W^-S|pp5|R=nGw*ff$gyxU{h`cp*@+G8^T<5V1Unk9f0WFS(&V5! zuD521+9f+W1Lk~gDQb9RvQORA)oq3p>)GPsz=W60_hTEawy-S&mq@>z>B(O&8LuW+FI^GdB+(8*a-vYzSJggyD}O~f)P3Y=wXdyW zzLCw{Z*ppv+37V3MyK~e;DFu8X5YmaSmks==R3(5Ccl^_kpA$mNUa_Y|EH(;EE(%i zpzWEGuw8@Bb^nr3rTuT{O{5RA{@7=x#l#L$XwwUweXfT@O-Tiftg7nnOT6$3VJOQ` zH?**Z#-FKM`n<(wIAB6pAX@l_j)u}Yr@cEszW->EdD}DXlR9Ipl(;#iq^8?sb667?zh)pX60cd)_V#X6I62l9BXB30b!xHaY~Fm8kqK1rOSvuum$ zp+{;v9&&+N|iufKR$21x%zjwGwPZ`%!9`fskI4N(G`_Ib^5G( zl_{Spxv7h&P&C^+DOnkLPkVZqOz|GVs##SLd=zlGIOHo!b4S7u(?PsF^i_$bChSK; zrO|{Ft!QOZh+@-1v{0mlooE<88m0f=qJj?bG{pnDdVM&r6US&xGckV;g~bJSB!A%A zAmg5UZH8PI|9yL( zRtO^VG03yvq-r~hTjhr7y=-$XC8EpRwacBZf{3P&A)W(5HX9+-2KTu17G1Jv?N_@s zp2OTS2HesQX~t+(<<&-aW^AQ z^f7Gb0KXG$?*O$TgDG>ZU9QP-3y|jbs`0sla2ds`qh!wNlN6iy6UZ9$0;`bX zHEjB2-!e6_(#zOhyCl;Ml~jTzwC%*K2g^6lTALr3>doxRxC^#=1l2x&eEcK6q9Pgv za1vWwBzVs~b(#I}9W{<#2Sa!`Ses1TEZi1!bcAee~L>hYzd-T%9uz@N#jNW^m43 zB@)YgykoN;MNETc{>;fK*IbC>63%R?#c->tE{~vwxCIVYMeUqfI?!hW zBXQ9v=8!iLe|?cE!P&RnKs>YSXzl^Z{X0Mvbv>^em#Pw=8g8o?SJqyvzz8KAxDocY zB_;)=3o67pJ9P*c6v<~**z29GBa^k2Zx{K+s{MQm5_OEj02~$sxOhk64opLqBg!Ry zK}BTnIdX4CdXJZ0Q++3Ek37g_8VI;&wa8r=(}g=sYZ$WADLWtYnowN2E6qj^pq{1s zK$%D5fF$iL6(w4B#iuZdR%?Zk`yz0B-25+xS-$fnIg8m)Q*14Kl{BGg{l#QMg>KCU z7Ls`4MTC>e(YQk;vt;`W4;!nBOKp&XwuOVUhd0YZ>}&D%EfSfv^EGDa_N!^}-H$bJ z_0-ep*tDH2>e+NBcql zPJmw$g21ii6+1YWv7T*1cw%DR#K!m*V{@)ry0`KTJ_>Pu06U zy@OIG9H*5;zZ;DS_30lfUErKaKeMIn5vQ4r;KN-%4Wc{N%6bpI>m%I_o~2m&XC1Wf z4)uEfE6^Y;4Jze&if7Cx0Gh_<5Lw^b&{Z-iyiwT_0CJJ*Pap96|7c+aS=WsbRtVMS zB{T=I5^_-ZZEcVttODy3Gy}0ZTUWy%&DFzbkS-;|ZS0o=1-~nrU`Wc}^p3AL$zA8l zephU6#Zwrsv;O;$3I~sr>~5`_TqCY{8ZFZ=_*_rm>cbJ@7Xgydw#NhhGmm)2C+3}p zhvR>lx9zM5Pjt`KHG%PrjWqhN{`$B`Ui3!T5eF@P$#0SSeg@!^NTSbmGk^Z^QGMZt zR9g;~teI9}%R$AWNrVnA=0H?RFvL&V7gcP-q% z_WjY_HSC>?;Rq-$I4T0xlk?x*HEGryS7a@NTm+V!!^jDllx&Wqpv5KO=XZfy*cv&P zHtCU)@qWoP#AkHps*Jr1aQT8xaF zE6q|qmCG|k=4&>Dj&nHGu9<}h6RPBvfsu#-9Xite;=eeym?H&Pc8;Q}kFF+5)UEfK~0so zClcr$b8dL>(UXVH2l%vK2f1=G$TkO1W=`B6rp9#YGVG+lN^x#*cll|WNwa|jexd_ zg`G}iJiG&^%6~ILzd?^#^ga^{2z^ZC1VUdDHGo_D{CtvCP3N}nvLPu6j#9*iN%jFn zjXI2rt%W5tNy&){a02)&YBjn0J>Fxs&|}XhFgM4Z_bg;>eh5^ z1PWXukyb55KFO>iA@x(#6o=>|K$2~(%D-O8y~l+Hzx!8nph77yP&5?R5@F^8M`U|h z0kbJO{I^Q}W1i93A1@V>5y}@+Ya-mu)mfEfQRKeG&orXV@^w%2rn)|ixzpugHY{g{ z4qT+L3zaTXSjh}mvvN%pM$tm=P(5b7o90aOn3`>FNXT4shkldnaqWjUirxd^k9L%CKq4UMgN53w6IM<+ zR05^h8c-w4$lHgoaj60~R%C?7!C6nAC?vjjS4$7d-oV&vwD*DL%Kp%uukzYtNL zQ#bv7So(3_p_v6%#-pceFrL)xEYA^)o&(CgtqgE+K=^Q@6@I1b<$jr8;B8xrQ`j%m z+G6{J>~vCXa%r4+nWWCROTLdz)A6H1> z;oz6yl~1>2TmL|nDg9eBe(F{06@s;09W#tb+dyOmV&U)z8w1xTT0y;mQ02=x)v)zRja zkI$cw1kigT#0A>m>(Z%{vi@shEFZRD;|upE)sYw0p>oyS6xV-uqIFQE?LDL^&|JgZ z8$`Y;Fm;+U?EOXhHU}y)8hcQ#ynoYf+BMF0Y5n4wtzSC)JNSc3!90RSl15?!&Ppn4 zJOf9$L=kB1ogp#v6LT_ZWP{Ylp+Iz_MGD$KIrW%L903B^pOen#ljJWwNFTto;=+Ha z4wGp7igzbmoG)i^4Qd#YOL3!8431@4k#nTLo5yU(YqHFfI?Ve@dF0D|)@oQ&q@Nr;ZAp;hxp)u|xW9Qg*5ZmK z-QC(7Gi3lwkQsKuSr`CvZ%fUJ;4Cm)S$uR@mz(otc^Y8zm5WSS?yw52A&Swi>NE8> zS(>$IVPZ=g%`t>6=BKK#$M7eKDD!d6xX|1HEi_BPfT@qhu6ojJaDh^6BJXY zIE1mkcK762qn3!WKcgL_ShSMZh`7bLU#qgq&&Mt=Xxro(z^oIUglQfo+%$2L^0Ez_ijG2oJQlE9U7gzHm5}}MX7_PtI~#HHXqMr|>wb%NFtNRi zK)*s(7MAyLTZrE$FmT+|BCslTd8SuE{?|N|wMf{Z_5HJeY-wJSYc41q|90S)zV{y&uoi2;VW_Y-m&zjm0BjQZW znsD%f6w3CG>kyr@GoD=%>Gt)G1tG=t`!^lM>RH;Z&-ThrMm|`uyvO@=G1h62Ghz<= zd5#%>(FfzR4+xGlFWKF3Ydz*DA6=jPjC(%OJY^2b!Z&)p6MIz)e>Xfo$^8hA%|Nc# z_(W}7T!Hj1GIZgD#5Ea!2t5$J<61=@_Yi*Pu01)aCDRG2{`Dz0gw^b|4*ASL)ckoZ~sjM9Za%`pb96qJMWe2M?kv8x0@gc}75jgYc(ZXVPlnC4E??>Az=Zjm7xYo%~9?9OUyvJhRUKE-7qmZs9Z`>VxJ zR?QD{I~m#QIar0bzbnldQj8(8=#4^S(ms~M-lJuOd81+N!fI?ZREz|UMee3i3CpRh zJKo2z)x0Nsb@dmr4BXpj{&^&a9|ZuZ#4TzT*UVm~jq+fwFTU4AAGOc&X}i`N5d}c^ z334@pepG5hN3xg>w@t+~ONe^>0O}p(-d-b(rqT1gc9N)M%#u5OW}xZ=;#sU>&sp~A z6wiq&duw+-1V`yQw8U2R+hc`?qIs~4(QoW1f$B-)*(Mm|E zNJ=plfKRG)6tioaRFIQ_{F__cK>DY!`0l;Peu>CCBLzB(-P24CH%)>Zz>gd=B9=Fs zn#q&iYfI(-!_ifS#nE$7+=~{s#kDvTXK}aU#oeKJaTa%Wad&s8cxfpt?p~n9-HPkC z@Av2A&P|>t+09In$()?~DzF^}-)#JQ2IIm#ZPvc~uZg^|4yh|J-9g4rzoEpvxnFqC zJz1je4ceL9PIK247y64o9%=nH0Dvxubm{#EJ0m zMw1z;1=)zMewioO@95YF?sD@=moXD^J1rSMda;reFA#rH#QuQGQQ9FeJbYEJQVvjV zi!Ldp^aG^m<5TKU^p@pPDfi^e8G*OmM_-NPM;82(v(GGx^nw%tL0^gTN`4>pUNxST zAlfmP5#0>))Kf&?8XQIG(Vem1Nbi;+uh0r8g^Dh8-J<^%H+;FM^`IX6mN89@3vc-4 z&Mk1p>K>V-s{2K%{m4i@oI?3qMq_Fq{a^jhdC1yif zxeBy5v`cy@f$cF2C|HL`D>xFm8suriXl6%DiF63&peId%6ed$vT(ROO{8QBO@dx23E+%rQyepS*H#j-j+_TRBreD!+m?WM%>ucF|Ca|~w0 z80>%AQU3FgHybdXqRfL9I{yi-*ePk2RPu&DzFSG+`CUphxz5QKUTfxY_kD{FCNUc=(azY%Us4jX*gs33pZ?1QMPYei93$z@~0tuOlC zAy(sX%=9JL^^%2PGv$|uk5}Ueog(4AI=3ufx?=v_0AUX*oxfBv{f%YVa7p41h+XK- zb|xRK+|?E&uZpJ7VswFEe!}be>0t+qoQyg{<2Y}?0q1|lw|PQ*1}uD95o8O49jwkU z&`h?4zH?kWTp)#QKo7(Nqz5Z-0Vh?)Kin1gCQVl)cIx9PepR3)+Szm#f{faxP3~K{^vuck)D!HPFMyjuZzncz5FB5rQkC&nXT+(!bbH;^wi)v+XG4 z%U%<>BEbn_vrb|n`5ziYh)!C$Ifv+(;aRn-b<$4dtO)PMh!Wr;e@7=EK=@8{5i7B4 zg}m)b#>Q0R8*IqN#FiQM!L>ZM_D{_zI^V8UL@RS0^nH^Q&JVS({jgcWDl@IY)V#{D z8YcgVA0rhF-=pC4TgaoPBnbIBmF_BlpSk>Z?H`siYqQY_2c0rwTov=>T0@8`7$U~- zs+(7q%fiV9*0aKsvCmei!A{l#UlwlhhTGKLv=db_l;`H(3V}- zHr9?oNJL)Dr0MrX^;|W)otWjd^W`6X)x{{#*}&pMr#xxc9P-7?{G8sTts}8W&zcQR z2+6?fc5!L7?Z}Bzy1^9G<%QMzsR8*9#&T%Dt)`xiBq^B1qMHz{R=Y-2WHMd;s=D$k zxM*)jKu@~6`Y}W_v~tWaYMSJauE2jS?X-hEqNCv8M71Klh@dbm2-Yo304`l0Mpe#a zGC5BA-KwjThX4xg7=0q$!Iy~>s?|cA#k`o&fnXvXtyhnl>>tFYDesiGRgaQDXFZzx zDDtElcxDPpv<`IKz5`AwVlTx6X6Q&$nWiBHi`58UV6F^(UR;il1_6Vpvfn`39J693 zC~-y%l_V$8fc)^Z0*_Z9ak{&I4b}xfgMD#~M2OWZHvFLiN-zQtdR}zRXrn}W2`_!5 zqL;6j?xrA^EUF+vaH?&kT3Fg}>p~WMRJ;bU>9J_{-Z;TN+x*Ce9d!1>?y;;w31M;5 zyZ+lLjIuYdi2>s2IS!{n8of9}uNBur9nkOUk?tLb!sGuOTadh{A8!I2R2thHczEIV zuzBNH#pELB5wE~s8!cwQ$N1uSUr}>8EcEAmCb0}PL2GR^ZgSt}2|}P3MjYSCq35hm zG1JArkQGMXAe=!#aQ4-s<;T@G(R2oUu=&6bcHnN=?>C0n!bVa9t$vR;$Xe&{vrL>4EuYohSN2| zG_QQM(7Q+Hrra`bYhHvbqy>wSs@@>O+7z=?{>g-_o+B7XIh-A@rXY!M0q!cH06Ub$ zR}O7wz8=g7mIiBH?r=nG{|T_vrOx=SL4?a_^d^6 zBtXen5*cN~ipCeKb$Qn@Vu+!5BkJVDuD9Zh$o#${lpa{90XR`lITFZYDBinOAqkEe0$Wwqbn*<>gjz=co83h5|w|WZ| zEfNg@J89EQ^F=sD87@RvQX+=%hY2gezO$%;xEB`&?9X`rqpj>&J8>G5|Bv?KdjZXQz1EJF<_~~|b)jEZi7;j($g0bSlCFT2^{X?p zgmo^Gxq8~07?kjG(jt%_}@$lnDdL4+}xm{{ z6-{V{%idMVMdyp{4m&+|>u4x+CGNL-{87Dwb2W`_M&yQA9{Tc9m=rtM*-xFyQUjEe z3r|ealr^cIq7)V{XAG9|B==8+oda`eu7eG8F6bI-qXuU-;f)n0ztMp8(Wf%R?N_o} z|9D}5pJy0HgZ1Aa^)*D_)R)r=guSD74CZeLl`ZZ zXV#N%hHn%$#Pz`@?9U4G@OBa3j=dM#=|o%AbGrOYTNMR^Kl>Ky6vUNs55CgtEI2>- zEyTULPk0n12I*H5-vHE5S#V>N)Wcb@-sa40D8q3s9k-@!?0e4eg+&dKcu^I zqlr`>VQsL;*BCN6ER|myb_xOkWiDynJ)#FRO};qcC8bvgVFvfU%e=D0N&w$wrIe4YRQ7vWQ?QX;|Et0aGhgMO?P|Q z=GA(yvXGd@uMtG|rq|VOFA|i{cXxG2MN941hCy5auyzNJUc_2i+JK+@QJ?g5mCK+xLR{-sn!Lh=0OTmf%9x zwGFV&W;L(s+)n^n^s_m-v(%qWI*qOa1EFkr)Boi@nll8Y2_ z;)~p=zmB1U01D|zYdrsPC2xjF1jk3J{rxJS3GXF+;$8UInR5M7w`Y1l%IVo^WFmXp zB4N4=y%W)D?ZyW@bW@3`h!4C>JS%>rYr;yA#?nIQ98L$cCjB3^OpBJ&EB-CoU$F(_ z;~wxZ_wPy~{+y?Y`Mx2nD#z9LUlxzD=OKY>9%KL15O+vX)YCknRh*3Erm#w+>My_1 zJ@cz4LQcb~hK+^*P|+@AXGT~#sQ)RiZd|YN=T{BaP6KX2R~$+8B4Pd2VPR!}flK>j zvMFsJ{IpiX@W3Azq0hZao5(!q0jsER)_WZ&cxb7l>BE;T47BD~m!Fz+q)<_}I&mY*)f8>+34T#}GY5{K2k@c|wk?4WoQjolXSkN))?~+=oN@A`! zV3sc-_dD3i1xe%X;Coi*Kg2I*Z#g$q;W!0lKnhBs7W(Fx#9Y&?zrghRSd1Xgo#&k3 z7Yj#*WGeCT;{i_$UN|DQbmO^?Vpk1*X+I9A(0^^RZvduEHXdJ0lstcVE{Rzk88j78 zZf7|0!3EsbwH+({p=qm? ze_B}KX7}IdHO`~#7Y^>sh)AXK_+F2zAgcc+%3es1XJy|jENsKLNC;ab-kMTU(uEzd z{YYeqiu7l=$vpIo1PVzeeo`-~X|c4SztIsE3F2H#V#BG{ThRtC>otV$@6NbAiI=z0 z{hi^CvAx-aA+eHzDf|>^^k?`a3I$C9PT>rxq`~HYv!K|)@^8vT@)i@@pN?L@M8@|# zDTFcp=QFU3mS`!3!5=T0N05WuJ#oe(K$F9D=0t31P&3vuJat~Bg6Iqtuh%oK98&i9 z2a7RsOve~~+-A{~=qD}y7)2+60oE>=o})&i*yuD}_Fx2)D19yIL9y{80)S{Oqrnk7 zl`v^MlSSvS)f;Vkx_)qC^iq<1r@TcRg2%VGUTpuSHfSu3%CRHUj&& zdriGy->UE9gpKXvqT{rVkw&IFE8m}g(k>=!dcX$8&7BM6`@_uJbZ2X5#|Q~+HipV; zwX!I2J_=_HBcewIh8+jj;UU3{ky-mE0z_R++G$_bxv$NgDh9UAs;gMO%B4?~k^c7n zrQH0b!6lHP@C4(*clkkrrzwnDe{Msz9rFtYWppKWz7}#96#zxxkC=!mxiuvupJZK?0(F9j_Z`BQwP1adsYCNl?XVU53&coV~5H|3R&7LN7y!!K{5 zT@kUOfOtsFYhhJ?)KnMa>``NvEsn@|C}@w~32_&SQDEoZ{zPzTXIW2=_rXae;95p4 zq<$PqzEKshczykS$(63!Jbt-r#6)2#?>myXats29nq+-jo?9~ci;M;Vl6Q?%E!z;D59yk6TL1^ zWEuV3aJWXrG)q4EP1dXI7>Rt|Lcbm9c6E#2hbOcXKiWl}Ast&91-USuGUU+FlCGu>-lwcfMK%bFh4VDaKiLK- zz$5}J$ZDy1jyx3Qyish(H7X8D#FxDF5+04xldE-{r4k~ul%(>{1D-3l`^X^4JQHtV z1L~9eLtf0|p0iq*+0|kb*vM8^JoRWcmB)V^*8BFH63|fam*LM;n|MrFK9HRrLBA;b z$mVaiKB7w#Aj%<8@1nUOQ5-SRUZ@dEFnRqGLEe3BSNRD$p9ntxtLC8@c5vJLXpt7&+?k_^JdtVBZMuVRx3 z_z(O2!P)b>l6;I+ipEqjmZMu^VaymIG0^?^GF#WX*e0u}yt)<=pT?Dl)vqbk^Uejl z?I(>bUINlMB?Vwy(QjFw0a2my>np#?V@e`DLU8*;gc|r0Ty@6=&7RJ*xI2mPH!gZ`F%ME_8HmBU_NAqyd6sOlD z(_F}WrD;t`yJK!(mB|Lt6&??rmTfYBu9c%&VIPJwklLZq%g7u5kwI%hp8u&%Ep$3L zLOu%*PiTVQs)ByY5vry*xC9WgXWRm>KXe%FWv32WNF&l|K}V>Olbq(72!%yKNBv>c zW;LNQw*XqEuJ>oFtpvsxKBBiK(AkC^!bM0?Zb^bv>iq)GR6;WW?G?sxWyaT~$4X+F z!iV)f=*}w7)OrSc+T$2Uv-S~Z;07L8FL))d`}R6=sz~4viM&RM9OU&2iYH zQVgmBwMNWJ6t92;O8RzRs>r7@K)#cJXqW!pg z5aoGCTbxMM=|p>U;J-h&FmqQ_G`kLjo+yb595?bwsSf4yu?|Tle$dF~Ecz?D3;uX9rX>IAEnH(SHR3R25{}fsCLQ zEF`Zi3@3i!7Vziz@R}S9Cydkxqe4L2;~`u@K>rUNt|Px%%C-Y( zsV0?NDWQxS4@14+E-){eeV2_VtXp#Bek{4+83EFMM?}?PqMwE4265x_Hmxi}HWe(j zvlA$Vz<)SeW=v6=!#&pxK0;3YnB1}^+K=<#@dB(#W*C}{sr}qLPP zzsQxdFF1>+M1(`VGcn%L{v#=>>PlE5F8Rd1%Z0CLkNtQI{4t}J_Nx!_!SLN|GB6wL zVs<27LRM6TVn0Hz`S~5&$8x-EhiPPFDXq&;x0!_r#ZUMOxWr!?ZNj~?wcU>RuWd~q zwY)#wXaZVO@G(J7G=?2@xm@bjMF0I}enVfngukv1?)VDf{Z%W9fB~&NcP1)hxoIPM zTrx@CB%mGAgy;s;tktqE0@oXULKGqEae?d0bxGAymfttsLDa3NvA<>xe9;u^`hI}u zQV>U>E**{0xMfsWmL|TFD6C$459;BaCDO0r!X(JlnMxSIRVK79J1-svLYcNEk{xcYdJhP2~iQ&eU_iUd(ouCwsrW!t8V zRqKL8`zTla1%^_x=gH{*6!M~-`#znd%a0H5N*Fm23!#*>g{8nPjx^1dQAwmv?_g15 zMzF28{?v^&lA;wDkKiD#NR_*Y3V}=(DE(ROv(mP}T1BQT+tKdEHdik}g%ExIdo@dX_^j?|g2{N)6aQ0g6jkvd>PNGQ*<%M9Srn-Wz7P+c)3pPP`MWdT!E{@vJ&aj%FSG=EP1k%n3w1;+3=jYf2AD9jxhGT=?Vo zrnVuG!sWExGa66Lj>}5fr(^ZzY@g0x=%ZGAXT8*j`k{@pJF;#xIdFyFNp>`F<)c$o zw1}_IydZ%l$?t0Rm0x}4HO)v-;fHKQ32iA~Efck4pdX!d(oZZlaV1@Iyj;sByqheS zM{`ash8sWfH|5om|D!{2$6}rpli49@pS2M&xYJy9(j(~bfasn$YR1&{B=0 zsiJvoE!5@hTh@PnlDFq=ApA;q!vO3#)y}HQ>Y}us@aFZBeyPMYhIN69OHIlDvGNLO z_Ec7LfJG+3tE+Z?UB6;XNsL^%jiKAtlG|~}*$i2xbah?ry0YEs&WVjM!!Gg5d-^-G zNOAC=_xi|%Yf56j>Bt=+_GgfUve9I*=B8BMwV$GQ3gW-%4C5r-lbqPg#&5@mg#GTX zJRl^jO}O1YMw|W3?Jq__VGa0e_GnY!&Xb zbwL{_nCmT&hHv9(th2Ru@>H zO#%JWmy4`-GyKpT6Zl(~m1Tu#&7t2jV-D+&^&i*kLTOevl~oYZxd`JaFfwSjTzCgx zbCOy?QxUy46G!E5FHx2dpc!hDDSCA`! zvr0-`0C==X&0Qd*oEY~&TBR1sU0=ka&eZ*PRs?@OYNw^=4wT9P_!hw`C{{2URdNt* z!RIt{k@8ER9joco{nzq52c4i(eH#{?hc?SBWY~<}byo7c+BAy*8@jLF>m0W6p0cpc zIf_t$8t zr>mT&mb7mDzcHOs=~mE*-o{ zCO!Asz)P&V<>W=zRqBkG6VmhDi~^HLKfYB~#?5Jv(GtX*_%1!}z20&^gx1gi6_tkw z&o^?w9b%T^Cp;!Q+IB*ULTAu9D^YSA9b)v$jz_0!f5xhM_e|ikxY3KVj2`>0Qj}Pi zQ`^F3V@^p(I`l}U5Dtaq~+>rvSS>>=!NY zz0+`V6?-|NeNJ@1npsn{U^8y^(Q-$^2QA8{cD#x~B-%{@0aYE2r}qDvv$&4NI1Job z19TD;mg?>OlHj+`#KT9J(a)?ULg#P+jB9fwMU0r~edVgdZA>gYURPKiu@&uyKnGBY zo4866#ci(k=umQu88L*nWP-b{ap zDR$ml?_pw#1qgrRh#28HJz1nLh)MBC;CmV66tu2A{L@ulTZT!b+9q0IqFnwtUrS3I zM@AIe?}2fvV~uBFw8L@$4Y%pA3}BEh{T7R?3_6jqtA6(Qr{2HOXH{{!6t<`a%>Qa? z#ru0)32h=3WI>$8g7}MrOl!@x1M^U2#iiR=(N^hIk*+ML#c~IAtHY5edG`U|umSh- zxa|)Q#|RGK81aM4MWHddt8@ZBMqe+3*``-tm0>|n0e8q@p-+hkhf>}Z>R!Fo^$HB-mRjM)Ym<$_>8r3@WdU)MCRj)YF9@P3nNZIc~nq5+Yb zZC0oh>_~9G-7A*OvQ7vY0E`vX>Bnb{Fb(1?NY%6OX0NaF6mS#wND;tX+H7ZrWxS=W zTYWmhit=-dSRf<`r~3Y?h#MW628P-2cx!r<1$HWUp{^->9!25o#T^uU_&S|8($W&0 zyS`$(A-aPIPlVSQ+C#fUWZ?Y{tF7S}d(Ep2P< zMELx#v}iHzZ$JN9uB15b3M`%lcO%L7?^Q@vSJk*n*{UWbeHh=>0HG4PsEr>S7{r`( zAK5Y*k!j<2sZc%yxdu&LL^WBe;x*!;6Rpai;JnC7|4J z1Ofm5D5b1}Q{899a!QGZ_F>^S>XtqaEtz(n4m84{rq1gLm&=~50yXC4w%1$o$az)Nfu@xf`$DFb=8V1BhbqsM7y#VXa%9YS zpY5}SlhV}nGAL_-9Bw=XkZ+gnBqX)K#2pCk*&1RgBfe8Pr=l9rjv3Pen0QvZ0<}Ws z!ENdv*{Yt+6NUdTx8-F7-wMEl_u0`ub>atbp`+@%cIF9bmyM3z$TWY=xOG;odyE=@ z%v#I5c^}I`AZyH8&8t12OZ4=FXGy>^&v;MRrZ$CN7pO!V@OT;EgPnD}Bf_iZogogd z{|GVl9W`Py&EkgwcSyfH4%0UO%PtWa<5h84Cs6E^37w5+GtH8P0-r~7_AIv46o_eU z1xltdzC)FNeEu2wIgeeMgKnF2sv6CT3BT0FO4N{DTFyniu17x#t8|CoyzZ}&iZOdD zLb0w%Y--83EXxRKO)^a&iKD)CO--`Fpr*f^)HaF9p$2hH;#lQFXss|u$sT5Nef2ac zOnEHr^A{G#Tm{2~wrnJ_l!CDeBzyIESUhTj^M_!q*86kp z;j3aU4%JrR&{uhQz|JpL_v+1&5Z=0pK#Y*u9!9}2D04gEJJRa#X-FxU z20#GhV{}fgD|Rc$Cm+bmT2YOSqlbPcCbPoP!DmB{_d=#+NT<2+qH^BLu!=&= z(&@HW%wxE5y^gf3%2MCd%qhrN-YC;a5%HV_*?ALF{b&=us{lg(EHes6rRhPuh=1hy zhE&E;AP>0xmc>4fr{m?6DbxGe(lTewJ~f#rWtN+08~!pFVSdAm^!T+0_Lf(6xTEQ& zo0}wWwb!y6hohVT%9ROi9)FLWRNZ1T)KPL&dsvMC6FGB;32(AdTTZNQ*|Rov*UsZ_ zaPrZy-EBS^jqL(@({gv@voKJl*-luPy6Za|l{T)MAbJ-w?GcI>hvQOI=YQhA4_ zTDJa%ASBf#F6p~(l)L_I#2(N>ie7N|?{OnKbjS0Q3|#N1#*P2+*5TB-3Y` zqUSskPx!oz6@eL?gY1IAoX$I7cD*?k0{)J57k($9j;(4Pi<9gxgTihUJEo=nw&K-V zd*5b4Wa!}uAsE2hiPl57Xw#&@0QVvlSpH?-3?K$6DyW=#PiSMVDwtE$I7tFkqTeb} z|A%RHD1O8n;WcEf_BJA~Zm$Ong^pL90B{B7Q_a>f#^OP()>a34Vh~lc1I=0<6rLzZ zxuY(v7W7Qc!bZ$^`*$ox%eQ+SC@!s@mcYtjYWYg+QFEjCB3#{0wk<$8S~#fpzQQk1 z$9U0m9SK}W;L*9Hr%QuquJ5c9VK9fm1di7H4-0cMOD=AzF(V;>7QbCK+jFsp!e;q~E4VbL7nT605UK?pQ)uy!(!y7%V;BSE1_*(I^JzvQ4V^>SMK<@3XLNRVn!lk^}2UxzdHyp}tCUILub&#d#^xctRD{cZ5 zY1|NJdhNvBvO-{JS?%BN3p(jNJ(SAFDY2uY(`$rpx{(``_Z>V}-h_;fAwJ0cX^;-K z`?{(J0QhG?rjRFcKYtks9I2EaFFv>3VIlZq@o3Gj)4zz(2OXkSuo|H3+gkob|4Cbt3v4k*AHt}%=aHqw~Bab+niEhxVx2R^B~so9!?4-9gi%$>15nAei zZzZFzZx#URl!IeyLr8vRcu^1QnTHe{>d`53U_v%$My||1UDWk-NcP zCgoF=o z*FD>8p05>cw-}>{6|#jsePV^VCh`Xk-EmhO-MO0CS0q&ZER66wH@=m*A+w8Cnql{j zp6cXuW18$o{CM~7L}~?%w9}h*XO79~_BcOj^F_owsIv&ohEhypbp9YxWvPa`UYoEB6ykj(4fcZT)ZEv$M%=f%vC>U`67C|X|Bbo-^;}|6A$(x(DQxq5#i z@%oSYZ8zyS@KbQG;a9e?FPw3>p#>sZ{Ov zC%orwJii<0eS3L__i6q4j&HF4syR>3+>LQEvU{uGZHd}vpr~E&`T21s@x17%PsH$_ zUx!U#$KK8H44C*%I+(8%7RmMW;*4nNN%4*MUFd3V0s+hGq5tLskA{ZixUn)*-i6P1 zi3ius^S>?+`IygAVl0zie(I+54|R#``UkWfi^07fZZ|jFI~H-6e#}m=o!-p_>pTCs?c)B;tbF2^^}g$#gLCh)VcFn*CNa*(kHWLt z1rp>Oud&vF`z7{gZ1}!LH-ScCa;w|b=i5izv-x^~+`#Ptf}}O^n`FUTZ(Dp1qyi z1t&hO`j)T_4Lz-h6(sDx-n_h>zag&$6QooQ_LAhk{_Mxge>8AyzS5hovUYk9P`Dd( z>+YhBI@Aw-r4EjnlhJ+pcg(3_wz>I0(fGFP`u6tFT0!9dCagxgLG5ySIDE#IpMQEd z3QHzWbM|*qFR6vpjW2PYE9$?B?{3aGI#85?s<&_Q&3`x$t6VKLlB6SSjqf*V|5-xS zZ74-SD}Cc-k;G?@{(3%ei8)v5dFOWJ1>kmt3k@?fEal6_%~fnLAP4nggTR@E(|_4L z0iu0W3e-IlgtUmbx$nqR+J8O)7QWnHIAYk>p)^a&An{rynNrnQN4K%of8ZV+5WZx8 zH7Xto$*0db&Zb1I8RnmZcHJPa7yO1S1T_ixX%0c&ic5~LMT%nkV_x%m!5#+YX>Y8u3z42e2V`umG$AO50f-Pp;rb7I*%_wMh?=Jc*oc#U~5an;1+ zoxR*VwY8uXJz*>(s#tQIWk8Qw!q36&G)_ACb#+M+#r`f&RYD$&x*EI2vuP;exFLlB zXNG78xP7Swm8*uRK@=;O!SYDn>_bl^YEp;bV1DoY7Qi$yUU|OZSK@puuQKpFKmu8x zK2})%x~yYhO2`a_a@^f)93IQdd<@5vZg@kwd?1Fx{mmiogXM=L6nYt5e-!f_5x$E_ zQK>&M+wUy@O2(y}MH!9by07Z8AudDW3&V|(u;^NauAi?i>7#GlsXSC^J_zT&Wgj{1 zlL#F->nzRZTwd1D*w=Iz`%dV(9{ah+fz@=sMO;66I`;>gnS#KJzg@#uVkrPDRIR^j zL@5EOhHe_Zxwz(2b1!EQ`c^J+AltiOp1}hUd*buZMaVl35iw6gSv225nEbBb?Agcs zV*a02uuVaeXNbj|Hy`DtmyEYPHI(SxV2(OXDTq#v0>Xkis~FV&^RO{xV6l<5=(=zD z#;Xw`LW(Zno3_7{VTrjUw^;@9vM77_iM<@x79@I@O48+)Glu4T(}RK}fji53lGU|a ze)y${`Y2nf9rv1Dj@(olTUgo>c~(a1bREPeu7rjClqAsCEbMV2Fv_@qg&-1>eno*$ z5l61ZD|mv>idwv)bOKjR(})aCS9_6F65gtd$sI7XlL93Ob;~(^@rB6nvN;inzo|p}@M}_US(02= zelTrh6yiG_EnF%c&h2|pO z90zTA?Jfn4)^%MPV|bIN9nj~**LKSoIrARu54U3B%EUuV**&M@b!|_tc$_V@*hVE; z&*u3qv1_=%^nUwA3Q2)FBoi@BC*q{cOdig*`inl-BK+aiJ;gdOz3;2MaHI6U6imAH zBe%uQ`#;Q5?B(-4dkQFj-xpa{*sF>|Z$dnM-|_eW95a%Ja<_nq5MVYVHIH}Ji2lfz z5Ph}7#|5RK&-QQljx!!ZvtyL9`#Xd_@ADobow4cLvBE{|{Pc%tR*$#I*f-#9LcTYSbh|K{RMPo!s6a;UjREihj@)Y=kf4^I)@)79ni2{4jLTA z0(=^ppwGVBjAC`el}tRlcqFMI6c1v18p3Mo-rBo@(Y+b>c?;i(VDFEL(;WQUY;y`C z+lNi8D>FYam$)3imc)I`pZ(+)&Puz(BQ}H%+2P5fJ@z>fyS2!m4O*(_TTD)$lf?yr z<5$gxf~0T$UNxmnmn9XVem9Zw_FTe~ig8wOIb249VjC|B0=-oyLuyClH5ZPS8!8$q zFn^iAD8+AbSTVO2s7}~mMk~sv-Adv{R13CTS7HqVQpvQC`PRJg5LKr^X=M}3AUeJ1 z`I)be`X_AL*j4i8hn>$)m;C-0Uc$W`x4|rrL)_t>25JKhUYc20K)1%@fLpJV0rw_n zW)%3M=GoK0rkqg|vUvExRga-P+QOQ*gtiC`y~9s%B9p=IQ;OQr!d3Qywiy`1dKPh| z%zp*G^N)T%6K4}%tVYa$Dn)jbE3yvtjS4#hn)}Q;Sq%b@@Uak5@&pIi5||@e za7eRaglo4dg3i|Qn){h&pZ}W&XUPkuVvumfoQ7*r;B-1|-as#`w}1F);^53Hov3)0 z?Y1s7V|ABhq|Q`6pqvIb{Sv(DlD5W-!a*XG4@gD8YklLus9N*17ZE!^h0vYY6{LdSbe0QOlE3k^P0+L@4#`ZO;wo)Kq(3y`aceY}1#K=6WvUI<3AF2Y1w6m4Fe@ z4Qad`arCxgkn$?ciM%(JP;HWx&#^)Q1oGX@9Mks!_@p$n^J?so=7rAhL5M= zEs>x9d?{f?47V?)XjMRqCNSati6o`A>(j zle>-We*nBdL%(g+N5)hI^jPK1@isV?u!4KdkMCs5-4li3klGx?VpX*oCo1BAZ1oG; zYS8&ctIr{%+h4^j{`U{;E086}qP~I*fgB4XCJ+i__v5D|mK<(aRJ?Q_HT)7a)e1NO zeXw~bG;}WXee_(U4BGf;_AN@(B;5dE=15EbdaSEuW7I+9h#BT3N3^s_^y{(MRd-?6 z!9v!hHYKr&MXKld-AEY>_FD?6Ku#aJa{xujq!#mTA|ymjss|8CnJvN)5J%OfnLH3i z)n<;4g_trrl`bIUrA>-_k2{u+7i=;WCa6OQ^|==Fc_3Z%rvf=CKPAQXf;C!O zD;cdgIM!p$`5Ys$)~fz`XavX`bn(u%gjiw`C5z=w9}@{A4#bKyyGPzBwnmLH_3Bdk`s{Ruk?dh2_*hnI1yWpt7$%-wHdA6eF^2crc^i((xPT}y6&(l zUK9sliYalf7OPzpjP*M6rjbiPMpd=N6ou{j>u53}FNvgq{KqOo$XFk-8cRCtKj`Zh zlLhQ-MM&4slaGlL9(5mmQY?~)ONRb#MSP5b5Ge!AJX&63iG|u`#}b6kn1RIvb{|u~ zQfHG40fjjIwdJ;CeAKUN;;UYT zN_6pYg@06;FZC+6=5EPd7c14iLGMwwsZ=$&%KsJ!!)px@mI#%(bjL^-49j_2h}AKL zvwg=>x%EA6CPrt6ojW!gv_}yQkSW)%Sq_fIJ9L_osIVQj;+NZJDY2DG9FC}ysl=&} zAW*c@m`8%Zj-H+j2?F&tJ?arV^@1mf>Rv|(Gq~wRQIDl)r5j`aYcVJ)dN{sK%tvYh zj%E|{5ye9~VDLvww*w(7O&^JLfLN*GG{pa+Aj2ucY0t5Yovww5e;xzsj#M20{Io_hBgqkn<6=&-_MUp#6(|N?L&S zuWnO2n_=AqhK}PnA~t1cx=x)w3k?LFShe7*y=z_^S2r zhrfSdUx9SbYdK;e{o8@Zs2v(N($NFy3On4C705i}*C5;1>?weSOzvJl*4XOFyv>oY!YLM!rU|Scek8wn z>;XBNz>?PvsQ;yWL(D#z<^{6kv?=rq99N?WEOmDvO_Le23?Ldu+<C&?l}-2AVu1ET$O4FcQVto&0+jP{ zBg+EPVj4~S(j z=6*+Q${0CBjq2jGZl_XP5*fxQAR?jhS5HmFU)hs@GFk#LQ2E(IlKl0t!gign}t~AWK6}-`T2ieNAZ;AQV-qWb_f+*^fX*R6vbbXu@ZS6tu>I zr>Y_b02EbR&qr1L48y@L`p}s=*+MC#GwR7){ z3EZl(-qBmW5MRduH4V{SomMp|8?mEvf6{{P((W2m3CNJ7QtkAx{qj_MH38(V_a!sQ zt5|2BR#c8YV5S0 zcR$+*iEUjhE_^YTkIOKB=lm3kVZI>A9xM z%Bl+d$8?Q$Rn-s>a~3faNcmk1g>y}a`AtM3ZXEluv5!+(0TOsO%Y5- zL;zqCwuW8+q-&vIbuU<5GD;0+MZ}a-J^|vsC@1~u8meo$FBy_iidG;3p#YaOa82f5 zYmgZNZHg)Cji*$UyJ_Z2ZOnpa>@UC^?ERy46HXa;Nkl2Zt$=J1&Z4CbKv>sQOdZ!& zUDMqy_Dd#Li@Ub$zQQHiMJXR3TYZUz$^-I#II*H65D@asq%^S)5L;A?eV62$;wQVL zsYHl*vSqX=9UC^)*|Hrc!n-D6VTuz-7mJpI#J)D0FDOs2TQU}fc4+)ARs>vT-bKiq9#;O<5r?M4KaOj(i%PM8kna^0I0D%kd-9RT zp|p4&fW$y_z~WAN`b$BD2jvbV29#rxDuu*AoBAvP?CR+&&QJ~0-8fUyatZmE$WYAF zpG$L9KW8b^>Tm&s)cm%>5;ZT@=a3f|ba(7*NDIU_UP`h6;Uuc)FUpifh2R77f8o1I z`GWkf2yF`-Ny-_4aQfxm4_`N-|I2Z3ruzE__7#XN$F*rdY&rgJA}P>$Z%#6SbbHMy zfIYovA=SLj$%__Y&PWHGXA2`8peYW+IuKJv z^7a{fWj$TMjPv3(WUeY?tFtlC&(cI1i)2(FoJDApTL9FP&76Qx=5l115dXyw#}dGK zg(=VPAJ|tQTYik{>qJ68j?8a3R5w_Z_XD!z$TVDKCk-i_vZ+q2VOLypRx}@-kqr=4 z;VqWtU`1*-kS;gY)SydrwY>BuTPa(2zDNa(=zJ`>0YbKaNy`JmLij6N&t=?~QYSMu z+~AX_tpK4!Sy*p6kqVG=Vd=z-RKR-ne53+sTxxItj(VS*0x|*fW4Kf&(k}&UAXJkt zDfknafW}90#tMXt@!|{*0M+D66W@tM!1dwAuzR<{vtO{0FlPH940)*n@rHDPN`u2-9{nTqua7;S1!kP!~&W_q5=p3*W1s>SaZ$R!E0 z?VGKTAhexqMLh>9zUTBDHO-r^6qR`a@kHVp0$5mQ0t;konyMT3D`j9V7zAP&Sh2oe zNzCavA>zwLb5;tZX`Wj2qmn9c$zL5c1*dDX$5c2;?d(+=aLJdcNmsbIVD=`ua%meC zAQZTYM`v$ISJ*#k%nwm8m+NKMA+hgUMr*ucw3)ZC4u{dFcp ze0=B!(sT*G92$OU&jciAE$aP{)z=MQ{jYS z#)Nc#J_0VJ`z=dqf$VqeD-Z`yg?GsLO@YY(IbZf!6#IAHM!XR1TKEYh0MkWg&rAGl z)=145lX_5mgcum_Vubo~T1gJ!@#*2#KA6~aPCVVftjRd3XH4nSkC-BH|NihuJ@9Xi zsM(}1-@oZv|5`KypHUPkPs(00of6L}CYH%5dTB;Ey_K0nnmN6bnWs_H+qLBMYRl`TS#KnD34kO5h#-6;rDDRmcQLpVS*KZ`WeEYA$cr;{5kqC7&+evP$YU z3a=siKgHy^yw!@n3hI1aPlB+#g^Gh9#Ci1z7KQ%)fqexsJjo<6Tm4q2I6&5&w^l!a zVy{`|(5H_SsMsYT*pH`h4aCH9=utC?rQ38Svozv}SL{(B*^A&&fC92CjSM0?DGS$4 z0ddIF3}<;;m89@%-|85{**Z79q{Cj`rmV;kN1AUj@d?TPgMC15 z0lbSe-%HDafK2)4T?K6UDb{PxeTO@-`Ry&ru2)`SHA?LXyNtDd?6L~5qT$zBsfArK#7-?t4moy~efELhKd`Srm{+}f zic7(=Z|{=|88a?GmZmDw!;W_R$~lR850Hlm8T8&mGsK{=N~bP6}g?<@<-5IV&69_wha{N%W6*9kX6^yy@7b z@=_p9fNH?uAWXdtCGF!}bBb)_MDXg`7E#llIm4-m35VrulNl>obRN+ z2Qs($1)o(VAvqKSamJHj6^Q9X)6?$)t&5j<>k}*WKzdFjjV$S@Tp+xzJNi+e0pg+` z3O&DnU|)f_@QqdLKqxC!3W@7-^ebBZ2*gQH<_m$CWN_-ea2lox-#AQwP~NC2X$CU& z?Y$Xs5|rU)T`NfjD;t2g$Su4N0CNoHhSs&U?9>TiAkKm^_5yJl)aLSbDEA8$9!Qs;p$Y-S?1jT-m6AD6@+2VSgQhP)%mm}>iY*U5AWa;XBMXR$3f&+O6O|R~bQW}W)wmUo2#D&^H}t+4 z{^GA81?-Zq2f{3n{U(qp&p@XLBtk|OoPT$_XuhIDGLCZ?c+P3wM!A_Tyj-9mzMi_1Bnz3p02;ccs_G^Rc$B+AOZvs zaV<`D0ZeJKBY$+P$IP)$b*3+onn3k!L3URMRM@HemZ0>bt%Cpi!;cF7t*imD1a)7-RNDQllLDB=11jvt zbBYhdB$F10F3&5t_Hi{*473evB7wwi4R=Rx%)A0oAb>32%0tot!s`A@f2H;{{O@}` z-}d(p>^{)H5CdHCuAQ46%H&z(MCrnn z2^2{1&*4qRfmi|4FzecVY#h@kX!TNL_3hB=%ldd$d8tiVY`h@VUurNqQ5>&%_{tOk zfY@3r;8{3cbEyd#<8ZvD6xo*7L~<=PS|CokQd3+|=A95^qe7XNBI}R9TGxjVxggA6 zG`c8GSLxSn1BdKR~m4D$=4K%rbY9c^lv_;nt5JV_P5~TWTJ-ZyFdj6eP#7fn%%{~T& z>o{wXo^&vUz-zXUDgQxf07%q+X@_?p+A3vid(y$OtLQ0oGD91XY3q0(+A0Nm#W0!< zR-VQ+bgnpf^YER;<_2p6d17RkZ#0>2DNPL|*wEOfbEB!bwm9I36^-$mQw1=bZlwc( z1ZTx>XebEvpRcEAI+m8O0SVrSk2(T^_Tau8MPrKgEO+GLXzBwTfCOh9KEPoO?LRh_ z(ltPWwBlFnq(l3U4Q($CAmpvFJUsOpZ7eM-0}}EU9+gOhQzZj{D4aeXrEO9kuX9LT z^-Llmn~dck7YvOr$eH?@S3aF`JrJgJmIJENY>x(;s`knT`~3s^3M2}PhEKRyF^l27 zSz@(9aGf8|*H$U_mto!&op33Euv91?t+=Oj- zJi{S25uJPz7apyt-BQLynPSro*cH<#beC=I0RYFAg@A3*ZbU5+d(@zjPu+ zAbSW2iEDU|dLTi7?#97!oRhzjM?XUQ&N`dX}yG#3zjj6;OknOMF2wW}48#gBa67+Q}r5=FH{Ty64k8^q81kkCk zJ$}>0ftKfP(EjB_#9g5M%ZXh2&hfC;5kmSpMQDHjz~19;X#=vcBohLOd;m>*qF-L0wFEZf!6@Yil%ZvKp0o2r+B+)v`r1jO+7pg zYNpXQYpMC9c)vLGwmhHYsG8j!8G*tliOnM;AP*u^yR`w?m|8#rgcNpqn!2^u3eT1X z(8XY;lol`^)y#Ckz%O4R7iXg#2eJV+Mp__5N@bgJG9D4)m?<$Huf|v$g#g ze#NlA9apDm+~y|iK&pPVDBF!`LcPOpg?;Hdx8v&ch~18>-bNY-DbQ584iHix?_|HW zwjUE~Ai}shRpbq1sRv5z+1hRlch*+8-?8`TJC3zO^+P}gze^19Tw+B-rAq6luzC!; zy`vq-hW26xz^FRSpN}>m!;MMgkPhG_Y~;fQ6OXQQ98;$!$)}N#O;e1+<@;e_y06nD z$mEzl+G}M@tpNl=20J}}M0!90fE6@Aj#`4n9qSBAd3csynMWHuI_^Dp|C$36krtV$YFtF?ecRZ_h1 z5fXW$hpALq{rFB*R*&fk(s59|`+zoE$uY7o?Ljt%7(bAxL?2U0j~!_S4S?vl@4pmO z?H+(M^*445AY?#8NP*F3}|Rp03^zia*%A~8A6vCBDz5Qs8R%k zf;NUa29P8FRrT<$vZR@-_P%3ZflNgJ&hmh4eLNL_eQ7JQbYVbPsx(w72!x|;=%}=P zO_eGQaabVw(i%ml09dLt$?O1xqL)!(U#hUiP-;y`w+C5A$jSj2z?Lj@H^xo|+tj98 z#Y!HdK#qDLYm+vz4At+qg_soiJ}R*uQ_gZD&)^skY#B(?N6_N~A%(Ro0%8tJg0o9W z4$BHLAVXe+t5kuAA(9yE!j&$!TLIF?(=P+@aN|(gMZ2v;n-(GDu#OWz99F4f06FSA zbZWbB1FCyy1L^W2oEQV4I5U~X+QmiI9>+k;fc%0(6xN{)$kCu+OxQ&`u0)C179yh; zJ!*m&yN7-`dqRGpM*f&;*;h=r9vB1e@x2?(RAncc1>X_1~?wTGE%@`#wh z%IH;_nBAXVbyDW-V=I^U-eeTWQ5`~O5OScYsUMJKW=1m5 zH@ugis1(YsyQ`zuU-XseiSR z5)YFOyE!~s=Kx}zi~|el1I=)$+5w@+a=)^6Pf76)NYpl|l$FRjpN|UFFSNd;zazan zmIPKHQ`2_ttp$YiW{Z+-WDmwup8#TOQMv^}GHO%oex+uhXCZr_$!tx;8Xc#3K&;U* z=de4MWj(rocX(VX)dgaWjw?@gR~_2es>T9BE|cA-J3g+Le$;M>hoic;WTWZ@U7L|5 zR|n$o$a(Va4v$M)7Xcae1+lCE2-&Df_UN+X&4ywo$$Q6hg^d*%g`B!&*d?H7Vh+^{ZAJ}^U_ML20Zm(}vKi$r< z>k!S`rFEW|ne#6ICOB1}q4Mi7v?g>9)uF{aUq~564E!SbOZ$;(8O%KV7?$K;auIZ*!C+wCV`Np;5FT zvU(cS22THogHzSlH{qUF+DWZ9Rehb`gxtaP;qg=-|CoHJ^fLNU6hZD;ZX&~;6@^tC zK%0W+H|Q&X;oe7A6(!$lbk4G7OKPLBId#}{s@i+1)En=^A*8(-qXpL%Vj@b>Y|oxV zR3m!!B%eSQj^2Ng-qD`Xai+?;@9CS4N_)85Ilswsd(Lb@j=Q;%h02>u z2UIJ8K(WEnFqVFe;2d+V#PTm+HFj7_y48goD+xdubyU0Gzh2nj}`!J~QX4a~|qD<;mP>?K8 zPvo3)>x|6XjqI*EsZ@b>&!kdUQw=4Ra&T`Ql6l9iJ(94pmIa8@f?Pbk_mtA@fP-X# zJTtfQ0b-?FY6Ox6^%>CjN;4@EBUf;ZkM~kzP!0^L4oCr#3iO4`PBSpmQ_^zR?od(543>)-LPQ*y$g?|LI1 z@N(d%USz)$QEe0 z${U`Z^9>E)({sL|x&9eS|4&c8&T#r)^XoHGJC$g5X3BBmJZDNg9Xk2}$W$L>DK(Iz zKB!5`S+^Xg7F_9^C61h>`9_McXXkuFB=_jN%;D3kfq0bDL7uItMXLNqCxB%N3&;>X z5KliRT`{A_xo+i_T09U>cF5d-cy7UG9b^kMx8Q6HNX{*47h#SzBJtaFsdSSz z0_oBnS#$_wIad~A;#@odZ1_k|08IZ6%>aN*=PvvkPc0be&!rQX@zI0Z#?G}j9WlFuh_D|E!wh^93%xaukf#y<`oi^4^jYf zzsz|7sUia8RzUQmBNJ@R_skW}#S+JOo4JHIr%x&h#EPiixLm2R(FFo&dKM!F5KkmH zV1PJN-1MuGGYJk(AWrJ*4NFNyl$z}+HK!6JFF=@Uv?dCKS$zq{0IX=sSfzc=Bmj8Y zz&0*A*DGsSPSLqu!*xqQa@KHs&GL;0pEObsm93BfQ1mZ)zmc;BJ$$6<#uAoOW~$dD z8bCO0u&V{Kq=9J6mzC275-=dn>enW~vjz<^=>PR8+nlm*@mif=XHtLam3Jof1)Q8V zup1X0m-#T}d8s;!4jX_c4Rjp8e_-#SSFcR-voaINXirH7$aab+gn(0v()><+0Le7} z^fjw}+@|EiS!4EY8D;ddEo#jyBcmXYeV)?!sV#{P%Nc-}>8Leo%bA4wPSvqq!=e@t z1tM9v_MAzOPy_Kyf`R+gJ5s6_K>wEm;ZzZbXA;cWz3-8Vw#G=EIhA0t1_&kX`vqra z^_xCxy~GhXqXXb+0~26CJnQod?qoHbwE*$Vf$;5gv@5qIj*)WOc7 zo)qE8Zcn@JtbWW4fjFzL?`+q%to~^w#~Q2sfS4LGE+PZqgbv>ZCjy(6Mg_)cccfJ3 zZuMq{L2rSm3zBl4*6y4>-G6hW%)Z@pzSkH^HUKdT^c(l2HBPI4$G!q_{8aC0Jts7J z*hprmkkCd>D`fR{*Q#l3H68Hv_^_EOsz^(l*@pKuTg4{SRZm-))7Ri{OFDS6f_CTC z<%OG$%e*}`G6(h18UW06)KS|VRrQ;b)Ak{&pA=Cw0@~5DB{UqQ4Ma=T-TRd)IHi0b z%;}pd0&z}XBfS^b$;mhMlH#0RxR-m5PJiEZ1lSmwdjc^l<+4s7R>8?!fmrcYKkYgg zY*;=9;;g#-X>VC6NA>IUo;iJL4?r@fzorn=QoW#q>fK%=S?SrnhRZEn`2ys)4uIcq z7psYs^qCobPDOw$)djI&<@BXeIn!?-R=nwh`??kHCg8ZFxbc#mtW++g>!i%#B=+wg z*jFIiU6B12IfKj2sR*&U${8pS>vLi=<4O*xC_k>`km?8H$~3V$;kYtQ%+8IRLHl4T zEb;}wbpHMD zbEosku49iR8G_eLm#R6LbF{zJ!%t!fp!kodgSL8j1gLq3RGDv<>kl%w4qGg+iK z2HJiKzCcpgp-!E3XT#+vS4(A6pS@Ztn_Mq`R?h_w8Um}|srY3?G)_Zwjihmk z32WSyYI>cKt1T#Y1F19j_ZD%T|`1$dIE$bM61^hG<(&9aLF4Gm-Z>#>?*>T3c;=-jF#Zf zZkf)NfU$MJC7d_8@@~?`wl=?c&q`lfsw1bndnN?^4Lz30R$6JoAYEA%5y>FFipQD4f?oo7Vat?`M=dK@2LSPsPbtGt?F(B+k?=TvZdGRiF=|#Pb-79fHwfI@{2ASh}TI@eI_aZuBVMHtTD4hhNmCJtP^-@@-uMI@&v9pcW>#_W~u&Q}$SF7Kjz*qeFs#{LMzj%#j zM+?NuDE<0Mem|}`wp%s>;wXQ0cnxIz7z+MNHrv&JrdCtk4vPLKfbuc6iTX<^FUJi( zrMwizD6zZ|Y-9HD!-2H%a9DxJXdK#soM-%bBQ1^QYq){u*qUGjqN1pLR(Gwa+p3^~ z?AN^lJrHw)*^DS^c^s5Mk#nntGLSJopN@nl$MU6jMi`B;OmQX^Q#jySwqz<<@F{Y150m zF)GM@-Ft$(5$uij>)sP2knWEtMizITxcu-*13sF0(tzG_BM|Ky!l`Q@+M{Hsqd?IA z4(LhCe``+_E`@p{`{ivh{2Oq|U-wqYfoSuQG4fYOTli?0)sq`6&tXK{ns}H&&mRvy zQLd&SnlA`BUrp@4wc!=#sBfguP)EW;AfHXuil4k{ULr$L_Ev?eiUlxxF3#M7>WrSry0;L(w7c){*HYS(e5(Cp9MMXV>m#{{}@z_QT4XwdTGNW z5u&CrdXhV|%|*D6rr9s;3{(_G8xQh|)=ET!tlHw|r9Erx7og;O_aFnYZQvCmtq|Gn zfoP9)mj1kv;)jo&h&PN%K%sQ{N0qkohD?EYhjRIB2>IHB=t@MpByqa@MsjO3YT$tk zxehflg#6Fk?&vBtJgy zd|ukphgsu5wC&oZXF-y$k1gK<@%~w}8_`Z(Vikj-GKU_{;Z?Vo4tk&17ZF8ICL-U6 zo~&;gjFY*Cejqy8$1O4HOWV7#nDC7>^9)wd2BJ7=e*%@BLz+8Zzmfh3()jb`t+ZrJ zNc0?4_5zUTxtpY{JBBUiX;3UFd=8-~bNX=VA%%aqipZEe_RkAMTM4>>A@@9XUVJ0m z_bhiC3`Ff|mIfjvhph<%Xwzc@#Q@s3PuM)Z$eWx6qMi25|A)2@y;RB`hzyk->)24H zh_M%;epQU^<0lHW}lmP z=LkzZT6hjyid6Xb5A2JGPa5&JPg~D4drn(#Ux{oTsWoMYW$P7%?YUmw&eH9SJ#(~+ zqFQ6WeBhDadcWFd^Xwl6+&19!#~;&Clg1glo;}CN%`sy^qM(0AwBcY^-$ANC2GtwwV)Jc< zcBBeE7|SlN^J&jrU)mF2glbowV0CH9Parxm#b1g{!E>MDK(w3ibrR7=vbGj71=bbH!N zmT~s-D6{;6B!PZ464~wE!1fL7mv*!rqOiyj;G0Xz4#*L(G3EKSKedV8J}+%PZPu|t zcR!-$J}>SLo4)y6-lf+)7AXR4aj$NU6hZ%WAAj&h%1b9xxH(VpVGw>gQUvAKy*+#& zI!QxA6-W8)+_%|wwR(DvP;V8{pXmHp{R2xv2L^>QQx z=CAt@h2KB0FCyByeEF^WOIvHZuOUmoOB7I$C17jx1ayRhk(T82mi(jZN zjN^Te-rj)Du~06cT$c?eF&l`_dRYdv5&OC?(RS|K?BI>CYV3YHAj9u_jOfrdzFxT) zL#I!;4WvIhBmUO$A5VBgeMmD*Qm)G~0kq8WP0> z;%?4f|AzQFKJFlp2x2u7y+U+Ei$s8eG(rF9TSyap_P-JVbovbD_uuuUQwcP)0Mb71 zTVL~|ZE&>jdHU3M;Lo$!WxLW|KHjl(BRY0MGHyYR;L~`e`wYlSeH}Rhegcaa13Bz} zEZle_NI+1EIC>6;2d>hdRAmj5k_4V}M1*h_I!1(3bONW6B|E(iM zI23;Wz`lqaHD}X}yN%!`uXiw9dChK**is<&t0VPp#D|jYYD7nwN!tQ)J_kLH=_TUf zfMa_3SuAV{Wb-35TPc+}^Vu9Rf#|H1<@Q=How<@v-=s5l=dT$Pxy&gL9~jr0k@MlP zD??(<@lg-iOf^jf!q?NhyR^&3vtwwAiPhpD5ZOwM9Z2+>rpnPbQb-<}**B1|RWrE) z5|ODn;anj2>pqHS5d8TOCjr??c@CbpSe>;hIMny>9+cjI$WZDet&u%EUZs<@w3qsQ z>oil#=55^b6I&fzy00Q)^E?1Zn5m_kfY^`M?N+OS93fNBnqjA|V`TyeJ9VqfKo$`$ z9eE>*b=% zZcX-V!9z~bT%Q5N&z1+mQNKjwd2!M&Uq+E0YCoGonVQlS5=-&p~=p>(y=IS)waC)vFDd7HQp!d(#88+V193YBa zd5xT6EIH!~%by@Az)R{d5XKu$3YD>JJjaHpLi!lxQO(3bH1x)s=DYiPWNZ0?emGO- z&llW`XT$XXB{Ep-D#O4ipFM@K^zM=&M(HlcNZTLJo{FWzx=IOInqS3qPQiRizoNhZ zMBT(+J{3#5R+YaI)}PI8VmWor(-W|%L>dt^#l z)Vgg+NKgWV{HgnQrk_3JyEFX^YKio2XZjhw#PzYa%vTw`7xYOWg{Q5}&V;nbl*C=X ziHs;@`+ERQ!jsP4o}~4*(})SI*IL{z;mH|*m_SZIF~A*3gjTWEok?gI6A}r#@&V3S zT=g4VF#=ZhQmwO-h4xs!){+RVBBR!l2|a$)BsvDNn$eanZln)FGQ#jWkp1qYl`Un) zTeGyKt9D{WTY4`K8xj=%p8p!#5&}l{fH6oQJAbqEcVzqNv}(4J@oWV~fUL#Q3?a@w zk_RIkkZt4E$hKsp{hn>fNLyWm1BhHx$lH`z)-c;kX)i#i4P~gz(~a^N@k~J5vvz8h zS=^85iFm+z&yh?*yJ(C#^_Sima6ig-Z2#Oe_e5!pY)1K4d690UY7BlYPm+37V~ zqLcFl@qp}rWNDO~%)Xn%RG)U~LjA^5F+arQqCi?x?xH{?V-)T2oyyfho6WM@(Qm*DsKf z-J-q$Lb~&KhL*JYwMtZ0$a>8RApT;n{o49^6fimJQvhulmt99tV7|v96Vfmi$vS~> zl`*aXB)Ijs_$jBbNM-;~SbYgFPPSlcc&&BqMSzfXOkN-RjeQc?ugxTocrmBmF3C^N zw2R9=>Teg3&#$*85;XKTsVZI3K=wj;j_1w_k3j|Stmm26TQ@OWF z&>w_ml#Wp##u=E@xwo>TuIuk+Y%pL znm`5#;I)Jt*Uzr0(=wHNtG>)HV(EU_JPvq}#jdv@#J{@k;vFQyKql!x6R@*6bQ=SS z>?q?iy)jQMZv!H-@>e{k0>rZuT6_J{$LTQwGRXkh(SFIG(Qr=flvWIdcB=r54fq31lR~gb5%!#Y1WX6+2SP$r-`W|_ zSaPHG&SbU6C|Yt7RY*CAWiN($YGOo7zw#s{TPYGia_AYF0O0u}26TH5QCCh?#1yDT zdObqw%Ji^~phEUMt9Kk^tk;AZm*x-ISXWR%CA)r+mgBW+bs?ybePF615P!e8Cwbka z5Js1eLlt51dy}Tbg2Cx=i{cl z1R(KHL_gmUmL6gXsX-VY=n5+6u>L{V9&YUV2+58CH6Vj>aRJ-kVqvP1*nUDvZ|xMpS_&fm9Gtg~lnG%{dQPkqg{N90y_k1CW){q!O4+`hI+8 zNOnxh1VY&{Up1}Jsr1-n+P4)=n9TdOqLY((-&W*enkGrtaGBgNTOD_jA1Q_Dnj=jk;WbG# z#++8PF_Xz^s`zk_6>lL#vX6VYuS=R(A6l0L#Ux=MwqCOl5rz3uNK3|)8Rr1_ajk^a zBqynF1P>lM|K}U}B(PpqX)zIeE2pckq1I^l){yKN%>Y6=LPrvi$Y0UH+ZPkTw<0}2 zNIq&TR+5ihTbyM@6?-A}?AI^iA|FiY1~T3nbGg`By(h#qxH;~Nmg<%Wx5?WM#P<7F%mP!Xtb@=vY2iSb%$Ej+M?RY@fo2}{3s?zgYq>Lz zx{j;&O*>>d8U}J#p4psS`kSKDOGXBEOrcpIl$@U@gQV=Wnw`3<>>^q6Yt^C|Fx??PL0f4Kl92}<`D{A!7x!AZt{c4)DPJ)nOgGw`GaBM1rw}Y`O84o+fKnzpOTQ~kC6Pj zB%0~eUJj06I(126T$ij_wiy6-$+Y}H^zB@%Ks-gmg*L91G{_WV0W$Y<*nwECBmIb$ z)D@BhLKei-1t5}M&H^ALA`B!9c&2_WrwJR;f=d}gON!!(nD(45g%2qdQ$-SPlPSvd#BWhE;;W1_5U z*E7_lQ!jS0#u`9RgJ#Nb1!Ci=7snNvDE0UF`kU?y&UGLpJ?W!;Ht?eq-lR6QI zSWn}xn)oUi0}!#EG_F9%ddO*k#LIY&*2Q{M+3y?sB(mCTiL_28RG%*kOKJ{8j5Uo0 z5blxm^&~WOll=ZEhX&~j5YC%=>y+puD7fi~6hO&M7eK+$(>UOyr{(NT2zij}S6jlP zNddyd z{dk&sAf&6B#5CEO!F|Yi!7v06xwxpI`qYQ$K?gFQdymmqxkmbwJ*9X@6Zhm64+ur0X+4_g zrxf_;qEmEI0~xOtk1~lQ_&}n+*2@@jK5`ZeSwzh)+|0{O!DOdyi%2syrno1wHh|C~ zN>PldXbg8|V=P7Ur0m90K#g1&h_gNXICH6=0GBEQtw1(6puwRrNlHs~n8ImZ07H3K z0rWmI)NyRM~hva_WWzh5n6rP z6~arGG!Po4Yu7XJ3TTdLf4*!KUwzo*;-`b*SBerJkJSLFFxnELFd7a2bj4!mmKZY> zi=p=$$eQ1XmpfssOJd?NAs`f!1h*;yjA~*vC7m-v5eQxUtYZO$J8`BQ0HKs5$<^gW z5fS)B=tYsngi}335-cS#*3j28J`I4WDKa^$62L^a*Z3FjJ}`^=p682M)aAYh!npHf zW0p)Ax1Z+@41ZbQwKPe3t7kMxPN#nUU|4u-OLq0Ut@vv-akD{E4anR7?-6s)s+rmI z*g}|&LBhRETt>QLxiWOGRR}Y5X>gV^flicsRSKAN(5e(LdcejV0#JK5Q^4*yu&?5s zQ3&H`44Rx`GF0g#J-bPInmM~kdZQI$?-{sziEju{B(2vYn=8meh@vs%0(-~>r;hHS zNE%JS&T5`}*9zI0N?k#+Joofe{CkS;RAZ)mZPH06DKrf<#k-d_;&ce-Z20ftWXfgv z-*eB9L-5?bqwU&#@)^E_I%?a$@%8`WJDQ%`ito_$ZWrIF*SH*B55(x9yV#a8q}q#Y zW_#TXXoviy8k&&DgpSi;JOi#>?$00WlgNBUP=GjJok944h(LQa5fOpcJhpbTRRK&Y z(k!tq;Ypm<#ewJ{1mf$B48=jUKekaxMR`mPNE*`oYl;EMcGy%5^nQff2v$S^!fX^S zAIn0X4>e)T{;CKX5PLHz+r@#nN3<;xq?vD9B&Y^&iv-cPKg=rXM`CX>qoR~%VnNz! znkxj#C1tl2C0Dgd{?dNXT!cqz-^z+I?*#}c2Xmr;P)_p1_@$3O5L!~Y+JM;0w0h-! zNwXm$(4MLU0fEU5xLb&yagtzONcryquGg{AVQ6TwHd@EwB zY2hXsR6Vy69v7KgW$w{);Fb0z+U72{s+HzmiST;~VK%j^riHMJJMukU;0$7a$IlXVifBiKb=ynWc=W**9QwO(XA!CZ}Fl}^jElaJ%5;5g+iX~nu>ll^IB`L-hlM%5F z=0k7&Mb5%VJrJd@l17JXB(+P4%D`fl)`%$22)S)UrH81!Av!q=AbsOPp4TNll7{%_ z5B5n!**-bxf%q%GZ(fZgg)ANb4_(oB1H@ix4hS1WmN&2db>a&M`6NBrK$vdK)ikdm zM#-vsK$yVFXdVzUO0LRzm9gUv49HtLKt7Qh z0djQ!VOlzi2?E()UEgAqoTc-!l9pt1=Q?{K&OOcKx60ggz1jc0G9&@eJ;EI;kkI}# zfl77emKzAk0dE}uLTks#JX>XFQKUWCgHoLqDKu9cUEP>Fh z$!K&YI^Svt&V5Qk!^2#%I*klOhpo7>x~nVztDFN-U4W|)4p`Hnye|x^uZOthR2xGQ zWau8qelb!YJf_D(Jab$UA;TR&XxJE;1fm?;&0n=TWNC%W_dJBtpKh*;@9A=tXg-fF zdZ#fPUB|yPLh$+@K>B`^RV5<@GIiF~g_!I{0#n~^YF{1v)=U_)4q0*yj425+7&FJx zaVu#sc>ViJ5@T^ApqV-y$0MKJ3%Tf1!;lCiZDkUAZfEToQ~0HLs02@ME^#ZrfJ z_!q|nLJp*rJY1(LhlWQ=jw2B|sMqz{xFuE3kN`;x^U|?%t-pB{5!K)Jwnww+pdJqr z0vS4{>_X%X^+Mtc=~T<2Ewf8dO!)vp0>Wxg6F&aOF#LQ&p9DB@=;H^%L+7#ybLg}j zgG_Ty$xbX_&MGRwIWVWHw@87_EX}DJ9QeB`6$vn%M+_n1FH<--kIG3^&8?$yQUh~K zbdvuxiB3~snz$?XYd|PG`cUU|MPbFI;r4&4#mTg?n>fJj-(HJ;#=ozD2p(!QE5KAC zB;UI(9n<4^L?A=wl$#JrN^@Y9Nu~COH!GJj|9BRpsJfoHIigK*HY~kEupnk zBuQdeWl*07-<4nAz-lI_Ennz2xmzhPx!(pzEbLYN`hi_dln(0 z#@kbbhyn7sr|5@9c`p$n8Q8r1m?`|B(nf+_Cm__g z%%+*vw2q|*jRnW5`WcX&ebAP`TGi4a`LV8bT*Ym_uumfSd1j3Ps3I-={J5*Mgb>!M zlk&DQn9TeHA~noaVO4SL2B?PX_jHOW&4!y$X&oLOZ>wP|FSQShDyoJp6C<1rPsQeR;21 zAM}>FwxHsD-X$w7G#^#8N}sANXtj7q%fX22wHk20@2gf55X!FAPZV0vs7I@#%6d;z ziiHSyv^ws})6)?7;>sIS#ieHLSujd z2=@@OmNDg26<3X!PSu+W1~;Gc?nG@qHT`30PovFxY`VZjk)k%A^`k9Mfk<5JyXYCa zWyNhs+QO+IEJ^F~<~eAmXOfLkc5Q&4L+GdqA%9r~;m9P8IMJTaBnnui2c1 zkU_RD`w4*c;W&?h*mDE@^9TC?Y1&$lf&dxg`FSAwWgCIerZHN&t}gEZ)gX}d@}vNv zQKNoXS5+QM;Q)AV&w;Sk4wL4Agy;nuSe3_UVu8?mK&}OZ^;&9xR@H0KugaowuLy+v zhsP8b!U*lDiGXnGu6jfjSX&4oBjVwxb=kicuL3Zib*2Ek3!nY&>oj+mH35W+jkR)t z&@avcc|cg}gUfGSAz77VWKoyKrmBx=v|80mA^!lvJt#MiK=w-m0}=U2ZLnG^S=kms zo7#r}i7KVgY75G-XQ`~{x!s_59_&`+sjMJ-^KbPL@)w_!2)~~v_D|tN-*;KByE}N>c=%dQ~m;lj_ zdg45ge@xMy>d#c+GYxp3RrqWaqOB*jYG0KEoYo$Q#N>szTxaahmNS)B5XgLOz<}6G zjdd*rw%5d2>4XBZUXCCj;;j6Ui?q@?4Mbk=0w^KbJ46Y_OBePi*3-D=UeG52%517f zAqSmC7`OZ~j>4~xON^EAD*FpxmJ?)@870*OLNltV zILfz6=^||Ka)SaXHQ`ntwzm1xqp52OMO zO$e!jjN#lmmm+#GcP$PVAd0y-7$)vO4-t_0mX($JTK%$$G;pF%m-J+1XC;eq{|kh? zg>LXQqxJ|lLiur11%&%?P26==Y26zcuUQIj|LeW$D)%Qj=epzPdZvlGFsK3K?fzV= z%g3epwW=0N*PDCgUfj>9o*Wm}8u~hYMnKlruSP}hCy`ma5!Ua;B_R!3I)=wUt*m)#R<{J@Yw%Fw=tbVwn;xSkVp0c%8`rvS0dRnP>`g zuh;TBO~!@HR~jo28XYaa6(S5S_sSRcNo2g0$f`WGYIG>)Pi@?n(hVQT%NGH_U(0dV z$tLN}-6TI|@~m?^AK%-AFdEE+sJ{mrk=R4QBDzL^=oAz88ha=s zuD*VsV&dj@Po*JJHSQ`FHtLCZH~71bH4q)Jpv5|-fC5cmm+xcijO$Xzvs*lWMXzqAspiK{#i)z%#X{0(%`I*z3ED(BB-VZF-v6DUKf`D1l_ zsbUFV*e8+wj5r*G)>V5ln__xApbdn^tm*r+>g}@4OC+aWv*a+**3MQH`R5M7mRP3D zzwP_uA%u4^a7rT#K>sRr1i}EhN8@=fAd1k z3Lz2E_9re;R_*AcmF&C_-B?535lwyoIq0HEdQ5#69`dO zIr<_bE3K>uh42}$-`7>QGUQAFB4K4GfV_pZucph5c&rb|Xz%w_9va=;K;oe%f4-p) zfHJaFoj`PhU#eFi_KG;~Yv{fsM$v)jYN{nb(LTOq>T)CUD27&0JqFK*q&~Jp7Ou63E6u9Hm2BPG@ z)OkSsX^J-d`A>BVV7vv>dR?)=ZvG;?B9WEWe>cavo{^gZAnzNcfRM)U@4DWho|uvg zDJl?q<|c0V?rHxu5KEU~RAVZmjK>;)ki$@E?^dRpmV_cU&|X;gDe_cOYVq<>+b zL>RVHqfJ*fvZy5xrp8RZ*-Lm+zC>S*aFz++6*%-E>|WPf zlDz>Dt4Z$!5GSAGis?=M6lta2$ZGVK`+Cb+h;IB#pY-ls0lVb702HvJ`s;P#i8O5Y z$|fTj0-{yM;p;=P(}e6(fdt-?2}C(eZ3rO)rJ@HyL1|X>^>qafkhiG%lBlX%TfQ7= zQsE)&bY^=pby=PKy(>K?s$RNesyzHr3?}jAmlJz1>L`}Pa-mv>=)enB%#@h zQR!yYAf=m;)B{LoSpHS1W|{$GD1nK|&p@{Fm_taY-~827D2SPNK;Ab^0r8hha*zAC z6X)nyb;7n6qR52_P`GgNkzH=MUI>L(-LCUa&h}ZI@Z=O2_oWURojUKtwBS7|*-WqT zuR0?@UOC-W!e zhLwK+2*1p|DiD9$&2?XIxeIw8qy|Fq(T%m&YooeXmp4V0YgJI3dut%Hq})~QrMoRP zQmc**w=KY4o|C<1u?}^+^31AnWkQ?Y1K8+s}(}8+XJze^JK5e(q{e> zkS|fiSC$eG64u=M{QSYN@b)DV%LC&;NQBg&ebt4VIbypNU!`r`b$PUO%)WEE3lI(B z)Y)C~6MNrXHvx_&K#Y~Fdk^_?sKOBz`0u&h#KrYoLVXI+wbfJ|duq=oCcJ0eFitD9 zr=;ilRNWJ;xwG$cPF~O0%crpSu1qBo-(4wX55&LPTxr^x-1~7abOLn=v<%aB(b0Ob zOAO4s0TObIa7d%l=ehma${^GJcPl5G!J%!J#Gt{kOG!xD+uEIh%`RB0i`}m+WWCa+ zfatbLDhFc<_T4M1JD)ie)_F6ywsbbWjtv3Pb<^CR+ns@}7FPx~wY*KaWV9BoZhY1p zusWe6t8I5KnCks~VV^|y)13`K7t*SQl^!P6ZOpf>wP?E>Fr0yA@{4F$;VNE#&3}0I zUx`ORlz7yLlo2dJRDPH=r7=J3F+QO!xm2*leL=SidHXN?daWV9Z+PwklyA)m>2*4Z z;g#)W17#<@-IsH_5PPo%@AA=Tr{i7D0B!rcu6ULb@=mW!y}0tN#h-lq`S|#zD?Tfe zk7Mprd{0Z!>vWRFqSCE3-F!)zX?x*y&2!hs>zZc`mu`91PSJO5{AtO3%X3l)kH>I7 z;wG1kbg!EnTs6S<{bB!drMZhR$kpdASDKWISAv*0gx4*Uyr>??e(ckJzM)S7uZ++g zm3mD}7I*4385(Zk_18LxN)MBiei5CurG<`4v(`QbF8%rHLsWj4dLES@Cc#DJhiSVW zm1eEA8d^+RR6#k=2mb70+T$;qoy_sYT^j zSD)hBKOIp%lbjTGU5fm0;|=5pYABiys?gJF6Npwsc#^sdL2l<2{~k? zNx9g?Y_q1i#6S*Nxnz%l99cDakPP1Yme1st1;{a6mny^o+3(jd(fYctsrGXNFXb))*|`{} z8faQoTf^nGs&r%57xqbHCc;zVK#l+}Wy4vE@5P2#Kq7Q20HFYDpflGDDQ6t$p1Ee& zYw}w?ua&^TbdFFz$!2&Yy;#;W*=z-KrvVK9CcRBSAV8$MxeI{+SIC@O&-!QBFms#{ z4VZ~oJ>x{UCVHk^<2~Ml%*oqneNztnT z#IxUINY>BAl+RD4O~qhcUC3VV(ee5?CvMM#Gt@ZnA!OyRNNj+dk308yHZFc!0v}oX z?9r)lNl=Xd-;mpJ8>jBsNxvKd78}BOkIQx~5o*?v^|J9RDz1@NJf8$j`Zd3>Pa>2Z z{be>X3k^3rav%^3$QCXA4Jrgz(XJ;VJHaTOjg!rN@=OZ=ZN(LmnU4zuv=#oP$xmm# z89qdDkIdZ0uWSi9lB)}wfJ7q99Ji6y6csGi6tc#<$(g#1UvUPEOx*?|!DPbOs%xi! zSbM)Y?dkb?0%<%~-KAwC)3R4x_66j;*i_jXh$TXy&oq@t=1o!$WaJ|(lnDfG8l(Vo z8qBnn@bonz?O(n|s{?NS12CHufaPx(E&Zh+$9DpRY-DCN>^HI#nQC$7lA*=y_{?0g zWnv98Q^^ick9f9^N!d0tl?>&}xnO4A+Mq%l%!S^G2XFHcSau>6te`AjQ`ACchAw34fmc7g2d0Z(58iENIn$D)_oVA2NLWA$;dJZi;7@nTK1~ynLwORuzi_IwyIPQkP+_|yM(0%yJRJf zv$CKW)(3ge%7SLAE|##BdD%;MtJ}ULD$VSDNmSe$1F`)Q=WY^}_6EC2RC;mKstRrN zUeG524xfJ1zo&Zo`5)rlU86@i?IFpDD(#_V#>@{OIe0u01AwE)Ln%f-|EkKrwliY> z{8dKGpD$ioW(N(wuvMitnzbD7U;mca23 zWc|}?GSzJDe;U5bG{bLhWMmiUu?NCMR%7fEl#JKTkooi5p;ab3zB6RLDi&{+^;ypK z8%xNU>2*pS$j)C$soSNmi-ucfpRGD&1O#4|b7hAM@f-@;56hz1C<;b;g5W^@h&g{i zcK%8dw)_sma%NebW!14vAZxwG&oXGfD(S>5gXYgqPf4miok4Sansnas0x*1im=MW| ztim!teu9@%NF=g#IOq$*(nGu;0WM(6pg9_3g;0D{WtNwO;YWEW3&_ZRv91u1oo%M+ zM6@6Q8B=o!ubS)(ZIs7*E!p(FHCd%Wg-WTMwv|MaPz1Y4@^=MVNtWW6L2U8GU+j0{>oNLgg9F=$%-O4dx{ z6&baD%(s~D_8eqUHe_j0)=YCUmN<9ch0O7!Ga+LpV;eMPt6XETHFdPU;j+&kabd<5 z!H|Wa&s`)Cl0`CqZ%vY;@&PirQ_r0V z5KA|Kq|h?xjb}y(q3ozIfsih09<^S)o^!FC+^?Hl1DNUS;Qb0fEZqe3RC%KrHSuI1 zgC3IEg=~MnCo5d9x(CWzW`CUn+FQtac}RfJf5_?9vMkD~E7XDTCSdK>Tll>5Pmt-r@W90zAfWxX+~Wc{6OY3=6L}IT0CA0zxMugF`?zktQIr7mOBp&(JqMKTOEV zzSFS>#M7yL=~IL5Uv<4_Ia`lj?m`~?}!S9P{9sn|O#LXsv zov|#2=zv58N1{e z1v1`!;5{XmBKklWkdqb~73S_q_<>COe#Y1dJyVhHri$)g*e4N2zw7%;0XZ40!7Q@J zGmL&;rS1nW=DOtT29k}IJ;i0dj3G7wgCRs};F0%RUP=!Fz?kONk6Zy&MmvD4{MFVd zyX42Px{r|jSVIcP%m!;#(xZ>Bb6L}+kN0p6PTtB@;btKF)dza?D|O))X_B8lHJgH` zJox~Gi3&0rv!dUca`5S|XJi{lMZaB0Ff2UytC8mh9!+MIv5IX2@n^!ruU%sJTYphd ztU3jRp>OhMAhF-?SV~i<4lGTQYD$H^>pd(pR!Js682hGE1PF5nG7jZTCE!NPC-3xX zwh&FX_?8uSgRXYphhh2oTR- zNdqsI8tX+97E6sO5e0x{bNKhv5Yq7tgk#$E_saYwar`y);rh%<;q~Hxi+N;^ZnMHl zS5UxLhQ09&1-h6=_IhS#2e=Ic66^t|&dNlxu3a>MnNrZcYq22NJq|Rcy=*eQ`Nz3E zgzUuu4k66t66;^gBu0Zg&dpO)8 zOF$nM5brM|xJ^`usWw2US$91`E)<6Rc2n z$%h4mEa!oc6W_B+ z2%C(dzoAb8B(hv07NVa^y{ddLx@Un<4!p3?{SpVv06u`lw6=6w0?9A&dQ^AX#Y;X* zAmiN{B=i6Gr0d?4&&QeMz1SybiFa`tkvs2_i-ym6Z`ZvuaNgT>6GNsb#)dWyOfy(WUaTjX%%l_ z28)lCyo0sJE}bL>V(LQnGTQrrCPCc~q)EI~1RscVqeChcT~kD&i(ZR|Dm`ct?*$)2 zg37P|{J}nnjJHaPObC07DMABWc67c53y|H)E;1wR7AGPD?WF`_$wN@xUfek=;Mux#m6q~TY!x5w7x(nsO&X>SWm+h*U1;V#}~kS zDQh4mB!M!B94R2z{_hNCe^jJ|IAR;dzfaHa9 zFRrCi1e{nv##8$NSWMZT^&^+Zfe0(CG$qpkA@i)(?AnT}IVMSMz1d{9vR6NUuumf7 zGxUJ~p)18DVW;>QZUewQ=T!h11=&?xA@Py&03n~L(Flo;$1Z?Sd^wS$U0=EBKzIs- z+gTty1w#LEv?lS<8w7+K^vmlRdpEf?kxwp~Xk8RX)4z4PQfR~h(2^Q~p>qVJgFxoX z5dnl${o;qFyf_--Hbr@;?0{@3I|1?1e$kc~k2<;ZX`bQ&lCA5Tk8GVHP+M4F_U~lr|sQAMh`XrE} zPFHsHu6aW?0A%t+$|{5awPqg@9(Sog#_Qk>5c+X66n&H*Y!jJvT&Hazl-@3Y2ehaa z`YJEZEM(@`&|?I|-pyP3G>t{ydH&-u!aH3lk6vya6r!Iey2+KofG`mHaJcOU@^+;} z_ws~sId_*Aj#)B5C@A{$fpCAvM6c+qvC>tD0LY~0WC$>NPPjnEC0`1;0Fc4sPOFej zU(Xg032;Xhqsf&*4+D_(a{d5udef-WN0wMA{|f*P7o8$N=<}kl2Z$VQT=s+2%DO^P zK(UElJAF=qmZJYf{*uyVsue+(y(KCA#&mL%3~-vvS-1fI60YmZ zQpeLJCMMqivGE?OkeD>}XUMb7xraDF{-)IvJUgjzSiB1Jx$fTBClTAv8Gtwd&!e(i zt86Lv`9OAZ2A-4vLP@b!RjmH+z3f((Tr{=T_%>E+=&Yo^JxVTI9c#!Hs@1#7PS&@1 z%jIo3*Ak}@X@r}9K8@azSro%wEIf8IkF`Z- zkiTdfxQF6+!kY#PK{L+!GNbv@n}_DN*7*NWa*ckHG?TNY80 z*e)hesOrR&pv2N`inlPX3xvFd9`3NE zAdtjsOOlfIwpEc{&V1VxRgKP81W(l2wrW9WNf~dqyw$FmYC$}ZCEejd6vDgMKvxJ) z8pv*osBw4If{^01khC-bEyNyVJB$@pWTt-pV4p<%8BPu79n!b4^-IiCulB1XNGW^M z#zB)8Q2~2R7Hm0dIKE1JtDfOvlR5L9`}4=gHwlflN4`ZoYizcNCqo&5 zut0mwQ@4uMt2rhwj>w98F;9Jqw)F8W7tPQ<&|R|PiK+0=*R{#>`1keVC|OZGM1{+F zL;wi0DyY|k=JXz%sJbiac{FVj)V^p*J-QP7fKXPV#?d7#R`mqJkIM*07yC?B)~~@E z6Gl4E4!|;08Cp5WK2Kym(E&WG$)q#t=MVM);<-hi^uis4rK!?v9E3&0&fNJ0c<<1l zkNhBKi$1vBI0(1saX)jo&|o5Ozb3O{I(@MRSxic}k!Oy?FYuKVbC5xGahVYA@p29x zgnRUyr@u%g#iWus2>0meYdQ!wc`5Z@q>^HCkA9HJUo{s(I+V_cU*wq|gg?cFQhyv| zJviS1NQE*9;1^-|Pa5SQba$umIS5@j)ypl`nh6^R5&szVjJD%vi5!HqHFpZXh{>#N zJ!3L!N$3wEv$og^FZRvbHCHmuh&ALQ?)Q8pH5430c()n9*;sCEZBWC5m{BEikmq>#2^9TDRA|lJdTD^31 zWWN`4V#GHNvc=Z~i2Ve6FpF+*&aPQG@mcY84`v)|Jz5h5RIW z+WjDMlnfU_M@c#X`?W9mv@|cU1Di*eH4f>%lv&_Q~Tkw`kg53*AqyIRv#(=-X(FH%ris_7&@2rHxwie@j}05CaGP?&8eGD8S&Jn5X1d#k)=1`H0uf~qom zn^!0dhJSt$OKveZb$SKoG3=9h?dhe96OH~=fsRs$K| z8>L)#XzpaL)InHet{PL9C}@7!CHYa;+ojs5dNKB4S%+>?YgK$%l(x{g_k#2U+O zI#r-GUB@h?ZC&D%y|Vr;xp@#3N2MTas51ZJ9JHaUyrt`H=t4}b8k@Rg@#5^ZSy$z? zA!Pq|myJIFFInuIU$*L!#R6smlQY?PyO3^t{6%(76Jz}NAcxm%<`5iY=dXe`!M5&G z%;@Yd!dw}viEB)jG5X97a)k9e4>f{}@fp232RX#XGLm_K!%M9Ug7K<8`$yVm4Dnf+ zZexf~2Z;`H*14C4b0*6;4^|&!<}(^E=jB3P)603ekTdn*AV*ft%%-0|*e8)=#hiZe zgTw){82>N8+l8WJ?2PhxiNblikds~iBFvX@=HegZ2+;qndSqw6WcsiT8~G`&0Oy56 zQL=FszYLy~KgcnvQM%h1=L?1*4+64dSFK{td>N!m_Id_Z^`um?g^cutr0!cEUo@)D ze3{@8h+l+8HOho~)`hU^p9UxMW$>$Qa)*A{HHaBM}NX+z42ywd!MJO$fWHk8upDDf{REE0Mv$ zi;VH%JDttZ82vnL+a$ zoHVdjG%HN9Q=ihIi5`%zN9M|)2hSRA^w(}QilWK(hR*elVzSC%48WdFXaHl{GI~8K*sl;{mu)C&JC)C zY>FZEERe_sb4CB^u0wl_2{i{u&5~)S2Qc<}6UqCCFxT{!OqaQ*0Fa#%C-Y!)HFQm1+j|kcAvygl*?Eruyz9D<}tKCz4gK?{aj6}Hm0|GLFPjODR%$Gq1d{XGv zG7gAm!i0df;yu2Fc#g9>pUKFebxpXI1(x909|G+Ck_-%jPjsR%7C$ifCxcUo5IU0i7;G!3mJ)QiIc{3G9&#Uo-O2NxwTA~vD$6{ znK|s-k^!-tx!m!zo)wlby>c4@WN^Y!rS#000g~HiAi-WFIr*J;hxTBU*AzlwX*7D? zN@V5wYdy{BpmPv^Q&uF=KGw&pN_KW89 zh3uCi=$S2ZFNaQJ+L`@%5YGmau(lqgJ*G*L#grb3zK3Yf&bN#!UqLlLGW7Ro{>UsC zbeiHH8T#X79U1ns_K#|JG?7r6^fuDSYFZ9i$IJ^kK&asf43QRcF(9Oz^%mN~i`$|$ zGQ4M3Y4?%gJ&@bgg+$sl`cvCjA}LL+Sz-l}>BvkLyR-lXLw9kvhBpQUQ~M7RiIC&{ zTEN_6N0EzRqWwXoGMLN~q@`^zau&C}TJnxeM-=0j%sp z=2joXosTe_@P%QyOzV5y6A3SGOhucOmyoo4hc{MXiAh#mql6(-07yeUxaxu zs<(3x-ji6((d~PZ@9M9spMQZ-moIaK<~zSrG2HIo0T0j!>$mRW}dOVGkr*qYc%n>-V%tSatJ| zwphz_dv=XGQ(?v}P*#m7moJc&9#uM=+v3ebgTafoc=6C+w#h+edgDbqmo6UCEZEn7 z52t$D%!L`HH+L3c!e_RAlENDbRkh7rn8CAO2bm0(atUqTzBg)UHg6u%T_6V;*PWWyVy}C2jhPk?|VIrGTQ=rELWi8EON$@oPPN$vTiOeO8tyh<-=1$wJPog@a{bf{hS+nbK;Wj*{~q}Qp=UWjfT zB0uzAm!UMq@4hgsIj@_DM6&(9iKu}6Jb`%-o~f4N^(x1tspVCUDa#=p#J+x2Cu8LY z@+!T=&@K>tU7cSNV5150o%IBNWyG1`n}xfykMpV*ad82;>F|4_)ZyuGFBw<8h)wnA zro->`ZLe={6SC}4+v^~ng{Wj1JZmrEd^vT1SM4SGdV#Pkfn17FwU;y&QS~C23j}1p zdKJ7)AG2R!~9E8H6 zy^FznYYLdUx5jC8qRKBZya{C6YfVJmJfzK6)XhWk)x?spG*eWJ^9A5F!TMDf4{`DUNpb0~6jlD!Rj7dO zYal#A&DdhUhRPCTmA!-THX(ZQflw&i`F9>!uGcbMtVSP*>mWY6Tje4c`v;;z6>|wO zsiXw9PDgX?0->OHJ@UGx>lZN|d#08Ez;XvP4nT}W()fr^JsFgo2{Q>1{|-bY%cx#R1YhAgnmRT{jSxxM2EDhll>f z2Y}4CB-$+LQCjV;4KbULR~4RvP=2H*KvZ;Ku{~8Ag4;46Ydpr|Ag_{1zetr#S|)(B zqD=v+9_a$eVCvIVFo_!>Agb2n^^89cbpIk%9)fNZAalHbRR%B%q4eHw1IX#st31Rk zK=lPUesIvM;!1w1SG^>rKmg%P(cJD;AEG{91tOS-286O=ya$LXCXITAvf}o)_bLz( zdh@7yIeJf3Owx?&Q?jC$1PJL0ck4hXiEaWYEqY>mUy_!Vey<`*H9S>Bi97no^%hY?Zz-|>_|R=_`AVga_Ryk zC-R-)s@9`k`yV-l=155;#5H6fMwFZ=m01S$fw0(;Ci<*mOX}rp5)`XzenFoER4R+Q zVK#|Q%WO8vPBv|pm6au)Re(v1YIgBV4lyDD_EKhu1iTmY93?xB;2e@2`E#FDYe`yY zP6;pco~en$Wrsk(YqHHMwIqShDz(H}J*(1E)`|H=w%8EE$3V!2Y9y-El62Cv5?(AJ z^KE%%)mo}&T&FDQBmhF6n`r8EIo)Usri&2KFVkmenKAeZM3<3j{Hoj%1+$osU4PM( z>J{sf+lKBTAoSbNwbPeME$N+Ad64sdwIV$n-qruT$6!^VCDDUbcJ%QK9c$|H8gg)5 z>6HgU;^CZDt12x?Zfoi^gT{N!a-HZ~^IfU&7pYQ9>gHn7d~O_mzM)S75*uyFs^UwM z$=d(=d$@Kn5h|p$B{sUt`!d-vsmFEKS>mil1mLybSSHF!9==>Ghz4mnMJL9yyf_fw zQAL)d=T;S25;It3L8WO{Sx^z`eU-dHRc49% z{l2FNYyE2d`TC-)E`4fA0JlI$zgCw9a7$QSo!C{~@kZ!0q0&A<*7u47%+iq10NoB>|aP+bZWM$(cz4+B%xa zky1@z4W-+Fn-`PO*S$(N(x8}E)z4ACikCXHvX3%0@6PFR+@m55Xe8-y#M~WYM7Za6-$h!!I2Hv~ajP?WGi_Wm`K6K?d z#pzWsLaW|~q@_ouc6?H;K6&boi|+pWlYdcgHFoPg1n<&>2UuS%FY8#(+}2Tl&o`U% zT{0sDbQAxqmRs@9sAuR>(GJN?E-@KdcgalKGk3|XI#p!|HSs(|K)J2*D1RL7xraoi zIqp&0bT&CIF;LC=xWqso&!`GD-xEzjlh+`cjFcu`v|~CXIW5%a z6_d)ri6MuM1~5i38IDDaZ|@r%`}1XaV@g=kxG~G8!i5^Myl-3vv5L!(8iWj__8hUQ za1PxiQMHqJP!tG{1Zqyk){(ONN0Ip=(rdwtv&CXW2U+@2J>&VSu3s_bY$;nE$jmcb zOkx6JnPt*NGG7oDUgQmc$oSHB&-I@|a>XF4l^uV|zem=5f$D4#e^_ z9qs48IO!XTQiyfJAnJ$%*62G1e2I}W&jA2n3zy7E|!WY$pGP*JSOD;;ekLV9gK@LmzLBw5FQ9*)*KMaTrE;P zAd!hzbR~_831?dt9LUPtu`Dfl5N4dwLp`p%ycTEPdvCQmc4T{@J<^O8V# zD36PHH0GSS&ISQlnfj;M)mVGUl@2}-El7m+NT&OeB#)L+^82tGkg>j>(P2C;Geik8OSr}+!{o>t9!^jF#DENI#~+X?f=#o{4(KGOtV`GC>sUr#TPdrJSo)mOyz28g!|HgG9E4l!mN0Pl1FFucGrnUAUqAo z>K#C~eGRyQj$S91sC#=_SL?StGu;dbmsQV% zZXleJJrlam2?iI!vrF6(0P#GGz(lJtPP!QYif?50Hnw!hTY*>}0ieblnY?{2&uBt; zfPth7$WDYFIv|m+A%z(u)6Hx!V;{iE)=0yQyzvj`chs6pH^T`U-$Dk@)KIOC%-+VY zMm=++SA`G8$ec6mLNyebbN2jIW^ZF(8vIq}oSDi20GN3kYq$xqY%-7Fjge_*IKtkW zko=LB@Hn~K_{~+n3I0Z3%G_;iiLXLtc7g77AeQghY;PLUQ^jlx+4+cTMAK~I8gkl` zk!I5-U5EhA0lX!TCJ@gb(SbDP$teSn9z*~~3QIY}K#mlaj*pGm&h{Kg6mq2S_*Eum zn=-1$%-j6%siSIt{$QU(W;TdfB|t2DajDID!ylfBLe7D^RSR|=QwiWIz_VW>OLOKq zph|NFazwLAQO-=vJ~zVa9XNZ=6% z;I!!V3`M1hyShY0uiaR*ma}LB;sB{FxIYAv%bW))$I6T{s{;f;sPUvqSKg0%iek7B z9?X=wSSydOBl)ZgS?i^TR;Fg#z1doMp&y>1vR|2-4VA~6DZjB#B9=OYI~<UH^URRba%rcD!@H_@KRq*NDD4RXVI=%<7^|B9$1Q@M~fH7XSX=Q;zAY@r9 zq<^Ve_f^Jz+@|RPiG3#b z{rQ7o%~>P;l)f<<(^iDanhwruA7HecjrZpsWRg~^&0Q5CSVSNXg#MS62V4jX4KNM& z%(MUQN)u;!B{`QoEi=(h%_0+$uN9rLsX7CNtURcG@2e~m(X4!=M|bB*Pf=gXL^RXg zeZR<7odN9(EN{WhQnmy*S`?>c8rlI|$mE`m)Yr}}xEYQ)fAgex9l8b5v%N9{mWkMR z`3E5Uw3L9+XkMlDEmRPK)d7H5_M7F|hG!lco}r=gixpIIE&lxP`tSe#2SNu|_CR*9 zgF%6UB2owaalIr>5am+DZGuh-+OCw}O4xxjE z4V}S1gzm~FhX5pjy#O%k=cngcE5Sq(m8$K*(QiFC3 zQoz-?(0D)&RRaP&i(h4?H&__RDW2JE&OGyZ#2pp>#y$r@+Qq7bx-&V!xh zsRqu)Tte`#aq0yxA_%IDPzJ#XS4K8D>8{ST;p_gIu{$6fFV>s|l8HL! zTp)A-p1FiTu>na62kM1pjB_1gBZB388hGiME%_a?aN<3%V<$3~&t&02yeIe2hoM0k z;LT^RbV3|^zmPl*dT*0a4qtTuS1UIq-7=V4Ym}hvJ6M>`mG;rw|>?of| zZazba?CEQtIWa zT=~D=2uulX6-|j^(+gFIy5#(LhPH;QYUtVB+c$CyB;6>ZF*PEfH!J<_91_M)-}cVu&Zem`1D!E{FEml#JtEkh@y>=Ev7=n zI8mhOyc;gVdLxl+^qz5^^;q5rX6$)iu7J3>+Jb(C)Kf=Yr8f`%!mN2BnMV5PM6?nX z7i8p3JZA__(n_+HG_@JyJjxzOm0if}BG0 zK(@Bl7RWuxoH~{~?^tomXW}?sk0>^QBfp!_M4p@~_BnB{F1*(vrv;F4Hc2W34g~E2 zk}MWTa#kI(oG9JsPc8ri{X47etWh9-wTCF?l~;+}8Ux6n4oL+HBzck2xq-ylCaI+O zyfVagh<{&14voc}8%6|0P|ln4Q?jeU83tsw2U!7dcv0vgD#&j2pb&kbtS2H>YBv~w{)5O)fJ=fZ1AM%uNs3<=G=^+dAu&Un(LcXG6Q_ot~#hlRML&*WVxfbrPEH4IPlf zhe8*40ddQjb~@OyBH__r(TT{pk|{tyj9pI8(Zrp)XTLkCMu7}&c!M3Bbgm30mH>&f z84Skn++1A>Gh{3GlL5>E=@6A&?Y5W;_o_`q(<-??4WziTierZ|ryR;o97p3(K;jM)%I( z$qyjucAE@aPTZQyHJrP8AmhqTXi%O0mGO8c9dBhVdeBR$i#C9yp?o4n?U3woj*CP` zl{tan62G&KLJ0i6XVn}s3nVS2@*F1a&AoD>rb`dV`ue-vVX10IFY)EB706&eX$nTC zFRrEv3OlaxLNb)|u=XP>Yo%>pM6guznFGu-@n68C@VG|KrMcOsyqsX-(p)O_R52rS z1yais*wk;C4lvIJxg24R#6DRV5N7HMT#(Bdcq2yjMsk9?oEGO+Y9UV# z$bHRGIR8g{A%~LQ%Y4dAPEy;SKiKCWlNKtU0%COA=ituIgzK# z_NP85HPWESfBPELw9A7?a>ZG2BMg}KQKHxIE)gaqJkK}aB% z0Ad0&LjdWQ0ODi65I-pn=gnyX5ESSc9mx<65Mz|(M)K>6&Zmj$k4_t(1P;|7J>S#$ zt@K77Bt^0EEYu4Sy~$f`fMo1QSt)ZhGQ-WiC6Hu>M)CzDY3UO=&K|@Pjze~?PFlJ( zGgc=v+*;d9X7xsBR+mN@6(G;#+4bUNPzOoQzLIwV$)Q-Xs!N6hQG#h-i08cEOj#NA zI7W33B9jU$XTi@O>~j!nFFuIC!9_O9zcZY4|DAz9-R}b=nW?HsPTcw=Zkmg4W!m*a zU9EG`$%9g^45*z|&DS_7(dNkuAQ??kEDK0Rla>hD3X;Pq?TPA-jLy)YuOKxoLwC+3 zQZMJ0XJ4eIW$1R64?d)==~pq=Jvb~4cfOsA8c~Fv3ncv?Kr-@Ibau<6P9~H9Nt3Gb z>-oM)9KFTnfEGv5i<$A`rqs>Aj^IWn^YM9gHT(ZmeTuvm( z>tqHDkczvwZqlhK}9^)#xniPYDV4I&R|_x~Q;)MQj^-dP?wKDU+(0_mvR zH5ikuXvwW(GOG7rEQWJ+2`7*wu(f|j7@;Lk$_!Q@gWIZ1eVXUur|f7R^8*sxkx=C# zjNl|Q?7Gp}f_v4Sh|^O+l6&so&265#?xe6qjS)r|^Cg@-Ky~klE#p&X1aq@v84EkJ zH`%iVy)7kmzvz|gtaJw?DNv_B6o_$uOEv5=s!Hq!k|cJ}^$H|Otja0_iIgAxFW%{G zDfa~82v?59;@?StRPl78@*}svddtXo6UL?s*~~J@ENdW1VO1*n=MVO~01;TCV#~Zk zAZcf733yg3PR@9MMH1PWZwci1$}pxUg#d_=tY-)xh&*-FBM50zuW>``n=G<3L_W_2 zybSZF?(;leb&!;?XF>1dYDixV!{=wn3P}ny`PZg5g>Eo-0?Ag@I+;*i=n5p+>fm1| zuzOE*cwe~(%%oi)>0Igm>XD>Ax@a0maI2eK=2zSCE)2NagGX^~?jb84_NpN5{xxdRV_To*iuCZ|K*TyCAEr+UCg@6&HrN~^hbeOvGL2ihB{H=;Hl3Gn_**`a zS&0)4|4luc`$#zaS9~GjFj>ue!r{+dY!33zAMA6G$(?QHF9Au{%3wbALKuKM+f0B1 z(z&zE#A6_f!GyCN25>wp$T&GKUWfv0W=EWjHjtCjgt(6D8HJEiQ7l9O7(z-00whVO zjtB!u5~@>SK+-PW&kTB2RAB^2`sGx9Vx2pj(&?W;`E|_-BBgQzl0hWpiU2v>2CLTe z%;7c_k6Bl4nhtVxA_`&U895*sFg6}ATZjWNX4~1G4E&#LmM&yR2BYec$mnPK@7HAv z`0)%0fD9KsfMXPWrE_mx&JQo{?0}pMCkAa3vHvIQ+^$^5bs(C`L~xe)0?9Z!j?Vvg zT&OBaa(~@>_PA|{4*&!}AX5fz!a#2Rm8MhKXCV4_I^Z7vP6ya>GWsZ&LVaD4G!O=6 zLkM}P+Y07u% zx{V9MNT12iANHFhl)gagX_T&5?UOJE%4Zdj3{Q5+QUFGex_klyk$}$34F*v_x~EeE zHWWPyB^Hko%7L0%6ov99W561Xp!vDRKmE4!;qrlO6zRj|=Gr40IN^Kc>jPi{RMoxT zQKTT3^RPiuL89`s#(gPL+q^jt2*^~0CYQxPARto}+^G+Qk=ml;J_sYV?npT5rAV!N z;f>1ZdFEnJoK$Jb<&1L>hGnfpMlA}<7FnnuOo4h5ra-wY;6S(_-}KV()T(@^qVpaI z^PP%iYi-JRx|A*olKE=$$f?S+MkXdxFrYeQZa!DD9+lm>GBKqOk+eQhL_`nB%TlZA zP&Ux8DHojUD1f9>Wo{iyK+>d{%gX@ag3L+ZI$Dk@jk=sf4Z_`4R8tFtL1CXB1}Z^r zt^>X2RJxNJAc8PoO+)(gjeZmCywke0l+nW}@4T!t=e)F?dE9zF=~%2C{nS>Vw&<7* z!a(gsBMTsHPmFpR4x>q(VsI#$aPu?ou_-$lAU$F@t)zYjNsriEUT;n6^q%0RWVPvJ zHIR(dPIpcntuo+;_v}j~y(-iH$|x-|=hNZ`$tdmgUHQ>;b!sX00x(2)z6D8B2uCUX zu=2R)w8? zra_uL(`{!#((IYKh(8c1D12bazec5-HyS8d8?&G9OIjdlw&wLOJ~8tGdF!Exr0Z=u zArB$)?YBJVj+w|6FmB*`-!NIFokwql5+5A5uipFixg^}15Nrz;AKu9WY&ZBijtkaw!? zUu(2n=h9&eq;qN0X6fxb4;`nYOP@|BrGn5Dy5#f+VeXTU86ZmnrR$f5a-WKlyg+EU zUTT>PLc{g4;6$jP^Udjv0Fek}>;NEra`>a&MKbpZ(!X-xrwk&W{y~^i>=Pyk4Ir$!NMZ=#-m71anU?>CpUb{mX z;P+1rWq@Ptaupy_ko)b(8AJ*$=@nXjqsVe~xnK~QuE&TU(x~^k9LiL?#nWJ{FJFs; zibz39dxus)(xoyx>(c{-?n%;J0+QzI46Q*#3d+!KDPPN2{tyq4dCiE% z1!_W04h}sSAn8(>)8cA5^$lI5nvBNc z->E+H#;?HE?PIE*p`5f^EDz;>Kb~*VQpFagwJ|pD(QgGd0lMr4UWp%BV~`Iga|lrY zE)(vvP#QPJlhPxU#yywfw;74=rvD$$)Ua_N9cI zkwt}yBqaYT=t04p(3lJ5l|eaCc?JV)ATnBmcPTQro2oIa2&Wu%AR&D(6CVEkOCnt3 zxtO6ex4h0E83vkL|Dv(7R26i@KE{fSbyTw%vXr>Ng88~RnBl*osW}y@8IzqwQnXwq zgNulD(Eu_#36Dz&mDdQhI(ZVE%GRFSyL&2I`+Vl-5Bp8R-Qw0HV=BE2dWge5>uqh) zq|a`rGEuoGvgIvh3B$HyD#2_z6?9Cx40C{JT;>&M{uMnuLoIl7BgPg9y}gI5%ii3| zZy#BiVZWY-uI`*3y%+DrC81!L!TY^ugG{As&-l0eiFBXL@Ul>wr#WpgPx?P{3+eHu zEY2rM@5x*~6Q%h_nJIZa*&i|uFKSo3%;M_tL@ZwAo%B#lC70!w6p{43;dz_MQsn^I z2bkAhzDU=Vf2{%74yu2^B}A7fln8 zjQ-%Sg5TVZsUl+-K>_J#8L@EC4;nAB|F(6h!`dU$AUHlc7jM=^yH$OL{^#qFhnD-2 z>waYLN(O2%Sz3mah?}<{9|zbSuhouZm7rkIu`aJ0^CLPG>?ylElpFzKyPT$K3(mTRz(;wZYOZS1KKlxtU=;gG$C_f;s>lk}n zCqIAKZ<3+%Mohi|;p{n4C9a~)=F%u2{UtdgLjwHF$bYjmH~u7zQGkrRo&z>WMqbap z0`c6@x(jrIlDJ?57ley_D24_y^$HX-fq1~+HT+BdaNvR zz$sh3%S90vuiE5_JETj1P*{PaSNSNTxLA)cXKM}-dMfYv+p-;obdiTRiTZB2B`R3KS$HKm3x5Iq~O^9z_Y=X%{S!jNIZ-tZ&|OS58F^ zqF%>%q?ar*Dqy9*MdGz4D{F@2VB}rIKu|y`j47@lLyiVUa6rBYH*Ynu;=<}p{kaUlO_R(bhR2c-WOMhBcr$Uo!k$ z#wMC7v%HAZjKpMPqt}Ne(X0o3P>X&Y6J1-cU&m_U%|H;E=r<|yFuF7*Nb`|3y(S=` zqIo9Qh!oldO-|`?` z7G|8*#NX^U3Ehs)764hQl13j%^dS%NlVs3!R$FL&$PLyMON*`m`EAAZkSX&daXrse zAZx$YWuNj9kMkMop*PXG)INqkKYYv=pe5sCm>{85NY4)l&sfLQ>PjPnPiS`$>cT3g zEJ$Y9%_>iLz@J|^Ix_Ueb?i>bD`fu5MJ$_gT=IGyI{;0emJCMzI{f)M{nI-RV#AYf zK2*`=w#wnox6hJ-dN57kUK#;+zFyQ{+~_uLa;^Y`it@>JfII)Weq21YZ^(Kb3p{nTu9LvvuQP!}P0(ZU+bRNI>r{$)dK9q2Fs^Wss#ycBnOqngN zDGTB#E7Q3^Y;`g>Dx_Al_{NfvcMPVnWaN!g*!-LQCb0t5fn{ukUB{X5EyJ%{V2mxp z@4Q1?@`H7TA0m`(Hl1`G>e=J!CnPFI$iQBxUwtm@BG6qNv75*bmj9}Xd7dL;I5Ivx z5TQCQnV;;>*xqDZG7uAxV3!1n<^qw8W^^<;o9`E5yM)_@iGI9b2gI_KxJ78xoVgBF zIm0MWD1^$K&Ef-gsEW%e7Z{-`E~of8h^k)8LevhpHRh9 zv&bW-0^35>9jmfgzS(b*%&WuGQxhrwAd4JvTdDS~s}qsXG2A?dSZ#7x$v#W>2%q|@ z0?k!ZXCy~m+8TOt(ElPOEdAs;lVFYMZRv8$8&frC54@Oya5mX#j(*L7D)uE zLCJu1DBUT0BV;l`EbBaXV*;UxS>xbw$0$Q@01yG z4=q(&Q61b^s;vX`7;M(EEU_M2p>z_N}@ zsv7bpG+LZD3Nj^oSj;50%9!1&aI1{jtzA^DL%e1+}3VQ;YE-x5y2oD$m}-Q_?dYRJO%nz?UYmF z9E9d#)t!adsz~-CQ#x9@b*lvS@px|suw70aWWPksye`=kPcrJ$-UeB6qjE~;rFvs? z=s*e5e4soe?uTG+%C_Vq?dA0cqF6d;mB$p#e?8E=TJ`-z5qe zhGYTg3+uX;0YZ0FS8csn+Obn^;`}Y<4ud#>ix+1>w#1G}SHhc1wS&;dVT}Yr?N?-Y zPxM+^^@}w3iP4LW6Pe*j8-)HSSCyDWHB^pH02$%qZx?YC%>y=h;q*niy%(d3Oinou zE)(u`wF{!M1EH<*B(zoBF6ieE`%OYqv&y4Ai)xLXwmBeOb<`<$ib|;5+ooO$jTS|y zL9(#JiClq%I_ppcfNa&{=Lvnn0NGnwa%jM$ zgUU^|`XbSsnQ*wfQPL0?s^3nV8zhhHv6YKBD~n%e2~|p_suC*UYRe#LYK9A(f>0T{ z@A|AmVbFX0RBG%+mI~EV$xn1(dY%{o=!~)#7i78sKetw$C$M$^-HBDVGeAO5Lsve? z)_T*_EnYu;4A(l&CcwCK0F9kX zH*sfEK3J##F+dubvDHo!Bpoad60-a*Wio&?X)tNjc575-27*|l@(4cLbgwfG4gihJ zOHM(MbaddyD}PGmQ)0_Q3PQ8fy_-QoqRV8<)8STFAXNudkMWj2%HBngrAV{nTfgM# zxE_RtsI$>QXoy}q6wj`*WYZP1K$<+6+K!zUgVJNN{25DR+BUr^#&hPpSH*ZP1!q7! zTT)`^$uzY|C=1Y&DP97&t1KCQoSLPpEZGVB%-&@|x*Z0{usxx~)) z>&^^2Ql^h%LCOk-mtGbm{hAen4NF*n}Ck0Vtv`2 z1@_q~gdMOa@!=%g2!Ey*7p|&44p}V9op=yq% zsd9%5kTicF+%JPdMfCO%?`e*O%BA2D&u7xrhIU3= za_G#IO3O|&kp2y()}SmGG-etcX9?wCMV6d*j$w3#DDY6V6r}E#E<$T{ z>J%7Op%0K6G`3=(An9p~t#pEk|JG>FG6@VM-77B=YW1rVi#pC`mt&reWP5NZibzJ| z!q<~PQiI|*DT&ln=x!oAWsScHeK2m;GpDn_uJg@RUbSN+O;sSf#nr6x!Q4dkQs#A@ zS@lw0B-V46C?LRg;d~tW#oi_yUMjHRnN zAn5{%B@f=@g{xfdJY3|>y!u5_tztFix9EZf+hi<}w1C21NRYIE!cKLN)T$3swAao; zU98lY3sv7-7(dNBE;)dR19aKX`Yox|@U0qNHqiBporabXx*sj=OvHRH1^L2mQNAfH318B=zcPrVg^z)Lyc4sSa7V zcN9oktKmCpAgNce+PVH0TP5A?w?Wcd_aZ^*AV=J?THVTan9FK)TdgjoR=>!S{F?eJ zl_5KVaY?I&6Nf-Dh#Eu5>mca>ihddpeY4Nr+t#$lX^R>r+#D3!k`b7i8b==YnX z3nrF=Qy^2F-1UfCMab@Dx+|N#pVg(huKAH|LZ#~V>T{=G_%T^3Z~7+bfr;h8*ebR1 zB5A;4^L3LnV8aQhcY4 z2aw`$%dloa2Vk%t{Br}q3wU1B&4D-h~E4lhb zXaj{JejwDV?(GGVKF^HT%QHkpF=`4`n{xbYK6y6cYI z0ZAJuCeH}~_QTNrT9<0BKo{%Z^wnK*NP%QNQWgv(;VC<{U)IiIb>~t(5f9;@9RPv>~#=sHdk0(h%VImMeIXlL1@3aiWdkK>eN9WWc&27_*=8r3nfu#K!F6axAPMA==_El7FCAvfv$lz*Y zbp!w!ko~*^i(}>=H380(t4o5!`u?MgK;28UsDN1>Fa(ArpsuQav)?3qo^jq>^~++M z5!{)o1ck7Mz^qUEY*jVSJjVtQ+C!F0RXN(hTc7wh^{K1cuBr^}a0N&Znyyt27Z94R z?q{&7ikF4Ua)YGzE?jFLBqYtWg%DUMd|=4|1QrU#FTI-}G>F`Z5+nnN;o_1Dk%ioN z)!VExF(upNg-OPL!*$F-Y`pUDzbZrCOkTskJWn)7Kr;FpVVPZ3xGdZi6U62a3zvb= zaJ|P^6<093dZ)=yZw#d=gJh;txRx+T`tHItfIsibSZ~PN1JETpRu{qlY z6FQ)+rmAG&hBhFyN2?rr3xNUngtNl138P9?2dkey>^BJ&r^8$zv~jA=>Z>X1I{JA@ zWnJG&vZ;znwDZ&|LI%P$+^iDsXS`J+^I}1oWPmJ&#!HZCcuaxxtHhA6Y&F$P38(FV zWC~LhFPk=HfL@YGZDsw3^kNNx4B>)s1t2&O8Vah9rWET3*$gbnu|&e@at}|CG(Y2# z7i{%QQLQJ*6sB-Q2!!V6nTW2Ynceh-+lIcp( z6e$PEkS(MpH+3H}0=st~q61@nk&M}fyOw~^1$Uiio-$xAohU%)SaBOH5ZfyxKY!R~ zzx5@9Q~fglGN)N4}@CKb&f&kf^!e`k4Bdf^CZ-S)kglX zCM-S(45goilPW;+DqpyOE=bCmBH#KN>X136s&>u;2^9GwCKLi)_y;6iK-$Rnlw&7mAAQ_;I%Tpf8tiES2l(BZdcPO(us`Uu= zg)A27kx<>SC<^z0(BQn}$OcJ^1#h0&aSKa$a{T1e{6fD8G7DTF zF0OR_w6fLkyn4JPZ&&qFf+KEH3e9RVB<+ihi`tSn9TM9N>`(3 zn@ZJ=%a-|6s&=@M;Zig|e}?i#A??R2O_f^-)=*!w9$S-YD6|8J8|E z0MN@;Y!o6UP`O!5l&F21YEz0cnortOscO+=EKL;~3wL2#Q^m#}?`^&5@}ev6bgX-g z&yWSEqOJf`noW!T=MVc$!f;a6HS0B%x*d*VgV64ABEV8gd5#5*2t))pqKx{ltZmf3 z2rbgf@@Fo2PKqVlJc?9GGRtIASnH>iqaE(xwAQ82-*GxD)mjO6Lj<9Pdf5@SGL0sO znDerV{3h_v!IHjh+*?uU|_IF{4?9o zR!P*g?xO@9QR?&k96j~J9I7`8z@MJVbpy$>#Bd41wf31P=DMw|B(?htuHwZ}i!B>dl(3Nine1AydtINOIG^h@VIH;8vTjaQR{o&z%Mk(EuqN+GyL}+RMuX z(SX8N*O^ZJzF^Hr-yj+w%TA~IY-U6|gh6)@o-U5nw$&Ch-0yAeq4<8YGindU_p22m zit|G;43{BXTU{}EQrxUzkOt%w2rWKlpRH`F!{KC3*4k=_39G4@P&i-zG?!DyisKyG z>l`bzkhU6P4!2YW$qlYN4w5`n+{dM@{$4Q0nhB%D^$gYilEwS7SJr1_5FTnSl|Ki` zgT>j2`{M4uUmYY*7Gvq`2$Cm@;li*Wj5b>@W9NS6$v#skTdMYe`Y(0s7q z!3Utpgk#be2oDyPs~|jBSUm4b4ZfnD&vbdQo2D3K`6!zQlzk1whA(N`pFiw3NpNK| zSOAbG3ncwC4p``9QFUbo#3zfYH??opp1TddzqAa!Kp;F>Sj}v>`6a6;@jw{1x55R{ zPjOEJ@YLsCBm1J^nk%(!5jsC<5a8caDuudg7j?wU+@>Xx2lQdrHV6+As=^JhrTlp= z+@+jz1Uzl#iA&XNzPk5!)tDfgl;SPh~nq=(sMPhtl%UkgdM- z?;+O-*2&mMh?_|(vg01pjLngPi}gYAJ` zLSE`iiDV!=G+dH@AbDsQP8Qll329@?wg;i}(+7W$b80wb%j2Q>RZGlpP!%Md)Q^{1 zirQaiI=7AuMTa*K`rWGEYX8&0TkEkXMt=0!&mZ>LdG%sw@q7v-J#ipIApNGp6^3`E z(UE604mN1Ws;|f#}_mDn}fr} zUe&q_pV>u(4s0)!4`9sRR}6NYd2u4#F%7_H2OhIQc;+j*NxSPhR*fVV{QRf3_ z&kko3)y0#{EvPE@0sqJ(&kh*Sy+zUoH=N$L+r^0eEj=0)%Lbq~`=kz>* zG|6=>CiwduwVD1a+N5qWy_=Qgr6f*}Gz^C;xPr(F$K-(Bnj-d>qQD@jEi>QJpW)F@ z_jCZZ1pU%4by+qxNq+vY-z2F(&!<4rDupJbY;SCg)=>LGk2sEH$a{_;=Sa~6^5RRh z^XhS8_F4x`WmryB5QJw61u}P=$K}n|B_MQpSEaatO!)w{PMbPn-sTU21aegm1KTc_err10>`P8G47Vp#2$P1Pts%!MkqHvY1 zc}HZop6m`hY-Ox!ADDry8$B@CsoF*28&VE)xS{cP90s@+j}v z>yCX~(JYI*b>;6)Cj+4?`ba?JTJGn{Q99=1Yo@cns&|zx_~q%8rr0d}WOJb^ z8SS3@*Oc8+ZQ`SzjO2#Si>UvnOb!Vx^{L9Zx?WQKw4!^f&UNz5Ot$QdCSN)TT~IoL z|9qq01Zg9Vt?n{=NpX#>82(<@?GocOpa+{o2P4iPO9>y0?(C%=TaLX0IMmLv79cb{ zn!QQz(knfOep8U9vkPxTf`l|QHT|l$k$CYPnl4MYvkeG6A9lZjOnEG{eODGwdN_Pm zKLNm-II~ikf2qyZZEV6z?}*eP!$B(=YHJ)rO>2F{G1R0`(6o`uP5)w;{Zbb3UQYS4 zJp)pemm}e_)MP8%0ThH`cK7n!OJ&4TBUX_tHv*MLU9r*`pGG$~^HPtkxX#cx>FaFP zr5;=7K(y3iD_q-PZ?)J$0xoy&zD{!9O{P+&SR-L?wb;64-7dPVaO|R8?D)8W^F%$9~$M|{~hzdVCdKx zdQl44RN9=0J&xl;=i)t%;c*lD%w*&2aQxN=f_mmM`KpW1P&-0_;>wj#=YK4eh8M*^zzzY`ivpnzy5Xner@rwA2SUlRGVS@S4~CgIYztcUXWd4u2l z=f7&pRDa-E9-g`+is;hSo@6p!Ff_acc~y)Tv}vNeC^|EeXon5GM5&&*sxNN;6vU#ZGl|p( zvy+qP1h1JyFJ5|R=*vzb-|?koRQf*|2Td!sAZtv&t)CkIbWXhd=1`>n-RX`=7Bv-b z_kRc!X_Bfbh96&krgAc0Rg%kgokCQ~EbJu1m^Plnu&e$xk6FQuebWX!Q zU{38h5opr?ZYN=qMst-BwIsm<0TY6gXr}1s{H*`$pRyvVR!(K3uHimsN#w5OwS^D) ztgZyKA`>(PMEf!c#XQ;}Ix+JY@gb;lM%_`GcHW!)lIWUD_`9q3TGbLvKR!cWT0HRM zbNVbH;m0ozbLvB2w*PmZ#*;kLIui_uaBa|vqX(yJ=;cxAEZwZjKR!5tL(ZrqX$r+Z z$pZNC6|x;+qKLs6F(h6;R96z21H6azAs_4Q8;plFkYI9dF8}so5O?aVlSCPZbmJ!p z+hvDrIvJXlT-{zgTT2d(e5rzQ$l{ChTu`n?O*+=m1#slw237uB#xYB8en|P}e7-tN z6w=imX~jQ1&nG-ldT%)K`%7*%6rK6+_Jt--k z0K7m$zoZm@{;*$?w77;s93O)8v7AncWH|A8?DJ1ixjJbn!KQ`Cn_C}p)TxzITY10s zL~@d3m@DLt{1A5P%5o&lB)3`r=S8s@Cp-Wy{Q6pbaN#S(Mso)jetQ_2N!H`u+Xoc> zv=f_>q&DqGbaZLcezsY!IeB9otqdQ&9NE&Z@ZsylwFo-3X*$t4T%ASEo{!wp{21#j z0{HN$F(g~N)aleknIz8mk=X+meu8p?{md8mkdHQfCi*7PRM8WfL{nu2)>-2WHD7L$ zGxPY&Nfxs))TusCYI&02o~fRRMY|^Ccu3MY%GPOJ+H#z2-Z$+UH;_ou#(OX}?V32I zd8f7<^SlL|@q9wh1f21Ol3wco&iGuV7X5?DvL6cyU3NKHx7vHNUy|TjVe;gMNT2zK zs42%hstNviM)#OBl4NmF(p&K%jZ^a?otxZJ2M&5Jucjq9zW;e@!QAHAb!Y&qhAWn+&Z&6!m8>)V(9s*$>v=8;4oOeY*dw`PLc!qB5CIo zIjlZp{nJay@<<85<)`CN?!j-e=X=>~XTp2YrY*_^Sq{-mSt~*f^l#F+iDo@SCaF(R z@%>L56*ftO4K3AkKxAnLNjs#YloKNxFz@Chv4NL~ZLehmUu6F#O&UcaJ0opLs!ST( z`sE_<;4ozTMRKnCQE|cIWw$~LYRVUA`=xK=B!)42`{xh)CE0v0I(a{YT`fnK`y$EU zGt&c^WPOq8>9b{q@Bl}{S_I(%j)n(y(a!1eIVWinC;oR%Upu=9m0T!s=)L%m?dkIo zJ+hkFV@V=5z+I%{7eWL5wWa6vPwBnoCedDE6tMwLOwl?OIih2!lyr6`>{o@8*_+aAr*$8Xa4rAQO?43uV-wqlUaTaOzm;5G5KRshH>0Y^yrrA!6L#i3i z#_u@~KH^T610B~t$vZ?0N`lZ41QCNAn}v@_~U+O(eo1_B0@q?gX2 zi`q04&i#Plm9wPu7SpWLc#H z+ZSz~P%?CqK3=j7@d6IHoneR<@Of?Q?ZSzw=WK&`0p+#NkDG-+^Ts2e8SQ$xWo(0RY+xp^d`4^_Xwvl1#(T40k}+Ny z1OWpsTb=3!YM|4uWg9PP0;&7fu{Ww|a- z9XAI+)hqr0W?^F><{^Uv&NQtgiyKB~*@9RBe@fB?BrP6ik0i-ydc5bL;o+M0NgDrZ z+$4>jY8L{CM1#zXf?mB6*q(^6&8lS$GP#FXhW|sPN}Vv8M8B?m1`^sZtC(yV8byP; z=wRvhTP&G9bkP2MqhEr_w>ZDPIe*osJ`fGhTn1^2RR2qJr$h4x@llF$5|TidbzgHz z0&}%*#REU2@xqWzygBQ<*O1%wMYfbz%`gbV8X zGm8dKaS#b)avtQ1Dup>?quMn9(rBnF+y-I;N4vgWo(Ua6KckfA@xHC8KpGbgC*kRn@kR}LNFkEzXU0I@Ja}bFp*7D4p{SP zUX{uS`a>etNt5QX-w_-|a5(mRz}v9I$}ix$nLD;!Cv@|Xnh0al8NMgw#{ zjE?yr>uEZb#>}(f9El{2d)i_OZvUxCC?=chm=`}kq}X`TW`x^+NTC=k?xCjL0JlF^ zpQS9^{`H$+qL2_g^gSG?OD~O{y#r!dH# z5AySeVc)^;Pob#T3J6S^9`~|XY0^B&{zsrw7JwBK&r~3=D&AzjbqE^yl6bqKk#Bqx z8Gzm~ooW&0T^lC)^*zpK^y`OI+BCPSgy)}YaQU~Ytxp|FKs152_~7~HdXm~hBVVpU zo07fd1a|wqN@qSAO6c6AkyyC(&Iz3I{s3%(<&TWCBGA!R>lBWE`VV-uEXm>m(?P#< zsm61V0pa-ZetLqS0POc4$yWD{MaSOxQU-l;uC99?s2R}#z+=28;fGjRBML`O54#mF?>1D9eC+;)I0>N3E zwqrjZ*^+x&+@pK5$zcmJ=1T#<4wfjt^f-f??eRDxGiLfen`8`5;DZEBo69=@zB9hV z_Q=P-&^qK}KpNMmUNf_}IhW)75lkO^v1}?N7HGgB;DtvEZ_Ry!#h!89EZv}Wcv)HM-ESxET~{n&+PrNwfEla zmxO9I{Oin98}-NwR4|kssAZ6aOeq*WsFU;8?{%N#w@z{P~=Q2tnhB zNz9<~yhK54lUbgo*1YtusejULy^hI*lERdMHsEIFrFCDj`+#(%;D;^E(C&lhA{)e$ zk#tPC*2z5j)B+gIG^h{k=a}`JI*P$A|2w20b9rBmdKH8MC{Davm$j+t5kuc=$tH^aVLg<-+#=zBB>=G-VT0wlO5 zZ3nJmbI9JM#bRcU1Hqy;?Q#5Hi`p~`4CG{?@Z>CN)5n`KE3L;F_(g5n z-2yX7aJKwQ%u4Iy*p~_r^nL6j1PCk?51Cxc3M&*u2;NhQ2tj}C&&9N~EUkF{N)za# zIYIrLXUB24f+E(6FITK=2j>61RK7t4cYPqSju_zwPF zCZ^?qu9<8dra~kQ>QoV2Iv{zTcN6C%i-$6Qai{4qYm>(IEC$&?8-^n7ez-Q6H0iROyr=MVcO32me4KSPMAAKS4OCV#&P zx4!�LqDy6<>zlag$SPZmL~ zQm|VkUy=+iTAc<#WQ}eFVCgXlux((z=he;oOGKCxs3YAIEwdEX`# zNKe`Ce@)uH-cpDyP}0c&1Zm@`&D!NNhgPE^3wM03w!(o5AGSf#3v>QE=fk2AU55F# zT2`%kf@J!EztDj$mFtA47DPrz&X=eZp>F>3tEBT z!}2TuKpo;#%@@H=Lo|VVMrl*^jwa~*05WAZc$&A*7?uWY+x$3Vxov*fU}{WOyCWC1 zUk={dd_y=vN2hVflHIB&L^wfvhL$Wynjhy@1ISbagsG%e_K7V#v=-j~Jz~NjV@atL z6S>XgD5#x@-#v~w(wVJ>^(rygnXT6A5#tcWJwId9Cr_bV!MmAg)hI;)WK-nnY+NBn zABXh>iez|A!y=T!L2{{6dqP1-Uv+BF9`<&C#CU1X&gAdg9_h^eK7NbZnfjgLVVP*A z&fI0{H{Nn|gT|ffMbVd+N%8n`Wp%HSZ4*_#kE%!l4M;%Q3#)vae4SDJ89z2J^r% zZJL0=Jn-%|M@bsZ3?*lQ_!!@c$);MOAN50+2hIx~0@9N5RaZm|xL1^*PzRH&dpl;( zU}jiv#|#?FW`?)RkfI8oLhD$z%9PSkhZNI^h=FvS?ETG~6LW5J*DMQ7y`k^P5^_hK zg*21?#q8;av7Z${^U37fu6dD}TT;3?c+u!#8Q_An6wh@&GdV2&nxl#2`>D}v=*g#A z<&Fo@*2!Xu)FLun;Ew0&^dbsoef5(C3o=QpX@c#bA$ug%g6Y%UP1cjdOP$8BlTtaa zHNwV%H$pJPeY@pAraTNXF=E?DHAL)}@N)$^7z(5AEtHF#RZO1Pv{u*_@3!p*rMNXSXTgZ|Su4 z;%K_b?CIOR2BI*Iu1Zz-WW!)ye#6NCL_4$;7YJ6w74l;-u*IC7MnolS;_nE&3;Mbx=+ip#Uar)V-YjT&Jv{;Zy zL(nS=p7{QfwD831j3^1Yj)t`Eg(seZ!>7izJ$nj0f#mEB|7-4-+})RLK3nYjvVHEM z+m{V5Yis!7xgI6MHnXSuxhMdVMqjbCffs%x@L^{&dAhsMP?E+S?^6}L@bx*@yV>%x zZ38d-e^0Y;H(FlRhrZ23v3~i2R^7~mfoJ;)%Cakhi=RF7WUOcU!TQ3a&Et@X{sX&mZwlHE+4hAq~-=iUr^ zZZnx0HBcpQ;DwJI9-pM(g|GP;8SI;x)38j+A^pFn2XAjXCb_8F#p~giJAN%l<>ufy z6kx;`$Zc7DT>Qu`TR=)%0g+=+A__!#N76~{k`i4ONFXvom6Qz`1IU0QM zG@B%>K{%Y+mH<<>Ul-{%7`2%}n$GOAn#eV%Q#^=5HF6iXi|Nz7yIuy!;CWFZ9c1wx zB(@rS@bx)UAW~$yp9n&2GCVkOVl_)&GaYG@a|J}^s86q6gVBxw-mVVaoN9cRzpFFG-p~#WolSpHP9cR-{~yoe3f{h!PJ#j!7-b z(%-Mtc``2cr-0Za>BpH9m(&FRU zt-%5R+R*j#CZpvH5ISVsM5d~audOoQ8av$o9^>_Nwb*qc^S0G$Pt(%V!38gsI1Z6> zQm4iybu9z^^H1u`(gV1?eD;{2SDq}fZ zS`C^Lr>Y5vrhv!#R*yoobga{c3w7_$ANEV40|WaOBvA-P_oF|S8&Brv(lUsw8J#OZ z79ZLI5}tID@XRQ4x;pRx;(4I;(%?-O;av?7{*lfU0690O?hl9z8dYm)tFfOyN4$-2k}sRU!#s zNwN8tln;F?q_*g=dXcGq3=>Jr&fxOB`1)n5 zQcDEp?>A_CU=MLGo~o*H?BDE{L^kF5yUH{7i;VVEtG(K>X1Rq={~?{$vm9$QY+i~s zPlo?JoB|Yc{EVb#?>1E)WGP1Cmsh~qQIkC0ydwC`KJy0&JJy=tlj+c~Z?vI%*tb>B zM`SD*O#if8fvK|odzkWar@zRud&I_8SNc{t(icASNh#IOXLh{FwjayZY2Qu&QdUH| za_AdY_<$*X-$dzKRx0C?6HO_XnF}g0x|)eBlLr|zmgPFlq$2sCBrZm^W#Y+0PBUM^ zuMS7KW={fSG|!cH^79UZL4 z#>u76TQ#j8(eSL&M{7V^D3rW)AB3_e0@dBpZ&zRNv2h*sgjY1)C=VxBux1zTe(ia^ zXEbO3czol|-a25(!6@+(nGTHyme33<(qk%zlDDdTP}vEcoBlk_utB3Fovhz4Z~s1@ zQJ$S8HoW~50}s;W6T1$X%FNOMG`_xM+BMPmW)Bz?a}csUSe zlQxbj9sYNd>%e2h5}gmF4Y&R)OyA~Z!-K#5^N0PC^tTZ)FRHUsU8}*>&jn~x6R!Ro zblWSFRmVWILDCw%d?6ZSei0=@m*WDNN``(6hLWLAXbWU>+-*S3 zX*Y>Q_Ov!t;ts&naYy#kRQA>hhJdv7O}^~bxor5@GMmz-)lOoNq2QoLnMFDuf3+_E zx&_gaHhq!#Qag*R<-dVNwrv|^D%y_ItfTgCv8cW zR_DxtG@asf{8`G@x(`I~?u$sk!Mk5y%XD@5)9C2=`9{A46nVP!)z+{jtI#lrY#}St z#loGv%4rR-wT<*Q;klEVSz#}UYFW3%Jm)u=d?y=Ji}g0&L`%SOd?~BB9Ghlsd&<0p z*FMgwn@o?)5BnvN{UIwFWR<5Z?N^aoOF7;EN}y8ZZji}W zt@meSfGE_{FBZ?lqU4SR85H&sDIjucC~>o2%AvaK7y{{kh>S&@?D|C=hCX#X$bn#b z-XthG{pL!cx~$Lpl_^wszN;H_+Wj&FLFRfBrBI#gVIY{mwr%c!#CX4_Qm7t8IaJ3y z2N@(vWdp%vLHuw16?NE~^aOGQ0>JqJKg4b(FgQTGdYFOyCeZn9JH`gG_!7Ei+Y9rk znmb4)fx+=6Qxn0jk*^)Oh0TC(DgQixoL>(jH^0oqUaI~4iU@&pK5!id^9@*Lx}A#s zAW~p*hJi?dJ;>&&)$y>ywa&TI;xEiLK5zZ=hy9YkT11lN(oitB>P>nA$uj`X%kV!n zb4o7gg{3p`QY%ab7o=swhpc!LW*@h6!xtoHF8+CJsN`7CA^~%{+R3Z~X$j;FaHG%1Y(%6zEmHEeSf|-NMP|^jycKp>jT!UcdPy}52 zr!x8LO>k_6TTw!wvUX;3SDO!E(7IVu0>IFC0lb2nekIUP>zyh!9-4vby(=@np1(|u zm$gYmnEBP*S~3Y7RB)$idsk+D!JS$~nE8dz)NRuE-b$PV;b3VAS0;Y7Q+oa*%<|;? zCY`S-3mRmSghzsT$Z#Q#X@Y>vn?Rj4#|HplAmFF`HOxG2ryv+ePL%5oCCTA(|IVL3 z47;u}87$r28dPR}wQ7k}nT*^{cmiZ|cr4``GryWGW`LpBl3HraMSlEJW97_t>e_?A zmTaf=83^pVb}mSFd_m)1X*D(Gezi+cbpRMK&7EfeHotc0VW>x&+dw6OQB&P91|Wa= zI>H7{{Ps+Vf3 zQ<$C|CYY(ZZZgyEc)TYwzc8Mym@K}z?6TgN`BmL31pqeB3&7;5^T=5|8}4;z_co>? zs}ZyaW(j{1=QHa~pyX!$j!aFEoTroY12RcGc%8Y(^;}>8X?y`IhR(v7?Q)6-$R<&u zRqvU4T-{?X0p_Wmo*un3^9zqme_qF-EJ5+D@HhG;Xq*;Rs_dQV$W=|N6To6@*V%Qw zd*_0FQ1FOX9=?@3_ZS4J0`Nh48Y4nW-YlJnHh5*<{dxIiVD1rL7DZ?<$E z%%OghoTzc$YEX?TGk8BdkuX-|UwpXU|Q-ljQ83yp=wf`&Iinybbo+s;A;P2=r(@H{ttW z@>lKmi{)0%^(D{XbFbX50X z?aX>=3xmK4s_jfnFo*iF;)2;u1R>-jhgh(DHK zNNpBph4x^s7gAXKQ_S_MuKNd|iSd~_q&BbniJ356PxTFu6uy^T9vx15e#WL#@UV#@ zmi3Snw(T4oCNsNWHcP-w*3PUa#|~s_Yf05lI!y6A*CDxSPAwS_ocWO8(++{S#X&^k zcCyx2-nsSmd$V7X!LOeFD{O2e6Uk_uyatPNk;VrNcV~V^YkNvlo+7*>7i(&w#_c?0 za^)zN(-#$HQPDO08{)Q{yZRu(H&AE-Wa)`DFN?>{a_(}23~jSZ(YY`7OR`>zeeon( zPE|dSHoi%41+IPwrmsw!sf#Dk7r;-W6JhTri=WVHTde(s)`T9>?YXn*y_gpEAp4@| zkYYp&UOm5-^`@#U=UN8H`Xan*1Rs#5ZnOGV_CQ=Fv%d+Cob}ZD0%=qty3_y?+(Oo# zI}e>$ThgAJ*Nw{QV*mnW2?vx0c(a;jIh7&$?w%-HoSUc4HwjLiCByFNKrOf5YxC5J z!5D|&_)yOMWe}WZvS@^cCkud;Q<4Y(Cp)Z(aY$%wHG|DPdr^S^Pe*Umukdmj0a;h1DwDy$RAi+f_Lm6c2dng0PRXu-l@`4QQy*Qs) zl8W4G<6;4@a_;GaXaaR-5G2-fN@B3tM|c73lL zUO7r%bT=8_VDb6%28GdXOsMZw zEToCK+ry-Bv(y8ELm{U*$mUoy4o-0`% zAi@1m!a&1S^g}#&mQ$o~+?GQLpqyuP%sW7Xk*Jy=|h| zQ+N+VHmmomR`ul{;-#Zp)&78WnT{kNvRUQL9&Ok{mF8`%@>NbnrP1PhvRe3bVa?iD z(pk@O)%z%ga(~ye?Fhs_g(QK8&2NqhB^u zZ}g)8EuMSv5PO&PVoTH3L9ezny>#BZJp$+F55v~$Qi8Y4 z$pliWJgs9EbxC2SN$;%K^$@L{y_z8}MlsR+jX0lK)H_Nt8SwUNeMxxr?95zFEvJ!X z5IGgRw+FJ~;;2Ed?s3`Jl!Ft*eue|$ z^?c(fLEXz4gHiKxZkvs4SM%R}C_2&=!C29S?ht)T>-6y(%2C{j4umv1!==>&<_RIfH3Cw@+e$xG~ z_Hq`09OLDDX4Al-gMI|>Ar)7m0~p_6z0aq?Mw7*5hXLfUvAqyS`8~*{>{9`w5#8pC zZG-4`c}Yt}wwZkBn;6G0Dx))ooo(F@JZQa~axfqHXXm6m<{(mt7EckL9$m!%k$CcZ z&*L*WV93en-=6>Yc*9?^yt{OL5u|Y$+UkrY*QC!*vFuk<;ffKP{;lbhSrE;W%4dNr zzPGYn2BH9pILNR^6rer>7a)_imN&8{&JtsmGfgrWCvPB0NKUqEE~mKKnCviFPs0lk zO_I|1LA0&Z@p8=O^Y()@T4LeG@smmwuPwzpS-LALd@hrrP)9YG^jk@6 zPu@r>CovJE@xA&1LEpaTf3n47J>Ag8W0Bz{|dw-ubLTiC7e3BlIInvOmw001IY)Xzus<1`k3{;*$?&B0I< zd#vR+-+AbzIG?;ni(Mu$q8`#s^XHa9Yun#tp|iIAUGx4c&7QTx<~5{xD#w5f62JPs zPN0vWtFeoxPbJks`X3Sw1QnCby>D@~c@OEaFgBYu7q_egSZ|NR<~1bzkrp?i03<5) z2r}C<1UzuYbqKWQ$hCo3ErM9h=&EAs;fpR?Kx|mjRYMO$`P?fR=nKZYh_~K&KvD;n&(M0K3 z1`_2NhX+wa))~@o^a~&*dzu4*bZM}5h{7Q5pa7 zUxqY@tU_H3jca*s&iAmn0=$c*n{e2x2Zy>5k6aJwBHKWtu9Uhc*U?UtCm>BvOdAy> z`s=p~FCogh!#BLC-0o_jwxbyjRZ5YUk(Oi~lD@M6nAe$Kq>bLx{ zwU}*qI(~wT@l7-@3QtGj9VA3ScQxttnY#iq87Wn+cfh;ON0#*q(&|&zf(%ZKGzQ4x z+=V|w)d&&>osX>i++dL7x%CR~E}e+~&mZRk>tt$(Lksc|FKt+LbqGWxL7h zD}ey~w+yDJY&MC7Oi>OZ#i%%P)a=51C*%Nl_LhMsuj(VpBrEowf@q&9Y78gZK1L1#QrJ zq<@uWY}Q6m*@wBF_UBRATp_aw3`TqH@=E1cPXptqY{OhnKQs^~`gr5lJZ9E&)io-s zh}CoJ5=5&+S&AS^R+3c;BGu^4*e+)r$^#A3`I;4QA_;m9UVDC3kvf1#z2J=T1j{{kp1${z_v-$cW zNPlIwf=tSZ(33IEtey^_AWfN<+6yi3Hod`O@~_neF3a)h{X@LYi?NkG)uc&pf!*1+ z8RMia-cr&X7!W5M zROoO`q8M3-te*Y_F{D9HB0tE~jfSSrbl-Z=p*lwQJb6J5Y0z`G17s_=Uh_S4tEoF< z4`fK*_ieI7q<2SXhxJ+w+J3);^2>(3yC8dMEJSpxY3Qg6pqbLa7G!A)c>tMThI#RO zE?<1GO*fRDeXdKyPE|yUrGXLlw)4m!5nUgeJ#o;Hda+~If8-l=Vz!wn}c5flbgumIiy0zu_+N6 zkc2!Sp0^wT-ghn{q(Fx+V1kU-EhUh}&sZo1v&-;T5*BgpHl0^^+-=h1uo@XmEUkmk zU8ZT9HA^|2Vrd!!Dy^E`q(7(Q-)pG0xQ`d4fTL_t1Pk59W{IR+sc! zC>i@jcs0?cLS!;Fk}ss@C!0KEdBtVYcymr(8<5TWV;;cCi%MB=F-%e?&ii{+jQg833I3uub0CXnDy90|L^H-V`84yznZyhsm>i*GkmIFwdlk0x-?HiibC{y>3_Bk2Ntx2)@y)G^yiPa^2 zw_LsiBxhxvmA5X>iWm8kzFX=Zkwg>agZa|+qtj+ER`p$4g+xGfi?`pO@jS_bSeXU( zc*(_->bez}1ki6Q_ZVdI9V{@H;@|tomc{t@eIpknxN3ZaUDSBlw@W|HG%(zg-NR&% zSZ%N2yR`Nk&Q^`CqbPSvR6aTV(4{Q0-vj>a) zlN(OcaZV;l$VNzI?M^lKt45C3dD*zd_gh&O@edG)s+d zW`SYhNILFvE@9s!I1M&4;JbfaX^vfe3ERtJ>vHdltfG75eACTzY7p)5&2(zq)4dLv z<(usFn$N8ZN-r|TYc4h$Kt9RvZRj&%EFzY*ZmY@Us9ND|rc}R4QyBn{MtHXR`G_t< z8%#}>*Vkr7b-R?71~54ix*`;txngK+=h0%W*qa0^B3M;ym0zjHIkTBj-A?gikfGHz z4Av9Oi}_^dLN$OVY8?{1KreF(WUn`2K3U$(-zI~vpl~I~;thJ)n)6~l*_-tC92}6z zJOBDb<20Su25GFApaUvMJPT<6ES7JeKKc2>enFUK4L?fNYi0egc0wcoGoG?`Ud$$g zpo&AJNfl)W39bP}%t7{ezbCWF?s^R%94`4l0j7#jERpH56taOpI2HS_c96-E97-#lg`FH&SVEw2K4pZ1 z@VBLK0W?zz?oRZ!Rq+j~MG#dLQJNEos*31rI}0Ga$oBqD*vLqKM+_wt;;O}paLRI&oW#;tq zU4|#h>j>_C)fhRT^ZDh31X1-D8T%lc^=nk)W)>z@uq+tpn3dJc-ehRQ`T?s8z#PJ)>bri=tW2tY zlgYWzB-j4_mnX0ELk7oOp?r|VF_&+0;yjJN8nX8RI_nR~=>;-LJS{j?_UEEy9gC+B zs7xsXxenPP`j+XsLCS5JJa=YgChg~{I%el$-mKXS5=q^0Kw}XoC6|MQN+^xcBnpG{@V#*vVXIb|47O+({9{k$!!n6Va) z{ykJeXdbe(;iWkmYg(fntu}9CCuKa!r4*Gf_DiCvv)*jXG=sCe9@6*<9&`*rVnP2tTKSuCY(F}OY^2sF~}az)!C#%ha(OkgVo2> zClzGz*<|I-#)Ry4JVmoj&)Y5rlj}-}5wl5$hTR6UNo5XixyD>;{E>`@wp|=e!AB5P zN7Ko7cIn4(xC*4Hf|?d=XIqDM`hkF~t-m5D|M)F(JOhjbO4glS1a$N*va5ax=33(c zyUolu`z7HJDrhcMoWFT&=e}JMQ7M)nsUdwwYj*a7Xy>8> z$mY{n^$sb>7a8p}TZ0NR93+}UHOl6ZhC?;VUL;tBP+mun{PB70;=!!z?1*v5&|gi1 z#Xque9!$H&F4dkH&9kR4Cx~Y6knZWTg)^8chP9(@G?;gtn`D`2>&f04!&9ZzH3s$6 z6U?clM8K@;c5cptq#e4Pr~ncq$`k`hQ|3XKE%qD<=3OJEcpZX=Ik$1L^EZ1JXomgO$Ilk+_)gC>qQd;1LE!6`~m6xn`GU_eYAR00+>@HJB*|(e0;Urr4XXnx<|v0Bk;tTrE?+ ze7v}1YcLvqSGfdPd|)3~g0)w&Ir=imeRf>hApCKk8-wBSEG?(!3y>*ou|Nei<1SC;d^kT||s zQXm);f4&oA;&)NgIWO-sdGbND)W-qA7gb0UL_cmxJDFXESC{sm%r0xE;vEQ|#)53B z#`Se{G`#4OGn#|M4mktiJw?~vrd(2kj*z& zKFC}weS!j%nq0W*<5@!)M2%qWURcYW(|lH53{B_vbd$;XRzzy9?PfwF4&i(Hl(-fkq=RkagP@q^V;-M7Mo${%-~rj!Nubf>1HNZzx}Il%xn6V z&v@ZwZyRIWO?tVhCZIat#a0v?>5b?a@O|KZuN;g z37a5Gt4U6jJv@D$h|S1!KhYzQ`5p>tv%A^H+~FoQ%>x*x=~^*xrx7W%Jw1C?ft#Uf zJWVSmlRssRyq7zTJcx>aE8P)9#lMGVczO1`EEv1Kd;5Y6k^3`lx<;}t=6Gd;hHau= z6%V4mT@r~PYF448ysqMI6%V4x(mDarWXV&p;H>9gDRBivJ=PQ#2hopjeT}x2{-C+T znI>w{Q~y6%XObl=&P3_?zlyhlJg7IVpyn0ZsM!Cs{5B@QW0V=+100Z$nXJV%C78li z`McRcT&H=YBf>$t?)JKmSzb4%-^0lE7LH8-ap$MJo00txJSRZ(+m6Z(80G8xZsr-M zG!*i69-RQkz0dXq}Ykwfi%S7=pHCuMA13Yjy znB_Gp#l1mVE{{>N+2jMT3B&1~4w79orXQha7mfVnid%!6K`H%fluAFHY4QOS;q`dE zW#lN?egqQbO;q=U;}%KWmc%abC^I{D9kO0ut!?yo8}uj&@aiX+9fVp(%Mk7;r~hO> zz@3);?W<_TW7&(cvz1BJ(j81ldOy<6adOTP2vx(De%Pp&bq<@+0s8(XZkBPZnO_W_ zT$RK7af`K_4k&(%diqb=cL=iko7C)fl3!h|`3jx-2;v5mhp=>YKYz6M8deqCb$7f0 zaks8RLoz8$QdOyc5=Q5D?PkIyZtMd*vTA$>n!)fbSbyB}W}$a}`tnfi|d4nf?u z^bkwX`?}dI%N7BEC1S%-)Huy|a{@$m4zd#Lco&uGD>+mR>W-Xs^53*;dWw zuxMAdRr4ksq<;gqcy%BJhzH6>p=c%Bs^uzSEB%|e^JIRSt!DFi8=yekR?Q`!K-L#& z+0Q(e&}JFhQ{|23W+TU=0YV}AAaZRZiaGC46~yiyo6+RkzWeJ%lW+TwpFiwZgc{H> zRz@4yEZaLZ5NbdpwWP4I{_gJwGCUgR5Z$vi$UwVYksS4ADLTBn1JF~=a{#r)nY*QE z7NRqKXVKhbYh=<02#4=@mZHhq-Ln)OK=(7wo`j<}Gr}uu%gu z<@Zx)Cc3=ctR){w+|%6Kis&kx@+9(h_fwrND0aVz2g>Hm=$5398*I{nR_?k$sPC*) zF*?27{gmd3E^l`~W!s|n94PzqqRZP2l6NC_H-5>Zsc~)nq|SqIlEl$DyByx=d%Jv$ zMd`|oS#jzkkZiHgEyYnf8 z7dGazmGDYJRpjwo?%j3DgN2Rx{nWGraaa1BDX`}2Ev6_PEk`ePm?3X>Uq@>k@^<%A z{U}Dyx0o_*sQ+Y^{K4NtckDeE2!H$3H3}H>CrJu~VQKn0X7x9j*$n+Wxgy8})0FypX2zn@B8Aai_^t?Ss57em2g zyz)*me3oUk?fDNfEmBYI9uWR|oHcr?9$7z?w+DITVx z$NH&j2g1SHXK|SFardmK7E>;6{F2wwDHr!+ZI~9Q`I3MBuwRj_IcURsOuD`MsZ|A_ zANM4fmawOmbxe16-uLau>y4UQ9*3#uv2m-~Q=ac}x(3BmF%_k)7(gXKohvVJQ=ac} zwEQW@H`-Kt0htUQ8~seBso*gca;cuS?At2COM?b@$o|WU4 z{!H`5zgvY zI|=k0biMFQTJmwD3w7SHEc3IUNwMVQ#$@&ywB+Q*WX|g-4h&VPcJB1v>{mpmIS?e4 zDvHe$GXcV%Kh8-Ij09X%p6sDsTyRlY(+O4Aoasa)34&C-LZWe=S~MU~Y*10kGZ|6* z1gSxV+}!JQ(Tb2{1o4^^iUR}jix2s^aUJhpLfyF5sk8wC{bHRK-XQq#c7ziaYWmINcU?)_IN4s5miJtz=t-A06vmmBRO{K`XaZq#t{9w<~0Pd)g2CeC_{LT+SY%2y0KT6%3B4eYiBBSzc8rIG<;{LYcti6@|E*ZCH-S9`MU$*> zZdDkIQ=1LK)=_(KKUsi z7(Wb1z9E%OLA4`)_FH`|-voR0eWKYxFn;K8kXQcP%)Xbv&9;_rfZ>BRW@i9x z>`nh4-gJ(zim1E^h7WIAO2ocYVC-`ln@2#P)378_PlBQ1vmOE^V$V!G-xq_%b_TBC zZw%BvMUz3`lfbh#Uqx~e&nD#r1OtUfiE|9(BD^5dm$1i{rXIG2!y|W z_NO30V0+vyEHTEOx@9D3Iw?P5Ruuo&@8Y2#{PCToc(-b=g1A}0X2S}dRZEg+Bv#@# z3u)^*{zMCNOwl1XzX~`C{-OD;9Tb~&sY$$WZdQgSv3|5!D2yb({lZcz?2zjLW$ng) zXjAKr(q@gfZ}QohvvI97{moiCJjQAwP82A{hB6ei`{>c`pd+{f9oWcFur&#*B?(&mkB(7J~OL z(*y&OYgb+R<TUmix~A6vot3qc$?u5ylOmO~u2`pbi) zveg(q#@??j0e^g^V`n!uxkT4i8}dLpfkPMoCQgd`ZX{D-8}d`BGdvow+K9fpWGZ^J zu0t?<;}o6Tot4S@IQx@LuRci*ahFW(_e#zf4*iyNauA(l&j0|1ZyZNANPx6-8*Vyw z|FJP@NdTQ_oKz5y&jmqjh1i|7$w2I2*mNQCGV=fkwQ-zhn?5@oqMh&VEKLTI>m+;y z|JXUz!$1$uKeadYb2EAkjY?;}8$_=WSl#FnsN;mKgJ7s&XU&sXnGB6ez3tg_N08(v zLIdMJ^d-$z8>ZjSkHct_*J1P;`iFY1cUBt*u#tb$xG9oPh2S*+$3g>qZg}3xPiO2J zI)gftZVxuSWJ}NKFqSX&D+2Xr9*4$;YhaMr>jeUVI*%I%1nLjWG5I%!3Ozl2gKz`< z>$e>P00Xm5)yF*~Dp`cPB>9|f{|G#W)K7;vu=qsBrDe`RJmn@L|;p1TkOH0 zYP6_K!2&Df=b_f=u)PQUK3@caZk=uH#uWKO@N!tXxg?n)`I!$!JF~}PJ{LOK{6lZV zmhT6}GuR5zG6VL*f9O`|2cHZLL*GGLH$d>ZVm%I-pC^dZyaNRC9eoBpypxe(AgPtY z4*wz8E?a+_j0{8jzZB<_l}^~m&jUOe8HO%>Hg13{k^EjK+f4E-%d5$7XAmn;vr)O& zCyECoJ`Vx&fR)E7akY=*69kIkJ`ODqXcq{~vl=)hudpS}Tb8`qDNuj@uwRjn#)0;A z#ghjU{~!9$<>Wz2hOy3r>E<)ZXX2n0TrO{u@nP)h zW|<39Jjgxf6jpB#{5v-gFvR~uceb3Mu*27HvT#h62-xfThn{Mwu`b4jeUZS+gsc#oJ<>^|%Xdf_%P#QSVi1F+fZWzD5#^ z6LtevN%Bz&N6i$@4?#hcK{ft>wnya;9iUo1IZ6@F-B~(Q?L_c;;ib4{_}_Zir|hA z`yzwyrbU({twX`UF_5(41cSuJowdD#L1Lqw%3&Z4WS#{jSQTYZK|jZAkjSk29SpQa zd#3YS5NU%U_$$HMBxyAX7DXBT6d?imT;&dk2EYI^#icG2vaoo$z5ZxC<+?@}$6G{6+CdWZjoq$7? z?c{#`uwM{75Q+TSBv>p*_R}C)i=_Gx_Wc>$hLj|2aIh40P6Cm}{zxOq=Plr#<>9DT zX9Npc&d4x8^4UtGyNcY_B%ixs>W?nd>7`?biXBNl%LF?tlyl5yKA`b{7D5uNl}Jk1 zK89{OlKgQ7u#BBWNJ&0A1-d8bJO2;{u;8~;^MVADEwXnE31lj~8Gacb!Gu4xS;n6f zs^R`d1Orcyu?-|2U1&sF`aXnyIySnvW)gg9?A5W8Ed11EyUK^qPlxv>EsF$VjlR5^ z1dHOzZ~_tx)vB&K{UJbPxm@Ye`^`^$T?UlGiknRS*(utd)+0skQkU%@eBC4l-f zv#J*f)SsDc>pz4Aa^=wHUl^ABi>^2JA6qpErUUAf`l}p63vY&{l5j{KWNJvdtxqKU z)$SNAlBis+^CKMW@52SWC4iV38Gk?mMPtZJ`S}}8LP?5Ik~9MCs|g^aMpo=0!I0o( zE#C`$Zxj^%=m~USr#w;Y$tth>^N5<3B^>my?_MzjGuYZ{-w#Q+r`YLOpyDI zK!ZH;&!rE*uXa{_HTA4`lffuo1VetxP z<@Wl!>xcJD038PRI1kynf4LGqgjE{8$k6Tj|)LHEbMn$((hMEjzxQcrk*7i&6d*8v1;J z&>eflUUatc5Pu76NQ24BJ0we&k!JfLQ`2NPwvnWXDA0(6BQ@Rkfdq1K%(J8|#;@>| zTBa<_&~Ck&Wb1BHM_6>WQA^FI+8U}1tR$ga z3_Eq|6_*y_eWrS_Oat36#vx0pTK9?*Z0W;g%fB8aRZv-{fBvvvkxB7m%Ld67u;v=< z=|f%C0yMZ#;L~6J^n*QpK*C~|fimBu4gYw8sb`lxfn>Kg=^DR%)}3GxN=o>eAj%8S z+r}l^V?*N|4^eag$&7EZ^$4kf1|4o%C`*ztzDaaz7ru^!C`QZLZY*gMFS7L3&vk-- zri2U$(HHPI6^m7jIm>D-?Ma1PF}MtBU-4Xv(-( z$QSw*2u(e?raxp#`Mi!2wHeOxMX3G6*$8eKF0p&H`o3kj9P0>_&CnGp*)_qI*vv_? z>1E^QIxi!`B_yf8jeR8P^tZ8Tx*YCe#J~B|9P?3FAz z3IZJnt{3UpAW&0#28Mn}kvS!+qm$U2;ynone|^|n_aXGM4Q|s)l13oQ5&_LASy+q& zW7RXz;6vzaAN{BqAbs&Va^;giXY9?H)gMAP8?8-R{6L_1^rI((V61w%AB)*o>;=Ak zKSSo6EVoKB{8Kvt#)?^${&BVd!b#`7GjfIP!b?d4S=zIhDajTYzVMRm>v7?w!8$t# z5Zb<4uKMMY_3}+R&0}@t--~~HUkU)Fryto`5En(D5(orC52>s%68~~mnf+#;Z?6hv=$4ZE?*sEylWDS-!*M~DpD}$vyVgg+r#lQBpAOd zqtHG?uDUBrc91|pxX#W71mg!))e^YNRre+cOy1eVn`AQRA-s+<5tk%&n9jJ<&N@dU z3BrQZsMugB;=*4|r>hPD7i}DZxR*CUP|&uUkN{yXJ4@7l$Yu}~_8mEP40}-yhyM-+ zfA|T9qF#1pA(0>+dY7YT4pwAC081)7<16gtLmc)JXJr@^b~q*%$U#RPu9ND)P}oak zh!+XMUYOakk}SsQ*f{`zs25~8SvMIh=zx2kPMtm9~U8Cj{9c&JS=%bdea42T!)=kFH{Tx#d2nKK6ddFZVpf55CqpCb_U;yLa z=c$(Br5xr*z!0yV-{D{%puQdh%%B$#>k}gs;MH=EFxUp@4G^%z2oH}Fy8!i-mF`Fo zV7o5IsF5HTZlB3GFUGKW&QAutbhWNBK&;YSXNV?y0DrNoyG2C zK_nj2{KG7Wga|wDjzJKY^d<-^gGs_`#$@U#!U9u)n`{DvaKn_vlR+;CNz7$#GJzN* zpPIQzh+|AGV6u_}q91edo@@eyu*zJjVewxiDR3sGCW0|@(VZ-c#6Zw}2!mP2k-jkb z>yW(6YhTHOf(FcwQ^4z$r zq4?+HEh}p({<)r~o(dPg?)S?I4*gV|CE1G8&-aT04ven%N4QwPp`Vi6Bum7Gt+IkC zSUAQz(Z!|(h}%z5z8L5Navqa`E=(-2)L0UqD4JtIx3*FZ?!{%XCK8X)?F0i|It%uc zBwYyO&HdKl!{cug5GBy<4-E+@%p;F>zW}}C$i1=r35iQ= z-fZQAUB5A>Cv73YdJQ067GTyNOedONV4xx}Q7IMuplci?x52TLJ=FfY0n@KCAc|xv z+bZX1NM7DsoRGY%w>}gse}ufQ+>u8pSuRov1gjqrco7JeKf05_NS4yfa;e*wa^+5F z1PF8GrV|HAlwjxE+pK;B;D_8riE{mzQ+83JTsy1mW~(1&AKGrTD^-h<4jBNZRPJNP z+!C2@!bG{_Bq^J4oYvvr=0=rX=Q-aXMu)b_}4|WAH}5 z0uWnQJrB-$NVu*8K0uT+oBQ_7dPq!>ojVB>4ip#l7rz-ehMe9UZw8Jb5jc0RTcwZo zK1P|X!h#@PGPlY*;4Ik)D)WYwEUdK-WazmawFVMA#2RV6RNi4{;dT;KsoKXK2(op9 zHty6*U47t>(B2Sa=$1Vp>&2ijW-8}(Sk;KP(@PQ#%$4@|%3R^B3yeQm!f0;?f&fIk ze}^Gpe4nc&>B^e+LISeB$owyVO8Nx|lKtU_$=_0`hJAJ}^;*sskMlQ54PeIYnFQsE zFmv-5)@9i3zO1Sh?RMX=suk@FizV60$G1*gFV$t(*~gKDue@Z;1c>wc9VA(c>N3D{ zC}#mk|3gr9CXST>7MvCt`-?x3*B=>mPr$MaN42d*rHZg%H($eL8D_@#fOOSY;OG7G zjeZ4OsUfFhQTZYqq8%MbQ+);RWsDbk)sDTsNV){c=u82|8D@kX8 zjGV?r<%%Nfw~}l+6t|bA34*aX*+?X)!@$nD zkpyG2PGD-Ss>ARm!zAxV^@*UAdW@^O_n>HtHd!G355et>+#dsAY}P!>W>xbZVQpqCJNV*QeU>)-Fhv9RpYUr~vRhXoeN4Xr5Dd4$MRoCcA zRM%)_O<9tzl0eq(K$c4Rc*j($y7#;ZtL2n4Q|s0Mo|wK$ZI;L6SKF>rTF762V_X<& z7Ufy(Qh})lab2UZT?hc)l*Ovt68jUCs?X^b`EKjVUO1g z)4tx16zxg}x{8;1PWG0=mx86MtPx_CJm{S<)u`-tl|xiAF4s30RS0IjE)_Lmq+3bC z;XCG`+EvsDW;@TF&d6#Od#gJMl%IJkyDD6YE8E*yJA=YNRzBy_@Ll&CRZ*jv{hvQX z9ehp*A4%0c=R)39*a$|$t0#d1G&1tPb~W%B%lkY4j1&TV<~d}k2%ke->rh=I7=g9* z18MD>K-n3`nFHc_e}}NH5rDv2J#xQZG&Y7K<75s!BhgtZYLgmGbw`A92CS9wSKQ$UugIePb62P4C9R;nMkB&$Ta z_3E4a>TitPI4)-pj@*N=dCxdOlmK0&CG*`(ja<*2e;rGO8egR8nXY_-rHZKgtk?`1 zBeBhEJeLp4p;9*4bB=x~#SpwhAR;k9z`R^o6gmXz0T`m!oSM>#vwz*S`OE0 zRjtkow=D9VvyC+XRJ1t%c9m%V-SdZ2`chn~`mR@i*|YNLgKX7Cc63smYJ%5q%?Z~1 ze|L8kf~Csp4qmBqs+#wUw782d6U_A}N=xEl%1!ZH*%YJY{Vmmq&OY8G?q*W_WzNtz zwG1Z&VU6SC^95OtDzyYICThzS5@fYEQENPQy4gwGEyJM)Ai8jFLZB_Wv4r)q#rSG9>*+~`-j731Kr~wU?5kx- zYJWmYauYAZ3gA-PyMC)DOKtD&urLspea|_#C^r%F<>6cEafj%#(UUBZT*8-HgROjd zlLLc0zzxSdv@k71^=mK|Bb#Z&-19 zVdVY9e{R*W{8N&VZ_@Q9yaFxtxa&O?>QIZj(?){CT`zK>jnm_9&2yF;A?6|MMyjf}3g*x5|-=MVc8S?;&x4n*^5?sYhOW7U6A61Gp9oD5 zwx>RElyx(F8YCBn%_e);1m|VcWUt-o>Q|YhC0MhjkIpn+P#~-AtH+DU< zcDu=5%{REanj>dr6cV<^eh@}aX+_xh`QZl?>aWe&FJaIxVm!; ze*8@!Dr;ESZ?)K~S@ePg%4ogC>sE`sCsA{tcEUkGI8^1RXz{vo8W+^|>SO;M%3Wd#&U)s?plbd(>V6fWvo|p>`EDN4_$k2Lzf9 z+Qj5#)ON3CLZ)T|;&viF;)Wh~5H zYbP0c2+Lp)k5%MPscme{GM6L}sP%+>fIxV|YL}0$E_-jn!CEQRK%i`}{@^)=gLOg- z+NCZ*sF2bQ873ux2FvfbsK*}WfL36TrqT001q1>W?p*D6LH2wT_1FW^hXgY82JG#p;htpZI*z>n3611=pZU`9TZC1y#(E&Hh#zCVY(vUhtUS@jT(OxDz|+&k$R z$^laYWBArcZMLaNFZS?91%ccEDx16uItBqdGqQyUd*sn;}9eMxl?xCEO zUO2m2>tW_v5$S5Jhr-hSYPtmFsdJ>Jg!(Bj^w^94Azky!QLAi#DB{8CmXnvut&%i- zYPN^7hh683w@+NADISxOsH;CMx=-dioT=dC7uqE$`~Bb+mG`RD)kO~zY}O=L0n4pe zc6FmI$7;#GM)6NFv?YP4ENS+q#kKQ}Q}A^4(Ze(3Nn3iwb@bdWNy)O{y3V-x1?Mas zl9VXc7kL1+3dXRtBwJ(Y=|74F>N@XgSWv#m(mPL4Fc?Ti)xjeLPr&4lTQUtb(R+cd zPsTagZCFkot2!Gq)o&7BHhnW{qQ~!SCuv&Ua-2rbae5Gr(>|*k3RvidbF(qjkM>Q% z&*0G=YNGcT-ND#vYCo4fd0*^Tgo77HmSdAp_We`pQHzgZ95TET^gKnn&?4GmPM`E6@WUK)@k4jsBh9Kt;(@@ z)BUQibwmPd7S6z?qds0j1m1x4O}eI_EuC1DkDN4sy-SAvoWGVUw-aori5j= z_mhi7#~OP=mn44xwU|>?24u&B{QP0~_7+3a*xkXuC5ejJUJnTo2dA)k)X>6it$x+- zsj?J^_9Tt!1@>+wLDS2yp%P?%1FIX3NMfjsbe&Ws7F*__|AWQXVgxqdjz5|;Xih0v zzn`S(OFL(&XI^pNKZ0$!<8#!1wz{we{vQ3clCn(|uWCCXLX4n+vYSUw(lsHy_AmCI zEytmTD5*;mAa^@U4fEb)NI%H^#!^gLIkCP7c=9l%m|W_Zhd0v>Sz2KH)S-~Ha*~oj zp5W(y*T3su`S*YS&;Mxg#^Phg>F@v2L=GZ170vkUXm@%3G-tk30-s}oF4@b4FPcl9 zg2;f$Hr@DAPO*;0{C!>2D7)y+)URs!S88 zd^kx4X{vRXeoFC~RO>F?vKE%?%2ABv?Hb~b#n?A-?D0+ z!4TH7zzORW8sR(*QG>p zx->MK@VY-oS7t+Qlc94Myuo4oEa$kahiYi`z)#B )Al+e?!d;~731cigay#!%AW zkb=cqk_-eZARben7y~7+NWh$|XFzjWOcdC7OEbYx(>P20fekew5wC3A!$^+hcRZTO z-~v_ja(=$iF9AG7F!*^Yqfk9Xc5_e^+htCz!}+A@Lxg2Z3LrExF9KSV+E5!J%E*<6 z4DXU|%V5bvcdnVoVA6xM zYJead*x40(2<5AAu1#-+sGwmHxUzH-10M0tuWVk#FgvUQDCI+o0z>hjRLY?sfQ&Ez zd7~K<2~Cte*L24!3r$ajK3@cOLUp(@YL7vYSjnzz!31^e(r@d7M$=g+L|3LVQ(?o3 zee&iTyUyw{m)~eGJAf_+2@up?#O4ie%VQN39Q+V9+a~Li;iV5p-G8B90=OXQD!97O z!WIMLsmq`bZPNhD#{<$hA&Y}Gsl(wpO9phPZ)b3FDZc~CSlLo26qn3k-;grs^=~n^ z=_p!I#jYvsZ27vCpT(`gfj|~NKB1+%pwgj%S?V_-i-W-^+72s0kKH{ln{hNpmkJWm zQqaPr*&?mbA4Wpk=&8Ad0{BaYTCcQA@gR)_JeJ8=BA%nmLQ%F@fXNUHT3Ks1>D~UO zp2xsRL!Xpn;!=VnZKPT|+()#v%YO}eTQ6rof^`P7hkhT@QVMQs_E11SRNdc5yTndp;9BZcvR#WNwCy@B0mNln|^uMg*$&8<_mgLIZ2HC~YemZ1H`FtE=F^XCo zR~{3^7xwE4sedr$wIo#ktn`V@T^<38Ei6iV7SL$yUaQ~gemUF9XZqIIEOjWFPbP=P z?zIXvl!V(?MiHLBS8Wae|xR;=ekZT0PZ6U?fX)yUdb z6bVBkxh+HL7*x+UX+DGoC4kx57uiK)rz|tHPi3lC&%j}JYHj5aC8`#y3P_Yev$0XF zu47q+dW=im?WHqrb*g?JvWG$o)e;6dbCrQpnVSPL+V~>DV8gUIp$}`R`YE{+K&bU# zOQKZ=y;`e&Yui)x&3;KJV9!y={G)(S6%D>h@cYS>xvps;@4qx_o zZI6?bcBsq9V9JzC?ufR1U?9{-AEfxF?z0Lt2;MTa1SXnZ<#kqNwCS6)r5ofR15ov0 z!-{IMXL%mdq@z9#QH6cp4J9K;wD%obdOprlmek`U6?lI9lGZhz<3p5HLc4jLCe(ah zB)nJE>V=G8YNLXnUwpUCU|)LWQn8R^k6jL5IdvnY-N)B4xF9dAuM8V1ECY`l zR7v#b>$GGXX$?@ye|g>Dk^&0C?JdZAbc-e9$j)M@B|ypexaE*yGcrh`dlQ?xcM&Q! z{BfOS$vCq7C`c?_nbI8<5-0{o*2@R!x*P4a)aOG@O2)#9rVP#zQhrqBbBaqLNGpJLksgB%23L~#hubGo$4QEj|nO^Py~ zCk@#^Mz(lmpIlF*JZaEzNYbjw4&Tcnm@~feJg$-{G{vMjZAGe3cc>i`S+ta)+9AwkW1NTIwl5B+-m(oZMBZ@e zE0z!8N-*upLtPT;EF&YOK(H5*M{Sx+W?D^~8bBxnkzQj`XfLC~jGGm8@1?s;D-5>asKMY>$L8kZ@v} zCkDF97NxVPF+leQiN3IDK<(sohd_B6s+T8?52P^_vYt0OWGtCkm$cQ`JP+0(dFeG{<3c9j3QTbG@miJH2HZ&n|a6y=7GIK&Y>P zoMWh7!hc2!GkfrxEQ+aGGaMvcuWvRHo55M!RI{WM7L3P33>mjxggVPicBy({hZ`CR(uc~$~6$m3)AA*OUZ9KzibD|C(cBDAbM&RYELp2q~!o1QNtXmWWU zLk06i^4IgMEe-QA6Sk}*uVZLiyI9N(v=T<;8?&+&$TcS;(4{KOl zp02d)NX*p!Y(B*P!=1oyL4u;4p0psH1p>0}@XsIiOR`u~p*ryrwe#rSIfVt-+8FD_ z%G@asnnO_4Kp#5WjuaMNkPnYl`LMX7=9ypVqQ!tdQ9lYQ+;YI6WN6uyqg)R?3-PlP(>eLpboW9F<(OJrR` zYz|iTYeDTptafc>ae+RSnn7pvHB4xDTA-Y zTZ@N%pEUq7J`hCWve{CP8kE#*7+$hXXuO(PqaTDmpqa(ZJDb^tQsbpXv6-#)0)6*W zHWum^Bahi#T8YZ(qO>MWBIABr!Epr9HUkEJs)BKbYReBavYH+%cw+q+%OB*F52mTH z7{9(Z`X$)hLQKc-p)#nn)htvFLUYKNZg|Ru)_0P~AZQ7@et|O>UK9?ajzijRR`0non3drmo}njw*~(*OC8? z)mMkM)LKE7Qi2h&7S({(w2>8xL8$GV1a*{ot*LKop1Qp@W8pLlVB+_t)q2X3I{etE zEsM{`byR?!n=UP1OIgy7P1llDuc;uf08J#13#&aex2S%B(mWm~g)~zfBJB`n{`T6; zEhRPG`%zf=y=V1C7gm1nS-oLi+ZK|u^$o=!J~qs#!eKMVD0&LZ*(_!N5Z>)7FcW2usV?4!3>&zz^eYHuDn0$%gv!sz z&ONBHOy!5W^DvpV7I_oM7Pq!Sa9)IRQ2CN2=g?lM>;4o!!UE4Owjf0iHvOS!mYzq@ z@JOv_m~30*yhjepPlQEiKL?Y3kx9<$5KQ`bbm@MBPO!z}L=pE@+O97UL& z*suJ=QD$)|pVmSJu^pKJwhgFm7MElOpb~iPGzV`B#_NbC80%|i?1+D8&}@bzVVfa0 zJ+DanR^<=YBmWFRU9JucfMcuLxC=l@XZeM#5m0&1N>yT*Kqyw#gckU$4y+C_6Trq= zDUkI;3Tk9=g=GMX39A{%8sXyZECZmOC`|GVx7++0e*Umu5-62*xp+MQ3?@uD=W2t} z^3Xq#zpb$bf&Qs{=w*WYiF8o_K=VU3ue|94c6&T1Jun6eFB*>g0#SI;@?1pedxaNm z+e<*Ge&VibGoku41-)n$*4+Q&G3c+`45s zn?dl!U)hui?GC7XUKx)7LIvhZWe$Wg5pI*EHyHl$EVKy1h@(@<5(FzHMnX}Xx>)Ha{TG^$!R`T4_sNf3zyBE<(iKcMn4M>?hnOf?`1 z(gGQaC;7KJE#7sf+Xvl6puzC<>@dNE;8j`@s4!2WeIS3Edsq;to6qY^s+;`rlE**> zKHsW@AoIiZ9kX3h<9DoRIgrJ%ur&m2R3H_3NDmW;MSlF;7lA08Z{->SgMQUzRM2HO z!2n6`l9YpqGvkXudj?Tb$fznMz@?`dG%i=eni&Y>q7wIu$>ww3q)^=i@md6{|55~^ zqMt!vFkwjm>L+MKQ~03wF_oc5Ad0C~D&l=+@o57nHXlSZ37x;E06JYrtddW(`8&!d0&zG#K7#yso=d=XfSyKokzqVSF zKx@-<*L4;(PF4+|MTAX+pmAPlrXDpz$FhRi&mZQeSRMxK^8p_8a&7cBHYqm!s!=YAA^_9nx@`kqZqMG_cWCy|Xn z?v+WC+oU__e`qO$^*_q%EG2P0ue=?)yKPhgnNHdC+S3$Ot(+@f2O(Y#-MtBa>twSG zRzd2I5MYqzpkO5!uv4TnqpX*8hl~}M`26`spRcVeSWt>N-&j|qH4o934C}x1sglSg z)3kL_P|t^A5oTdeGLM~mSYy->uFZN&{syH``g^*U?FYVsm|>N?8M z0in(2L8csf_f%$_lX7qLUAcoNOBLvgfZ@L=g~$3HKUl%DgDmY#Tj;uJdnw zDXnCn6$o|Hl7UtrG?_fkp=Mg94TOWem-KDs`~U6=F{@R-0=ssWWy_;yZ2K z>fGEPdG5m-=qFK`vg)={_`8KN_r0vDSrSwEH6y1=&GCmcv!^=Q^JaPy+CHj-fCsGg zwY)*k;tn)k4jSO~(9%!F9Iuz6mQHt>i!n1Yy5=5ZD(QxA+jlZ;3#qx~nHd`WBuh!& z{7dzVp8uY5?TjIe^p~#T{SF-y^;|=1^_`s$LRZfDcPbzL%kj|AgQd|-wU@sOfq*b< z=tXD%yPtJkj$5z(i)qy7F<^r)nu^|pEG3IQ24OiC8so$g3n0_8C|mb_vtJT@966De zBfL&Ul)>Ieg~WT|rD`+G$k$AQS$-X*n3WhBr=2 z-476FuMmx~T*qSDg))}zLFL*E6v=*hGYFeJ1KF>fBe2O|3eT655rnZu(0)B5La|0I zyYhl;1ARox;a)Af27@rxsMY+ymjj_&#<7o3gCW)x(*zHtJwDEYQNHLpUNFM~??n{& zpJm`cT&7MnK1OIK0wM>>2!}$m^-wpVyhHI9iJYj`7{hMb5srnv2Q%cxWbGvFGQ;u? zVN-g`p=zA0zOr;om(Es4%8FoOE@r4?ZCKpZY??j7q0pzs3`p~*XDu_7x&8R`V1W;P z;o5Qk{9&I@FVr%k+N+Mg8ERBZelf7g4;QP^S{f?P$ZRyf9fyS>3ufmr%9hLg!T~dV zk zvKDswrW7^5ci8E>c5uq_9=lkJ%qmR7=2s9)FO*kgYG{_|9kARNrM6jPMezNl)Hd(f zwtQG`LhntvY_}fU!O@Rn+DUDsKNCReT}fl)w(NWn#ucFgnil)5dSiGhDMqkVbYsY*Y8*e?l3uU5N}LBf(-dxLptHNLeY5Gj0VSD&=%Ykklwo0sZdA3+F^ z)$5f10Ww_+P+nsY4qu%fi+QR14TW4?CYu*t}%k&~j?P&^m}P4j>3; zyKOik+spJ8Pzoi84CK>!jI5P4r%8DISGwE0lqW-pFq;WYS!{+~Oqi~E#2N_GRZk7l zi4IILUdJrvtG)nr^T&@XHuQPRVQn#M-hwR4YI!`S8<9~dSj&V7t2G-zf=FY`f2WtU zx@7r8`=yXjk@;XMqw+B$%4MDL%$i~!Hzh_AZlY>>bwH*!7k=elM!1jB)PjZI^?$TM z2chG%q$M1Lj#F4g^d8V}X}ic#2@`G}N(NVg&~wTicrlU9YFJ{-(rvTq4$=hSexhXK ztDisYmxOzal9i+eALBDbB69tN~vUD*GWoFc@jvB*zGmoKNv1T8SSuH!+Ua6VT?29di$+ixExj)3L+ZucB1%Cdp z&xeN1*!436L=fvb@daIw!4bhXX)oY0LITAQXZu9;jogjJz;VYfd)p zW?Ac8%UM%c5Qq{6L1?0a$(m~YY_4QiarRn7)UtH?dE8&TkQCWSpZk_0Qb%jT~0#;(S{+r*@0+tFqPFZ zn}XW!LZBc+b5JfQfHY8PM?0H?z3{nfel2prTld+v70wJV1hJJ@#svTd z$3gL5+k|ou>ZO#Lepx?H0~AQ==T-<{p|^hSp@M}zq(%E9=?<2@m-ep8C#rK?O_*zX zh3%%Zvxg_wZH)}g@gmhXsFVqoc$TW@ZVc_3RwqGJx8ZpVHI^$kK_FQQ#qWzPLcF$5 ztDIl#mqfK3&dTlJpoc($oqlL_S0K@J7Y@obef?efIzxc;wRJhWRn@tfG|R^v9tV7t zk~(L%IK0<)8tMlJOdbgk2JEp^$TBgIAc3i#r5l=)9%m2RgPT<(=k0QLr*93m`sv+@ zKJ@Mouv?et7KYXhL>L|i2OW1kbEv)|3o=WO8Wx7PC_$Ln<=PS@kJ&E!sQvmxVWqIO zTpz_yYzW;fTJlF0Ny&ygb7YZ}EK3MNozr=DA}Zc+fz|O)mXC-5wW)IX@>`ril^cb=CDL$QQ>AHyYX;R8_4WW6?dq6%mYkSemu+9 zm@c!iJS)bu8F}S!4iyW?%Ki9T_R8}$3~5HJf2|dG#N+soepk;YKeX# znMwd6>sOXSpD^^h(6!#=v~#<52cUvXZ#mQ-Z?eB$d1@>${@dtm{b{x|GkcQ3_FrUw z@|JTdfSR*cOU>-IeqByy1d(@pD}E0keWk;9<9cBwT-^?YmddhHE;&6+<|hJ|Mp2n` z0ax&|2%pL!eCUx=b=+y>s0Q+uX2)?5nYpqZ$z-06HYoo1rybj+re-=0Fk>iOSpo_U3#Uav@QqKZD;GvZ`Lf@^r1jss61~FZswP)=20aLkhcF!Yeq68QO5+>|ot;;6Vfvpx?3aXj zrU=f{%y5QEyBxMXm)+7=^`I|pE*b8)l2Biv>4o1X?Dj+9d)`|u*Z#WFd=5h0@=Bxo zbWRPAF|o9}(hLux$i?D%i6ArxKYl%=usn{jyhAvlH00$nCg`-$l2Ez4GK76DR|LDN ztiJ$sc3w@c!%5q{;vc=04>h-DXpUxKFpG;trL>(1O8~||IlsFr{m>v;X3CN*RMmhT zDXt{bn@UfoD6Y!29pN+ME(s>PB#4yDk_sqn_m0GoHGhWEzwvQhzC%g7TTKjQDczPy z5NRgEj)Mu)ebEllOJ}$w*e%4vbxcY&WuD=ZV63TZAUns-Wf8V}7aR6M6e?=?P@-X{ zAN{#Sgr&aA<7urmT*stl9>a`v9H-u4$2y)ja>^o+Q?ZB?%`I+01UB{fcQ}#v9o}IEU@+;Z(`?s4bb7i|75P3AS z(aJ<8q^P; zZMi$?7vPp`U1|{eCgUZHK@=<3on5vrSMY)~K7@|XBYQz8qp*A6g0WywcM)YNDj?O% zjN~(j^oeTK1w_GDH*pb?QoN-GVYu4a6M-mLE+zK5Ed5Y$Wf>^a=gKDcU+9-WQTw?? z15woe*4$ZFioR?{4Isr<^vhy5>WZ$%#9VDanWjJ0}xKL=eJ_MmUcy)JD0FmtL4&Vl%K8T8neu_=U=hbY~ z0ifsea{E;P$-e3jbQSxpG4?vfA)=JB8Y_qDe;aDcr2r+{- zFN$k;A^4vXeZesO%*y~!#z20cAT&c=mq)m?lQ5tK1cZ*yqdTl(xAm1xy+EX=+|St+ z#)cV9p|$8rm98ZX2!yil>MlsNirOCC2_GPI1zoPByzJ(qX`?I?nxU@j0iqm+ zza(;mo)x9Id>7uV--K(KU}f6XWZ9LWz>bBL*S=7FGFA1W@9OR#vWm?dPUs9(mIZ%A z>>r{9So^u137f|XrcHw9(_ zu-d}uak6R#dtJFg*M2OBnj_VPOpb8^B;)HOzCiByI)Y)3=edfDc|Cq;I1KLcZf;R6 zc_?Dbfg8_9avc-f_g7uk@9x*IY&<+~>K2kx92b=o4TvUURd_y2%zFUBrl&L+fiP9H zxRuX>MzSRUWyu7QEByO(srg(&&qSO{v&An7mjJZsl~p1;~VESTi0 z>~sj(+~I&o|dBS+8sn zu;fp;&6ohx?T(Xb!API$$RWyp%k~@~lA}+ejDd8KEqDJ^LE$jzx#RI;xZu~>11;Ag zRR_RnLW9(m>M=+P((4=}K{~9cE!gQ*)z=fdEvHxv??pi}#X?&4YOZN=ug%RhOP}ACuXzcxe0g1_+QpfDT|wx+c@d3GMp!L33w|EsqF*nvZMcxRZNcEq`P6K00~yvc zZW6L&3$hzOAgW!Td95HycH8-_kIS{|@9PxTuFu>+kgQ$rHDeTKE8aw9Oqheo;As#gk{-=$ zR40-iMT}+N;`uI6z+uVIqdhf9W|B5vr}=&9uP&9aIb;EVq7r(pFVT-JP22l5SRnlI z$qb9iD}#eTq!P}Y*~772SgRzmPzMqO#)Fd`+A0DyO@2} zAXu=x+X3Z)ny&g)vJE*%q)&=-3zqkxFom9=+a)D)&Ceh9OTvI5hQ9EAX0?vmb85pH zPhFwsS}vF?zObFvt(7ZOSnLk*OskSV2_NzS=#%R<&m|1Fb=% zo|ZJDARgb&T?_f;N+#v9TMI<`X*R6~aoFpXM{IA&47w9YGd&YT+D$h70FidH?de-f zL(N4++URmH*A=cy4Wa~6x1ay{MxU>5&684URd2a8*uCs67Rum$)$dO^QPlJ_;%iwy zoH=h-3e=$=2aug5>l3V%FJ1t5K>ri=^6OJ7-O`9EUd`KElm|h0U~wiN*h5a3FXe&2WeM%O65@Xle-oG2vpU(Ucib@Rh7B++BHO{ zm4zA9S{Y#E7qFm#jlVk`-?uYdmf=YtQbDZjhhn_gPTtp%xP23-svrtd08yoen=Dsq z$XZw+Z7RRq+qYP%)G!?V0H8_@*}{88xKhJNMIpkvPxlrt!m3XONUYc{)X;5*2T@Um zo?j>I`BlfrmJ0&y1eHqkf&BbopKotpF4WMdxcxtpVW72j%YX)={ED@UD>XRq0|0gw z6r$0Gwu|dDWO>}Rt7}ALts)Q~qJsYbP$5{(CV{FnR69{W*Mgvb9MN2(Ap`G0U}Ry* z7R|rit+$r*MBRF8c4!2V-kQC+K=#me6ppjDcK2_hA`K;1oIPBm;XY=%NW*>Q>A}0t zny$%kljWKW*-s2)Or2%fJwdF60ThAZXk4%cM3&kEOMxN^t7w<|C_i7GJM*U9Q8 zmt}ces`+*QItaEq_jTgBTm>P2J+9&!4B2oNr1f}Rxwr3zE(g@L}K><$sIQMmdNrz*aA-Esg0(LBp_Q&LtAd&EITR!2I=gmeU1BcsUqOMAMe zD4YUA&Ubz0Aj^Ihg)T->sS_IArvWw6qp^USc4%n@ zSs8&yIT&Relbam&Q5+BbBGaZj85clgY6)vTQB>-L{iQ}RaoC~?7XYMMSbc-brk3sC z!YB>_Ls*Mn>9WylD~>FRBab&zXhgB+{B9rf*FQq%DaVg}Z}DZ^@1G5fk&Leh~J-b`sWY(C6RE<4)Y+=Tik^$nqr}AWCjBWOG(AHuMdRkSgQr-nARC>({I zjD{F?{nFouup-+Nz(U4zblEP2>rHT5Ak)`X;Pdksg@QegQQ-5NP@#-06d2t_zGB!? z20|6{ah8jGMYgj9!Sg-OlIVM$B~#LqNYa7$JBM9=?AQIsiSxYjkXH8~lNONYl@&wr zd>e8z;Wb-d>#E@P81$}&tehCj0Fn+s#!nDvC7h<0Y$D(6^R=OKR){E$3Iq!vKNFfN zKv$g&!v z&;SGN`O-=~RNv&@z=5o_o*MRm=Td9h@ZT&g>d-Bb>FwrCHW#Osn#z!!g*#iluA!P< z+!5=^hiZDUv96C%Q7e0@t%X^!2Ou+4e9rQEs3jy9d|gJ<=ml8W6dQldlp$fr zp2PY^hoZx7b3wRy%KMn5`gAIS6GQ6_>(lLO!YZZ?EfX1%YV({VSvVbz7$ZDVXIn8; z{DejAw!w<>I%KN~tdqw@(g0)02gAP0AKqkh2b%SXVqT|rvGtUBd8nQwiiI^}PXdI{uXi8v^NoH9#+33POKeQ#ij(NWnhL1CYh{A; zreBY9%<`43c+RYpndLn}nkxk=Edyk1T}Re25LsX%RsK1Sz3e84*5z+$uRRq$eOI&u zX@0JoNOyUjm2WKXXPrW(`4kqJ+g*78B5R)t#3^i=*Nsz0bmt*+zaKnoojQleL&)oD z(LuutS3}L`&a#+C^@9<=TRoIc2_wEej!K&V@r7lWi&ahuQ}2&faT(EVTQ-RH^v|=x z`{*RqT4v;Dv#Pbs=P^<(19(VKJ^5zS3KZ1``@d377d zwiCi*4J(;hqz^<&=94f838rC5%Qfs)y;6OJ#XibIZC}|;IZyie!+uHV|GDiB%hA-2 zOUHjUOy5AR)GKB6%I?Wmex56w0)8pT{-ao`Q}X3VQUEzp?{gdzeP1^&x0=qYge#id zCxt7TJP+BrIjd_?Z18vz7FoE@ai_<}Wvkpe_x(maDn(^Dk5mjNg>6qjF%+ zv!;#9+3f}-%K+cUoHD?^4$2bh3$Om0yMvttAwlN#tgH+Y-ZfhKqjjxUpgbnL)MbTV zkSqdh(G>es0k-&x?O%T$!|lO~$f$Wl($8bI^*8OO_HY&F?%b77`QN*AaM;>2n3 z+$L?-&##YTe*Umuk{PcX8s073WO}=B*+mMX{lfDYc0zdE^z!cDCgBzL^7;y*&A@$~ z_|F%$)ya{#x$92@P>Uj)XR`J5uG@$nXB5Bx^sNU6*kA}@{ zatxczAnls6#_Xybpyy@OvFdS>8dlMSI=TrxOL$4n&;`u6*I`I$m7JC!x23o+ns4F-eI1vvK1+#=jRXmB^kE8Nbv%Zg1H=PxZALjmo`igDS6qu z7i6W~pbwM1wb?9wW%Fzi6k7r^z3rBp21IEHxs%*&xpRRX7yvzkqWsFzeO;ZwwwrrE zUYSb>(wy$@%Y^$DbgTa$%0lQlpPE{AFs4j`rEUAp=XvwnKb}?AHjMaFo?f}iL7Gd# zD6jxT&hxZ7fo$he$%MIk`OozM6!8QwToFblU=W2=Ua9AGH?@NF)hgMmTNh-j91sva97(JB-LuzKw)q56P-S=g?e4?b zn8W4yKorn9Y}Nr`UP4LtCdhX3j=t>fCXi*?tOG*#dCAtBAnGQNzMS2cI~Sa_w7Ur; z{niEw=v+3$?!KHm8#aP%nDAX*Nls;uQP<;`pFiyL0m6vyLVkIreVQ34t_>uc8JG+= z<|yHyQ;_O>GwU3qWLts<$=Yfv_P5<0?eXiQp56p?hp3PiA7$u2uH*x!_l6_D?RI4;2G(l8tqigF0pkf={$+CM4SFP&y$%3d< zX|pX6g#Pl<9Fn%j^p7{YG(fr&5#{y(Vb(#Z-nN6d-jdc8*yxuN9#=ORuFB^XVz_%1 zlC-1-z)0U+Ld35F6DW zh_aTmIW&kWb}VM;?OB|Ox?C#Q^ zQ}IeS+n#Q!cwH$WXZDlYN|xO2K233`0iM}UD$8?#$P$rmKoEMlA!uhe$$nD4aJG}m zGG!n#MXdiu9=I&&56WOb>_7TXs){96bQkdsncOxn7DnMkc>bA>)$l5q;AKgoN)bzRO z<3;o7jKQl0OK(cqTzh3Bsr%h!BgUCZ0c_@eot9r~*jANQefLu77AjGaxodiu&emj2 zTdQ0cW21@mwB26|BzijzX-xUbmvReW&JoB4QP;U{Hi)_$a{&@IZ710dx;vi&Z04@5 zqvVI5KkS!80sb!bvm<*(Ro58=QO~HyA*`nXeN7J$mjnFM?zO`$qh3UDcrGWfqdJ`b z0TlPv93}`NCC}v_0i@%#RPCcVli(cEPBgzisAz7_>AaB7{_#JzX7mag-Ld@5p-mvN z*FQ-HC@S1~J$E)Va{Ch~+GcOsxdT zJX33mu^hzJb4?G|%sLeacDNZ7jA;IQjn^se1oa}yTI{*3g*!oA-HoI{lw@%T%plG( zm2ng#vrIiD_I0vM{Rq39EK`|FK~zek%h?Su=ksO3NZQAXxDV8Qj@v*z0ZW9Q@)w&? zS^GJ3yPc#{F9O@Gpsu^Y={Nf&QN4yUjcKg@0>73IikwnbAR1gI$X4?o51uSMQ?~M+60+#$+0`X1MjPpJztW(^_xE<7sWW_IU z+xB*FWJ!6l-4N<^Ot=NB_STc(%pX$zb8(Uf8MR8@@e8seBQKnM)*-Xc}wx zQ54^sCF*|O;Fo{?S1nzJFA*BH$3;V~(g(3$IWJ7o_0-Z{Nmh9gSkEmRB9hn`krNB? z?B$#6_eqGj5*aN?3X9lD)?=;v0OXQAmP3*@9!n<4?2qM-#5D<|L3~L2&y@@wWIU6e zNkR#Do;Iax)cwdgUM^V0%bR@W$?JC5dFK0&8Q;gaaKcuFqLa0RB(f2mDj6>sr)@QFqLaSJ$GtXp6Kh4@Yc~wI85d1eb&%ejI*A=R<2JX zEDB&N@86_7wHlK7hd4_`8{iN5XkGk3r)Ms#*mz_D1xQc=7 zrX<^?welr9OVwpL2{OI(fN*bFAJUFcltGWAKQF>YP&{Ji5k&)4Y*`^`?~4@u@{71s zL${!Uv0P%adu>H~tMyG*HuM%~5=@Unurnl)4Tog5uaoxIA&90D@$7Hi6*9t-wpk`- zAFK~SG}Zeu*lF^Z<%P5jjZ+pOBiZwPWqj~Drqm?EAy3m^-V6N-gsc*(WAPyfruuhR zGb8EWhd3b2bFD4uGnaD#K7@j?I)K1r=&Z14Y6yD#cUSrNkgZhB$1$);{k!Xaka%;O z1cq{LfVbZl4CUpUWOU~4Nn*c`DgTvtA5;EwcX3(DNR|vK>WKUyh+LK-W$h%6Rn0{Z zmU89a8hMNbVP}8`{Uu&ZVJYwLvp%Ac7K4;Ly~_YI&$5ITusTK?QRp*Kv$hcPJT2Q-I5PJCubC%r-!%F+E_B zw;URXi~uKj#e{zdiY1bid@O{6eG{kb=I7V92BO%#^ciS`y~&^74jJ;ykNjKibmaqn z0AwXYL#zd&<7>zZUbnx!H~STt@d(BL5V?6(ssw-jSLZje`c0NRv?<}7WRjmW4Ca+&-o&XX-Qoilb7iJjdW^w=i(%&lNmu$q&Z7bEj8ZM~ z!jl7c5-UjBAL8VT+-|^Nt`rw*{DZz_fZ=s&&~o`jqP$Lu|MYj{5eTOGCQi~xaXerI z*F#lbhD9r1?`CVD=GiI2U~U(w)SBQFMtlkandnn*m8^E%F1Tk&hn zb7Ha$-R-<48D1sUAt9o|xF0gK&JG(ENt#xz<@IMekSd)3KY!S-$QGHNw{!kyf3_0A zNyd11uSw#Wlkg#n!$*sG0#}=m7nQ_CE4=!_T5ri@6$aLNiL>*!Ewk2OXK?WLc0%%p zY>nQFxQ3M{Eo}7;UG~(1tzL@JRC09TPR zTIKlsfcl?}yQ$m3Rxef5Gji4cT%fJSA+}FiPAnCzyxRGsV6AW8#Dz^2Z1f>rzug^5 zMAH8dn^be#y!wB(xhZezL&kq;x?6|1q+CAtNFzy_O<=C~*4lGqO=+Vqvc8^trJbaC z#aZjWG`aaBTI)YoeR+`WIxsopkwcXm8<_A3>V1fm&+`KJ|8MNwb#z&hEIqxRA~{mG z&^Zx)cMwzv5Cc$~*`*Pr!r=@+R0`z#3yfuJEsKahPc?Xyv;QwWZhkX!b91wAZCo`C z#ko@*J-dn2(L>71gky5_$m((TLKt@I_?G*J-wy_S4j?PKFyPm(JW+H3cqM<`rU%EFat>8amDP| zoqtwm=$0?d3g;HtENcHv*Q|6Dya-*A-=y}3dts2#USd6byB7n@u!ci+eTvaNP&XI3q#~&6;3WA z>?2Lsm z)frl$KotK)3J%ET&a`Y-C+!G~y|hjGGx|%Ar7%xj_X$DzLAVu7e~$oTeG=(AjNfpP zYJKNH`gqQ>XNbNp?&Rw}?c2veMloqRB*~AApwhE!>H*QILqB{t{+B@r($_VU&t4J@=b->xPoNEU`psShUbbKN!J!~L>U2oj zy~q!L>p4?RuJ69M|#Cy`x+VLyU|J?`MIldWdo z$RLd>r|f_r^IfETD@0q~v`9^TfbrBp0pym+)6^HK4va5zz!`a7X(-Zof+y8@mub{~ zQr`fPYl3!nKt_Gvr%_RTkp5lH_f_5TYHu+2`%#11;^TEj+TL!mKkhTBnI8V7<8%2c z)0VERnw3_zx=nOo?NP?QKd$2KV~u&$rdIkQ>)kL2tUh1;3MsP3V~qhIuOe*;g6#Sx zg?5o;s|*N73O$+vtk=*%dRGonS!qD(df%neIJV>u`sWw>A=w0pT?c0R`AIg<+|lLm zBImav5NKh3Mheug$HE+BQA~ApLD=c*yG#j{<6Xv{S4D5gOQa>A$N;-PNvHePk{qk` z+o2dFGHd&m)7OyntBozyztv5uB1t|jk{Gk|e2`k+5ASTK*HxQeaQbz|w+|mK106Pe zkh$JfGpTe8`9cM$l-IJ9gADdIItm5Z^U;t0{9+hbu+(#4X{7?|?ItHc?K2i~M5sY(hZY0>HR^}1+(+_!|@k>t-W z_CwM?Ze60~=z9^Mek)CfCy!pgl~d1i1?>0)Jui|UxmL_)r`K0#ea%FftsZ66a@*h4 z-Evm{VaoqS)O4}}oPA`|N$kLse|{3ypyx8=gH?QLNzP8UuSigwq|H}nyU0|Wd1+yN zeJjz{gVg@&w4FQNC(qW1?D{5~PAc0=Zx98x)=n45dI8w-735G-a2#|mvR)HpFfyXH z;y^ZIE_$4e^V=~O^~ytzVAEy@5C!X_eh{kJ|e78e6& z>M=0s%iqACx*R@3w&N2v{rX9o4h*Zm-TWl0dZibW)PdL)4w*gSh>obu;+)GvzLE2?Luq7Ozw9- zK>MaT<>7+NveM-wx@M#OBYkc_HV*-4fX_~q=TW3nV{IvpVaun*hCzofGQO$YmHgex zXNk!o)t@xEj&9jqVaewg99cwRzibGalMCsds>@uoeGHvP4WgLfn)m0T#@cg$!IIB7 z9ES$;+%$fS?DMeXlUU(_*`5X*D?G5<>maA@vlxeR=A)2UR_i0BJ^W-CaqCP^3GO+A zRCcSa&bZER1xnHW7|7<+GzwOR-f}Ik!hM95n&v9s3MFNO(yHG&SZdvKRhmIwM3J|O zZqvM5C$l3+dHH{UX!PtXvgAhMXLmc6SfR%T^mvoO*4jDw!MNT&%h-vvqE7xAI z-7CbHMk;Lg{Hh_ayeNMVFUo!6WwTh;#j;&2%WN;ey-t9+zI~FV11!>EBY+0`g=U6* z_W54qfGT8-5qyV zI~e(*%B9~r4Ulql|wGm4*eWNv8a<2F8X$a84=MbYweMNjQL5Vjuu~4zsoPu%bkiPz-lkh zs7>VdO*!N;y%nb{$ly0%JipZYU(X0)xLcNqx zrd8>a%k%79<&f8O_nrjEP!74aOzbP`r!V=+G9_hzJeROcru_Je+LL*X6+K8q&ay>| zxHtMC7>Zo)S4QN@uZJUPVcK7w7}+Kq_Szf*kab12oO05ijF~LsXO+&jx5?N~*#NS& zJwoe7IVC5j7mFbMnfoM&oLb~~Q_kv59w~0+l$`87zW}1J5z>^)DM8uoBL%{XieIo% z&uO-`gUB++lSLPipmh58AdQ=AvJQYuZp&|f=%971XsH9Bs8w3DfDFZ`$|C!Gf%%=$ zYnzFp;4+9wkX7Dg7PSiJ#0=tCBL3~TP3nDTgsO}vI$hVudu&^O0qNtjjAG_!nNvzQ zS%bLi7kQ5@t5YBfTO)O1Y8s(vfmhs=E-3YE0fc%^9(cF zsVtYJAdWIOv&^9KJzAF8)U3D3Nax)%2~{EgdPSDMh@8i~djZg1`+*?d|8cFSpLM>< zNqf-yIVbd3P*-75G6(RM1}1FY780=NKmUZU23OVzLh&eN-T(Soy*k}M9E(*IjdaA z((M{V))hw63*smS?2*_npvs_1uW}$;_Q?d9Bo>R6nu+XJ*H4>umOrUemMyytfGAOR z)7vuZF|16rnJ9JkgGld~e)6P#xV2ycsLGqMvWQe3bv|qhJZ|#m6Jf|uwmM<9(|kH@xyOde>`0-#`@ zfW*oI_6ev`QCT_{R> z?Jbu^|1l81%l=ku4A<56;#~W`r61|VE9I&m-naE+-VeuAx0J$O0o5dn^?rW8_C*04 z&s~a2r~BBw)mN}D@O4KX{qu=_2>PQ;0EMXVnCkM(Zgw#QkyFxaNrp5jO{NM5ocRutZqJ^sd%8X6eU@YGS|#hto(oo1`ubK*LJ6V1?L9j* z7`p^j?%{zZUxcyi^lYzSbCD`EgCI2Wp+Q$To=OZ&Q+kB4`z3V`q?H*Q6v*9$kg_r zAJrY}C%;OL%`1ifpks6HI|3}uf!Z*-)HgQG%r_ofWerpF?-y&#*rxUOEgG`AeTFs>`HvSh_rvg{wOscp-?7g)&jDiui4BtO{?$y9&L8_C!& zt5}(bjs3ECfynzu#w(DeC7|k)CijT7qGo}~T`o>i_@{lcEX-!{5b{EM7J48oZyAHg ztf&z^i%+?E{Lae5RVyoFR-bZnmzdS3-15fF9z#-2VR)CDoP^G#S96?XSSIozvLt}z z{o{>0&sO>`R;Z^1w5)BG$mzZE~nq+K5RgHzv<5+1QozZh6dEwk*8@*p}KzHcIj6i+X)l>cJP0s@`S?l~OR zrm~j-3gV=Jvc{{a!X820Q#BKTOh3us9B&mdA|q3W<&C#uOFltYcsEsGoR$c(OmrIP zMXJKYX+8|~f_l0PE4zLx;d7R$&hPvnPID-YdN=lonQB?YaF07%a|_jqM15;_K5N;U zAKP;zHo-+~GT!;fs}v9~?=vW^9%aV2_vyF6jl~ zIz5Xx{)R7Vseaz1(qn?dF^2s30LsFs=`O~%;)BrC7@89Yz7*8>n))s?XsH-J9ZKg8 zUUdwU`Spl-!j|UpvFW18rg8)p+DkYM9ouA$_iYw6!fwGw1@isul}+XM+rOG>J64L8 zp`p*J@yaq;d}a3j*g)aKWf%*!c)hCYJls@T&C=uO^{8+l`+9^*2`8!cS!UNaDc|M! z5r2NM9}=0lE5O6OA+N#~@N_ zX8mj?AFX%N-7Dgx=+T3_Yh5wBgJ{o2>v)il)`RW+4JI9kh5~^FaqA_R^VQ;uR<5pC zxT0cR8P5fb=xmMdU^Mg?f66fOjz1KL3=l4k*w?yyi`Q-ha|yjIjPh*k7^JH zAX5F6Oe9PpTuWiYbPE-bre?UyDC&();8tk_`7YHFZt}_U;%b(QwKP7cY4r`z2;|vN zOZOICzDu{pB0md|q1bM;)@muE-T08o3CQA}jA*U@nht+}<^T`OIln@t)3 z3Zyl*!DI)M0jgGs!8G%ONWqlu12Pl`DvNB%R}IG6t*~fq3L>pR#}+`OVanE8>#&BI zH6c0ZFvCF2gzc4+XZ;wup#$9#!7l6$1CYzEd z?NK0=A8tuhw-rvUu0S@GZ41wKSmAV;c6`5Y+zu<8+9s*(q|~|Vrk!aplZb1ln~I&{ z&oA~vqV}u0b)k9W377=kzm_InNha9MDK<~POHB>tE@L^QK7l;2?0(YjT1yS)CRSl; zHBsDB?TyyfsYNtf!a$nVXh)Wj-8{?C=lNM?I8?x+%xIrw_A7KjZ8Kv9sJAsn`EsDw z016;mbeH9zhVq32sV~1)5IF-qh@62G^QN}#&!c5YzEQxiq3O`OfT73eO-Ys zS57ZofiE3>17MubgAX7Ku`au2?R0lWrlOXl(dXWh5@vIH?yDE~(4|9nR4?xIc19W3 z4ZWRFM)O#ww{zb3&o72i*XhcI6PjuVM#FqQe&~I)Q&-_({|PEHH)xvyWHPx!me}+C zdU13p6l-5YPiNGYuUgthloaUOdz$WhJ>9tET~}?>&yYrS$c-x((jZlFDd@3`OKq*MgN_flS#dqk3P= ziuq9N%M7*$vN(d|k5FOd|DwHW8&vM+%ccb~)+flJsd z!pg5ikljG1ygX09%CC(bzn~1SZWhYWBbPK|I>3!}@G%|Xh5?Q*vK-+i%Pd+Xw~umy zC@*A^Z68{z(_?cRY}?oaGH8Le;tQj`99z|IW*)NkZulGh5IE(nzH1)#Irg1l=BLe6 z8;KxF@i-GG#iOT}d44NHv3A4jOh+ychnbFCk1}%Pk|r>#w>58|v-%o|v(mj}D5J_n zKBue=WvP0xxC4s%_$I_1J?mi5S;_J;bd;_ z2FcR`q|Z;{Xqme6IvgFz)xIQ1OOC`vL0WCVtt$noI}U9B3Tq?{2e$t&dgJ)_qNr87 ztYU>nrbduPHOWGK6)LOu+HpyYcE^DLsazO(NxG`dYo6v|-7sOaZv2*BMsy)}*#NbAnvcZb|v9W!tFM0}%-311v2fT%Xz;Pha~Q5ni-@Nitg_ri_7V&g2?c{vWT3x zvVflKh51ewE?cv(4a1H+McfR2hlNOf93Lax_r<i~)YfXrKt1hXaOmRP5JAv1C4(Y>z@PAT5B7c>%yeQs-TR;kpdMjC2!KiPtCInuk(W-L;H1cdH{QrH5P7Zp z*X9*k@HH6baYer$6CTPS!|}U5*bfPeByD6rIl~1D#FY+XeE|1J*y_J(bN00WXu9UG zWbKTYmtj)a)dWJPEpIJ=VBOvF{6~viZJ#7s&Z$y^K;ktgZ@ox(e}$ES8UslE1S5c3 zn{La^xn?hd7$;F;bpz-sZQmV&Ud#7g3Z0g_6L|(fyY-wWO2oo`1GHRM8qW*RHLRa@ z(s@D9WBQr>tc2Uw8|c1LGFzdS*PB3aDSKWJdU=JxqnW@a^)7=7M{EMMcA=LS zURiTOp_kXY%;3XI7FqjEMl6?MTTv%23}5*slSGoW6*?gIbhiSj{0Pspg|1%jt9E^t zp~LZ;M7>wj%xS*HiD{608+sJO-lHC08`~n|v9%f-QegwqxQ87c->~kwfag{ig>;v}T3;zk z>j<5zr#BkN;6)alHNsKC1|%i1UBac1Xt34Erph2_AkkDirD6@&t>;A%j`E`jl#!lJ zVht}hjuZ?v{E0zingl^J4X5l2vPfi!Y?pw-R?SF@AqX1kU1pMK0pD6U6vtI+%oc&2 zKL{EsLQN#uBs#yD!9J>qywP#%O)AHo4wZsHYwUUG6$DMy)0w2T5NNRaN~dTM z#kpsWkru)(h^%(4({HP1W)hG}V)d^}qU9+`kPto18|)2M_ZCEEIgrj-Q=7=G)7`n( zZ$F%lTir>$f^Zhs!L=5DqqwShQMA-)KkwG*?Hr}q+m6Qutlp*Z&J?1K)@Z!+uqD*A1;^#2B_B6XPEX1g_u$v9j}jx92{>ad)f6onYY8WNL1w?I-ie6t@Cj$@hR0VW5(SL!p4tp?FJ zM&ej5m29J!m7_Kf&4R?J-S%>6laaVE^^9rK>nB;9u&mq6&c3m~{cwuMmgj0grq)W$ zU~@{7uSJ`KePyTGH?`c`*-_{4n#!XHo4qG8Fh`hyz25t z(OK)UcAH%A^;?yJHT?`ClN<;|fWlk?@bxr1ESfh_g4?$sl|}ORXz$;9Jl|~beCp%n z7Xxth4AKCy^vN2Wu%wsQyDkRcdXve8rsV13L7>O?tO#iNtc0aC;;W2Aqt)s~*R3~c z`UsguR&y)4-B$l>rPaACd6gOGt9E*J5zPaOYs8kpF+jQ`Y_*hovmX-nN1f7Yi_6BA zVJAUqSI=K2>NXFu$Kzoa;j-~f{BS>O>EZb(hTnpc)~iXA#MfNE=-lBUGAWUu=hdbhLeUQls(CXUeqVi2D=WL6#ILF7yR@;X-i&AYe0U4f<+BV|m2c9^(@cecR;+Xz4`Flv z1eM<)Z&r};GIs4a5A-y4?P>FuRRU}x@*<1r%~d6&pxcVxU2hVT@wAU=lcD~3XQpI) zmWha#Zy;%^jq0`~O*4T|hf$tVnsWm{7%qoT;DAhOirXu>5B38Rrmfd?Tx+)6SOXc) zI|Y#zD($}?h0Qmt{`Z56%{P(tQgMd*QLTnPNTrS`X$lez*zKPJve)}6Nz#k+wxtcwelVtGEFN_Y*P0O|b(v_St(|3tl!#SLHmAVly5T9I+Ykyu36VG6 zT<)D-NcNK((;!sV`l-ccF6KZ6&4}6p1=%$A$v>)}Om5uM&!wLdsl{J@@{|x(pQ_%NMognF9g`^mlOH>tGHDK{Yqm&fv%0|?dQL73gRXP`llriFKFCTOgl z_WXV_zj2q>`kznqLr`fR)Jz0|=IeL2J?Y|wV5%BLCzqc+o$*2X)4l+(X!<(@7|*h2 zY(J1_z2Q9xkRfAW&oZHtJP6}i_NkR6K&Smfk$gaw?1faK`?;wPrRxhw=tC<9@VTjy zWcNS0*6ewnu@@d1>bbc9(rI)$?=p*5d7>;lHS{b)i5jkE)nw9Qs9CzlPT?o1w8?qU zlwu3qgV01MQQZqypRl*>)1>nv$ykt&A{404A{3|~6muYhcEyokvxpnGFvIc4WaPat z7T24=4hrI{;zZE%HuH;qak^sC4Enf&qH>(_dhUg(ieI4dP1I@1iu%S8dW|s{<@std zcY##C8V_gw`Ne)nq7Cv0C&(s|#@CU6mai-|6(kzLS!)3xriZi7UxZ?DWFA|P+CK>d z)8jVWzkU{>R2_>gTe~ug@yH;Ay^d@sHC-KU6i-KWxC!X1)oTd5af=0Hk>%Sce;UYq^`g4m09k~> z4#62lG1={1h9`JNx;BEyz^#xTy-|{lban*c(AI7M0Q^7$zrf(2w0Oo&Gl{i_MnU#0 z!yV^$nbqEeDT!m!SSF38eaocAl*F*MNquNM?~3V2qYf7M_id^lE^VPzZwKUuH*E*V zL=Vtdqp}czsKM>+_(m9WjbaQVOwtdgDvfwazeYDJ^n1;pE#hRwRZ>hElN6(j^oKUw zdfF@mS?XMxt6>{u*Kg8QTBIa?gTc-ov9T^o`~w5!Ldf3wE}^P@g|G+(b~Fq+Ds!<$}(xZ%JnteF8Qd)M;t^Q8TR)x zh|XGp;7NIc4Io;k*<8>&54(;`GYJw+)4b8zJJ*4ud3x)cLcTr3+nfE6#KfMbtw3P( z2p8^Z0tIn&+m`x>q{ZRFt)VvJ;7@pPcZ2l?JokeD>YAftqz2J$T@NW1L@NLc%fTXa zR_%jld`7wnfpij?2SA`8j&u|1BeE-g5GaTv4_ASN$XoKn=!55c#=O5$LNAX}fec<` zWdJsM7SVthJm&+mx2r;8@I^vjS$9!HDYF=8n?XP0@B_uJPU_e#&hVCk`s6K>s2?@>2ow6 z?1#iXM{~oJJY7Cg+-Gz1xl$*0xJP?R-G1tllO9_rax{~{x3R@zN_u7_jXoFaYo_I7E~+1ouUc%u znQHgsai8a%Hx-a+KQ55jb!V1Y%vC(nM+KyE0`b6tA)oJa=0%(HhiB;}0h-P)AZ>q= z$yfGFzKR=5)?$##NpSmF#f@bxbkVzOWM0({TYihHWIzT9nffB3>kONe`(nD{aa;Ld z%jd&2*Dq!(#%*?9v^j5Ey@e^CK+5CdCil2aVM`Kqq^h$9Jy%AmRgs*P)4wGAV&G=H zpUX(3K3-?~;Vp~k;e4Gxzt|7SF7H=lw6Evmm!#SQOy0(}8wAAtsEqCQ%NJq>SnT|^VaKG=TuefG)roAQDJkXXwbOQt?F?Td%IFoO(Qo*Be5#Id3F{TX@u^^=F1ZSAeC?Il?QD3oI$#OFAgJlZS|cZ z)$6HmYoks*f#`q+=zTbFK`^oeGeKQB+NPmqUxl1II z2qaW9-YQ6_Kj{bpGUod>iz-OQe(g9D#!t7Zzj^5Ad7sU;$`p(Pp{+X0a5^1vj)-L_ z5=NZFdtY^ODW38CK%%i8SIJ9k+av{|54G3H8~p%C)Nb1oM#KjuDcfZ7yJ&M9IL6D* zk_rw|`C0ugGx%AW9>&3QKXDSTn{*NlYY;wL-Dw=%tu=;0CD0T%4#xIEqWjrQpaRXz z|1=Js^O>2O69fViq=`(*tPJxw;#3IlT)WBCRa+!7If7_%0D*=x4~=So{rXMeIP*-v zI4B$=Vqh^rozFaDJ5IWQh03)}DzDNk1Ty$~y79>qJTnjGj+3FgkPhfqa;i6~PP(JpG%pEoW{LX2l??kddM_$CC>oB<}kTN)+EW=kmK%z#mz7tI7}zI+*;4#JZ- zM-Lh0XQr3~@klGpWcK%+=@Rz54>J+ZJc9zFrqY-xEnDi;qZrF;W?Dp$k0*7vl$7F8 zMrbk5Cymfzp0^opst4Kq{Z*0IAin%8CfQWW1fp?fwAoRZp7?p^I2}aSEd8FmM4hcL zlGi-GcY?wqmT-k~@l7BXqg~hqD&^v%Og*xts0)G2kE`f1cE4VwSoGWc`9wbigR`0Z z20*sHflAh>^cQ zJ*y%z9LJqcUB$ye=t>%jH8LEdjI<*VwnNEl_I}O$mF{BrhB-|7e9h~1xbaSZIVI=w zNpu&(x%Zl6e!TH=G;mw0<$5--4N%{2Cuy2VK|wUCc-5a@ z?1yB(A2!^2GID~b_2k1g+HmXTRrDDHkrEgls{Hr_gWuKtTTM50*X3bm(cT!v1b6Mj zWT~NwK6AU@$R+?HQ7Zo!ka<2I)sNS6dZcT7-nAcovaF&Y>N7GFjeff6w2KcCO_!l$ zK<39)Xr-cmQs2n%Fr#x@duAGDkPxAnRde(R0yZ-`5kSn#8H*hx+NXObesm^2oG_Q2}iNTmuvkZh7Lnj0XKe3f51_01ND>s%v zpsOOFLC=dei5s!=^wG+UjUZ?w1QGCkW+*!=-SJ1KqgWU)wh2aV*dmfZ+u5nCb~;(p z8X$08veN}-@Hi6=qD%O6dWmg^FZ}b1VYCe%N!l59b_@#Doe^$9p#DTyX4b{vk)%6J z^@#nyFP!}Ld^N%kJ5GK}28{5-2GP2IjMxwdv7E&QLEJ`bkwFm}E^i`~q1$$IfEHii zcEL^%uE{LhAdsN&7*xL=l%Oz9_%?L7zEc2!pzTn}l2C&_Vt0lq5VRc{W+#cZ%fs7a zFz6Q&9{TBY2}6Kpe>WYhVZ@SJMe}9VbT*jfI1FKW4s#kK^P_8=uGGjES(9Kp55BsZ zMh5-ARvxVwgTB=80$$ss2hjK#;Yy7t9h%Q3^C%!qrUvGu_g4&;Bv@c`CwWXBDq5L^ z8w4_NrBXN<$!i_<3LTT4)9YTNPkK%x6RD<=Ng24avM1fVW@gL+2{E|rlmrrDFt-Xo zLSb3Xf-)u#70ujG0tu-zEk7pRq!Cv}tvKnzHI@6|&nNmJ80|IBVOA_L6?$DT>D2Wm z{d`WBQxb33Iz1-6x)3c#LKzQTLF6L=5@wGFk&GL6CDVy(j=L`C#5M1ZHR%-nd={O! z5TjoMb;f}qe6FlJ>xe6CURjcH-ILs+1J}%7YrHRzcq`R*WbBJK1X=hQ)&D@;>ndh6#*DzR=aSw^R=;4K4B4f*< zGxW?OFP9F+mdbQEN4=&~FkN%Dr~m+yZ}-&`?gh0gX*ZXdF|K7PILIjfwa!vv`%q>5eE}ud5}wOdvCI+Osc8oL3gp0&K)3)0$%2EkVyeA|G)U$ceV++G}QF|%tX2!4^pgR`u!M5 z^rH-<*UE@hAe--_CD}ZgEn%g~1JVOXdI79ApyXT`(GR4ujK(ksOl3%yQcsh3c7{H? zR6e%VvYrIed6g`oAkkLaR?Z2dey4&yt4X60FLMUSte;nHs`dI!_vn?`c|ow8eme_3)}jm9%Iv@(FoWC+)LH04ww4?! z02-S@o^c?2KRFA}LKm{flL}qP-euHUNf_Y^$!+E^>Fs@=66(g|ZRjDrGSxjuEANXW zEgz)4pF?-CSAkG;-euN&m+7GuKFiQwY~?O6$n5VjBbLt~b(%mWMcYxpf<(LAtyvh~ z>q(}c?)ELrj_`a##`k)X$fx+MEs4wJSdSosudMY4$o^=C?WW2ybQybo==Q_?ta|9- zYP-tlUXRXJ54V(yeEj;ZuK`{qIG-ife09#sn9$FQ3iS$?`SXkYkW5Zf@->~64rHP6 zHj_|trX5K^LeY7Z+2?DXs^NV7EYd9|QOZXZzwsqg8y9k#MO%4o9Has3J7{A*T+ZT=HXUZcoKv(b-wWnx_rv;$LT2@C?u z@kTGOeaKyQHadar+>`|g3smNR2U)ZO%CUMjI)TBuBo(kR2iHhD8f2;WEt4acE8)4`5nV@ z$_I4{#hos3vva3=rwba$`eK+*KC08@>rDm?uyXkViAPO4kjzd$YFs5PwbSQor@tA< z;#F>%PCx3MPG2C6rc!x~fJ9^EiR9Vo^p&BN0V-cvUTU+`k9ymY4Pd`Z(C6z-8i|HX zXSRf$p>AiV7xl9yBFuBVokmfoRNQ%z9c0&cP0;1*c@_PrpLd>Wn5<&De1Y^~Qh$+X zs*I&L`*KscCKwm&4qgq?)d#o`27&&vZ;gI%XB%CK>s64(G9EI6``B+14KqCHj0ozy zAJJOh=!am}N1=-p_v5^A@erah3}C%R!=QIp9MWGV8bb=N0W#lrsUAW)ell+(d|t$D z?8k5&+{WJbns;#1`c3#K?N|V8j(RU1WP{)LLT_-_`b`#zHuolM@colC&lTHb@|Bg& zW)Av$;RQ8o5AIsO$vEF{xY#mzPGb&kTkm_pIJj-SGs8E?oUg7k8R+EEo|6WNo#}NZ zopD}-K3_YHz960bLUulo#cdUdm05Do@Q@Tp<3(QkO*(z;dwn?h9PKvD$-pKU4w6li z9$(u5s{och^3-#3C}A2WFo6KshR?1pP17Vo_i@w_#cG+Uid66$|sXnfoO`E+@{`{ zKWV~*|89uwZjueL*>-8Go-pC>G)vDF9#?ldbb!8Jud=vZd~eT980zNhBNz9JAFZ$$ zSR^a`BF&X0b1{f2OXg0H(cdrFTv~B1DC`FU$|I3t9COpQCu>M)%1DxLHLsr&>r?`Djyok>AKc6pOR{n(jl|NLS< zB>hn+z~oox zGAv)Ixw(nFGcV}e+(drfXH(~Tm9Z)wy>uOPuu7K&fGTaCJqILIt{2%{70AB5j?-F% zY_A~FA|7OMb6=u#!Is`XN#g=Uq8)?}A1c9HXx?2%^@>H=(H709n57)tsWsoz=?DuU3b-l+$+*i)({PTriwm_tI=;XsXxdXlP02qkW4h=F8sU1362BL+H zjD+i~5?yj70%%%zaZw5)B}2RU>rA;hyFrNgjJ*sp)+dQ)FHP9%q?;9{0@eA+4QPa` zQrn#po7)m_oeVL8>7q}QxQ~= z0EJ?jg|emEGnlkZ6Yo*=&by8y84xL1ZgiG^2xfK+uf-EYl+C)AK&? zasMn5&5$9-R*UWBD5Fl$LM}!bs(&ESFqt22wZcYtkxC+)Do8X!CY}S?HHdaN7A)!I zlk}5!R`-G>{S9J&xkWCaVp8=Hl0+@`mp`uB_A+@f$YhtNn(Vi^$*fXv~>frc$Jl^UfFzk>Jy|D&Yk`}&-h*Z zQIT&WX5f*8z$#yl9p^~5q?x_Pj&qdJyYy(jBc1v{+IZh40+d8%C)drOW|OH8K|-^c z*1UU)#&wf@zRCP%5qIN0sn}$gaga&rscneWB^rlpn@Qf@S^uB$b-Z(G2TvR#^eDM5xlTpo{a^g|F$W%tkp%R2gmfAr{zveE)f zNpaet)`&Iub2yFIT5e}<{(+3~nr}vIEkCF05n)J>qDh7_kWeA^_s$|vUvQvv={B*o zj0{IIW`JDPQZmgm0Mr+_Kxj~o*jYwKAJ5h!f_Nb}k2_<;dHF)V9LwuCivJaPZTxkJbpn>}M!fuON4UFahw zq>MoE`YK!>z^}I`01-Gwric~(RS4(q^$(ok16WU6v9*j)?Q(Hli}G*fHUJ3Jmz4&4 z5VXv4u&uQsUR*>*SM{w(I2Do6B^qGC|BATh(i$-{?>vdUR@i(HzTCR#ifv^CBKK^v zBA7@-B9}J3!rv<5j!Rsx@V7z)arL7W8_N+=Tt=w}q<}!fab-TMEv`M>mMCXb~*9k5i1wpL+I{V0!aIAZ3*+JS?Pn%%TeM4qSf1<%EP^1+ zI^hj+NsS<~1ccT83o)0ij?tVCGF-_Knk(WmYr(>P7D1P#`GsvTh_-`QY=(U?=yH}p z^PTBkg$WoxEk|L@|3dI&8)$X}=K3IO1+ih^>c8jpzU3aeJ7SN3$VYTV`t`2}r_93< zJ34s~Z7_mduYoYgI=l^nwhHr8mf1asP7Q5X^S=-VSqGE=&{S~gESZjO|IIidAI}sZ3R=#nFMWBkNoh6J%UKXiaHB|ri#RZ-DHw< zKRe=#M5tlkCo)YTkZ^Z`?GN@tGHQ^0=5_mOt#DP;r!O>LP3J0rtGa3~j{#N*qJh7U z2+M__zcQMDRD9RE>nl$8fM}5jg66AvYIcVW>I=bnWs3*7Is}Nj*BQY_5QGnZHt-o@6mev=zq-#@2p~qR z#{(?-*N69%4N+fQKIHVLrAQRt^ne=uEmn{&vzJOGgsW%ztgZ%l$en>Wf`cer)NDp_ZYSKiw zXaynAhhFpLu|GiV0X&{dMC3w*Q)MUx+2dU%oVMaNF4Ne0EvHS)yKx)YV0Y?50;%=M{HR1KSAR)u5}pnSw;#02-Kbky284s5y=b0 z6IZ1$g&WyjX7P<>SJ^eT#}T?!wighnJ#RAkK7+@bc8%yGuXm2^@pwApMS(z^KHr(* zG~e*gFNU!P6F*;3lVBa8ki5xU@rwQmN?0t*B?fCm@`@trD>b5zfXFljvU!zOeY-BU zU(wDOKr~;qg$pE}UGL9|WR8e6E5k8J3((y!!m$fsWEE)#1kx1Ca(zRKNM487LY^u-{WBH>roZ)YHotNyS+@XvU1hW-UXLqU<} z?}*}sFp{#$4!qmC_p*4LCZkp@&)h37w=gR6KCL_WdJqJK8!GTC@vWS3O z*GB}knpbVyc%>%XLrx+hnG$z`T$(S!d1;$=_ekIvfw`o6z?y%3RL!uzAXn8OY4uKU z{R;uBtTpxs$u(N83wmgwBR0>n$TcPq?kT?^_PNKMz7+(|#=g@^GI5{fY!n;TeB5WJ zg4$zm0?~++1p#D$6x%^SE-h)?`O-I(!RyPJs8`^st$wQmFy;qv&yVyLUlEx{vMVxI ze?=UgEOM!?05aWzTslMq-O)@u!d)zgG*(#mN#vffBQeSs!sTdmj0i=-_&L?&s#?Ux z@j7sXP#kwo3lOvvF4hnl;p{vj`9qRRpbuK`1+KM91gKH%g-ZE_z%pLbjc|4b$u|yX z=Wz#+-ckGufnzLxL)ZF32pG7Ry{~C8x(G6AVYeev>X>c`3#9ncQ zVcVO5R`i15>>NQ2}0U|3cUj+ZiIX{1-x!*s2gA^}i5q zB&!EzSp*P~XTye(|BKN=mcgYKAj(H^<%Gvr1ohDS&EpG^I4p~2c#MrWlD zGg)}@vsYRL?Lu?UZ_hso7W2wC8Hc7~sI1Tm0!p5bSW zkOh`PGd#u+jzBgykgJ^{)PUN1hQ}B}1Sp!qhPLq)@c_;Q*DO4bJXjAhNM?eo3UEwc z*2X=<&wA3*AkcA5=E2($*XIi-*CyzF)$*W46G-tRKk^o6tPQUhjqjLq|2 z7tZh)i?izff^f8sv+B+;@WFma;(hLQ%nIl0ICrid7~w#^aAMrE@d}r*I90Abxx!^^ zM%uMvQbBT&vLa{+PHcNhjJRh(tZuDvw2njE`V4Ff1d!V;z%@wYe734*Mbr`ycLI#2 zFPy!$UKi2RzHpFQtH~8cJOC}DSL2iW{n_C#2I8KCeF2b>bHECZF&uW5X&VHsSA5_M zVB!lh7wE>mKnb#35pWorC3DE`h}-rRr+7Mwe_ z#b?c3W{?Kbvr2c!(l{-w8r-2@%$g>y9S&nS!Fc`kiz8;v$Sr zgii0u(ZSN=Zt}%olUvL2AX|}54n0fZ7Utb`6mDT^KPbpzJvRbm=l%o=jB%(XdWKtY z@9L+bI&A&?=CS&wF438u2eZnYCUM5=kTPoF9FcYhE<{r`F$$fNwxSmVfxinv%c~Iv{av8KoXrHzNeE0+ z^v3jefua7GCh&KGDs*%cI4WQZK-D#3dk^GP`;PE;VE`WehI0}&F={v2bT{P^{UQ-> zA)G?}q)x}Ergc`3a1*ULI0rpo;0W2KNuyKrd1jeO_byskE;7S8DL32y{9->Ol}_VS z@q&bx+mz>HkVRL$!{4#!pnmsLEWhZy->1Q(vmAG&FA^Jkak@YqY|u{zTd=#B=p2Jb z_1N@|zst|Eh{1q{(0H7&!H2fu$~{Qs$nto^ z5{!QD_eJ59UGHaiI%T))+_T#$yQ(YCPEWx8?aCVV$!?n5C!J-^`CYR}_yJBWdV+*n zb4>-lh~6^i`j&{Bbe1{2&we|I zdHO*neX?iH+-uUY{YBuFecDy&BJ1PlH~XaLyS3<2zqH&7!k42f;{`T7>X%Xy1Zn#0 zUQH%Dpjw-uf}%(2N&BF~t)oN-86m;^OO517bW@hzEwW>CFIuf9K^v9B6C3nUwwc~_ z7dFw(sbv>8(XIxYz^dnty}hVeO^>^>g=S8MTaxr%lHe39i3aM9EIo0!BTLNlaX{rF z;U^PL$C7tYe*#z$*|D(~XA`DZd2jYZ5^Y^_^z3k+i8DYeN#m@_)oTz4S9P&H*=R?O zr9HWl*tsf=^O|(fuhT@%*+pNl=*m9iBpn0|hpiT^vUUnlcPhALQ9k-fo6kN|&D@)Z zypH=DH?`GmW$HYbpyysgoyXw-2#+#Lu>r!Ybdl2s+cklLG#-bhtt3c9Kv0g|3l!?B zMLrTi7%ZLVbOUs*1689ST1%*#pLCaxsEWrjX^eCzS$7^agQfYZ=GcccUj(UK3~6x- zG8ns!UVuS1BUN%2>>}N%`FA)I35M8tT_k5gl53m(8;nXMX4D7KDI+xzutqu}T z-ja@gez9xVopFrj>yG&!r18vyW^Rzl6QQb`^Q5xcvqzpMmDTxuCeScD)Vycx^~E7b z&Qj-DsH>*o1Vl>kss=I4w#D~(R_dzW;0jVj)Q!(b(G!P#>S?k$4;-qVGq(TYxX)Ql zIuB*aWCXH!2xt4tV?(ep_lv3ul68G3jxH^}1bre)w6%PX!p zhXJ%5%pn?gCuJzSKdBa+<)CHf@DdcH@*uc}VhJ}H5O=qt;7412V;5nD9uT!dQ3Q#t zO~N1%hrnqpFA^DguyvxbSc-$YxxbadFa$F@oC5W@my`^CkW#8r2IhMNe)l1yQ^=Psn9t zNFP_}bilU+=I97D9HAsHkBh*qz|K|&__{PIN@3u2{J9i%>!ZUl*BV?IlM5vAC<cOMKxuQ96*d>Ogy2Z?ma z_njIu4m`^+tIlvR%OG`pmVwGLv|kn=QX{A8cs6Dnc#}>dS=ksQX{2rOYz&fwC($$j zQs-xx!K*Cx8Z!>yQR+~Q83&&CX@2;FL<>Hy>P&F^B2%B$^v;9Xh#zGb(+}o1si`gE zBmtCd5b21u-*^FrNrHEUE0AH5B1KS=$VU7i43jkKx5idul%(OXr$M4&s$7DCY?4EY zB5e3AwqUH2wn()DUlR4x7P)rlT!P=7F_LfzmvkU?zHZVF=0Q#~`q>#I38qwu^3EVh zjI2|^t^~skX}W`=QW$xSa};v!_#N#{evNoo}}gWs08e2xjo9IGDtjXc+Ud_OJ(f( zs*`ZOd|kz$M}6p!U69q@B(m;=2VOIXR&ZRsAd_W0V8{IU$yOOQ)10);$8G(4=^D+> zW3gt2+y{a{=75|YKyUU#GW+|xnTMy_VLnLZCsb*CFxT^{ra?9$4ibo$uQSr_JT96{ zy91v-=?#-Yu;&KDIhl6nc^eABKD_puXFhvmkl*^ubUgxApd=u=RcKbgDStQ!PITw@e^fUs3@HWd>-oar^sG^Q-&edE@Sf=j(L0pcfu%P*y$4L>`{U+YGm# zZ2sp85A6@4=JG`niZ@t(PS?O&%Z-&y!=yVst)}N<(w%36GU*QV4bA*?#e811nOy)x z<7hMKPOmx7@5s8-y=92s(JWO*^e@5`J8v>cJg-NPe%?kp^=68ljO7qy{34s}a%yte z5d$gitkJh4#ZJH1gF8~}^xO_Sx8!6RY`4VZ{Y^};bCs}Cw3%QB?;=^Xd$zy7fSCmF zE`6A|U8M8C_+H+xH>g6?oS(PEX9Iji`B<*EN9IWpu&{&zyLwpz=~2-ro~T*jB?PQ3uoI_H^EGb+ftC1gZ^C10VB}(F6ucTlSJnC zaxi&L#U@NKL3`uIdzlQD(Woy+2)VL7paGiR#%~;jhIERbuxQ|u*EE45 zQk)Yd2o#ax>^~Qw-xh3CqnLDFC664C#jCWiE@x~;gUA#C(nw^N27x|+r*jg8j*Qnk z)kbG{ZUIdHJ(Nha2`6}vrB>q3eL0yc2W_&4Nh6{D`sWw>A&G`^WQL0{S5Ebjz#vdh zs-ss1fqDWDSO11`g7bxH71+_w=+m0&K%kyfN7@O3mJ5TI>W{*$Iy7&PN}@dl5VT%x z@_hh+Y^x4gd=W-su8!Uu1lEk&?}t;mMYKRYoT+kZ>Q5kzH`XvbDeh{za)CfQshwFN zFR=VZ}JrDnG$9RADlm>ho7Y)Kc2|E``~2p7*J- zVul@(`w$?}QaU+s0VdO_PH_;Vk;q{IWb&FbFN%h8#GH#Tmrfm?I0^+|9oa6002Wjemn!qvljQ3T{rSrTq#a~UQY!J1cr^K?|dNLN28VCPBNN*Y-r-{ZHUFa_& z`RB0DLE8E1+Ay}idUlmad=!bu4bQPynR70~S_IKZ(}=E2u7hVwm{lg%!9_=wnHof@ ziyAQiqs)1lRKBs?l|hC^QSBydtmO}v+;sYmAdSuESrWzBEhHQ&)9XAsWgTp*VN-vp zlA8`p69lRX?D85AmFachYd;J+!SrWNX(}$k!d+@hh}f16;2>zecI0QYaP0!oN};qkbrfYZcfvx?`^bU|g7#~UR~;l& zO>du+7O{}xjinVd`by&k)#xzLOZDXM{>@KXuCDOw0+GWX$lx_H--5uNhKlf2bd;`J z+sOc-dOj`+w=R&=pG{Zk=nUONt(P~RZav?4xuHCjUZm)aPlLWci>#%p(zBU>Cr-;Z zlg7`KRR(1C=Z$-KN=F;CB$aK@ZUVIjM?KUhdU#4ldvoie^vF!t^6&^ie_s=x(lx^p zUL>}p(IL1)4uFP=vo@#6U?a$@7G$%|tr=mRG<8)s>AFhORF61FHP7{2q*0=61waYX z*ml-pdxUO?QSRyr2d^N~Phgwp)G$5pUg(D)T5owX2xM{6nOYX~NXb)uHZDMDBR&lQ z5N$W_DxDN)^KORldyR`Uk;2H$8*956B(&Cf*Vm#dG*j#Ek(aKf8$Q6~q$qP<>6^OH zqs*o*l)K*`gWsT?O_0qy%LT2BgSwDYjs@wQ#a+om($r3AWt`N7rd?Y>co%s-0!-dT zqX8!U@-9-S3Z*X@NGI_`HVT!GnG@Ndhu8Byl|5(bxM7gV54RK?%v2Zh;WUZ1THaLx z8SFXQ#01&A${O-uvbu-l8R6me5Iln(ULfkogC1TC&>>I>tPbNW_T-alUbJ~*8Ij7E zlxRCwp<`0_*xv91S)9zYlo^XnwY_Z)(n#FbNBDT%)Bd1~*JH*W;Uyijhbuk2q(SEN zLhsFfNEW4zwXS(ko}Ky1lj-Xq9o3U(cus?ODws@Y*Ul8wlfty6gAWLAtPz5kE11rT zoi@r0FKG}ja$)B`gUF}~vIr!jCzI77Zg@2axmi;pPbRBt-tjGyx#}Qc)%zzC0ztx_ zN${YSHj&9xb*<$L4I@5@h9)|7YuS=>uvL1F=E*#D&9O>@ED|PIy2xY;be%B{0!s>r zI`w3px;PD|XHiPFk-}jzPhA_ih@Z?;2jVt?|8s4Q5_SPf$u{oKrj$f1la(aYnW0UG zvY4f=jZ{O{L2YKFQEV~!Pwe3@lg&4_{=AsC?s*^Pt;1EcYlE!w^>F5`d)|h5>zV>6 z2Y^1)W(uTnpl*Q?Vh7n zWhjJiyM^xx2?>Qoh6DN##K_Bc6fK8k7%W_=>z?| zF@2z)H>STAoJ`dDHgo2+JY!Jk;2RC2DHaC)7R0*CroUIa7bDDW6&7r1JexkyPeLE) zcCTsTBqM+)0ea2Fjir=tx`efztKUr@=$7k>O&@3^0MO!cQ$j*xb_LQStRFHVZD!2F zK~`5N9l}DV7NJ8}zn4mz4qf*`R!SA1d$1nNz9@Y{^VV7rC6Ybe) zL%kl%qSwFS1+ui)z4eC7`5OK} z%cT7xlP(Fx-$f6x+n1m+XT$5N#eKZAgn?|jNT^%ZgNgKR_YsgzGF|iGBX&E7)RRtP zJ>B&|DxG-PPXPwKWMmBm*-x*YdeTMgam{I;BU$A@7X5K#7^~PWAki`vB-$$dl0f9} zq>nu5x75A9dxD?%N%xoM72oubavwSAE{4ETRKDuT#Cmz(Ag#ZzYV0*RY1XsbVT;Nl zKx`i7!7Pv=Kd_M(Z5BCoU+sbCiA|8U-nX%t||>@HH=B=SoD86?{40^z$bZNddA9e^Ge(L?%8CTmxwnp)@~{VYR?2|_Ke7G{}! zlRe&b)BW_kbEjL&tIRsz?@W>Td^)|T-(}Pz@;>yUem-k{KOg?*6a5f$Iwo3B6iLk& zY4tULik!uk-3($ow0@GV(JP@;=pfy5Z5+F|pP+Fz()u*^7VQJc+f@2TcL!h%GR7y_ zyo%Z%wi1gbDAj31!X{DYsf7+I4(z^(0vO%Y2uSGnkVt z23h@GM&4kLcV-&dH<=&rEN`&;)5o_QL^TD~@%`~=`GV!?)-VyNsU!s|{iAyxc%^lR z9YtR$;dl3(y4*0H!K*~w-IuCF-93d@IeOis(XA`p3c^6j0b$Lg9q#@zzJ(!Ty~~`e z^qtyEqpx#!jD!*<1P$vYm#q)>L(()|N$Y8H>&oe>Rcei?_=a79<62v3VMh1_OEN{e zL2LBq++L)DG&wfcW->nr<=IH@2$0%83G|R*w+n#qR6kO5HYSRVWJ#wvA=8w#}NZRqHQhx>I_v>(EW_^K3X@&bu9AiqKD^H}%1#U9o@{nawJNK@nW zbnDWxp_VAQ|yy&+1OL6xtoMW{#j`5k`KM5RMBwg%~HjKsHaTJGCfw!Z_@kws%}lgL$42O8eUv<`9r(RpI_{UL~Z3E z+o$FnebsbZ<&9IM$;&L1+x5O`#X|a7W?4&=VL9fg{w}kr7A$Xnu-!PpY2!{NoL{ke?ysn+7U?R&LAb>cVb=o`) z5@)kq=FcyNVK&1@Y^2{IK<7tn-&)6lioMlwgzx0BB`@M9J)qxY>S&WX38KS(Tt#nZ zoCDe2gpZQPCqNu;dlaEV*t1O2Au0=yNoVIsQO4$;oyXg%_m$)DB9DEYQfnq-eT|G# z1hV_P%wY39$_yT(s@dpsu)ZFI4qZ)HwgCXK9}igrF#h&GGf0{??jI1kA?z^S3q$w$DeXM61g7 z*v`K$;9KC%LyL-V-@{#pCg5p*K9y+9ZvKzIA^Q1W74R)^*QGUi@w=`@F#IYik(nvy z`s)I|MTBlW4q90w=TanrJ8HGKP}ppjp}X)u{uWVo|FVSc5_g7kIG%r7JOiY7uYb5{q%Obu_+K1aD7?*Kt1or&PBEAg+@T!}hdF#!d z-14MPmf61bKL1&f^S(6?2r-l-Z%tomCX0L?BI=O>P-hm~KPz(F6%r!-RoA7ev9lsw zChIy@#D7`jS=Yzc@pXRvmurM0q)%+aln7n&a}#c?TqAfej_hxsYyR=;E-}gxMFQ;f zos)Fk2od8?Sf;-R6XzFG8&L*|!MyoQs(J$a@{_*QBxHIA_*Vmm*@2t_8fIL9&En#W%NU-OS&ci~{~vEaMk+2nr3hxOlDI3JNSZPJ3S>|CybFgq)7wC4(49pXsVau?oQ#F|0esCre%*y5J-TA# z@zI?{kVrx?vqx0xFW_tb@#`)+i+tGCRWYVaR`F@`%~$*dZeP=nyKtN<#KC=Mle`fk zKa9Tu_nklP61DO5->?1|DKHRM4u=iKDF>*p|M&m;+kd+zg8%-v|K}?66*B_=_kaF; z{m*~@+kgBomkJuT=D+{9>qeY0a7@1=%fO87lfVD`?O*<|N6K8?O%TW_1~~iyx#d={_DT~8=iiR>wo#jzy9xk|6i|5S6+!V7ACC&m;KBC z`0LI%SpX*w{{6(?|Chi2?LX`FuIcPNBTiUE&S%isvlRunFBzKlpMLQ8ryq>PCv-V{ z@&AzT<SBy??_lWQDUOOQ_1$zf)uX;i@K_COh_34Xma|Jz(bpr$RpK z0Xmzj0J&;Vmvae{^yQuNbmQ4 zzyF*0#J%Ty&-Z-KcRlC(J)e9Kd@q0gt-gH3@`<%SL_yi1MP{EkW>c57TrUw+RldKR zJ$snDk3h|OYnl#)vu~w_v5r^XOZD96hqaQ5D!U{xGiK%|~;p1%VEcA^bPOVxb7LyOrA2s;dh- zgalyl5{?fBvoS88Vt*HENqXxB(%j+EmM?&ox& z=%SvDNjY551ED?SbRl5$MbNtp0&KH{4I%pa-812<>ZB63V-WChc5-y!c)NQMG6BIk zY6sgf2{LBDb_kt-;GzL-2ueWEu16{Xk*!V+6F#yFlMzRP;ar55*x5R=ZRQDrI3C^t zF+zs%RufF(E#?PEMPdlS`C!*6TD*$@oASjHsj)9d3{k-!u;O$*BM1#%%I8XbC9V*S zjL-DTFX5LxU<`u>dVc|dGH~ADKV>rjsP36)G+grXUmS`_!G+X`jlx183X6)Xlh9kl zmR4Qs}s2=;k7Xb}IC*M1%MKKScvrh6PCY{vsiP#)7>?0s%)( zKr(~sZz^nC7Yj#IAR#YcDw2?&C4|UK_ZK3f^ooc=>5&kF!RWK@P7J?VH{SdIT{i_5 z@P&aA`NiTc0JbP?)Ga`N?&1hI^bVWg~}QE z|LQ-$+)_@Uyr}v`rGAo;y;^ewAPNuU){Q_!1_4z|OPT;XccGzDnE)$@93aGN!qzYc_7Zcv{V=IN#*=nGi}4xd+$PM0{b2zt z5@N6zmT1YAXv+7;fIi`lNG?*!-n;YwKu9q$zBnmnf&qt*0UG5Uy)kTs34Nr#IL)ZO ze%DSXIQf`;hmF0@B>fES)jp+;cTe5aO36uXrk{3Ub4f{zTai;QGV7%4;t9iz<~e&3 zR1c4;ZMjkp4Y9wn5ROsRb}oGG>^Hq))s~GL@>uTGFUX{h4cbZht21VJJ^Q5kQB$MYyz;N@ehJj=yX_{}9Z`98{`Cf5$>7ZRRHx7O z<5cI=xWH9g#+~v~NrUc9KEZQxEJdfhp4aauoO)9jQIlt8q+(N0! zKkU)ECh~QGIO!YnXzZk;uFGDT&tSTRslMCnuGQl17HRM}+jVWlZ+o6(f2_Vhxlj6$ zz3*jfb6C)C=f*92;}Swxu}(GYGQ^y=O*68zhA9~Sfs{(tX>L5%d?=mm?!RcQMMhfO z0a4wvGi_^G#qU_O=n0KF>AA!6Iu;IHVQ_Xq>GdTHsdHOtDxa8hu4#p^*0O^hIZV^V ze(%1e;hFbc?>-LdxX{{o?Ws9`cK#dT`r3`cy8X<6oJkAv@Dwi>RD2? zdzAg(W5*W8*0@IN`W?DwL8-gHY|nS^(bio41IOXh|7y%Qxp>Z0sxX36JmIJ@nR3rG0ej=!Ki2;?;9Uz6{$oCcgRec|zv8)u-GxJ5DLo)6C-CO;lIX zpQ1L$+^hDaiqE3TV*Q-8S30(sDXwq!f?MwFRQzF_f8Jcr=Du~UB}zBuQp@Lh95v+}mcN5NN4 zUA}c`3hJ5Dp>%M2P(s-ldE15dr zkJ)ZMXVnxoGEGHumiX3E@~gBvV-BFlE$%u@8TSor3jC(7TTr$3%Efr|yU!GBj{RX+ za%`rGed*yp1uNMZ_YdoR`u)q)^rfMpDqaU32qHE${H8)2w)>*Jut=d!&q{4%ZjqWx z0i|%nsn@rB&p4$l*KO5Yvm8lD$viAEOU%YZj0!KC-HcT;Js#%{)v$0nS_k>Rw1 zS^Q|+pVzS|t7IG3z6UnBlS5CK>)qP-28)5Wp54&`VNoF}4Tb0^y*pY^djbV$>=P*P z*PcKDM*bpD&=~{8iJs6P+m3bb&)}7?w2#}Dok)5&)2Lib{O4|;&ZNtE{YCk%=JqS6 z-S{ARo@};{5@lFh>asU2HFdkdg4l!+usiI*Cr zB)DO(Hf_ij&BaF9SDYgX(pw6Q#~6Mz_(**H@o`OCZBF9sc17UkiR3kWv?u( zd{}$h+*-UY?){*WfO8#@vz0$C%=LJYIL*k6V#`yoTwwm*9KD=sl7BX^fqJ1>!6il4 zW7X-*i_T6Jo=ZG@qXfQ#+n4OTOLuiSljqhOOB?!{SC}8Gf0mJ7rsr%Is36?!>zGNaYdEFPoGmO_}_$ zU2hikP^^htL+JbQV z#uFW{W<75|wZ(eWj@GF3N4J-~ef%YP%2kET(SBt8n#mtG^2aXwv$*K>iy2$)AJBEE zS6y3hjJkrYb4dH~47HJ=W~K+DW?U#!+FjQ8hIQijlNJ1}!;){<(f8*}Y(E`k_lNrN zdlzGln;P5Bb|Kc+^L#>HPeQlU=#3-~dGcc3=DbWr$LT9FE^VQ2+mqp$^88CmyH4yN zp5v6)ZOl#U2pc2Q4oBCHWKJG8aq(Z{bl}Avh4gt<8iD*XUSp<*UtQ32Ax!aYR#c#6 z*r+cW^M@X(e$w9hI4aR~t5jF>nt^WP=$!e%?s2Wcq@sg^XSEn*>`VW;?Y8n??ghzU{Lg#A9vhdPLi*UXEOQ}e*K)^_e{Rh|xgJZj>T|5u8^^#hlkzCUt0|2(?s*NvME%4}O& z#qrf!12^TR7A^hAPkQ27myvP3)k9+*gOONyzQ$ucto&AC-=4KJ73R>m+j9wZ_p#OC ze>~@+{`G-}raN8TSCSAv0xLY9w=B-{RmmhPg`>sQRYf1`o3~OZXHa$0)N3+sd|1Nb{%|nqMkedp^4_$Icd)}8$U|p?vAW3wA#In zXVSFJs~~iIDyli;Q=FCd(YO#yPkQCac;v-g_x7&~42Eq~R;tet1#kt2UL0ed{XyB` zbK+519sj0(hhd^E&GE<$HJZcIrV)w%}qleiT zo#jScax4EX4s`#vi5X8NpPWXRVbfZ9yUlL@Rn`aby@Vr;wU+5OF{$d=ch;=7uy==( zeqR&pvM;Xf=B?!0b5Cy^{~*Xxav-Z|dBZ)%7IL`9Bpd7O5tHA~YNIuk7P+iFc*J9S z$w}6mprtNHukNe0EUa(QL0lWe3tFNaFK9F=DnuTsTIe~d@<#eOLrKu5!o9|O;nF|M z7*XzPCf4gZw-q0-+g_AuAMLbsQSq0jHg*caG5fAXKl{sguhG86K4%V_6jq0p<(n3N z=2XzM9_=4)+~#C8o5;4*$gEu+8%-N^32~h7p{U2*qu#J%gmWv=`04T*^I1c-zjv5X zTtIZcW@Ff{s`Sp>AmC&?D^f44E##5D_2IVcX_r?mP+zJt$tc!6FD!sk5tm(7B&~XK z=}z`A%wR>DvnaxX9LbYB6e4r`sxxIp=XF=tFQ` zK*Q#`E7?(2q8-9UebVhw_IhzupZ6p@c^N;AvuZ*~R)u9jw9@*U+|kQJ{qK1;xa2MB znDFpcR>6tX_0Nu~DQ~z_s5$;fjG@k-gCesAEj}L`PNMFzQQ4f8_4?SHr0|GE>54HO zu8xgn*<(^}7OqqZZ)lxv`F#BH8*JpE0(#;Y=e=v?%f-wICL6C9(6p}Suhaj!OLvCR z$ zfH9jkCl5C%c>nC#Uho%kT8tNNa`;dj&Of7O`Sszwh8?_QUFE4Axf7>uDlmxRzwa2p z3FB#_e-dj4PC)f|Vicl*)H;=dbbI37XbT$Uy|C=H*9)V+*iz%!o4*OSAdl3?srIW4 zpmJrLf9_OKDnrhv_6xRodHsT|`w#DrV|==TZG2_X`fJU@!|PxD$k(`W;~@yP>F@qy zv?X7feQI|^L_}di#HqN5EwQn4TFewH$2|Hn%wSRs8eaJ+%D&~YQrWgo<$e@L2!U9AqIJ2K764b@!jR?M2OGTBQB+}$?O1Q z%$IK-D#q+XtsT5W{k&ORkZU058gM{;4$}_i1ZeYQc`peBa&>y@#&%Yw>Nr5KPOug~dc?p$K350h zd66mJn71~9FuC9d578!r57@3yXml!-OlL4D-O~lgk=bWH&;cf-06u^x9Z-ej26|&+ zJ)+qXE6B`OB$0O3!yv#8G7;`t{=Y>Pkj=nc00Qk|gD!y4VS}<2FT@07H1$z3Lf0mv z+9>LP&~zwN9SS;+jOdWbx^O>8Abc>?7}Rk=BJ>{&m4lQUDiS*YmC)B@8#-7S8qJ3s zd@+d4k^15qA(;}YaU$~m$Dpx|80(Q0@&=o=ea)>EZylaUEZ_j^-~#cb;ITMNl*gfXc%f9T z2h|IqdoZbpmj{D`czYw>T+EBiB7s_3r_lWQ`kfCl^lNrQ@Gr5wcCMc4&*mxsfj@dBTG8yHI=gR^75 zHaZzpljYk`FqGPFEJ{Y1WKhtPhXeQ+w4Z23P`q|64+rouSRfVKw~dOjewu^K0+$r} z!OW4kXZ)5&-!{Oie(OcaRG_5&;ixp) zPjECA+KZJX>wzwVh$(?ie>kF?D?S>&@~9Q z6N$i;9=t{f!4^WE2m*-l3r7|vkgG1!6g4GN7MUz!m>QBO%QNr!qm_h g(f`j7?)YsXiIgLj$`l+WGs$!+Va}XIHl~FC146RMrvLx| literal 0 HcmV?d00001 diff --git a/paper/figures/CollDetStick/CollDetStick_Format.m b/paper/figures/CollDetStick/CollDetStick_Format.m new file mode 100644 index 0000000..22eb05a --- /dev/null +++ b/paper/figures/CollDetStick/CollDetStick_Format.m @@ -0,0 +1,140 @@ +% Automatisch erstellte Bilder mit Beobachter-Daten aus Versuch E054 +% (Gegendrücken mit Stab an Struktur) öffnen und neu formatieren +% +% Vorher folgendes Skript ausführen: +% experiments/evaluation_settings/ +% atlas_identification_experiment_test_settings_ImpCtrlE055_R04.m + +% Moritz Schappler, schappler@irt.uni-hannover.de, 2015-08 +% (c) Institut für Regelungstechnik, Universität Hannover +%% Init +tb_path = fileparts(which('drc_paper_path_init.m')); +close all + +% Import-Pfad für vorher generierte Bilder +eval_path = fullfile(tb_path, 'experiments', 'eval_atlas5', ... + 'ImpCtrlv5_E055'); + +%% Teilbild 1: Achse 1 Drehmomente +% Speichern der xy-Daten +X = cell(2,1); +Y = cell(2,1); + +%% tau_mess, tau_modell laden +figinputpath = fullfile(eval_path, ['R04_torque', '.fig']); +uiopen(figinputpath,1); +fig_i = gcf; +ch_f = get(fig_i, 'Children'); +% alle subplots bis auf shz löschen +delete(ch_f(1:end-1)) + +% Datenreihen speichern +ch = get(gca, 'Children'); +% ID +X{1} = get(ch(5), 'XData'); +Y{1} = get(ch(5), 'YData'); +% ext +X{2} = get(ch(2), 'XData'); +Y{2} = get(ch(2), 'YData'); +% obs +X{3} = get(ch(3), 'XData'); +Y{3} = get(ch(3), 'YData'); +% ist +X{4} = get(ch(7), 'XData'); +Y{4} = get(ch(7), 'YData'); + +%% positionsdaten laden +figinputpath = fullfile(eval_path, ['R04_position', '.fig']); +uiopen(figinputpath,1); +fig_i = gcf; +ch_f = get(fig_i, 'Children'); +% alle subplots bis auf shz löschen +delete(ch_f(1:end-1)) + +% Datenreihen speichern +ch = get(gca, 'Children'); +% ist +X{5} = get(ch(4), 'XData'); +Y{5} = get(ch(4), 'YData'); +% soll +X{6} = get(ch(3), 'XData'); +Y{6} = get(ch(3), 'YData'); +%% zusammengesuchte Daten neu plotten +fig_ges = figure(); +linhdl_pos = NaN(2,1); + +% Positions-Plot +ax1=subplot(2,1,1);hold on;grid on; +plot(X{5}, Y{5}, 'r-'); +I_Ausw = round(linspace(1, length(X{5}), 25)); % Indizes zur Auswahl: Alle 25 Datenpunkte ein Marker +plot(X{5}(I_Ausw), Y{5}(I_Ausw), 'rs'); +linhdl_pos(1) = plot(NaN, NaN, 'r-s'); % Für Legende + +linhdl_pos(2) = plot(X{6}, Y{6}, 'k--'); + +l1 = legend(linhdl_pos(1:2), {'$q_1$', '$q_{\mathrm{d},1}$'}, 'interpreter', 'latex'); + +ylabel('$q_{1}$ [rad]', 'interpreter', 'latex'); + +% Drehmoment-Plot +linhdl_tau = NaN(3,1); +ax2=subplot(2,1,2);hold on;grid on; +% ID +linhdl_tau(1)=plot(X{1}, Y{1}); + +% % Ext +% plot(X{2}, Y{2}, 'r-'); + +% obs +linhdl_tau(2)=plot(X{3}, Y{3}); + +% ist +linhdl_tau(3)=plot(X{4}, Y{4}); + +leghdl = line_format_publication(linhdl_tau, [], {'ID', 'obs', 'ist'}); + +l2 = legend(leghdl, {'$\tau_{\mathrm{mdl},1}$', '$-\hat{\tau}_{\varepsilon,1}$', ... + '$\tau_{\mathrm{m},1}$'}, 'interpreter', 'latex'); + +ylabel('$\tau_{1}$ [Nm]', 'interpreter', 'latex'); +xl = xlabel('$t$ [s]', 'interpreter', 'latex'); + + +%% Formatieren +linkxaxes + +change_x_data(fig_ges, -8); +xlim([0, 7]); +subplot_expand(fig_ges, 2, 1); +set_y_autoscale(fig_ges,0.1) + +% Vor-Formatierung +figure_format_publication([ax1,ax2]) +set_sizePositionPlotSubplot(gcf, ... + 8.67, 5.5, ... + [2 1], ... + 0.15, 0.02, 0.02, 0.17, ... % l r u d + 0.075, 0.05) % x y + +% Größe nochmals anpassen +ax1pos = get(ax1, 'position'); +ax2pos = get(ax2, 'position'); +set(fig_ges, 'papersize',[8.67 5.0], 'pos', [0 0 8.67 4.5]) +set(ax1, 'position', [ax1pos(1), 0.68, ax1pos(3), 0.3]); +set(ax2, 'position', [ax2pos(1:3), 0.45]); + +% Legende +% , 'orientation', 'horizontal' +set(l1, 'Position', [0.44, 0.78, .25, .15]) +set(l2, 'Position', [0.44, 0.43, .25, .07], 'orientation', 'vertical') + +set(xl, 'Position', [3.5, -13]) + +% Speichern +Filebasename_res = 'CollDetStickIROS'; +saveas(fig_ges, fullfile(eval_path, [Filebasename_res, '.fig'])); +export_fig(fullfile(eval_path, [Filebasename_res, '.pdf'])); +export_fig(fullfile(eval_path, [Filebasename_res, '.eps'])); +export_fig(fullfile(eval_path, [Filebasename_res, '.png'])); + +fprintf('Nach %s gespeichert.\n', eval_path); diff --git a/paper/figures/CollDetStick/GOPR2201_ImpCtrlv5_E055_part4_t036.jpg b/paper/figures/CollDetStick/GOPR2201_ImpCtrlv5_E055_part4_t036.jpg new file mode 100644 index 0000000000000000000000000000000000000000..a59e6a3ff984206f952c2336cca7edd6d9889270 GIT binary patch literal 206148 zcmb4~WmFtN_vQz8Cy?MU0|W>X7~I|6Ed-ar-62SD8+>qrYjF4A?rsST4#6crHt+s- z_q<=X`s3}>^_=R{b#MKizJFK#?f~!=WaMQ42nYZG!oLgfcO4)JKu1MILq$PHLqo&B zK*z);#=*wI!hT0cghxzCMomRYMnORXVq>JC`v9b%c+bo9f#V|>45nt}7v|#>V&ejH z{^ubG7#JAXSlDlIaNcs#QqXe#e~-Vt00MMm8Z=cT1UdjB0Rj>M!rvbN3IG5JfQ0ZL zz5jP0AR-~7prWDwi`w7=5Red&P>_*Pv9Qq4(UC9^0RN%{D1@}AM06j;IVIFhff_Df z(1^Lrk_z6CNNT#K)b-8I|0V@#X`8!+gr+v^>OhkVztu0$gSn;L2j(u(-}1;$pHM1j(;(Jf`79jA|N6oqaYz6AtU`~Z4r?O36MF7 zXz4zpyy21%*U+q+B?hX4&3=PSzqq(2^+^`g@BUo_VE?-rkpPJRAPRVB#}Avs52Haj zZPpn;%v>}1#fkM7pi6ors&H8fy(b4bgeca&c$%F5R8MZ))FdB>X*d4RX}&&cIl4P( z?&fXZ_GeiKje9z-*JU$?jhb=D)MotK3cAi2(zJNRY=2(IkII5cH;QMhEa6Wr{nx(F zf&mk&lJ@K~H1Q8+0Nvk#~w58s|TY|k(vTRJWn{$iMcBs^w8R#B}nkUBM+J=fx(5A=L(XYy{o zTzyrY1lR3%oF;dmt<>*NI4p`mID;5125=&xbwm__@g{azw%MXvRUBzn$8|}812=~{ z^YsV(ylHw=@C%tv8*CZjU+gp0Uc)KZ_thm}guHQBDHqotQG@&?h{3PIr}W+~L5tco z=3%}F&NL_wZ}Fb3kLYm#1kNDzV>5?zsT<{pVuIb4#i1xQaUNkuZ}_#&Nq!mURO87l zJHtsDDM??T24G1wh=V&isy)kzeW%&otQkagZ%J7c{8J46wY0skSuzo22 zEz%~qU`-XKe1=>*a1F)mAryb9_F+27G!PUMns2L5%h8xXWSo%bH#MIh6+9XhRyHQw z+oA_;3S$2Sv_uOk`@&TZH7%~0XfrwN_t}IO6_o7MM~b(Uo13$fSMXpN8eE1EF!TDd zzFEO?M&YdbS3m%f0y9F1ZdfP5jGghg%xr>%SO|dLT_br=)0@Nrb*vESrQqQb>Gfa~bzbsx!)lDYYI>fJane^kb6VIuercB0N zb?c0RTz>ziG>`Su{nl%``Evz_!eH$?_m5lbc=+qe?cH&=Q)qi(iw%?A2?Ijk&x*i2 zddssr-P4A%9R_M-FBrsMeNZjq@M@yEDdHTXTFB$%=vFcK&&SRO@ zzR;L2b5p-fg+y+)yq-Q~(Yvg|*99ZG!=KpMd4@$ONt+sIJ|a;;t?|d7`5Bot*Hk~- zd8abDVxqAzdL~t>ySLLCd|4#hf9ZVVweYq00ED)a|4kxw9&o27!F?8BOBjPKws0fub!}&IGLXPYpB7rauBJkQWP|A0M82`^;M;j|1EH8~ z_=!F=*Ro(YR}iC#=83}nyDw)Ye1>cHMF&>40!4*B2>Vkzzf7pskA;V}%;FRFvJXp; zdL3(I=em3ER@h{3`<9&78u1~r9sG-om5rS}aQ0TC@bR}c$LqCwV^d2qe$ERc1Z#;Zve&o{t z-2im#*mRcFbQAI-43CgOXMY0I9emQUMpQ7vb;mjZ>e$fZu!D zccY>mQP$~=yPMd{&pI5F{M5zvf{k_jRbJ^$rW)cDfso|SlivdJ0&YbvJu$|9IiMTa zbqqExsEi&K7eTj=R3ARn`?WujLl(5RJ#r$HsCqfix0=SW61p6uu)ix9=7gV3dwiMQ zHneFt>f-kF*J(dkjjFR86OJ~(l?%U_wHk$Mk+4NT7kR(?2o&wE8@}VSAF%u~$uB%E zX->E1t|9pc!lS|+iz){`4*ATw{K(CYGA_98buhZFH?rTGQ$bc-^XCBZ$FF2Hw^c_u zp(Ql#7nQQ=P%2G7V{=x1G=!0cw*wLbK)^A54Ce25^L@eH@V}uP?Tp(&I93? zlHGBw4YncM`DU>3e@Ff2m9SAHDx4FG?LP!E& z@ma9=nRKNa(60k z2Ca_-39LE1WWM+Pdi6M#wSoy|USBc#T>l%cTWCz&c#?@=%-40i;0%}UwnJQaU~~d? z$N}5=3n=kF)0a+(lQB*LPQ#cew}=UoX5|-3X8|Tsyd5X>iyFl2fyZn`iA3nMZa;%H z4z`r2BGH0Ck+OeAzKc`Ny4S=Uh9V^=H*J)*$E%2uI%>J^Djq6x1mJ6J!}IgBL01;V z&O0$hzdnb5xYi6Lt{xtx5RpS$)2wlV#lw4=BPXx_0-OpsN|;<`=^RsMaGwL^7$Z`X zW^o}A5{VoJ)b3F>@abZf<9OMP;41iEfUq2#pcE#+IHLJTW7&ggGRJKEz=YyzCsn+4 zUz(BZ&Lq|*GNPCvYrC}&5>x#%w$qMG+vHo)C`+LM)8x;XjzQY~MrUOjM;M@|PEB9~ zv}J>qrq$;zYdhKkGbYq%19E0}|8PUcs{asX#EdfCnWsfdLl#3$iw?-sCXt@&8pAd! z32S$uiLezk;-~W~I|EryQW9xSw`WqOwSSpq9k~PiIbMIYKp!V zina9KREeP2nXai*|Is%23(#a{J$LA@V6e{Rp}NF*(n4@Eom5Jt3xQU2Vny5OTRBmS zjlWv7F%Eq+*N;70^zP45y;EqeTd3pFw9n@;uej!m$BEiq$x%jSR91asq=G8T^En`9 z)1PYo!gDQYj+gdZ0jzlNWfUB}eWq|PDEW0ZmZ#+%1Vz~WLo6(k+?IkjCt@Ae>G`uW z&IGrp-|iSyDg`#m8UxNKFmBU$MyOo;e#LipCc39FPQaD#JMC z+Md$7DA}l^cE8pV{?JE&`CMs+T3=y4OCMja3z{f~o>9`P(8{Z8DxwCQFhvBu#s%>1 zRAA)Pzv0`|vVU0OHF|9L;;J_-(;HMm6>u^nxU)<(RFZINuWUteviGC%41u*dH(@_8 z^)Ax($mXcrmWhq2+|&}x!%JItMJ-VY8HPHYH(1O`SADNTgb~cj1&7&Cq*)pv1QO3( zN+cQy8OhmM!-x;&+a9uHxFG97|qTM4(qnr9-)bTp#MxCJFX?r?88 zV`Si_CXQ2uNLbVD!`UC3M0v-^@u3KUlRr@BF}VXv!?*ldKa=dxFRbnhCvQcHMsZKu zH;Y8~ro($UEw(G<@#kLfg`krIlbLgFhK}GUlxE9yKcA9weMk5A5N|gyQ*&mj-UDe* zh^|(E#n zRZfolwbLG>qwZYJj^f0qU{z1;rlaczJ?o$`x38ORDi6I_^_1gC?htETB_vV5RZR9)UlSi|HkL3&; z80T+d2j})J8wk6j%EKD?;dSUfklX4~o{hQrC7B;{oBo$)YHUH*hBb~Z$@Fu6iWjw_ zU|h0bqOom-tm<;wi6Dgt39>%7QZW73LsgcwfE=v^yeWJf3?qU`@PBd{z3C1NACIdu z5lMa~&rGgq29N1Vg95!3cqCng(@7%9GCscL_LzdqKw;p>7LRl-rrQdArmekWz$T$e zzt$%^okoF>Buy}zZ!8;uidC<^JvP63#365P$w^53ceX@0?s^?OX_)s}mVen$>}3zC zqj{+r{|j(T{?nS~BPi7o#)LRck@;fKP(GH4d)PLBYAi;ni}&U)pu|~r{ruke9w3Gl z6(j5Oy-lFIhrXvmoz;2$PpX&A1J1Bqk(%E43ZOyCOOt?Ql`5k7XHjEUh)maz&}MT8 zi5|DwvH2cvYKGkv{@Nt)wfXa`->u%}+osp=%~|V&CeyHf z>0lH)dkyDN{}@BD<_&JD#oCnpdypNgP@~Q&naG_Fqn(sExf)(x{ z6jGdD>5h3Pi|5^_rA6gq9frga?qcY%NHP7qaFa}?r>`)e8{uY}Z;TyHDg_~q7mA`F zAIG<;p*$p|BEg`p%_Eq0(o5*HUAv_)uoxJYF7;;wl#Vd@@w)4%wbX)4Zh~8pF25+N z2~c~g@+|t1E%&BTOcOD$zX#^oF0~36Z-pL)1ur67B)kE#7>+P^Ko7q#Zr(GLGIP;P zJ(ZLe`T~P(G=pGYCK2Sl0>(V*D<5fa@4@G(v+l9yd0cCn?lah)m|n}xP~)`xg(=&6 z;W4D@ijgl&XdKr{`@dxIptb~1$J8+~FG=+Pd~9-?_&MKg=41%1;%vF`l493|_LkB+ zcvweyK3NvC!Xc-V1^vc7^Ih3bO9=zZk)}s`cR|VaoEg@;%qKvHYO&C&Bit}ey9$S`wQ^rYDC7{j8 zeEY?oI*o0iE_4CBA{&!!(-~6Vt$C2Dh`_G;RuRv%TOMr}Kz8_!xKM1Iy8B$0-1cJ? znjORwYS%K_ne6HOePl1`+yaf^w>$ax3xbXP)S@8z4^LP27}MW_k|u3su(wy^A2gkX z=kVyz*a4Nc8M-@vy0#f)MPxf4ax@;xyRzEy&;=S3gXje8N-Pu61ycAaW>Au5Nfb6W zI+?}S!@)fmB##xrdkgK%8b(D(ljvlnqaXVKThShnoPqwDU&AMA=aJmUB}a^l_> z!jo$>4oSpVAb%fk8T!?QlV3k{0k{ z5-9!{EQj1-yzuF8p8ZWqrX`7HyVbow7hw{VAr_>+tqJLhT+bZ;@otheICEsExbMw## zewo1;=wg7&4ximblWoeDwYySPIXbnL`rV4rjoKWDT&QtFdmvhj)(>{E)lO{Ubdvgm zg_VbFT6#<&N#Mx;8W}m=yGWLyj7Mwge}1{t#rfg;kK$S(D$u0k1TzRAst)(%@}h zC5ULh?}?VktnnlF;y*u1A}7+vDmo>ri*<2V>UfvqmSr|0-U^g-r>d8$$A?LvVa#ny z;0Kp<81iS%JD&BgVz|c8^K>#$G|2|Ou%a`2|btZo}(Eb9-lwbEbAAdfP z43OL30XD+5Pa)ZgWAYoa#@v^eZ|PL(fh_an1C&?_vb^SB=@KDiM`8q^_uQV z?g8VfVN|5>rTKr{<(Qg<>q2oDa~u}|hgj)r4AGArH}KREZ_-~tp?3J_rNXW!8vToSta`Naw|RooH$yt z`!6T14fbnWM6%~JwHk>g&5)Eao^(z!?vu*(u*4}|8z-xFfBb?s8B%8O@tu;&=nzrF zld@=m`Bv!FzBWXRk~q{_=EMd(FOV3TOjUI4H|P}N#Wo8l?+|K@Fx9@8V%@yhFyfbw z-;W2dvRp4A;NIKc=`egnqtHPk_m-wL2~6D56}sg$gx55d1*=4M1ev8vOTzXz&?kZo zkH1ym+u4EZrT!3ge>%q2@A)pf^CxjWP_73`ND*Lx&-qlg>#96{AzsT1-uPDNbw?Ao zS`{a33A%JH4N$MkSx6q-7I!T|JdAmyJ9gvQRC}`*lad|qPO=`(uii%v9Z#=+o0U}f zxu=jI2$tmrzH8N_NXg`_r^uK^*Gc1idjY6yF9*f)LX#lw3a88srE300Y!jux?9(_Z zc`NDA=Y`OpL6p!l!8MKX0YBQ|h*1u1s&xicjj)cbJtX-~=va(%KDiIwldD{5As=A7 zW4usDCQa@z*b@`Tg(i1oG)(c#YVD#EwGJ;7+b{G@{+TFKjE_iAAy~FUaI2{>meh+u zs&`3zo~!}`SzoKgAlu|I*tCNcRfwaEjF@aKJT<+*WQhXh6aJ~V1Utb7{9DXWC(sPa zyc0NSQvusc4ZbSU!_WF5xB&8dPkaVs{3FCZgDdTPFAs!VUt|?uMpnQ{qFC=wmXjE) zyT}2P%n%O=c5S~CBcq{-FOfpq^8cSzW`)C z^1}XOo|+1pRY?5LU?J;|(%XT#j92Wezf;9<7teg+dFt{AN^+_pY>Iguw$Cv~f&`H* z1S`kh6k?vl@Lk8dL3|V+%I>Jkvl5Pt4Q@e^gX>Fz!N;Y#KvPn9w`!#_i**@i{atEo z3Lf?uGvZ7ih{*mN=lzTzPKifX-B3#d3W*Z-K%d$fiV(kl(%@cF#%Y2X;%B>WOLsJ_ z2Dw*UF3c+8v>ysb%Q>AuvlcWY&95P<@EBm*A8%#^bZhXR?!92wyaBDEyMU4Rq(6JK zu5J6XI^=1MNaw=zibohEOCo!!Qg2iak)kFw9a)&W9?RP`WQ-R%eSxs-W~RIy&*msf z*L}I%v6@Ka6Wa1z8!<+PbPq70A1zO8x$)>Kn>g->_+Gl-=Hu+Z+}57q#z1v|`uz4| z@`P)#YY5vofi;?|jFg2KZSBLMpo>i5E0i zTEW@nUWuxhx=KtRMvHv%lSlh#?|aG(RQC5m%`Z%*uZst>BJ!YSOEOU*6Mnk9@UW?` zW4?YVVQ`#x@sR@5u2zpKs^x66N>M+&UXHz=Uz;S;V#p&1T8~30nEdxuTp0G{7j;ns zh&ir)wRcBTIQ9D$isJ$VK)bc3A17b8=hAJi6wfi}F%re)0rd%LFX$a^cTIam5r#L6 zF3GCNV(htj9;1JJ%Fet&SW0d4j4HNQB6gCEvu|jYZV&)X4LmAedP|520)%9br2Wz! zKe03TSV(S5uTI4{ypN|K&9*@DVcZMcpacZ=Wi&DaW9;T7##z*lk6nU#?ggO&6Sivm~#G zJ;xPen_Sa>0aC;x%Mpfb3$0SRyD$kI3=Ugd9dS+azW^NFC_~2Hkv+Rw>r*X@hRD@g;_5BDbN?2%?BJ{{g%-X)+3W>mIOf?rH02YYriFEZw%ad z%5Rux9So8(aQ+3n?-G9VhMU5{f_U=tZO4hARkhl6V+V_Rio7AcpuyqD=v7D4X6ZoT zmotZKAY-DbF%>6;vEO6Wrv$DB4mLly@h3Ne1bU;HufO-Oh8Bixaa(3QJ{^$wyqV32 zSDKiU-eV~or8NgP$N2Ny3UI#gvTd24C_J&S;xG{u7*n)yvwJ_yUQipXnZMn&$N>n= zlQp#!SbjX2-l|L6hpS12ZE&`RC5of}!{GSA|4d$FT6BZ}QZvyzi=g#?=+QIP|0sak zZ17Gy{gqnu9z4eBnJs7@{!O6ISnWx{B$m5l)MNk)j|oIcGELV=O@90_eZwjgFJZeU z`7fZcEed>7HE{G!kvz|P$m~A%!Ju{Fvsngqpx|;%ofTyDg_QRV@T?ZivVrU8-0vWR zhVdX?S=j?v{ZjQ;{eO1X3XYN)e<77i&4~pb4pcB0enDO;T`e(Vr{C##nbpFnDy&m8 z*;Wd$Q1!+wO}#ldG;qILCvW(9S!1o%y#2GT70dnfLz`=^{I=GX;#;yR(@ucNMpdYT zHbI6D&5Dl)I*wOWJ=VVDS8LC-5mR2hZ4{sMkB z*oa-I?V;~ zPan-G99vmzCwf8_la@R+cj}s8I$0cAO+}99?7NF*o1L5Kq7vuaA-*yLEGp+JVTVnn z`J?ZkB!esga<6KIZQAy}jaYma7i#*}a*N;L_%8-zXWod3z4wNNb5&=j=l1l%uLRDh zLWnCln(Dp2^(=VR0dXZy`)4RuwW04Pvb>KrypO)OZ3LVn1ZWo*>|9u*iQWcQ#d=y?oVo&peweHm zyBf=NO~*U4czYhWh1qeY*z?Exn<5Rtf-zF~W>^Q~N=5&Y81R9)=~kS@OTLW2xi%?6x1+oG%L8Z#B5@ybYz^s z!7Z4Hp3Es%!YNit)OAR|HIDl8ZZuKdjOkM27HLR9+2!(=3gWqn*dz~Az=6L2J?p;! zWx|Q30@3a|_Jhp7fO)AXhJ6;;SlOOmsNS~R0hO{j8R@7e$^r4(Gf%q?+%Ie;W_y8f z_G$kHr#wTvuJyE~BTvCL^DK83=_avrxNkwJ;>X8W@fwsmSz>I`3sG&ZruS0LJY#cE@t1kb8Gus!9vZp@du`sjUr$;Vf`h z_W5IREZb4A;QNR7y_eAd3J|T9B+FQ*bu1-C4|up`c43=u>>vTFAAP14FxJm!klNP=PYCRiWO} z&v-n38f<&F${x3vQUPp2pTH` z&^jkxVB0hFZd7rKlSjIlw;I%x@n-|5aM1vhq5@xczI$3_0`MB+R6@H<) zJ}>W8iaT9)K%$SsZhCq0@*jT{g}ovhHd)wZ+%c~$TJJW#_N#TTH*0YO{l2Pp`$9#- zyf?aG5mPn`8{o{p=P%gR_Kl%iVg5M~GIFG7Ss526>KElJAfUjE4l~1b@9sR9V-;2N zN``DY^88V^U#br(sch$`xE~FWm*d;kwQIec_zUR9%A-$ha>(I`{nK+MXu%o1AF7CZ@J@WNqPoMnZt-oaoog?bbPzM zS8J2Kq!;H2OV)*7EtUV-&V~vB)NM#IqqA)G1ZW zvm(3b66pW@`Ttns{~;N1b-1jnUbrSb`~PZ)O#i(r6PXqN9thj7`CnJRgJd%Q;f&3B zE~dh?63BUZ0kqI~I~d;hyERtN9ycjiYoT4Cy!SF07HeGM6lwbIKFHGUoBfcoFtYhv zO&An|!iYSnmVWa7xUO35E1tqRt1d$=OLISP4)bl^+0CFQkd1aV`sdK;x@9ye&w82J z7dOj>j@{Jt^2+k?3A&t`Zu@Gq69aO-%>}(|B^yU23AvlAFq96-cQ|Yw>!0gP-C z2U1o4a7%j8SS~qp_cz-lZx*I#1uhf)4w$pS_ql?^n6Rx&mYs(1(O$Jgf zUTuauLu8{>Gr>v@=upH13QzsvkKLceea(-@r}iJ_Fl3ZvBbqon^!s<%94_9|-~BT7 zLR=SJU`bZl-bToDu&!dYR#nzDz^(%fi+a9Ry1v8uYRKC%!YacXo_5ZfVQ6!0Jv~&? zER-g#4bmoY8#V8K7#z(-dUJhk+@_*EQU30_VbnH$!v3ZQRju*Y!>#rMF#oI2U%-@t zD%?c&kTmjvE8)IbROF%s>|%BKon`&TSpUE_Z20?Yv^fm3I4V(;o6KMhBq*P!4VZOz z7bCr(narLY?cPJ(*76J}M=>U?H@?V7CR#uwI!U6_L;+-cS)p!`0)Go10p}8>PM&+F z-t4x3<8_*V54OLPorDQCUpk4rxOwKclG3GK!`l6lMm88AlbP@8?^EErs0!#y{QB3+^qgH#n#eQ_%}8FP=!At%x<*@&m;_{#QGiJrq1-G@XMMXkR8KnJ}C&#r1`BG{NN&=ns+pzyFgyN{!TY4O9BLQSyle7N?4 z3pc6LO;;o)#gJuO{CA9_yyghsdyO|WQI<|+#G9*G9yTa}@-tyk%v(eC6QD)Nd#$>Q z=19`|FOkVOO{pIDDdp61WAd_&KrjB=X=2tSwm9Q~9+jl#)ne z*SRt)8D&<`g?{rMSYeQH7`j?tEW9uxsI1ed{Bdcyd6)~E@g+N`(h#?P`Ln3S$y8&UFimYNa{LZ8(ReP>8X8TKo$6vsC z4PL*8mW$5r44*6;JgjX(*ys`PJic;zOIxriM3Q;$Hc0H`BkJ!w71)x>ecf0goI^_f z{SWDc2>$P~5L&~1rI9ahZZrnKq4MeKzRprR(%ilIJ=;5Y2Uw;&_x@KO5s04RrH(4Wh=p11;I z9$L4Z{hH3LiUq~*g>%h!imxmLq>GEbBty`~x8M~>As?!LQn ziF)t8+J}3|AFDgLhfZP$)~lT>0Dksh`oFpoHme1*pDEdu7Fs+K_X3rgl~sMz#ZiO_ zG9G}VsK!KYodh|+<&|Jxka2(lCH&-@iD)%N$OOTnAe9_rXEs1%?x_4QSb%X2A|XH@ z1S&!#nq~Qe@58;ShPejp8t8}V?#fX`xvQ4qB$i=sbF;C7UXHBp^3mwse#S0Q64F-7 zQMP-j`?%EMXax6oF#>$H_OrfY0fw+{`4>vo9cq6jEbhqj3+( zw(=Iwt-Ta$6S;_vLZLa2YfB~QFY}ery*MF}A}W8OcAEGow{qMHxyR8fJ6Wwh7vDp& zB#VW%bRM7<`CHFW`hHz)zp!Wz1&7Q|<$H$sNHIFcw8-;6i6UBon`-i}U!LaJx{LV+ z9_;a?k&2)3?O1_L{$uK&VTG!Aq)X*;r+8*$oJ|OnZz8OioL`sZ+NTx{XvLG;P;B`O zvxxVX4=Uw1Spjm#IJx{jEXhnhE<1N+nx8y>!$0?=M?cmq%-7?TRPi^!H|6P<=j;rD zM{slCOd}SRB77x7aEO1y(ck!cg|RVjM;aXAhuREW&jU-)@mJy7p|%1yVTM-7Io|`} zxamOt9b;k?g3IFjYj6)8;;j?ZB8{U*I`h;f_JKYfc-7S&Z^vo{s}p{7+RH3wJ(U}@ z68gbvs25|Wu5Gtn$X-?ECt79bK@5iy03R}@*7`!z>WhnuIz*#S7rD<1G7CC=xDM-@ zx(vQ&UONZ!qKbFc>7$6bajwC~vn65dokDF@;YHcws@OM9ZM{@zhFf2ozE#YcXZzqe zE7vyg2PiniHaYQU8d_aeIZW)1es(ZlJ4YKTZ)oLklZ~*e)tTH(-v{57(X2y|GuB^@s@-*=w7>c7!% zPfM4^S$#sG(4EynWZM{5zU-#qs+-M&pLV^)ZF#7KWE;Q}cc$%nj{lu^9MvU>2M6#WNT{13k%ZC{Bp;;1O= zWaQ+|n@M;k4HrtUU$NC!1xrtjcGeKQIOmtH9%dN4bkyLagWZYM=Yw%-K#!_Z?WpIm zChcvlBwo@nOXDB$Dt}mvv2Vn=gM|1c1r_rc_vwd>Xc>Dloy(Q)LTwoK?asEJ=nrjI z{S)I+S9p(ReX4L>G*xwVraKm=)lY9?lDR!rkNv4SJh&SguvjTOt4Nqh;e*YQjZdO+ z!yQkEYo(T%DV}+S^ZgB~+VKk}EGChA?61X6^M5`*q~0CdAEoV&Pk_!eS_pU$kK4R7 zeVP?hRuHbWH*16*piNo*`}q}qY`a=w_Y9ISd&hW2-WoGP4GPLsnk}kf#A^2IIm)bx zdNpyN7D5Vxq~}m&5KD1$tQPhD!+M79;M zT_=sVXK)KIoaadaVoUyQ(pN^&h)=)&K$(m;7jDGUzPyuQw=j&@fXSF|DeQMIoF|=v za4?KXl|qsq|M6n4_n|DHpA}=2KkP#mjrVHP+w-Kn5&@WQF|IOcQ@IWzW-{h5&ZD$7 zSNXv)r&=~J!UUsdm#PnDNbP_-%zj^(aF_CoaOZi8)Xx7X|fffsUSdeXAta0QO;^>CHMQ^x6BAKa8NwqD2;9Bmq0)Ey2jpcn75%KBKgjU3mU5 ziDh{B)DR1j;6h^!wbD4pX*ls<^)Q29N2AspwK*ko0ekXUkvZ{t^fCH&ing|#RX`t7PC*PQt2JylLscYooKapNDS)XxYs$`tCAY z?CT}2@Z>G+`zy&`D*>pqky>21eTSeQ5OQ)Wh#751GrlnW*xK-&AjPT>Pg?EU(hxpo z6MCWe(qx}@pZ(55$L@&V@}d5+md5eZ{mE~Ic!B4SXnrm}O|o>|P%B0pI=wT$&Wxx{wK(V;2wF7%k6fOIg@DNp73<&p5B{;U~wd z!Hn=VlXzWKD{x45#rLv05J)B3G~-e{lh(8coxq^_l#aZX5Y9H#Wif7HqFLa|Jq?)v z&3+H&r#)&0!~XcPdi@X!@=-8TU3;P_3(cixvd|);6PEg9xlNud69T%1pYXXHrowBz zwKN-C4XKSWm6IY|jDC_t!YCc%9DZN=Ihb%lXvR)&ys^D%iwRdAL*omCCc-Q6*R`63 zea!EQvo`?9j}W0w`5Rd&1}wo&b=S~IP#cN^L16&lEV9(&w`9%brYx<<9!r2-I+o!M z(X3({4Vs&JiKS1Kcca{=t@xu;9CP8K4YrUo4I-w)5LKzO{y6p%pjxthIVqOsjkcdB zv~4_{&5MR^b@fcs^u>5lGbdyD0_@ zmzcPg9xUBUCJ^jAsiB(p5`p*8-_sAGBmZ);V=sZwZbH)?XasXFCPKJ)264US5^>pf zyf6y|kKC*Fyxf4iWFd0(Y!`Z^%kj@mvQo?%=azXIcvy|!7b$pzsgy0sYU5;WLube)H)sK=Ia$kSI$wJ{WuSEmt|F*G{;CHL)xB2~e!kV}oRPre!B538|d0CwVzIqilk2Ar#EF9CsyaII=9vDwYb4PeIA4=uJ3KUX_`9S zpVC>h*M}UVTV6j&hbO$_e}VLz*+qQa|An+w*A{znQ{5$N_(4@jd1T3lX;X>aJd4UI zHJ*-QW*qBHCz5jHp-+vUVO!>`H;VQxX4Pmv-(#73`1AB!eMT<)caEg(SY!#<~1x~o39W+{EB`^E-P zbtJ#(@^aOoimJLnkaZ-0d0m}6*Lzv$<3_MP)`l!HjBZh%{g2$f)LvZ$@CYko{kP zP9M6&Y~=s5RsdHl3p+{O9|+0f<7#tx6OIc$>0Plbn%-hZ?ED1~SV>rOw?w_7ffO7Z z6tf3+PO|;%F(XC zKtJcYnq*b@a>nXz$7;4v=XKl~wb_N4Mh1tGispp67KvX7+%%TJl$aniB@&1g@>(gJ z7peWhsnwu$VMRzR&&}P%VUsfI7LG zB%BG_h>$F&Od9osdTc? zB9mJ!x}6+PIFyED4|kRY2H(GJc&#K?MV%Z*TA=ogBfI^Y8A4)dUz;Y2yS@i+{=zE2 zx9YZc(sTy-loT6*{vb?i^lY=t1IX z-dAB;ZdOzroy*Y4`S#wNUw>mpmh<~X|ph4bw8E|(;(&@~}q|cxO zH!J0y8y&DrN*p^anN7g%P0`s(EfZx~EqywAC+AEV{#F0`laCRoGPbR2=pIne9liPL_UI@djQ7mBA@|*^3o66PCleG9fz|B`-E!qnWvpLo$;dVE zEvFx;u4;sR?3LuHpD;%0YBqh^FAlVzMq?IzB^Q64cxd*Wd3ZJ2O2reqiuoj5we3n$ z?aLw^7-3TpUOHW2;mcTO0g$Il^b zdscEx(hvW3S7jzw{t_YL#s{XI=|YuVCkDTHgz76ygWb{($6r<+=pnRAqkDOuz|?dX zzm?6KqYmys3e$U9>j~SB3$4z7lH3W>HyE?6dtm?ix_$suA}`!zrD*W}b!u=~N;hfu zl5LWr%Sr{ewFu+m=E^Pjjv9e*&q-l=ToIgb++Jlqe@+ zaSE0(Y%W+X0>Zm22iANWB*V;80eaaC=jd{Wp*^jc|| zr57&OueZvbg;HMNKrCCJ6>Wm<+7RE*;! zAUBbG$2pJw^9R||b@Xf8>o3dc2lh3d-G?9Rf;tbcz{n{Rxl8&94;nkX>+Jrg@@SZM zNm138WQ_%x!_v4H_$}7;5_`kL*QuXP8A2DSwMEWp7@6fz?0i`uT0((=msnuL-T`mD z{)9JUR=6{dpzYU%(?)H#g^w$7?>BY8xOC^gUY?iTQ)7L~hV5zm^V%@t<;UdighzhX z3yR~M(jmC3ZpD0)dhZgrEP>!~6&3@-)dG>5M4?d3_!P(#9p^@U+MX3-^JQX@x~`-gtK^|nE{3OSR2#DDFw;zo44z)7xA zKn&Ez)lrlmI4~ata9$r(sd1XD_X#yTm6fJ(zH^sfJCN)syIso=S}T9o5$T2H;Lg8h zZTA@|E7?26a~ijN#bCsxhd^%5!8JZQMxI%NCiR-PKE{8c)?&m`ZP(8jx2ePPi6Aq* zo!L1jQ1e8w$&0ZsYn0CMB<*CU9ONhOhHe?_0jz2U;rMsyktAqN?)PGKn6%*x)#3`k_yM zB~TL1Lfwy@Zl1lmAf=v-Elo&{c~G_e7ueG#$w)xa${KrW%c517FUPj)H_ygHO>;jZ z;imWr2W#p#VFFE1a*k?Qo>O?ccN7F$=VEx)=00G&lCq1{d^Kv81QDL4k7M33+0$kX zshRv=Y`tYyTMg8%3&o2TEe=JBQ{1J+-Q8V+2e(p+JHeeoaCd^c2MHS7tyrPO;W@nL zobitRVSmXO`2ks(>z>zrP2qcHP5_wHcMB>OU;T-pk83+Ew3O#MLjJ66Hy(yqvt%-k z%u8J(yrwOcfxSWb=nJ=tV4FD_YT`~B6`}eM0d!*kr##$op4;U+Xh3KpGg;z2-J4Nk z6}C~vgLz@HUL%|>buaOap90|rdu*Nvo!+C(E-x{;OY)m529@SeS~nry#$kfSHrDvA z4Bd$&RN0iVDs$RZ6Mml7{(s2p>t*6m@L%%eBO~lS*lSJpjq3@mcNOl)#GxEj$v&8* z0@aZZ#V==7xxyR?ynPd6*?fQHp5S_do+f|KBf}Shj1b4sDUxdb&#}g2opyF%UUNnt!?hAqw-cJtUpEn{DQw;=5iX5&bsA;W#RFsLYyB?3K^4D23v^-Hr6)7gof@B z3|rbXjD7z#4fTjvw~nxR%KV1_U;^eI1uTS~b!D)3%uH1NO}BBUaE6W~XE0AJ)^*!- zb){bB`CRMY!`Y7OR1ELV_E zAAEoujw?i-b&yM`9Gk_@DZh=ZJ!91kpnDf*nKnPjdub!;xf?K2xl&WUvjm`~<8BBm zKnst)(UM-DU!Ip0RgEPUQAPQffS|ADgx7AcIR!6piY%I;V$X)3p?w&xtC=r{ObVYzw<0q=X`5G_Nl9Wj9QAPS- zkw~t(CQ5DSo@f#IVqR@rFB2z&v(xj3$(9vml@xvl#$3Nglx3LSQ-afN(1`JXkL%&S70?9{k4g3ERID2c6}f#QS>5e){|9X%%VSH|p0@HXq?Rxc zVHjVZMg4_}`!~4|9R>Z<$xwOQuu8MceG<+A*+YrD^<|N{3G&GesDm@O0Y0S5Uy0uWio@?b|9R=T0`E|BBE+{vUeGA>YrF`?KH4y2yW!Mx zxmPs--OfXWr&bUF(4$Oa+}7)I5$C+Xkt3Puy%JB8h<0`C!S0nL3dSj+S?A_A?GXR4 zNCM+@0N5_TfMXtS&e~HFDVu#bz%R&NPI`BU_ocd|AENT`8F=vb(`gXR~ zsd)}@B4MYBGLuykjt^6Tm7X+Sx_Lw_3S;LJ9{$|AQ1W;s$glZ0lR{qf9_FYhCZhP$ zOG@P*22#l^;ilqQ!|E`97}+QZehI>@MiBl!%NQ*^&UIieYqo_V;zLFF$}K*BV@|m8 zj-(;sp*9$YoQ9V1_@|zB;tp*I#Vi6eO+09!vH0l4;pcJIVJs2H8|LXM87tDUV4zwc zhKH3C`?NgqO86W6BtgmRV$bWTp+!uv1-kA%b&^ngtg_^WH2fGkM|oDfpDH^q+Yv`! zCs&`yb-(jHfW!|nbhW9cx*t~hh<8d!yG`-n4t{MaFW(Ny*^2K7wrL_4NJL1FNW$Q_ zs4tRhxf!Q}*m6jyEK^f&LQxnI6~71VCa|a7KCpc6kS8jO@)NbJEG8@-;u5yc`*U8D zamIl&Sezr42CbG*i7byKET#w&sx+kZG1DYBr_bQL@d8+x}pso%-+x zi!vOBnjqxRk$7zSAA;f?a&@x2MTRdTJMk2nUtyWSuGBU;UGue5EB}=8XaR0IH;WZ6 zBoM*aAm~w-D`6+O&Z@B+MD;|~gV;*Wy^*?_b(J|(hFfJ`T_UhhZ*OJ#d%MgYs>8O% zX~gE7pE>p{YP&GHW!Ju8@_Q!R=I zH4;!IoJHjD;m)AHhy}mXqe5@@5E*yG{=|`Pdk@ZXv&()jBOX&24pV(*(!}5sZ?s2o zf~u&R_%ZIkqeu}=3hRe#GJVSdT*~+D<6S7&E^-UL{D+Xo&DO=Q_C@K7d}lb#_jx(# z7>7QkykMKpA5O#WbJc-<6=-iQ6;|ZeRD@s;mHn) zXXX~JAUt%Ysoy}I^*e@vEg(LsV0PNH((8KCk&SD12I?u18#~UBz7`4LOJ!8Yooxw{5!{vR~pv1&6op1+Hu%D?KhHdxtI>#XNL@g~hy0}2t zvOWl#^{X`RXB{`h8t9>1P_MGMZuCM#kn^%v>51IH3G|QUWDz1O(R9;nk%$>AwJ|^e z&55^m ze!P9lpNUDNqSHEnqCw>$$!SnWbxp~JTpIMcae`t=e#7_8f1^gF8?B{yX3`#oiQ*H5Tz@GbJyNAT6mzMzkB10@uvj_kbFwd$Fj)OecvVor^6 zUjMpE95EQnY_4|oT32|yA@r_ypxXC;uU>?^REtknXweND{(sEntwQT*v=YSUr306e z<5OzdoNLl4o+7&R7Mdm(VJ}FF=#X+LV89= za4Gxjwu9wl-tgnE^&Ue6Qo0@<0|tW+2~LSYo&O;~j9@z4Tm{NiIdbg0)#WwWC2{7# z2jKq@KHtft7xl!+9p8Zh7OiV)?6QiT)7Z=7F2E=;Yafyyc|@K=N5dBc2ujoIysZ+L z?}TezIO(T`J|{4*)7V+^RF10YR@MY=_&};@Z)OPT3c!Z49nlSO*WJ4ttsJ!OlXfk& z&tDok^vs~1R)aRjXOjsCyT>`y32rTw?krir$c66S5E4P55i>qq2c$@u7Pm!VDbe}% zdRt%b4*PmJep~PR=LI2^U#VII`#e5O0{kP^~8q}>vW^H8!oN9H`p*hO;cdp^+ zB0Dg9PYm?&p-!zK`Qw%2(ZOzh=hx?T`JR?h0M8hFs0mjt0JBa+lVaOYZmFAH-Jt@s zu9T=PpvGZwUQ1O#S4^2(UP!Y~F?(Me)Rcg<3swQq49xQGYX(F)0LYL=m1-we45us_ zCb(O22ga6K1w53s#*97cA55IN<7{cy(+r13J2|k?lP}P8Yf=c18=52S{HIQByQruD z>=740pwiOshK4T+x0gy;V4JY52Q{Vl!<}*CsVzriBb@;xs&g&%WAdBa`CDy|L~z*t zKOvr;>^oCEfxOL-v%zql>&PpRt4vM4XZcoF2KK#EipOz|Uj^MIi#lqq{9z{l;Z&7u zSVs%(icixG4Ko?7sBYu?8yit%W$uVQBCxOgD-cr?&gBCD*Q2v=zN39%=@C4xfE7^<3mO zcxH>bygn|K{CPL|qHs-!J-|6^lPEw!RnZkJL+h6q8XNo8Sen_df*u}k-|GFH?}VH- zT_c!M5lz*_n+9)aq&xXX3RmZ|vOXhzju7vc=2WmN{8hmLc*mz7m z)JBtGEM$vyEPBW;_imOgwSm9==)D%UqP6@=Z5Q5w44Sp@iGsu(eUvJFl;2EkChSG; zcxV<(2CA|{eAU&QY5dxgbEIQapuGu*Wzi_ngi71a+>yUO+w_~2~sP|l&1iH1G&Y zU2hi7k)kcz|HvOq2K-^`lY#GQ&tt0EVRjygQS|MaD!F>Qo)=i}M`TY8)x#dMMe-;_ z&hEnhIF00>7OrB6SN!=Y#1UUh9Qy00+UY;DlD)LJ0JBb^AMG5+x=qYqe1BEMh>~C? zkQMt!y|RC_-kSD(T514&;!FO(Dbn~95aArQMeL-hvHL55BYZE^IP$`-+%&rM-0;tK z4)?fE^BSL&0{gWqQ#NgIk2^weOS@HAtn79FhEwkM-_@ z$<&SsZHVQXgWg9Sd*RN{Q;j=?Z7>^LS80Plt7=_)af)zUd1AYJULl%9k-H+fy@qQw8d?pc$12XDw*bX5+}EMLyMF;$new z>&eL<)n!4aCcA59LMN1LmL0Lw|2X`w|4S@{YesYYgDh}M)PGF0zJZ6 zkOExlq12`%IqSi6NbtZ#hCL`r2Fgx^W<$G)L12695-Jsug`jX0jbJyI>nd}7?eD;G zl!Ct>isQ=rW8bI}Tc{BtP&W4&hZlLjv&MQ5;`S!b(X%i5MOQE35?#UY=Kos2pufTV z?DJ6K0e-6hb{qbhJLxBV#5ccIow}mdEHo z@k1}0b$ zv7|&;YaxWa^+3#c2viysTiu7Q|7(D&^vJDz_{Z)aO>uXC-LXayp+;0a@@0UB5+&V; zPeuGu?hnw&+1daoXx}_YZ#76ZzOtAuF!pIOiFvG|iYFSNq}0Kdr4)@gBeBHBZnF*( zTw3rzYvM5~eW6n?igH=ZNU?-gzu%bl%>o^6ITb|4!3Fk?V zOhBx!nIg-qGv2$HH1jZjahWbmjn1T2F1%KRF@Gwo;ZGCK3#qi0Kz@+ofc3;=+c!MA zsplX0N-9P?WFdQNvrKNTpBg@{939TRgiz24_TSP#dPmAa)4~JSJH@ zH*+!>UnV~4o1_$3K(aX}p`XzZM+Cd(Lk?(V^x+knP~T|%er%WSmh@(uvEAmunxuMn z|5)I!g-(8>YXgs!+{9ZpcA*iAH6v_yhB%wK#-GLZyE7~Dvdam}@7nWWvtJLkD?b{M zhlo!Wik2=lH0<)$xN^n_JdNui`eWC+do#$ZN<G3$9FCam(~#-=ZmGT1;Eo|7|nj z#BMs-bHX3U5b2l3Cm-4~eu`$4^ntV5MdRbACwt%YBfb4VFRwM?+Wd@DDY$Eek@JDF z@Evi}A4S^jT}sqcImTEw$|CBMwCq*}f1H8wc@ zh3b7EFv6o~ChtqRM<;G_wI;~dvWN}TVo^M>LY&w+MQAr=h8nn`~Tqj zNLkppAiEiPBHwJ*NMZ{;iwnb)>C-|={Gr~N6;KoP3z$>Pd8P&MH)ydYrNI{|t#l}M z(muEH$7HWu$(|6}$31)Z)kp#_9D=cFi^Y7OpN_4^BSJ?hPz7@uq<=Dtjt|z$0vD{b z*N)B3!q^6c|C+|WBlY$O6T1TzQ)k)auUV;dXI4^XdmQ>~70p)1*8*)`);_M`-EvvsVL@`C#6wnm zTDeCO{4z;$Y|}`dW0ThBkEems9!oKwEbE2V*X%4WoU9lG_b!(B;;c4Dn;szF_5dG* zyM1mcOIAt(CatWDWbfgBYd0eoQ|u%(R&OI)#*t|lJE{B%z410DBpHxvqgr(lRx^{CTW@Ee-#jMP|>EDGT;(Z+&5^IJvm#Ce|{d7y&R%!f>EBX%?niSdb zwP;tFKW@av0k*=&9RDGhh`klTlTe_c7^F$qDz6^6ym{$xO?>;Qnw_tBjpRp8 zw<_?OGCrYE$QKumvk>iiB*qvg_BnwEu=y!8kl^Bh-cwY;7Ixar=<{%NthjD~w{7Ho zPt!3PemJ37nts$y%pfm}6%rOn@35cnF8B8n-dtt~+8gK9m6lT)Y@*{vl$-3ON}B4a zv<{}+IIP^53;<09dDh(E{mS7C(si+TWXLV%`ljQ)_Bd<&5q}CZ!2iB17ucXRUYG+*0EmcM8xaW zX!MbB>zj4Tnbw>h_EY(Lg%Tw>bhSkfq)*QLEQr_2AhLYBxc3jIW_l4}v*AqH)D?wP2+(&9}jg9Sn z{xBWOT>Z*gQ?xnby%*JR(5Nvq2}E@|kiY)}O>2e+2Q1ILzUObPBZ>&htM#q$qWn@- zT8`|hKX5fVbSW;eRtA%tU^8y6;ggG6rly*@d?@~oeexf|1m#xD_xz@ueES{?H;V0e z8s9h}0DE;R)MrXc#z<~b`to$ia#v`hH$tnS?VbhJD5_vSu1WnpZZKnEqsCa#;A)EN zUrUiLW~iOI)CvZ$3CTYN+_%vE-9_0a7b?~q+GAiHxJM8P#Q*~-ZMm9n>5 z;8A1eTEj1hKgEF+V9!ty`Z52u@vQ87@l=QBqJE1iHKmfvfQ*>h1m7m$tKI40@ z0Mb7bR+*C@IILEJPxh=c6fV9V7gX(R#bqUwi|8EA?t0c zeYw)SFad8&6_U$p_celm4CZfeco2|Y1yWoFLB(j}?Sp6yR3Jpsn~kenUlkp{?*%zx zSLY;;A*U|fC5d|=ddfVfT+%y*Rj52C$yV4>F`-^$D4nQ|&ivMtcT|)pVW(IS5jUlR z6)z&^%McUqXJ-hHgU;(1;ymWF*^keU9+Hl1cbJ(TuV^~MA7YFjX~B@zyW%8-`Jcns zd(JId-X+2GW7EbJJ}(m;Or1G=!J0;2Nu@`4WK3WMQs+Q}Pxl2$+u zmG$mZ=OWqUF^|W02JON|E9HLz7pg@y%C}M1SLlUkga&*6l>m@o@4rnuVgO85mA?G@ zA3-7_4nJAviR4#dZ_rn`_*JCCD|2K+aa*ZZoQKMr3#tUZi-_ah<4D1SG;xBT`x}?O zF7IvK2WU_r^~IIZ;d3`D%HiuS3^}V&O1`5>-CpkiAGwuSxX5>QDJBUQmvyt=FyOE+ z@WU68>aWmG#*tURz5(HMre4T4Cv$9r?2GmppRkVi&NbJQyBm%6$0Q6n2R#$iJr65% zd~-D^*A8r&6U>RjtXMxTcMAV@CO7y4KZv@$bM1ZNd`cS+d$%D-!f00#+fdNVXE@DJ zd(##(b=V=E9bWyg?*w-pfUId`@{%8tu~l0D(mPFq0-gx0OLpJ-;w8>SWEaazjs3(9 z7;Jm`UxBz4^ZnKlfh7r-{-^Bqa9G-qzVP!>D$K0)>7A#`(Dc`FP;Y1V;1N#=Pg$kbG$g}g3C7( zV(sQT=c&613bpou+RE!UMl=g(xU$lAh?1N3GZk-0QM^T8{6?%erjMpcQ!n$qDaze7 zSS0hSQJG8am}cvR`DOsJ!(CoTry1e@gmMV`B)`^hA7vw72WBoAO#K1`#q&%#HU2r_ zg|TOb{Vx_SO!V6usQh8N_r*oEcYLTTd0(#`u1j*Z4l?`?p%?u7IajHmvf#YK->d>l zQzrk{^q++Fr7Cb7iQQaT-qKmgc|e4^F0p1ryXbJa)J7@MdeT-o`d9vO{$g3w!YH3|D`y(a?4c!nv&~N9QSEsfRxJ0CAZWmF zKm~#V^BqTs&s&Kl5!ZD)0CdNuxLz1&U)w7YZO&9!JBzsH;uhAl|7zaIowSI<1tOmN zhdb~3>p1|e;NSG-z2Yl zui1f~&Kx>@`|g;6q0Sd=#TAOf5mQ#no=Y&GbZjF4(j9Qzsz$G*>HDUHA!Tc0SOa&u z-8R0Y*RrnCWvq82aY6t*)Sxy#p|__6HbDgrP**@efd6*0(YCv5LFgR7^T6S~Eg<6C z^5(`4QK<9d@bPJ{WLk5x@s_Rl6vZnR1{vNgCIIZETOi8``Oes}fTRQ`1_!o8il&`( zg)n?%Dv9V!D7`d%Q1-WV8G)|0D>dpc-)SdK!OsD?&EXlY{STMP|l}B_Y1H1?zmo z^`Tb(YnAloP35TY7K{p46fVocm)#r?88-{pL_AZ!ml2w=%+8%9_?+i=OGRrxEG zWS7-b|EP`+4Tj9+NHduJ&6Ol!CKygbT=sZZ`vb0(1%Z@(rzg#)8;UI&>-ehT^}vX$ zgECPYjzc7k>7fxsa7UM7(*}|Z>2s^6FTsI^h@m zegKXY^DRA%lwutHK(k!7}VFK&15} zKVrP)eVo1&qnDG0426cF*n(9nX)uVK+TOIJ7xSZJ^r149y zl4k^3d-zq>U3W?DOo#@V;TOl^1l}n)kPIT1&zQ2!|E><8FZL#t1rbcUG*V5x*LbQH ze;ODIzCDO!kH~fNjEFmC$RANEiju0%RH$5y$JB4;APjz_+~Ul+LD@g`p25pjcHXJy zTABa(8;MM%uWkJP+Ej~9vPbs?BRMmD?Nm?EO(ds&X;Pjt?Y4cRS9mSfzJbi&VLP7q#oNcd3aue<2D*K|#u4l7$OM)$xO%T5p+VYgbEx(^6S!j$=fO@yeWGtE{pwsb z5GpFc)c}OR596vwA1Y$!#$Wcor+JK~@*Rz5)hVgR+-kvq-2C>qWX8l((LpU-V1yurV{q43wTDwQZO6takIU3II zj=6)}b_2D}P>sXVhwS8*j?c6~_-8F_tDmjGF^{F-JWXK84HKI8p`5*Us*hG1_^t1c zWWV?JiFo{~{6rY5|3V0pGduye9rgwy%Yo2RT?i+PmqtL6QDBdzBo1Oq%+N6|> zvkt)o3E=|nA_Cqg0wBFzN!kmU>TK2huvkW1kR%}G^TONCRh-Z-7Lq1_ajl$ubK{pv zYQ{9jdYY}rME_4_bXv|t^EF!*1M*Fn7DIm5+_sze%VDyY$(Bck&D39cvaN*U&z=81 zL7!ICjkEM8|DL}9K5~er9r}PGyTPg2m{;C}8>~XpH!7z|ax8jRi1fKG*f2gb0bB|C zAIqgKfwN~X?+jkUoKWC7*_^44U_na0#=JwTnRp_G1Ki`Jpj>g?P2`I9Yi1x-qY+u= zRq(MmmTwSi4VHrkzy=I zkCwZN+Oo)oDf2S#_PZ*soQ+5j;YR&* z4vHep%ZoeAF=Tfyyf&Wh&Z7O1f#bOz%+ik87_l`Wo#WklcJ9Xl*eIaedfSdRXj_l@ z7EG?EADY75C(oo^pa3uZyJ|qbhs2sSd;1da{?wjLO2pj@ru+g|*j1vRk+Pqgz+J^6 zzm2Ukaf!i3+lAujfEiohnu= z-(hmHm*2a;%Ja7ZHkAmK=qMP2vSq(>!~&Kl@CP+8!GMusUsxvy&E+6Ke_Fa$icW%z zG`@hY6SGQNijLkWahUbChz#tu!u)m_ac#cp7gtzhYi&sB4I^i(tmnZru( zHo;^+SC+g(lf}eE^@ij8IO{}yXgcX9OQ8S__5@HEkzY_f5RubS^n(PtbC#N-!zJPd zHh@Btm@F1CdZ;7v-~IWL#!Se;?__yziQ`sCgNBmPebhW5Hxdgb`X4vur5LQ%g4aH_ z7$}cwKAVp^6s#w)$MH3$@4L~z!*5V)(o}TXk5u5-J+_YHG-(LywWDMmB|lXy_)+(= zdkxg4oJ;3Fq>J>w3BMOPw~oUc>H=T0lDq%gNg51807@-2mnak-T0$LllHJDn4W=F?b^QeFiXjSg{5mol4`ikwDO*+{)eOb@YV%XySiCkMq*m z1{wY;cQVgs+q$qZd%sjtmgdWIkk%dkgoDO9bSL5_G|6zUvtSO$^f=meb?=K!0qzDQ z(@)Iq(1G&bP&)Eyh^G>l!~-3V-`&ENGztcfyNQv?1Dg-iXZT+l?j{b6B>H7E6yk}@ zWR7?J9%O-pLKB9+xxP%k?XmlzeGO}oKh(WuOID0P=7$;=7+bfENkvZO_(E)c6LrU_ zWcQ-)OFLc{<2wQukUT?gV!gE0@JF*Y8&rOpph-iMh$J_xrU>YfrsxBie|50hPc{5} zj5*>2{I>$-m-gChLsmjJyv~8sA z?|R7nssm5IilsaLz&@4#xsScW2D`Xn2=-qSb=!N=iLz8-_he7Ln$K+=8|&jrIj65{ zIA7voL~Qu@^A~?z^~({;@QBsgV{Nba6x_-_CJ!b%(g6jnhjPsWJXU)O_&3-YkpJp5 zLiK6OOZlx_*P`9S;*+N>8214~#ILuIni)zRWp9aZ8QPZVdsUT>iodJ)>nnZB0zYZB zZ@SXk3`9AS4S1w?_s}{Em$v5%<^G3oOoZxRzsaciCUCQi)^w`3EcezfOi3rES$lGXaz*&iL61j})YonD=4!{@$}02W!; zs(BfWE6;%N#S-2&8fH_DZ?%h4_d)!0faXGuP*>vYuXAiKFtr|Etx`d0^v1gPCaxtP zcFl?CCzTP9@J5$r=ty$RkziRzmjG=*T0LN*GGxvmq)gjTZSL&nw?5H|E$_G zkU*K)5pZH-dEG^L!GCalO*~Q*M+u8$5B0_s!AO;MnerqwsUHdnYj)F`7;Uj(%o~iS z?<5~Soxj9mJ~j4%-?eoW*DzplJ`#8=}dJusB^(F{U8^9JMo?P}h4l0-``?VY@8oj4B7=PK= zQ#t&pZN6WmLf8O%M^p^_V}r&eVK;y7Yenr;+F1dAg(SB|7S35I7(aJ!^i=s~N6xrc zvyg|-Q{LO9Ocps>SJRXd&irG)q&8S%1o(NN{q2sAW8y@*olkynDwPSiPqf`7UE4mx zf&N;E-p}C6_RfGysHbEqfwQ7fzvs%~3Gm;qtTUl~1sa?IkeRcAs|QMTDbzKT!SOw2 zbN8YF9aK~CRH?~>xq`ylRzOpFoBLY*$i~M`7}LmF_-;qpfI}FfYChT^=2|khNS{O@ zu5hghBv^X{`QS2qVT}#(zf6P8?dUZ6 zqod>U!v3-Wo(dOp$Oq1%2FJ8WDUSF5A>^2vKoqdYXNvx{&-3iecy;0v?H^2%7i<^3 z)IL*Iq3vJjxTU)}9)u~eN+2+b_~qing5I3zNo_nm{_JTp=E2dZSBD1ZP#>T{m9_A> zbMzyOZJsB6TAked74yDYr8(ISC=@Qj>=d2YBcs}EQA5$2qB}_<{CL{(vlOttGqUDJ z&#tRQ>p3&6y)Xd(gmSj0%NLaE!In62Ofh(=bH`X~9$;xMMGqz5n_sPBU&n-0H^i@T zdQ?tY;Lv4}=#D}Xc5N+*4s9AkmGIpGCIf$?z~Nm9-?4QDIP^c_ zwo3Lb7RgOgI@%isJe$ysr{wBIMqy=s1L>?V?Q6xp8Jg5&g|CtGmkA~-IKemLzW>hs zdx3HojP{P7-8-o@$+r69J;$AFs-aGk1rhN}7_tfv@;_^XVjZS|`OEub2A?{Y7k>YC zo?5Ioq00f-|El$DNyeVMZo7yvrNqGTGe@fbo}wXpC|vgT(EAS5sG4!o5enmjj8bP0 z_Q6z|jfm*e0Re%(3=0KCh6w@jO-Pg-Kto)DM|wv(ryof;GYIOd-tO`bXwBgyG*hGQ zRFz(<1JD@%d$|7C7O%y{g;{;2Ujgg=$0vb)ODkGVb|)eFf1#STp04q8zg?tRcB`G{ zog$3Cd7Q;>XvpDMJfBTk3YWH`k@VP&7bHLMRkQ>Dut|=H5tvXQg1+S8Bss z2M}!Ha$u2Ra~mV2Pz|8RUrSu+)WLNCj0gP?FpfcONmCc$aC-Cgae1-SB=-uPazF9Z z0i`>6T8Gsvv8>;spVjCS*P(7)U6HdKXJT4 zA+0ri3ka-YyiYK6taf>2J3+Tv<@3`_4@Y|CRKdb0F-Z<-7rf){+`LGhoV8lF(kXf;1<``k$71C_t#EO8I0tBZQ9-}&n#K(y%PQ+<3^6bgu zb`iA|$4{Hje#=#JdUJNT>KmUAe~m#0Jw0248DRUwuC+Pe@X%)t3o%*bJrr**D)--N z>#F;S=FQB@P?1~hWV|C9`wZ!^iv#89t+2F~-MgY!1-H)hil4{n(Vjcnp`<r< zOk|wF#kQZ0uCj1~NCGLi{qElDLLZboJ$qSG@|o6qTj zlZ|ofi;h(wBb5Q4ULE$}iVVa>#k3-;w`NYu@@*La$4nFJ>^I|u-D_#~U;OTBVmb+;bpM#89YGlv`a53k zY=L&6=O(27hm^D>p}^uD2})<%#XwnsuHmr$&SWUD?elY)1S@AwM-fO(aby8)EoZOe zFX4)H$2 zBTNRUwJ-D61hGPSVF8pR>5;cxb{+N(uhTYC|gnyjpo z-rV(5M}VCY3aXe?+{D)A$Ex6AOHLobnf3kWD$oOe0wvjy-{7wZweIlMrjUFo(C>KF z47xs){VxLAa{A0Hbd$UuF8OOdUE*nnw{5*ijHJeOS3Tv=32n*CV6Fa5kg6z&o zE=tJe{ipeFNSm(c$QpG8prkW4<2af&9gVM1t`pda#Ehbw+wnruu3H%wr$h-AeuXhsifqo0znri$2G}_q)!D84c}$#bLViberpJX4>!Dd5^;Tn!HkfJxq>}R9LzrRc zusF68iqB$QbYigmoNt2&<5zoVl7KNSDrZb+6J)e(s#Ejp`4fK!>u)hgHMZ@>1)EAd z40x;7lnA)SEN^K?G~IzE;uy{J$z7wl{zLc=;Y&>R0f@;mFh!WZ8E0)V$7D!^%e`^F zd}|TblW#1RXg#R$C)_D;m#e$fk1k|`B85MUCP^vQcxp<2gSF>Ip!;nqg$yJ(U7SCI zDnPbm^nTSw%l{#uW>s98Y=*kt;FT(sxWxE`_^84118a7tz;2wuY;QauPH{NfI_XN8 zh_LAQZ@lB)y-wBsMnM>_!Gu5@=*88%;ukn+sl(9)k^w z4msvIrHf$F`$pn-wVoEO77jK(W-|$q`LjWMn*x^b;Yxi$*I;SCClH+xm1FI4TfCe! zve0y6P%W&@j1yv&8cU>}MCM_(S?I9Y+hCmDQ%NOL&?Ed%`t8!HBP`*&=BWn{Efzum zfmd6e(5n|?+-qVs$MXZ%sWxsBPHT$cKm``t8 z%&5iAKL&Rf1+q-R?2s2>X4vhuj*q-2!!Tl<8P#Ki?f&8Lo-H;HYG>u`BI%o`qh_S9 zOGQ7CS1q>Bfce~eyXiwy_O9@+YIncQrnpi}OCgcHA|8Nig~!Hx#}-{wr=pJzm<#)w8xiP7cA-5Q#C6CXoHwlcg`)S7Xy8(6?aj5Rd{ zGs@h*l5WU(Cq>NPMT+Tp$F{rgNNlGY6_Cy8!ck?8IXp~_KlB1mgStAzvbyv^3F=$Y zCy&nYn;EH+g2`4Q#UG8=Iv=Xl61fmiYSfc6*dN(EtdXxfCSbGAd)XO^bA9vwDviFd zJ73@b)6ab}K9nNQ>bXS0Z-5tMd@Jo9wo4s>gKBe)UTeSiyrumzi=$EZf2}`QeRzG; znV=-8No?7*eN0CJ;R(^&kNvM{6>+xi*O_e&=a-(knzVv5Iy2E@y*Yjffz_&P)B@^^ zmkFEE)A#uOVdZX2U&fWwH7oM1;u-b9~1 zp0M-<(`laC<*tO4-iLN(2jSF0DX;!{Bekhg0TU97Se>ULdeq%;=|$*03f9gv1`ikhDS-uCm@qv;B2 znfaeQYz!ISF-*aLBJFMY%Y4_eUk`OLa_m-wgzp&1ekCT9R0D-M!8_kp7|CF3ox8s- z&G}7k#V+`7>&i6S*ik53%*$-g15705-0YlCdmgGar%K;0=~`W-K@twsSrjF= zw4siEMVs=X?7${^r0*!mx4!DT*$DQs7Tcw(pM&Z9*L^=dD}3)rtH#5^1~LS0h5qy* zG^;c}w}LAPOe=26_e3>#a9qqlNK-!R2!%t!LR%X3JJ^iAeIB$Ju?8wW(@X+-h)y3$K|B!|_yL3ffzE7?5g5 znrEHOUGeU4{67TdJdK>Lxsj!R8n9KyZOUN7!etjRv~$k{*?VSSN1B{?Yws+W%Bl9> z*p)ha%0=Lk0x9htmLHXng1#B6{-qMDfosoLSZ#k#5od-9G5>Zy z@*GlHqx?pu9IHu2^AgSgZ{ty8TGF0ixG!Qv&C~drvrnvNCzQ|WZO&AcH4vSK0&?>g zg`Vev>HGZLT`}7iNg#u<%_Y--?x?duZoX}SYx-rZbW4NA;@H~`)Tyw1D*q~X4gmpH zM1a>W^|!{UQIMjBklg*}ynMP7{mDSmry!QWCd`ELaxEpp3h+-`lti8Y0rcA-N9&!u zvauELLvaFgY1&Tm$kb)W5JDSA%=-E{kP0T%PBHW|<{SdIUlmyVCo|+tSCabwaP<~U zadct3E(s(gA-G#0xVvkDySoz@Y>>d9K|&z7LvVK(d|+@1&H#hE1{>U6-!tFYr_SEB ze?V7tRabYfb+6~XF2dhW)Q&4fjXAk?V5*I`Bpn}LvnW8c<<;@UNC_<1yJB^54A0AX zy!mpcBIkY*wx2KUoOIc*Fmp|GWyCWkmU>d+)_V)h_9=h1eP)5}%@Z5SPzM z8ABp=^Wi#E&!sMrBo3FFIUd*8x|bEBuG2JT6pvNvbFv10(6sA?J2)%a13 zArJiol^_{6d0uvp(lEj&<yiMDp}PJXl!K9zq2Vx zo_f!`4@fwo_B14LgHhdj87}2ilW*m6m@W;G25V_qCWw#4Mv`pWOLWW+pAQete&YnK z=YHuwx=HLnMA|D}#i3*qk2&Og+7-eSwrl8L(W^&E9!=u)EmveMPM&IcGsj8-*|W5? zv>u6xXvKMt)p4KC5kjB?`Fjheh)eak71nzqaFzXxGe}N%VRC1KJK(YB*zt+|DQUa|21{?imp`Yeq?|!+pX~lPUtSt* zqX@ejClxB|(Uz{%5_e2}XA5O1Kv{iLs95EwhMpBQZ&@#82PWmGrRN#!*}Wz5ysGXj zO=HWhnqwSjw6~+HC{4`2|5t1kdsCo*1bcE6TdSb$_2$-I@72CvnC3XoKLWXpcHhd1 zvi3M=PtH2VB8Ne$;&6&`&?UEYs&;p29-g^^9R%DeFv^mGN~q*^y%fdpeioUNWo|A@ zHk7;@3iw2CJ!*9|&@ZupLD&+L{6nt!{kwAs(QZ_Bcy+w)y)qTmSYE@@Sb#;xqf3ZwozM~Bg&4T7z zpn>0PF_y%5TBcI^F^%cdyazj2PZLyC4aKVRs|w186lj>856xi#&bT6i2p~k|cSb-?Zd5LPi%rY8t5h~tVWU#w<`pp5wC%mI4DZ(GgvciDSvD(j+B~9| z(=HjaZkys=7U3xH#-;4y^4Az&B1t7f&>@hHY}t^@=+g%b?Jm}GTTAZlLcC*clnkVH zL~k-cfnC@+-U5_)9uA_UxF_-}u9{)Pb~fDbxC6nSm*9CauTG?W#okfhGj{)cN~k41 zW~N{t&Xn@3Z&M0#AB~*{>O2Yprf2&V)I7wAl&J_gC_m&;2x<5bJTkv#hbu4|!?+z` z4d07aT6~$%-de#qE=t{`!>|(xQubk8QYPZ3Roal7A2ch>4jFl&%OSs5QI3!wh0X|s z*z`w0yO=OR{OKD%b_XYHGX4~m_zRArOTFF2ruIHE#ur>!LAkYrg20rP2;X!t1rFiSf{^LevC5Cy#t{O&7u&oV30zP}8% zv~9C-wdwLX#Gb0d?C2rASO{RoI6eqDK$|AHD@mnqJ7t#e!FJG>T=}U~1>h7D*s`T~ zRMs{m>T>_h7QGykjzat`iF@0B3a3qmPmnf0-1$G01Xi4)LV@R98T1-DdL^ixEYw(# z+rKWHY&>TYZ^3!O0_}m#_ai4I6&G_GR$+Y5lO(3Z0zuo`o*mm~{4nH68i;$9DDL*{ zHvb}IdBX4?Nt5u~9a*oypWA@OEQ=cLa;K%IwaX^b{i1wy?omQv) zKcGJ?73o#N5Lj%HRqRAIiIfZ+cIxyF;0_>WbwPuf1$96@)^gij&^5?D;070ys#Y8T{%!iOQ+ZC zMli_%I#2~CvHA}sBf(|kd8Ary%va*sA6zJ$^7*rU+v%z5)WCFn+1&6s3p|a_wev*B zG`XV|8HiT#ZpGv1c`8sS(%fo09Ms^(%gy85K*Z){4FA3vg*f?&(G4f@KyU4i%jz7R zkxfy)ow!D#hMR~Q^nyjN_r9VV?(0D|y@h3wzQXYFmR9fdQ=CgRQ2P2Tsw(M;A;n5H zcW|M3Qbr1Ipzsq_x{HglQkFGIXwaM<1!^^WDV=n@9MyNB+sFkqFBBwppD=Pw-QLJJ zQUEE)p;}XF?)JRNUqal32t`6)O$O`0GE3jkE z^&g6r8u1u5?UC7|EnT8`cvjy?`~2|0quH?KeJYjdm8mJ?j3=`RLy%FaCz!I`NNE0P zq5%^jmjf(p^=OflQVg$Dyk=P<3CUM*&K$iDh&g1hA*k(%E3) z^i4SyrFz(DCQ5y1hGMomDIFEDZ~)dk&FX-GU_6>J5sNE~u&_ysCcE`fs_}#bC?gF6T>~JL}f-KC^F|$_8s@;OO3W zGKQ8$AamHZ@%06l%wm0*d;okd-FNb?)}m)NnddqoA-PLuWy}ti8{BPgQR4{F7h%|r zqw}L0W?y{KXZ6<=CRDpYEgjYBj&C{jh|>vHR)iOn{f>))Z`i652to?uc)v8cenU(3 z%mEF64ao`6GSP7d6D)mi6H}ozu<;nWqv2g^%i-O@+$m(Xkf>kCrrCw^=6IR#=+&fpGFBvA3fa&xTfJVx7h9UHMvQp7h-;{%*c0!IV~sNykl zdH&qKvloM58q;mhdD(fr7)IP79w^K?eKy^;w$j*Y80XVZhBKEK6TNa+*tDedu!@%C zxQEixx5CWG>fNAg`^$gvfdHM4n7>-V+0_7g-O7{6Ao{g>YGj%#D>>fmTy%`{^WkDHeHr zPNr*$coIBsv|5_z!^2vZaxZZVFq}Cgf`Jnt(!yrAfz+*X+eZI53=oPVPxxxf@D1U77*3llth4icW3! zV}D$2OF#M0Ywh|oy46aXSlU~M`M5`=g*DTrR#W_sNZ@OV_*MVui{=Pd5N^uEfOrC< zMOtI|fgh2cXp(_{T?G-XTA5<|WRHS)HR+OW86(|~D_z*O?Kt?$NV8TeuVG7kLTG7b z2wl3ZXoNoX$&UU7l1VizhC?7ynPF;0D+LiAx7RAiJn~KG&&-_(z4>zS#p7Dtq9WJi z*&a*r)gSvwjpN7vP(LKmh_x@KK{JJvu!M@ zNl}Y3m=dvBDtS(A*58dqAw3d4!oSdxn zDyM{#6`oh8)~6`%O-d=op*`I5I;!CmCHrmAnjmS7D0aN&tx>-jTqofY3dEuBqsHd$ zCmLrQf|Z^dFLwPOv3B{rhP*5vJ!TSdsS55rc6%WqNaJ1Y9fMt`kD$vJ&&)=Ws86=; z3EIsjxsm;?YDOvQ(LJtr6^LJB){uVjFVUSS*rL9~8LtIbBx8OX%U+eeS{@G`YH}4` zR)wrc(e^!LaQy1*)C7Wdo=RGb32m0Y9^2wO)e7Gz+fjy1>lkAvml!c3C{)qSl!ryM zhdO)zau%qY%R_VDM8`U0@J3s>4IJooerG6)RCXcpZ~6~Khw~ltI@`Tn#AYnQo9qg92lqR-nk zWlCdETV2FN3*6=f#MXnVZlmb5dl6L#X%4|n(c9F0%P{HM`V}Zfm1IH+NQN|o$=#S2 zEbzyc<>cgzB4BN+ZFJU)whqUdOAl&U5WS;#p}tB_%mMvwV>6#wQ6sT*gZBPZAZ)#E5dpS<4Uh0TJtr)U33B z*NAqv*;?5UWn@CjaDVlGjdtrnTSBftGRrc6!gLeqL8sB1br(GShC8bG`t?0lRB|7AwxVXuIv=7VlTKwnEZ3A@S{vn`uJvvHeCV+$1!+lB(!M<6;`60sR z*YeP{Wp|9iTS|B3&~+w=?~J+3JJNdQCoIJ-Gy7(Q*jm-*>(r4wcjjwmibQT;2&subI2;&;(*$JxOVH{rIW(TN_YQ2!8ar|EcI*YwzTeZ|E@_C>9Oye zb~(l;ZO5@UZ<7{onJIJSAUS>#I}w9TCn`zHUJaElc5FM70FZ~~(gvl*@2d+)A6C|! zNhN1T$bCM1lucWJIG0Z}N7)noeBYw0o1B(UdufstN-v(wUGoI-j)6D)z%R@lu2*WzmjKg1%5DmlRh%yz@9 z*A2l)q`U^xx7FGKa{^pXvb4S{}c7u7Y5k&hW*%qT~Z{Z`3BAL^VX@G#SQFLW(WXy4xcJM**IeB!89yvg%ax>cOb zIg1Yo#et$%PEphn?l+@;tVHW`n}c+C?AA$L4KXojeXp|+jEH%v`U^!BNJv>(0Bc-PD9Yvf&)c#?c6KECFc<6BuN5fb})RJLm0 z5|brj0p`};wbM=QT|05#{0aCWXBZcStBW zGglO6m*}<4&!0L%Ly9Adh8R3@7yE9h+%ZPiH8io6ectJ4DWB}P>k4e`&d#9R9|ooy zThXV5kDS;q%_sMu#U?jjD}_7>Rf(ub-4h0_+KC{I-_CTjxsy6=!qnRWD$FQ8Pxe#g zJ1vd)&MCFf6_=9UEevL_zuvnVe##!@Nt+g_CEj&}a332UP>}P++IWg$U=eMJ^KOeZ zW%aa%5sN6BcJ{+EI*YbWfzA8zw@K0BE2`H#NO{9-{hyPqB zRSeOqqfv+eOJn>#z((Kb-pZit9|%YrJ(4Nr-$oC?_FL!`93LthqhG_^(#TzlBSW-#ZpZr!$ z)*N8S*YuiO2%6q3N%PRqGs`Q=N#tewpbzH)d+BfCkdSsXl>X44Di$vGZMSxPn6CC27MNdAy3Jf*jf#Qnuxc4WVGL`o7ZKUv`yKCuqesyrCvJRdvZQ>>E~V#Eqqy$2py zfU~#S#8nd6YL9Nv=DC{Q7lT@D>=Gyp7PA{j@J*8!`q{#|k|Av7jzWr{%#X>*oGuE? zF4@lS3as3Cgbb!9&*JM%$A}PO3z`Uun{Ou>dW}hFeI*iYeVSFx4iq=0Gnrw+PmXIY zgbHT6hTT>3YW_*ZN#T#3cs)#Ep@Am3FFOvtp1*y0 z?I2ZH@FOFQ*L_y=#7#QyrigRW|SD;w@x^6TuUaKWUX7IY&d)r&aMc%Gi{F;73I#~XsSZ2H zbv8z0>LhI1e25NSlDzdR|FX(qD2*DUS42kI@JX}PbzTT3lE=v;^WD)CQq1CS;LP*G zVJbr}i2qQQ4w!4%^htU{sfUf240cbJ1be5Lp;4w;`BAcp=I3Bd!i9gg;t2;R4|5_b zaw*kcd4D_kHjlvdZsa>WOl9Mau1%b4y8qP_SwCrrXD+Nst@Ksc6;-&;+yNLq4Q5*u z*%sPPL@pKTC+6Ze%XB96yM*aMkA%z-Hr5_byGNv`kFBVS&yM z3OU^-2lmBHmN%kZX5_=IU<7-6m9?_*n4@o~ge>)Eu9vR1xnWt1J z2~w=gjZjd2iqe_rjmq}e_vEm*znMpgZ*H7*1Qfk!ICt?}2J2H~L%TwT_FT!7LWQ`m zpc=|A6P2e+E)zts&*HIsf+2rRt;?GR58Q6eHm;M2E=`^?usPklHZKu5W~{WVAWwWl z`{jqp9*WVGS%X6Jg`(d(8%?gd6Ko!;uY|Sd;dBt*zjP$)3%6{+>~qYZ-7>7tFzC_%x`?mhB!o`lO$5eh)3A?kb8z!S8i*ofxE zeqJ>o#$I$a9AE*McY=6=oDG=cKast+#UrSRBNos6Y3X&Rn*BG;*lHbZt z`|SvZ;3>QGq(vTfd zm^pYnD@^A;Q6lY90GR)zFl>@08^m*%&>tDTDZ5&zD4_5?&>7cD6s$U%<@BwgMSyF$ z-O%b)^(z2-GwGuupcR#5*Ru@dzV&TLF2Db)9W=72xaVYR>!u9T*>~R~dFc}eI*hp}5~)leOpI$X)JX3Z%XGdtdQ!f&+4e4gS-KJ-is9%|kmh#D^e$O6 zmIZFpabiT~!WmV(>p*sP#h2{Z}TQNK-Bh<$NL2R`)Ij5a~Z)P$yZ#{zWf}bChLcCDJ*JWyRlV{ zpfz!gN91vgZfK~;5F`mSZo0|yJod6<=$+Jr8C1v+i}`*i%Jpn*A3!BZQ|&mbh!F)+ z8q?z}aq&+)LCC*Vy#dH+$Vo3SFBg!fJP9-<8vO?SwB()|qKtD>BV7toaJom6C0&=3 z76z<7GcSC~|7_Ee=q*HWxY9Jbt}zs4fZBF5591b7KR}iz2bx$5x#wqOc6ldTSLOu2 zyq_)IH}oJoI<4|&M~9P&amMxoLRAmzn`^HPjaBiDur_|ZwDvJ?dbg2aL#_6K2j2w- zq!}1xu#6!g(MY~6%VoZoX92@ka|K!oNqnoT7dPD=iq!J3{n<^#Ln0FXVfeqDkRpUv z;=$>)8`|h~v5rtTp79rF`pe$`>2@kBpDFSQONi26{D&flw|V#yRZ;X1J34OXQ}1oo z0t%B*KqXzy;9uYpOQ$$_O*-ku;&xh|F}YM86V>0p@_-dF9m_C^XjxS%xLepIUJ|fw z6QQHCB2Oy7h(f2qyB2a=c1*#f^?WP8L!_%t{;eb?2K86UHgwJ8(hkbX>v)$w@D5hs zSs~=0%$nXdCgkN0(NnVRC?29K`SGlkXP^#ZJJj%K%CBoMN;^X2 z+tpale|wUx6bj4ku6C|@Tne{!z6(81QA|LN@dIj#iEd~)Y~SASR+*^T({@+n^q5Gn zs7un z({0=Z=1s*9KgNztlEW8gRgQu5IlrnybM;s14kj;8#%yrPhzBUoQwobVJ?AN zoqCHFM~pBp9qPg}JJxEgx5hon5Mr1HPo@2);$N)-qZ6O9R_Zsx*v2!)JdKlNW<@f2Ne?`)TPDNp4dt@B%!buBrSkE*ZOk@AZC! zN@RxFSrBW*KeI`Te;Nqu1ILph3i#V@T4G=%46#BOZP)zV-&xL_fDDVQb(^E{^yuRzcV(fWg({MhtTQb>@@ zn<_-{*wn$_`(cVzHVxZ_8}Qh=q19exb3PryK8Yd1mcjsCQM$_pVAj1uPoLiqDegO&vWjTYw0=F(3#7iBC6XY^51IptzC+1t zV{Ivq(=71MpG6Uci_(!>Eo+hI(k9c{0NP%WW@gq_6yR-Bdk!{TmSYiph;rNe-Q&@u zBdGJZwjF1WVl%1e9A}lpRCmUV`pl%%Gc@uin-ItT39Wh^C(4zfG>NsTpO1cBo;FaJ zc`_esyCPj>gyluxAJRo0uXF z1Z$bjN=!##(+v{{=Q-ef@S5?-x3C}lSDt532HXM}f!K20=X)>9J_bvlDz^M6k4AY@ zS!wqNHiI>xTi6qS=%Fr|fqD5KN(cna8?7zt{dnQjg3$@P(gS19?qKZaQ2hT; zc=*PeE~9qw73mT?PJ9rpT#tn5#te=j5F6~n&GMbmV9_*a#%^sG{|fL&)j8}d>aBjp z#qQ7Q2F$AT$j(BX%Fr-0-f`Q0L`dg%EnZ#{d}H51g|m>#NVG{kDiF0FEIeNSAe%lC(Wv@AQB zM|(Ush;qKrC`MQ{MN`wp>`=WSZ83~X(uZBfhn7LUexe1)0j#2AS^9E_F5){dGbBf^#dvqY}1{L&Lc(WhX=xd!j&kel|V> zP$viX2Yr}W4`b@dd|YB<4RN{6gX*Ix)!QzR2^-=0w9d|_=q@OS>OYLB3Hdgjeq47K z+?&WM55jL5@jTS~hxP`SD{CMl%o4{Fi&(8)@q4TjntHgZGTJzyHcy@aKJ|)f$C~{G z(1pB5m0=359;z|hnhm!~6Vz`vF2JeE;L+G5fL4}p*=D8w5R7qt{jhva=J(phvbo9$ zi{h@(!kQQFMSe#x3L!L7^al#5L)evXmBy30uetaU8ztEk^>eixRsbEc#bi>rd%bB{ zS;5f7L!bj`j3a{WhyjvB>LF%%!KE0_BPo7x-%m&feH;`|koou4cEO}7vMLo^lA&mK zsH)iMwr@tu$?A*dj;{?@)_NY*wHD?3$@DiGXD@@qf`~jpa39* z(V|H#Nk? z19gL&NQiwX>6Vqra9k&z`mUKbN#PvR(M^{=|6lx5LxiwRLg9&9q3%&xte3Ce6Q=v< zm=a=OnP`8AQ~sBB`YM~D+N zU3j_iLcChwl}`4R7GfXy12jSrn^sz4bm4n#H;m^+cmKQLIA7+xM;8ls77LTTj)Jj9 zHll6_02&Q;Ls$dZ7o-fO_>S_(5B*@p45s65oE4pJUXy6<%nA0+;hmlTp^RnV;3kC? zK*dkps>6lVK)}7Q%UQ9)e#XmNhJsPIr>l!teR=Fe>z#vQW)$K1ucW3PCQnmdwh>&Z zf>Av7%Ls<}U8Ixw9Ys)ZmSn^z$hWN4wDN?3ZZ3Gi>ZEKRoQX9)6DwC3Hv1on_-E_m zBk7jhZ`SgeS`5Q6iKo8t_@#;Ve<0}o=HxaJ@ zrpU>0n3vbrEZa@@}|`PBx5>n`nU^zRnMz>9?wFV$7R# zata{iuy-3i+#SyQ-N-=W{>8qFACN6kP|&ULtuxYXfAAZm*~W{X&QOb_d+5hoHtV`V z{wu>7+^RKg0m*D|Y^yhG(+6yDPCk80?%z_*QAw#%gQbVPl(23kc?o;>tBA{&+_~gj zz?V~SR9nriZhy`*ZYJaF%vTFy_DvC4)f#SZ&o2%tn8iE%H1bnfeOR_R5h*5PDp{45 zD&)o!w90EwpIY0OB>}MAIu3j2{gB!?hrd&mqF9PZLfqZq6T$boNm z{op8dC;N3)?^G*0E1EX$E_`AlMM3AI${&$!=bkhg<`>RvKf?`aSA)IW1&yv%trH}q zgwkigF(9q5uUJ6F|~xS+`cqPWXipHMQ-x7uiVK6$q8*w_PIX%_u%2(A^(48 z-h28Jjg%XiqP*F;p^eg|mztcp?q-KpOO*AAd~Hm3N4cvq%@6;fYCdiTx+Z{zG}87Z(V^HAdJ&x6#6sFo{JLVu$A0@LnGdhz&Y5O<_q^DgLbvsz!sd2no(f|uL_lhELbCC+qXK9^#i8e! z+wN`1u{rx|C%?PpE~lWpsjeB?ky;(VLP>&oHk>$%Gzy^>LOyUv&6H$ z>Qw_S&ivvUca`E6ILE6S6Vn8OzR>#a73AdT>UBvq%P(3gG`%5Ins?~nFJUq zk2*gUU#Xr+s|S5M*-HT{U>LZ`hIMe5mipV>gJbkJE);v)Q}NZ)^$Xr(F|WrRC~fqx!h~Zeao*WU#qN!t>UqaOrG2P( zgzK^S{d2pOp2Qv)Q@L(RWJ?oG*T`8;@=?M^XBnwM!YnQurs$%XsV1wsuaQv!sT+9H z1*6SwQEP6cI7wE`SzD^O1}b`K z%k$Cs&`p2Gon8w>QGr!SC%bE}{g5jb$3G~A;8Tl-+jo|U7X%hLO3kUZtEzVXQY0qS5QhEqJapKRLEB^l9x-`ItI(!5vI z`5pM_JyU-|udgX;g3jSOXLWizcF#y$-;MM0Lxd#FJ+%v}|1W>r4f_}&Pk5>%EnN5O z<&~vh9_Z6fqvUrL($&6JU9RAIA-}<yv%A)>%BkV@d3fL$`j;CCYbIWCvAA z31?fgZw2JjubxH$2>w+2m3xN;b4!Mw3MS6_ydV0$^|IvZvWebpw)g={8{!4M!p0by zeIj0#>2G=K$AUP=R&{n0rg)fW{h)ZQ0zExGm2lCMN>2G#m$V$WqOXOJ9&nlqq?BR z(j5F+_alO?!rgVfPHvn6Pm_|{_djHFID9L8#3fR?0P{|fi^brKG^3oaRR5ybtobKw zowB~n{;PC-NuC(4eiVo;{`bDT4DmfqAEt_TObIQn?zS%O;|hgOfl=R1bf`2A`dG4^mGF6|W6ykKdus z+1V#+%SCfe6ZiVV?1UM5*0ZxCSD6{Yf6t3!to^yns& zYI0B6c8!T+KHaiem!!}Y87#w~L0aZc78L8u<6Y49l+SkU?sfoFR|>?}mI0?O=F=RW ze^A{eC(8dm%BLFGo)T>PtDHFoDKMK@K8d;xy25;=N-e8esp}zo zr9${iq49~Hd(FWbARJF3$bCvBYCy{R=+aoh|D<)|oBZi3H9DVpLln(Y9)28LE@dzM zeM!+?hW;lA|Cu7q2GRTSgTM+VXitSNe%;v@*%p9Y3>m|grCU_&Z|V{Cr=!4CiEln( zkw!u^uYb@P9>kSfcTMF5PW?LJ2;x`g&?|=@mV8^XeV8a$)3%QKow=hEw@)a({mXqg zOaRsfrZ7rl_m>sG+#c{v&be(Nnta9BunSUp@SOB)YFNeTEuiie`*Bx3k`NhzdHQ*Y zukd$@EH!Um>8+#}Lb-jwP6PkXoiN%DSkA~Za@hSBn{9?^$vxqh?~BqI)Bj8|6sv}l zGJLu&7>ss}nZ~zEsqNZ2i}2*KA`@qZTo@lGsTF)LWvyl}F_Q}yL~-#% ziFXN!$A^>p9=+>~xG_iI$fqK~2sV*!2qHP1ak|%xaIT}1=J|!}7a!%{cX{(`^ZlYx zp!cYk$47?zmUA*O42vC%a}X{;^*0|G6JI&i?;`nn$b8+?r80ITp%E6)-TcekptD$tkkb`Z^eob>$!ZFrr}z40=orjN334<3{Sb18a^FG z;V%Dt$KR?hUAi@&n#@1WBXOkbkE{33pOnRY42ys{yw--c$BV1MP>$h=I*3Z8a|a=L zOMCO2_?B@(oY+T`>e8I0Tbq7n)1MFj@0xFCb*Wr1ErvDjf4Mi_|F{eI|DnqUzyA;D z^63qm_#HvC{VsAQVdy@ zgGuSN2c>s5F$(u+4_v-4?$T0;akQ>Yq36PcT_LlFMY{?-wf=3w)ge^ zR6jjr{O4nKTdCRxWBy3|9X*?>OVQ|~hx8CMW46E`>(-NOmo=3^A8{{QskOt?xNA(l zXfh8{ZCPbk>lh`?n3yNb$*x=%<*yz~HINtAo57~ZvBC2mX9dr;M@XCSgt_JtVxqO2 zie>zVaycioCNoBTkZIeH;%l_B8iQ+8UpJF7h&E>jJ2oUl4w*L-+jYum6enS#zMx}KOp{j6V%)h4_y+p`!% z`SGGDX@7s{iGSsLty$$fY!`5%>3S{clCK-a%EUQez{ZwDkB${szRfQkaWGyiaF#m} z=s#wPXE*HTQ{I^sRN+HCuKs6!De#o0XaQI}4RZTK@|b(2?aQH-abGlDEi3S*LztSA zNwrGxWMj7=|03XYG@cj*B%O6iaI*5;;a`R>5z^j*7EJPHC1eWoOgHt{zZ*PIjhn8c z1qkzUyRHF%$}_w+ab~aukGIjnEDd)xHnStD)hSJ^(!z-{#B$cIa7>7e5YF3^@_IK( z^Q|M+*U(Jvj{f^{hiKc(!!%!%@#LadyZ!oZ5nG0~-`Gu|UjA?MT$xq|%#~-DDEqL# z_oDU3j_qIkVB^fFU%ZGwf4~Mg7MKf{pmxJU?=E@}>B3KpOLgCCFT&_7Oj8;ZeJ8*5XpVw1ch4nB~o%4CsY)oH(9% zav~W>l*ILm?+-w7i)$thS%A921Yd5*x6IE z(SXGiA8s zco9VZWJQJfM1V^iSk2=nu=5=?bSvEaxd9-YK=EsAXL(bx2W-7vL>l@hk zBZRv*j3M9Kpvck{a+OAJ5Uqd^<+>n-7=q_9p-tGbF*AsmanSY)R5CdHBeGL;H6_49 zTUvyqOAc@m=TuiZ*7z5_grvIsJN(Jm^A=~1@KT9I;_If% zdqqWOb2mQOE9kY(h$-`bD3CAP8Yh!Cg$4MiG6}u~$L9~zuVMJ}JVmW}Sg_&bYC_Mf zRO)!DgJLIqk*scZwm?yi(V$(gEM4Y}|4^RevG=uqW(D{0$@a(NTc$E5=3Cd>g^3LD zvw5w?I!v9?X=JrKn20v2-W;T)$f_rO-%{rMP;HXvY_6&Crd>=yhhT?AO1SAvs)Ei# zU7fBQ-wIB1=%9_RMi8rmONmN`C_k#R))F@_SEsJ`Iz5%^=&Itv_RUapAspxH#zM{Q zwtC$&yqZ~`%nG38v1FV(EfcxWGcxi}xKKzN#|GqT#lLAVWXtc3I63I+QMXi1@`(4j z)zG8Hx~w_ULJy{zcHd{2-tVPi=`W`0 zsDY{A@5#8I7!%GkZEZ+TPxUwvbx|nkN!i6P`HjbEsww68uOuuIJ10-D&>dA2)XV3C zJ99){7e^DsW=Kdc_I)gXuN{XJ+iC^;^wo;m7;Y$0=pVs0EgrYr{bo^}F9XXAYsyMD zihsZ1cZQKL!}Q+$m2zN7VUjoue{exXWN;xN%$RvQ-5Ch3??Fl*zZj0BV|i%>uJMU( zKM(5|4)~gnWQed}`(LwsozAEVqEh*JQRe^&e-?(oAExp~^Ad&~WkX8V6AS;+M4!2LfI zwHoZQhsJkOM59tj*XIA?<6$fxRkpR0#q2D8i^EMof;a_fnbn`C&M7}!FQCCixiyuT zsl;l^6GlItJTO5`p4F$_ue!88<@8^2$9jUYUN<mTqx6voumy?J8O6l zT^gLD{)fV{ktp|6y{0hs6UIqQ=y&Ze>o3k;c{nvfuDqmr>23&CM&THpR(~=oHY)f`la;t5?8srbD z?2tC0wY-X=%jx1X0uRJfn8OsDjMosoqBKzq;jjDH>SXtM7ig-Z_{r6cPUh$()HSUG za9|v^aNeTxpZsmqAaCfuug(@cU5pvIct=iHAg+UV05~DL==%diV0B$W;|G0|_jgC0 z|BN{!j)i|$VqSCZ6NP{{9t0qZtGZ<1?H!Ru?vJuFl`-(JfQJa4@05D&@JtWh-LTEh z@Pk%ii-h7Ds}<#~gkawVBPicmWPSpA=+G3O(N$1<4#;6`a*<%`qWUipMqK?b zC^sS}R5gK@A~To8b`M9C zzD~+-c>-?5BFz}`Xr+e{I+7<7ncVppfVDcRDTsf3I7fkN`GjoboQ7kSb$r=hYHO+F zHcsI^Ve!5)W=CGFz4qanQ)Q)45eR&xde`*)>0mdHd#nWkL;FRw^;fjFOsJ>9b-}>G zYk*{0n-BXT;d1so*BzMK}+^Z z96~alC?QOtQ7-J`uNGqIY;-K1LdBnO>cDox5zs{%F>SK}>pjH8v6 z@@c`Tw4=>d4j0-PL)E#Y8Xv7u+izogodD%G3i@}{m-%tPqFPypC2I_<09o;XTFfo@sp*0jyD9xkO(@ zuS$s0x_=}!TPTLvC~+am!5g=I;wjrQ+Yw%vtS zFl^bOYIbI7c6xq@?)lVLiQqZ30Y&LpZt1p$QuV%L%F2bU_Qow;UM~KVn-YEyu44~; z0?peNWlJlZNprjA?`~|`--n2qQ&jHxe(9k&u{Ym6u6-c2p3y^!rm+}Ufjm74MRV4o z++5|^wXD+)AY46bniq)AH6=@2ksDs!VZA^`n-h~XubLzde|RE!V8)aBWc@@T>g>|V)T*lCY*T$Rtin`1JCG}E%VyeEH*0STWwx4mmEOGs z)M2Wz1inLN!^!NbhEhiQJ`qQxu)t%oFL$fl~iVT5;vpD!Ui# zX)&)k1!YY^HakGrG349UA&4|osV`9e?cQb}@9nQ|I`IQjy@+KK^*S)2UQ~Q68u=qr z+QQQ8uCOPxx};P>M8gOKh|600Kfp)pr=EtT_f8t`u8CUz0bn^b%YQEjd0(+^E73A) zT?JJPof(av^6w1R+X|>Om!&?Gl$ir$>G`nVS3jkK4}O?|QHR*Jy=8ftYehbZ{Ij@V3xS4)cg+s!CN(0 z?Jz%d(QWAd>QrT5zo2aoI=8L8z>S|$>ByPiX^+bstLdy>Y!d{ad>Lk5$=qE!2Q>-gan~2+gV*&PV zREz(F#9lv0(qZmuSRj4z?T>?O4weSj(7Q%?T8RENsk!a0>ULaoLD5k>vrV#%h87xQ zTni<1_!Ma>9xE7&(hrKLa3O_81*Wwvkz(-BgniZ0KK*&1`M9IB>+g$g@&?va5mnzR zteh_^>!)Z<61{#Sx0`nfqREdvqvF9g3t(!2eKkvx)h!bC4QF;j${;Uh8QfIao@t&T zb4IFjkg~vMMj%h+VUfi~;?-k%r0Chz;}C$Q#I{h3-Kg$S>EXoTEtA7mtyLv;B9U1H z^v$C(OpI7s@ie$!ElJ-~^R7PoXvfCqQl*>3yjrqf0R1|OXiiyN$++lB%#=LS(40Zs zVuS6c)*H?w@NDQKj(dT$&rs&ipyzBY^dQ7b7ZJK>X972$SS=LSjJ1iXw1E^558uO8 z@d=OLB{@I86MfsGz{&05FR8X<=?7kNlsh0fW6X~^aZc?>2{Pj*M?CtqHS1P$%Gu469ub&o^|&BHG()Wvhwu2l=y- z{>?qqi!3@>rxs&-uHv+2&x+XQ!-8(Y8;@?CWz?8+HFu-ZjI<0CdGcAWH@O_e#z%kK zFpZd1luskQODY!*50XsmAY(3vaV#v+Pz&Wftp^gQoVBAFf!^P?(>+&guKL?28j$UJ z`0J(GUSiG?m8VSTYwv%)E@#N+|F5qLo3g!sh_@Cg`Y#E?_J4M+o(u^{dJO(wy?+23 zpF1TM{ffn{o!QA3^%q7R61k}6i(1$I-fFspEjMcB*3fjC&Pk>OC*GScj#`$1Z}Gy7 z6BfPFhR2wnwr?wWFkL#v^EwN2VT*A=om|Z~EqzJA229eOIA9g3_-@+Ro1>4d{lpOh zo*_Gx1>;Oy5%BhQ?S#JL)b;(GQHgD1}*a;eiDqr`ugN!gVTy{il${Q^i#$<3Yc+huJP9k#!ueO2oSZgoat3V&{tj^ zMm+A?Ow%uEFoOdO&xM=PKN9Vw-J2UmuY&Ur`8I)+>laAYj{JlU+7Z(qyO)Vy(aZNf zze-rh1S$D1;6Pj$KZcK9uF=?df1l%OzK)d$p3>K_C~&%fPc#;+ZsX!BreE!PUWZ)J zcded6s~#gfKg3VZ=8P-^rN=hAzTLWdoI$l)e4f<-ena3BHfVk|9<$xoLlho+oC23E zov>YKehES)cA(&G(b}9HpOUkXostS2h$2L<)Mi zZOhSw_v2dVtiAR-@w|%={asO~a#P{nz>gz-Qk=`n>#Zq+1T4(Dh<*lav0>G&GI7W zpqfLz^9x;T(#BnHdH)$ceyE&PoBWwDjOHZUR!n-JCY@+0OqGw;Ji{eOR+*V1DWsiLfC&EsUG?kZ6eTLIj!05s1Nz6E-9b9qc^P=-1iJ z&xs3l;dn6zR}{B(BXCqdxtE3WU21L;Qz?WDa2(4)EAS@$mTO2`^3#^8l*0~eHe-$X z3KVtnuoA_}x+P9*Rr8z^@vZk2sH!xV<%X&A!HfjY+a8s_K;)2RDXOAQ-xpSccWj3D zso;^Hg~hq)nH`|;3Y#N6ja})a-992}8#wLiY|EsB(LKQIrL5+!?iPi)U?g&7qCevw zl;|u*HMQ_cN2|BU%Qsp{r?^R82!?zD;34(z0w0g3np|o~F(Nv(lYolnL{OEdbplS64DaeWS(j@{PtNZ?al2Em0IoVCk?ZdDn4%~y!#h$Zfp4T zj+HXkuO(LsS(kbKn(%1-Ov~emLC+6NLbBNx0&5TC(IiK- zx6QKuLG{dP$;9=U7E5h$9+8gHa?a`jOAr*&P4G_{A2wJVq|lh#Q-!;X{;o1%vQ9mb z`jd39s-63$G!jHfC(M;iLtO`M4 z(e8OtKfo48Ef$`g;&J*PeiYni@%Iq_6p?FeZy)(vhxpOP@%Zwum4|t2Q^oAh@a{u9 zl~5=N0>x<|ck8n{VF+H2m?G6)K!MSZcb-Y5kB-EmKHt7kVX0#W_pQGuyx3Av#a+!#!hG=pysnD-H) zqs+S?2VJ-ENHzT6l)8ZsmZw=1I{(eel^?uwB>I;a{@>Lk53HXTbjE!(Lmj)Q6w5YD z9(GL|a%kDDDy_VhA5iC7l58f8ny3)J9-EeYS!5dAwoA|0-`=jd(zw?62ViY{FXrLJ z;8zCR?*L1j7lwXYA60pmS01>mA~LP;55SBSx?uRE@!P1EJqU;MhV~zzy`=wC2ZBr7 zlX1_g=xU7NKMq#SfDvvH|K3;;-Th!m5O^uC2w4q%97N5Hl_vc-fkrapAno`~u_Yq- zPRVIb>l%IXWsAHGeDg`*8tizo?k|H3XX@vF?`(J%*Mbd(LAX`sNz{ zV$>wNR0xwFmMxZe<`Bs$zoW7k21K+t`8F+L-W|z)4N4$-7)=uC`>`%!5zz`o76~7v zpzr&3p=`EkVIev(ui$X->@&!}nUmKp&;8>sEbzyjVGagYi@~#}DUdzcNAus-?+Lj| zev??`VRA6?71PYyXxQy-DkDayKv7e)>J(NAnuWe$I5bujY%b3kxRmH_;=Y%5ls-YG zc9aVzjD{|XNH(iMa3Bo29D2pWIC|wX8Sj%Zp^M6nKn_YSbVV+O-D)S-Y6M!?K(nHR z!ls9~#fglvRFdXN9I~q9DI=rT5v@BR0xuGfci}lua!Ye8gO9&ilY8k;MmAP`uDMg6pyag#uim2>3CldW z)V)Fp5Y@rQ>T^p`k2sLe*3Gp1^jsZpE#p-Y3vE`xUr#>$S$)>HQXfs+s6lgCKX#`} zYKrH+R9NkuMUC%3Lv+pbAY9$7_#qRv#GclsZ?SWxrB=87E90`jQ6(`nrW`%X*J*fn zS9#CgaaIG~L28q@^35yboaKig*0g46kvKfv>_?9{k(N0$a^3OlOx!iwMmxd3RBo#NG2M#FYcpB0`@JJV)E*&@&Du+86YH|Lrli^$Y zDtz!g!BRbV7AatMeyzlcHc{zb{b=YwJof_6Yn|rkdbv&}!f~=h^~o!^MZwuq-8@H$ z!P2mXhA717@PO3LpJ&~-er6fsX8NY4e3`^-d)GP(x!i|srwOaJxraYz4;XIPxoUS< z2uXv3*cO|cAIlx~fQ>)ADoeMO${Ru{6}O|$)(I}tAbriqxtfwdQGb+)rLhy5HSLx z2*uq=CDkRZT4Ne8Z(VD=?^r#|UrCu8q?HuG^7n<9td09uglb zz6&26$2E})(@`$54gv--!lLwFqYdBjUvk)2Pp;_hv4nd|J|1Z&2AWxy$t^0Bb;1QT@*LNhprmstgLi);E3?C?;QAc z;V!GgNDSU*oSgAOqa!VkVv^c3Svfc-HAaPH0-&(f`vqK!f2pxqG@h9vIj8VQn?%WV zB^#|)nZlPvcc94Fj9Y?MCCi-Z%5f;dF%t8hrri4ZeS2!+i!*tXXGh*uAtbkcH;HBN zmMT9ANHK{1Z6Fsk8}jFBHXm#W8y zcszn*thbEsQ_kLGI-Z8;jqdHuqLJ|*sm&_be7wYfz4=R%$hMuS&-jq(uOIKP(@$jiMV=foR$4@D@q-jIhCDjm?s-we~El70*a`_w|#ikw#%Zw;u{@p{utP>#0>9unMxpe>rhmma@I| zts26@2cf*C5>C1O@$(V*or4l2H~u<$XUlSWG?Wq!N;TzMKwN{W?U zcx8ecedhkQr%{rcPVMI%N!mpj&D~zA5}z~ouA*~wfG>V=TC?Ps$#ECNAKGts8?iVD z-Tgj|ihU*HvN+b}RvJlKK@`5*;rXIg2P-uAl;B24dO4Rs1pkfuK9q@!WDYVD7?u1n z8Q)i3^-5r{a^Qm*`8?#4Pxad;RQb?TCdzxwOh8;2`W7`2_?QeExpmLswVv_=B^EOm z4&vNp)=fMHfc4=MDqcjFn3!IfjZx60jO=FM(onA1O@mVPVa@KIx5~n~oGLIk`BC+2 z^`jIcc8z$KD_Mxq)R>vuM6Rc_iy3mr(BjF|_EMBqrSf}S4DPO7NU_N5(eatosSln2*bT!tEk=fu0 zpfh70E=q2;Ywd)J07?y;YkqIc zpBT5QKr8Q=+^;)=Vfw@6a=h5jG4`W#)leJtP<&23Oab}~S$>bmo}emNr~f-eG$*Hp z2v4zhK5s3&UAw)F(=}$kl$u}2yuBa>?s|Z9dhGj%UZg6=fB7!YAuV;eaywdpT}=P&P8`x1dZcmXnbr99-_TWs_}28^>9McyqSlIoMxRuun<+iu66%(_(IU2p)eN$9(BRo~ z!ndUbCNcG=7)7MFh}YDlnyV|Z-ewuD3_yR{J}}bCs2=5V@-(>B{XMnU*s4J?$I?ri zl9vN^wxT}9r5tMxsw$~W2tsWNU=s5o_;*fby^O6DHkb9yvuZLnXAir}d$uGk69TL1 z-SHkrTg!^We3ZJSUtSpWt_ZhYGKkKz+>0yk(OC#fEv#oak23Z#@wdLs%$v9vG|~ z+tbt*|4Vdlp#AM?ewbrn_!zN;^mKfR{erjn_Qf6G6u!C+ug|c+HOwMR)$CdYj$6SO zHH`K!yi%}I%euBmds($)f1{A$>(>VD0la&6dMgF6(+Nxw%!roL#?DSx%QsU7F!~J9 z8mg;-IW1%8?KtOuCu9q8*)!>&_BmBk`r6Dy!EN1sq}hGIkP|5+smN*cP~V`tCw;yt zrn3+oQ^v+Mtsy?=Y8oNoW_>7;@q|cmZ?wC8z_25%eSrDdD>U(!y`hp|yQQV@Y2tT& z#iVu%_ryCL8!TB8KI+L*4wvbThvK4dfC=*?7qJ{8*44UOdP1+!7y1+r27$;Buh^rU zuYMZSts*GHZpvBRq?G14}k!}X*spx;)@(yG6Bt(}eP;>&Q0zo73&m`k+4$kUm7 zi!Mb*B~qPC$Q@MCpw-pV+K*R`M?Un_~IR0GvOb_4uhZ=l75jsY85^LGNV%3*HIGn$zLW zIhPLfNFk0BG55%yghv?uxQXvKoN?1XVF7k<{SudP@N}oVeNv)qN8FU=fAjDSj6(q_ ztX;)Feb25YCV<8*HqHZ_f9G?ErPsyM9i5pmF&o4YohuxkqP@=)ky`9>3ye!JN`L_% ze4Ugm;@I?`2{stT+ngf5x^ld(O>BKLh7O!!h#?6eSY-+4cG$B1^*utd`G@`F-Q>cg zZ$QdN>fhG5$+Q<*#1p2uHJ^&{Y79>t3OU*h%1HttA4U>o>5&(=uPtnnnUY=fEp@G4 zRL}*Yhz61+t+{HfC(LRXP||C!3kR$Qk2x0d{~G9c&rAGn6@OxId|=rA#gwY6t=z(A z9-ZnWv#gibuW(Y9yq%0hvnE@i+DuI3{xZH?Da&NC=<-@0Tf(LFyOO#LTRdgm8EuVG z84k*!sm7+avf4nZ0GDTbOOy;8m<%kAx)~-h-m#eVmj+623ncYwZp}P+2{DJOe;>G& zBJBqg30T7sq90>fvdG{Q`A_MQ7OTM3Nd89_9b?B(zs&TmEa80}6dT0#3aU)k{76ha zP^r|{QxkK(EF31OiTX_P@ulzbi-j6$cD015O~i9ont3rIePJe}zMR|T1=;$D;*Wb^D#()Rd1^{iTrby>a6en(GX&h2%DIjBwzfB?~vSB=y^TUo0Fh2qDoZ+XlJ zV*hG6acAN_37-qF;s2O%a>nkXjHF>Q$+;LbLU+mVT%N0t;Z-QSr#A^}dYud+k-P;- z`~xhMvAhfnZdJm$Fj$KJ0A0?nn2g@N$0!R%qj`lTC56RCNtRSbwVGHiw`KD83Iq3| z-Boxb!iNU`05Npar}RM9dm#UsuieX%Su@-{yF1Kj-s+@Dw#AlB%J!?uIgUz(f+ zsEt!`3n%Yhll3igH&EAKf!iUG>z5G)$(6WL+?#J3{UhJ7w6^-xH5H6oVUiLA&(-K< z_vTRMPfFRp(@vH?7@2%1<7Ykhkva1#w)22d1mP|6Ld7MJ$Wuhptr=^R3*Sn zQx1!}AV#pA6-%p$-Ae<^Q;0!ZgMC)D?gVr2Out7qptjb)u&UD+))3NZ_QgIZWd0k^ zc^}pGrmV4YFou?GKo>xUk6OK8y`7&a|zJc}K7Hia9up;CTLTU6Ozw zW3jzMzu;a2^dUO(IaqS_gpR9?x1Sqg!A)doU-Z>7{8x{;yi%RR+jWXD!su>LAVMQ!nRPOfv0bTpa{Sz^76K9_#+jQIJS{CE`(nh-%l0~%eOIY= z9w|mTWz|PJtJH0v6PUgNAu`;+HQ6z0Py7eaElJ+RpE3(s)4KI6SY&zax2l8usLRES zzYHOCu|3Qrswdy4dYpgbc;QAJ-@`4*w(fD}w%d^!JR9j};5TTu1iZif`tqV`#lyC{ zyM|#-NeUM7A@C4X(9Cy>ba$}F%(|!attml0cACYE(4yj)sxA+I-~tMMc`U0sNkFT0 z;uo&vt$=PsRp(jN@554 z?O$o#)?qJ?uOIf6lYJu0>Ge?#tu*y2CmxfrZO#GdU@-KJRZ9EgzszAWwwxuf;p7yZ;AGs zg*k+&Qux+X+>LA(pzsai>G^L~vD!?8xBhAt#LNUCpGlIFC7|&-(T=J+P4fnp=(8T} zL5tY+&w8U7dzhsWyafm?HKKPCH+wu39&YI|bP?>xL&>;qNy2-_=xQ;o z2DsEdjAD;}s;xb>kSZM7yt(IUI1~3M9N(ixhDN8tw+ADF*J={fc#w7!4Tp@Kq%Bhn zTlYsJCL~qgbV69$`S*_~R_Q%w5L{mS2o$MX=n@xvk)b2o(T=S{2fd-LQ9tO&4|0I@ zNVp|>QDNn02*x-pwKfS#PAA>lfFpYf374zsLq&0eS)txqf9e{l;Nq(jHl}51C9q9N zV^E4#$4`=>j$Q=Vx-=$`{5G9BojPDA+cGmfMHIF@)>@+ng?oEFF<%`Tp_x$y%J+%yu z2vumJT6j-~*WvgFk0M9CsQn~5;rZthlAiIL!J{=Q*7P6Ts~GO&7(1`>EdKzVS6Svb znE)W|wwWin_TWK|xJ#o^kA$w4=L|R0XH-65d~e~<&)Aai^JKnnM6dhFq_IiblkJ;W zU7PvLiOL{W%<}E(#AUtR7x%LCwqtz0U|==6wSMpG<%4B)@bV>3{A9HU zua2wa^4-`5*<9Nz8W9PCz1@5HKjTzzk8l|B-gSnK)^#WD^;EnEep`zf1SBIXMKH3c zJ$>eYGvYF5D%1ZvJ$tOBYiALy!Z4GS!kNVuKq^bZZ5xJa@cW25qC?Ta(gvJbd^&G=5$;3&hYbAK*99{n5it**!|8?X*-`EhNmKek!PyE&-Wmgc<-=0(~1yh1Wf7^7VR6!Am zNGIprIGXc=f8R-b?!I($E)PXAF^hl{gCQnCV$RR`=|0ATAz}qrI>m9XzLRExW8v&^QGmsnvexlkDW;H&^t>^wf}_F<&|3Pn6e8E#y7wtit{_?uIN6 z3WOFL%7A?%U8U{Ivf3Aqx667ZTQ`!0XS5w3IrIW*&d;a4l^TL^26-mkdK<@}EH}NU zg*&`?82HocTtcKNpu+pbo#k79UzMzkTTy`q#k?pnCdPQIBd2>to5cxxz zu(2s3%{P&)CkKtpQ&qbL=WOwi7>;cU`n_>OZ5^Lx&M!u>8>@+upz>oq!=^!0b@7x% z$h`Bz2U&ji6`4q$@OUnfn@_~O#LLq+^im7u!yq1s*mqF_on--qrCqLVFi%%Yws|Ao z<=N~WyG_dAhGQwX>+REZdT#I7huY5pDyRhzA!b113iWme$9HX0VozoO56pzkKqVK` zOExT#uh+81Y_ru#`|tj9DLLOQigWJVfV!dWX0@NKWop9;Q)+tm?TW0P`qaFOJB??T z$n2;_+)_@if+6zkZ*W8~*Ro!`959HBv1D-Ats?;FR8uoGHGA$the;9r4uE1-+B5awFAiE?JcagdNiB1BEl{Ez4Bp|mm?-rvn zjqLYIF*8MyH#TVsaJKp8uG-f6IIfkT+KK;zxHcK5Wa0bhAdVGl>AP2v>Z?p=1L@nu z%t(UnhMo;t0V8uTk*r^bi?MOu+ocagZd-JVAjW;S3i|5%is|o06-!O@+xcvKpN))U z3Fl&D1-IjS^Lwhid>2~KPjdh6S2NjujM+>mhoYni!bU!`AbrI|WwE`~F29%hi&)dR z{)9q(9nnGd{H4w(I+CQIRq7u=p3ML7B)zvGA`u^U?0|M?>F0V}=&c*mFZi+LUVmi% zL}5y*uJg?vo|DZd$USAr9}JUXqkw^0u7nCqjT-nO!Q}k$@)D1z-y9!mON=J`i+{+r z8%F-K+u^7dyvY>PiQP++kiIEOqQ*(hdA5KA`P&7xAT7WTRbLjGt-866>qLEGmD2jm zxsY0zTiXH2(4IbdGZI^a3$4j~>$W<&smR57|H~>oMni9kYmqb47Kbr7Y!Um{O8mHB z>P6tHoya@)58%prmkZE=%fJtM?kRK`3pN?)bYw8EY@o6u`>V3nx*I=KT=B!s#Y{&lzn#FR&78FMMY-1*8)0AU>Cbv0y4;xAOWM%Vfw$IpIQozF-Z=f1 zq+TiU&5Ct3oA(MBNKr|9&Ys_A*~aiPDI7&nNBf)y?-dtiQTGC zKZ%!qy0=~;?HWb=&}XjENxpLwde3OdHtuJg);r4jqogvyaPDGzbSPA)ltq0e@FmNW z$jrLOJmc)nmtM@!pj1*uI zVJW(KoPTPTqe0V-JdMh#nsUceo8ydxu>XE^$x)q4V9GS1R>h*YG1^t)R0yjyj7UoG zE#>S?;~@3=s(2fRo-6ywUB&C5DhO}EkOkZ*+=)RtzV{~h&i=;vb*5v~8eC#7dTr~d zy&Qb2)?rOKC+jw`zh!^I@6X^8jO!{%=ndMZags8oxBc+JCH?&j6uLP}EWyka*}W;p zFsz%1r9aF^k1}?L&cU#ArMfdR`JF|SefL(ymJ^(ej3$`l-_um_8)k_>+Ux~iqVCw9 zdKi|&J8xzTOfAqU5qX4%{lu5&@KqBcYUH_X+VcoVnKCSN47ju$ZljJ~K*=Wai7Ns) zkYumH4was0z|m#!dnsyuZk+_W6*PA-G5yvL$HJ8B7C|Zxk^EB_g@g zKQ(C&quSP=Nl)?1VAQe=j~gvlx5ijtIp6GO9a=BR_b7BLyz3CZrRCps6;E*lsNK`M zxB1&KHJ(V;lmtt!;WMYd9j*qf1nSNzPNY%+6zU?oxr=A{9J9$@L-oxD zxwuB$x5{&iD+0Om*WO>OpI)!O@NgRg%Z?Ayg)+>?)^xQ`!&-M2- zh0xB>qTpAL!Zk&ySv@AVr&Ynq=8fYrTk^&}7473@b-LKzkqV~tapih>;<-AMDns;E8_#d+zuM-qN#JklmW9AW~(al=jOwo~(UpcBudI&$?@wsw2 z6-&xUYjct`R)7I4So@9imT&#Jp!nx1HgoePR_^rgHHYaD1tHBa+Ogv?=k~55*_PWdC*Iy#|`W0<=JVu01%zqUU#Wtiv&!jc7xbD4@$ED89+@BMsSOzF z1}jTkr@2kYbrzCalGz19JR^+VXnGdqNXBEd3mvyZU25&J=)P`BMiA1HBt_5&sQ&{% zaU_{$fJ=X8k+eekk4jLvT#&InrudJRz{rf^)&(vf~#S-AT$mZWaL zULg8_>#c>Gg+>@W3P0aUG=3SS9I71|$jL#h5e)snkI2K%6z=l@UUZ3FvhBLKno7eE zL%9g)0dBNH@~?j*&VKM~;w31u%Wqgu?MFy!VzNX8*Dv!4i-&qpV^T(3e!?Lr->t5m zyJdu%waB%0ZpepnZl@daEZ-oPPa=Z~9zBMd9_3y=C+~&$C_4FL^6+K(SBvLe@+lR> z!)qZEs3s(Fz_*kx;5;l<(+$wFh=1e{up`>F#MDOPm_qJP=ra5~KJ);JB`OVexQm%u z-8S92%TN8Sg^6=bntdiej8FcAd#AY6ClL^DOk6K(7`3W}J0@gMA8)$hu2dNFL!MYS zI+d#J<5Eynth*hg%s;)BpEe}$o6RfeX8q&~aZ~%j!UzxYa9%Ct1LQZQ64dJS?b*`! zRsN5uL6))8=8viLG>n${xe7AR@mL={ax34*Y;BjUf`~>>?p{Zf>%dgi((p$}PvuVNIytXc_z1F0JB;Eu$9d7(` z^;k$o8`RTwQN zBPAy|!h|=4Tg00c5Db0Iw52=39ls9>1+qJijamD2kq#-!UC9Q`Y*g;j<`zS0GP|fF zi_K5)1`PiJ%z0Tpg`FVuSez$2ptnyD&HpkYekmQ8`LPh#XT-ITfIca?U>Y6Wz1&O_ ze=^>+J(>+By11t*DX^%m8J;4G%1EgmW&F}8?0cr;?#PN5=2fx|cesn0 zo_pmK_7;3jbNrnhz1{R7>$$W$h)0VBc%}A9EL}E(ciRX9;E2kI>)hyPqu?q-rj3eZuZQGZwGIB zp@S?_|Z7>L1M?UgzV2OVF@h1yvVLLKSPP424a8qwonxBxH0x5 z%38SVm5fmf#PUh*B3GUU@t5uO5=mm*qPpiNYjuHVMVv*xrc#>lsKGBVa-+eWJIW64 zd3;%`=!?eW64Fd%YUomH z&GGb!&G6W?1hN;KRdjoVFN0ZVL=Ftd8oC|>qEXob7g$Sf3nm~t6@}*atdSwh?z)X( zQ)ULUfUmhC`>vT-^ul_oztH6OnxHO^9jz$Q(nZ$U;H^7Wa;Ly5+g#EhM0OrhE}B z6%dTO=kAgC9OFr6x-hPH9gXrr&7!maibXdeT7&hB9ol#abbo9)D5`n@AIW0o1(>t*R@BOtR}kpBr2qIt@)CFs8(VE4K-*|Nqq=_aNT|CvUA4-Yc$?-W_>teYKjn{?4cMXdCtp-ynK^MYNODw z_#<(~F{pW*H`boun@%V{&YyIx{dSP=jbLfJk1=V=vAcFeQ)M)&&Q z%K64pDyOXcTxEXj!0u-kYL(ZY#uPqEz+s}X-F~D4kXB@uE+wkCt6gbT*~!lj7hUe&oQ<{m$LJ_t&688|rw zjn&pTohzfQWM=sDopefN&ov^d5!4-J9MqZBvKuVt0q2{VMNO3!kwNU$cXx-W?q*cs zh{-jmG-4*PHp1m!5p}h)2BS`zN-@34OXLwAgb&Jsg2jwG8fU)?$Vm3vlsQAslpX3< zMR|Do4w7&E?i0T8j&FE7!{<(9La&yp9-ajyad&RBi8x6LATlx_3n zFKLTz$Yeiek*N{s>v%{Bq@;Zu6#}qA?ylP0>-_!mIL5QN*zqqnH}{2Za_ON*ynA@* z_^nK&uy9B%Jkbkqz-X@9CjOSN)}{5b9U2Hk-d}&TyLim}PY!DJ_y5R2v8gElxDN0v zNn!nh_(bN0t+xT0)cf-v9$sM;_Z8#|#vQxWPwA-M7i442EiKl;2c8TU`UP$6s`=Fu zyj+shDGsy!rYnMUQ`Cr#UktnH=FgP2nyUNN_5ekKl>FT34>qA}4aT?n+-!Zv zI_FiVEuFi}c$O!6&dIexUxJ;&ynl?AofydKKzKIeR64#a8<+{ZX3nTT2^{s#_**d# z?&7m8eiiOAw0h9LCtePYPDINJ=e`gt9n;V&46z1fvDaR1dNa+0I!gxdg2w zR%@#fMb-{{so&2XpO!ydEyS#j?@hpQbYr#z>D-P7O%VaFpqF6Yq8KGd+QRhV0sldw z`XokKtrR&K;@?i!K3WMOy<^uNWbWtWN!QK$WF)176${O2oNB)sr$ zKbRn_(Y7R9Qioz#{tx{O0Y$EAx*>18^Bs-1@KPUupT3E&Fu8FzZ>K>+XEhV^@}`Ch z4cvq$!Lqx9hiOYqqp&fF1&oZ5$1`gtIrA`t-cPxr@qn@$NJ&Aj{=QO1D-SUOv9=a- zm$EG($@Zp4PLGdVJlh|rTcPS%qh7eQg{qe(0)S$qYXow%i7$~gX9mI&hKC<{SoFz| zjtQsOs_JQP()rc$!`9v|~&bZ3$&`x9GV>~hg<9B@rBMfA1zPq+TI zgSkqS7H^3>ag^U+f!Tt9^`kQMSbl6%C?}CW6pA2Ec<|&P-41h;QFH_n(Iu@(IDC)d zRe^3629%4ne9>AO2`6ZZnHmm3$7o&<>$Wi7k3+r?Tmh*-)BUv?_amF1dy!qVNz23sz! zs-(v-&*SQ$__|Sd`_b$eGKY{B?nkDR`>L<4z z3(Bmr!u$mEL}+{Te53GG3ulwOxI>3W@K484`x-Go)$my8Hr<9J*x)CL=mckR0pQ_6di;7MLIf3^hF-WToTASHXBY&BY-8_aI|f3fwJO>MAU*e(=p zu|g?sE$+qLio1J&;;zB9xDyEO#odCtJAvY^#oZn5H_z<-;oUR)7i1=rfpx8Qp2smv z=HSi~)@;pfQn(8Isk-q?4_q(CkY(s z6HCWP{#G&hAs+p6td|d?$cHt#y+{6Sx+cq5U*VL}%E~!?#BtCZNNvhBu^2r{-tf72 zcCghtniOK17GhtG{DZk+fIh8{-lj@hK4}B$AAb1F`#-qASB%M$>J>hM`?hN788xo; zL;^wOXDQ{w>dn5cNob7S?H850xB)uL4}u5MQg5iQ(H=x)!N2a|XH5LdblGYumW$TZ5a7Jt1B*LY z^wRyyo{FL~^{pReavECj*ubO9e%TOQe*8xG9(wwY_Q$LnHK`_{_%;csF=Q}*Ze{%( zsjjo{>FDF>x&I&B_C~)jD$~#?$TS%}lX-#@dr5NN4E*qn_xMQFLq2%#Xhr&F7x1WE zJH%+we~GTtm3?YAs|G z@)02;hiGVi)`r5qD@jsfT}Jp#=>j|7MH7Hpu~9Hq{TDeT*EA|Omh>#LgwxJnwt$z!6CWe^#%jfgGk<73Y>MiO`fTgDucH~n`c3Z{49+`|AA z<%l|P|3OfTz&O{6CX6o5y(uR$LF5P^ekp`3hQ{4iR*5;4xTE;SxN=6rbKm?M8cie; zYnH+75R(Z3wqW|-?UoAT?he>=F=I}u4@q0!m?*~PCTKuSH({H58e%tWL+7c~cOn;G zOhP!ORi6F3?C^&F;9kZD&bY@G?NYue%WG?Y)fAHVsMV7G3gh(z@w*zyl|8D&#ntcB z^bo5G-+0&n#326WTTT783{Cl6gvI%O=o*S_gK(+dvLdd3>2r8*Upg^CwCX#y0gkT$ zw>RuuH9=Y_A6!y7e*jyIyq43cRzSfSQuCdS$kkvQX?zSaO5oDs%jxWe5t1u32t^Lg zKJ1r{k22cD3$xr=!lOvR*VBe14X~!t^t#Wem*tF%T=qtx3eQ;v3evKc6eu1{nYB7h02tTdcHNM-!(Z&hMk>yfLIYBSJz;i;4YG@3?c%7rudA)Es|9z3w`MeF#J*%zwzoQglYQwZUc~z0 zKRDWUB)^os!Aa-#=yT;LRr2W3$2h;L{2BK=&Qta9q*QutSbxhTe~-ljt4^2BP5ggF zHk*7U3=~MN1j7~rR2jIIOU-?!_V8)EoG9F4EUZ|Rp0p4;`%N|xvW$tLnJl0DdE3SS z+rcYQOtuVT8}%K`*L;5|E4j8e&4UhQzLE;1HE$|iiolRck%Hlc<9A}ho+;N*h`HZB zS3sp{{fSJd+;$$y-Xj!N0cEMS=_Bl~tlnBrqrcZighD=y9~X!6>*tHn-q3gg;vD3b zf2N^gPSf&frKrsLV@1Kb>6 zvfV~Xh;ECIwS}@a1sWOy0>`t>ANTp@=A3nhV0|w7I7xXO00HxoF4|*ta-?`ho&#sF zUi!9kK%uyn{2Hk`OEYI=GbhLR{cccM;6O#wUCj0N<+K?JXhSVnaD@YA3D?&jNHyL- zSLV(LrSR~awfvs?*&{neg5guorJroL#TnHG>jC``Ua@;#x#a z>GWpC$I}V?9;80Ge6|J&U^(dOb?_aHj*AXf-UlVd@clX5ah|wQ+iIrHDWw|P#y`#2 zMaVGbrBndy^1yOF*Ua)w@jp0oSaiJ_=k__EL_1;5Pap9cn#DJm=Jfx`-C)W$qO-V< zHRbcZaS4AnBvWRU#ygaieh<|#5UAb%BtIhIBFGl= z?&g*8=+>{)!TnxH%J^R>I7Tdtap6{;n126EyEIKv&+@KzS2+BlsOet3g5XcNp$D< zsq4SwQs%-76wneI;^bU_IGHB)uU!WAQG}`|Ap3RO2h-*i$Q3z+lpr#do7{_Ny=rbA z>vB`f+Q*oHWc!hA3PN@ZJ+>v&`k|3ia(Ubo1A@*%@%+`snzI z`=Zj$?(Aeo%+Y)Q&~;Y+w}}ivnz%B|;Z{_Y{kjh`z5o8XX+hhkWl<88&`;m-be<4{ zGX(p<@I)2P?Ng1i(VQG>rR{1{W#an41bt;VQ32;wN)gO4$Y$=I%DAJ5BW`9Ut7C}- zvXcD{`LyD~$z9RrTZg(MMIcQ|q zvW~rWR>9Zt-hlW}DX50>V_QS{Q|7K^9o(s&7jJ=u{dh(x?kSH&8IM}|+TW|O5W!5IH|1bKjY_-hw_5gHU$xe5&NL2q^X~<*aW_&5EA-9__xste$)du>^1+IK&&Ldk|A_6|f+WJJ)=nrJ z=CBQ(1gxAUzld}#flv-l+BFp&VTbQ$lVteYGhMEO#8_RJ1&=(CZTPm^V zqs~KZa@c|E23upVd`tz3s=I2Yd6p@&ZOhmd-$+K<`lU*O8_$f(<$O0C+{3Dt=9P$y zF~Y)R>2T7=2YSc0f%%$J@m#&bv}MVkx&F~$o|tzDPwVrTJBT|E814Ka z=8|MI_r)U;--UF@7$q6;YkB;G9+?;evz<#aCZW1#dS_NB`4a}a(cG|6iz{8MZDjFl z*mH$Lk;Sd8MGrI3Zr-$_-l}oMQ_FZo4yqd#E-D;)?2lD9v?X9GDL6GMtx51F`)oSK zw9#~P3%HAaN$thEOQ`agEyxo6!^&5(_#H)}*fT}9&QXb6_ffA8C?56?8YejCz^NJM z!5zF5(6V`C#2;GQl6IWS7x~YX9MNYruHww|%g*Y5aKUM$dONd`v#1O*cuu9(^*KV% zHKA?v+X>Se68m#vDfG*v%P5QThb~=%m+K zxBz^`z7QzYjL=ky_Bi9ss=%(CBh=F#l$SQelk3>aK4IcYGX>23hS7TX;SIl@;K%aB zmydlBRvDpdgaM{BfT>8@6%C_}Q9GXAH!vN4f)ThGZC7m?B z+k1;e$8~;u|H0+H@?~n)D=#z2rDFOsoJ#vCSa|$lYr~6W!Sr~#1@L75b*&+dmxVxe zBQ#Akm8+`DQ_8(oIOG}aIMtQIMx%FdTNE&$s@in1Rp?DpI+gogxwK_E8R{?K7q8x9 zHu9hqbQ(6Bg3#$^dJj*B(f{C_N-nd`_Ipi!PWXFAxuZReY|eCIXiDJT%_aQ`YjZjL z_3K?WOze&o{;~+9p(-sK$c@~VQjIqUrGD(i+`D6T9FTzZ_Ah@7Y%)o|J^8kC`-V*k zxj5o43!?!r`^+au?WFR$^&YD&QGOfkc4c0wf|M!umzRmL2LA=wY+ZUT-B4K!zkO3x zI;grr2X0;827FX9^~bWk>8unXD4NUkTdvq~G0`xug1Kr<^v3y3u7>Yw{-zc4{oamy zOyMvRSMId9tJMSpA#W9UC!;{4m{VLu%*Ta^dhS4I9FNhVOttQCp=I zT7=*IMB}*8YlQH95PRSGLQDuIziF8E9p<%QzZTB=O>&J!g%w~|{^>ttVX!G;n$%r( z+{7bA^ z{9U;^oU;4Hvq&ZA!NO@>sOpq$>Y_3n=7u&^X0+X{{H{zT!m%%3}_6m&S{r5~lxA_x zuV|F{KoS|v4_gEmOI@o@Rty71huy`0Jkgp7#qt~yP*D$2Abo7MR) zXE4QI2mQ#j;#42VVOCvM%`8^>+o5{<-$q?3raT)}BZy)d7HDF?MFFx`ZFSzNAxE8` z$fn)Sv%@bFW>1LJ>Y~}9GI;Wo2-UoQ${dF(>M?N!FDZ7aHIq}dKx}f?@CSD*^1%mO zt!tY_Dm!j9u5@>{U~9Lw;)%`^D&C*qveii8$Y6W#??WT1_nBsymIC>HE`G9`P*p0d zw1nMUC8~&RHB-qL;HUL;Sm-@}XGDcBM{W?nitw6+wE)Q$(>cz}K-ndg-qZY91Kgjq zIE+aD8|dgVB5FPPaL+Z*|Hor;YRzdsZ)$9JV%PjJfHM8BM&ErGeXpng1r_-4`XbJW z#kZBhyGqls0oh8FNBU}rAz)}jM@sn*leFm$z*D`nDL$vwRM}rZKT5h-U`I-{o_kKgQUv%wE=gP8dQmzuxd z+4ZZ^rMeIeNi>wNa(bS9$tP`L@Md;S&IU?jWPT$&5OMXnW7Nt?zJ0ud0|GhzB{;HE z=U58WH8?r)ZZ!Q^DX_FxXR<5*rT=DAwDd>v zYXwZ`gI<`?^Lz`J%`NqTQL8<)BnZwu#zo=@No&%JD(OMh*bLxBJcl~nu zhpV;5*!7tT9W6(9zHxD}e2DiaJjR~=7xZOisz}St4|-S_GsW$+NHd@Q`Y`}Y(%yUV z$9_vkR{wi=q+n}x2{T8@C!ShMj>iX1Z4_16`p`8+-bca5D}y@4bq9wFxAw%|Ow zo8m;nwbO62_~DYZH3UwFwNk%BgZdcV(}V&?Po@%N27J?>fWjo_7QosnDn z*< z3Wii`7U5!XvZ;kI>A$$ixJXx=y&jQ`fjR4)HcL3qfnGQA^g<=L2)oINR!5lnON9tMhEzO)2ziLZZ@u}vpSEj#0 zLK`O%&d71k<7QRB6FDjJLVdjTUipX!`R@D4E!Dw&L?GA=k>Zx@*~a_3%u9E3keJYC z&y2{A-oGw$Ijc`AA$}?Of5<4)%FgOzTs5RL+_Qo?`qs)^x5apXp0g*Z`SEDT<&~*l z4E7T}E5Gd8)VF)YD-MTrzWx*UdP(Y>+ztSXUB|ZP*|W@;u-F!ka={+mv^UYiEzkO! z`k|*yPdDwhb$Qb62A}@@gA9&mOewBX~^OeRB(FIq6BR} z24cEVv1xqr+?pH*g3hxRk~w$siy6F;n{3hn`Xtx`T-QeKt}gWoz}(FJktbibL<*CLQU` z(07G;uv}&z*=jOzdXKL@UcZ`D5N6*XN24#BqFf_wH7z>4uPlH4N&-~dnn;s*7}?;j zp=jSk)|dYM>xJgnPM$0;zv}T8M*N+DuUh^0_-SW)Lc$-Dsl~ByW8?ZM)ZCuY*5hl)>p3#AKY$L@X+2qN}AB-=xtVXDFBrS+=or9n}%|TN{j4SnBhiA#na?zKo^dr zKOf&Y>eJp41Tv$30qfe#OG`eu3)Z+b7<~lgt#B*XC(kXV5MNoa>lopNf>LMjGXp0$ z+}j?F`jMyR*ow=Ur8N(1%f}P0b97ne~V$-#H8BnWcSLvd;gToH6$rl=BYuOD=-TgZ6%V?L( zq-#9Lz$m0+MVB*kVN8Kl%Y$MndQ8YS7XzhkXZZ1BO?Ce~GL(C1NE$g29v@pEhTf_}KX z+UuYMiuZ5%>8Nqe>*A^@APc|ykt&1Uy{l+?95>bhTV+-1WOY`eb931-xa80oBc8H% zGWeEx%ok{Kgz!!uYuCu_M|Q|y3=(M?){x}Q(LXqOwF4>|2|nuiHEpC>*82}M!F2ED zh8We%ZfEU0bHn*}|G|A+Dnh1jOi&Eho?YlABO1x&;>_1VNjIOBkFFuW0%s1lR}|FT zn_B)AM!gbKZ1|eSnNg1&qOgjg%ju1M>o3`O8Beo(R!A^G9p4)@NCM=WZ1?{$i5BnW z&AyrEd!EzeE8LWc9oRE2&0!-BVEGuk%i2BK;6oTW%c)`NBgBbyo0-uTVUWmUT~t`| zb){a5RKk<6fZ8-I7gpC6x%I{LmC)+a=7;cf$v_f14!gGN8eLzEE`hSjDnPEwPoHXZ z_$uK9R!#aZbO*_LCdZpF;*&5dKVyxwrEz0~8P8q3AW4cVBTi0UM6FCcgny?WxEUv_ zsjRkRjU4uM7?tD#l(^S`7 zoaegx!s|%oa|Se@>%07T4?-?=M>pW6#2z`;6+Y~r;p$>IIbcnhO7-y)4!@K!^KlPd z9EXd`5HRZE89xlpxDi2_%TG0-r|wYZnn{md9tj?eo^5!l?8Xy`%!37^#Uq>&ku6{a-;3#PJdbr+Km&tbv6IXQCL#?kpZk@$J>QJMTy*q= z1STD?6wxOaHs<4A37;99ZcUX}#z@Y5=fHq{OPO17kpHoLMc*HTyu{jY;_k(Hcvxq; zsCsKFKq-Qf5J1IC!9Z=0)M>nK&!SWY7_i3UKn05ypIMWunq@B=owN|kQext{ zpq%~Ey+K*x?z?a~>?1Jl=|7&)1EWZ7(Ta*1AO$GkLCr#C5B9$LuVIC|CC-;NuIKz+ zetP@ToXh$I@H0|%V#GDSs@=^hlC#BwMi!PHmw|V93$PmnX%i+ia;D|(|9yF^YOS>- z{~-JiZod-N6YeDmx;T2zHk4Mqv-=#voc4da$xhrgp>dJ3{JWA&HGUmD&aBisotT&i zwLrqgY*p3=XD08cv)JXoe%@^fP-;cN`Z0OHlNq9crYp24Cz#02W4+!(lklSM;dPv; zj`Od0cB_&xkZ3pvd51vYh(X^(=h47kkfr1C_BmI6ox9&cNWX(v!VgDbS;slqWsHyfEdpEqdV&rNACsbpuAtw!e|QTPq5K` zqdHpYceMq4;wgy&`s}~2A2t`NqYZ8kJBbBfJm?I^dhV9|Ln$FD3;W#ga$1Ynlka;d z2RA3Kx8J@^_^2b~3v}%U&XzO9ix^nY8rq`XRaaHJ{l$M$En(I;N<4S(ZpApgdb2|I zTz=r3vfU`DqZKU+0k9#GY$vT9M!!x~iSABW?kjH633X>97e-eWWhJ|c?m18|P89Or zGryKAQ?@_ovR{6p2n_`TJ6)H6x~7QwKfiq9Z_Syf9$cFjXmb4bGkhG-a{JAHsS0?15Z~I6$Xh{HF=vE4-4(>am(YtD~#C@8_b1wtjZLkov+COR`;R z-#JUcTLtuGa;%&NW1MfB+0j?dg{-ESNMA@|jP#yd-lkyp$o!>RKN1FMoOg=HT+XGRCjet&W) z8F=3><5StHG3O!ly7bW`&m7O!rbF>vpR-M7&C1>Ki8n*e6E0kf&et=LJ|`1_odvv`%Z8bjtohX#l>pfy}^0f zeY7{z;M55@E3xCMgnrz3mb}k$5BunD;;s9S3-@Wq$K$;_<4I{+qeTL=X^0Fo?rnlp~Xi)8hd5cDaTCfzrv1$bEC4i}vv zl9N>MyISg;leY5NeSNBJ3p=>j{M1!e|IoKH1~tO)=12r3fo%x3j;&#X^lA z?IvmNO0C71ze6 z!~NC?j{waoAD~Oc6QZrg<%oG=x@)R3AMm={Q)e)=%55m4$T`jBN?9+C5a4RQR4KE6 z5752XtqshiZYyIYY(0(|)GX31O1?nh>wHz5Tdw+hILJ58wJtpuKW|Uv6id8YR?lmj z_8(kYorThvAH$BWKf65dF7WM0SYhiRw)j7|(Ml!eMUB;j;e6|v3fE%sGTN2+d3pWh zzN39-%k22_dF|S<`D6&r>n@K-wW$tE^$(9&=A-g#J*UyH)STgRIv+jCP!0I)Xd)V` z!Eq>p|G`mh{*7YzHInvle6G9DXy7*zYmubLC0FZUG%KM79D7og%9W%=td?Ap$XPw{WQcTgb&U4`;G^uUnpMD~0M+hm zD%-~nZ)ul`)po=zjRK&2-q4Uxu*b*lR@}Ks#^L2*MAN0LvAbHjHn49lEDpD#f2Wt0 zM|8{!`bnR^K6H{R;_Wjj$QVP3k!;(Ck8F~jZ) zNz$*+O&@oyFwB@2{;9NyplCY%HEEpxB1dV*tB?nJn);Epm|nE}DrHU8Uq(-45g0h5 z%=A)whHaUww7BGtWt}Ts|7BL#ZaS);$y=WyF%iGoP+)5jBNuboW?L{8SXgNxB}sGR zP8q>!0*T|5cnJc{gt$HwOOGlB2l?TghKh-22z1DzH)&3PM(Y6GsBTEU{zY}s;4A!K z9dwvtHnTI959eZzlA-nS7z0%vl8(*&QAbysqJ+_LRDr;evtfJ|T(B(nDDRc8rA(rB_Ehb`TBJuY5GeVcbx533l36Tt5Jr&ai&!k|dSmtS-Xv7cusn)^~ zVxOmF>(kaI6`G5{NYzfxGD975Fq-v`bvT=#lRqdw%D5-|O6xgXrjcNNDVBSB4{KEl zdJhp7M7H?-$8}Vp>X~pd6fdeo5*9Rsmar}~#-y;5Ri)yA6Gvf~Y~WI%YYVnAqR2YI z+~~5A_tsT!^;ux|R4-N1PZ->)l@RfRVWh5@1{bDGM{Sxm$rCbsL&VewHwXw^NgC8{ zhAI8Z;!tm=MeB1NA~=8`A&2Dd=~6$4J3pF}-mHjKj}1zy?OXuI6s8-=ug_?ygsI!)PS) z4K}ViQ(A9wpX_pqICPLxpSBxN$DvioMtmx9-VS6K4e*%zLP~ znMi>*1n9kP-WoOCTNe)_N%UAsPr+-=(~7bk>|d6~?+g&pVVq#KD+#|pWgurP6m|TI zNQt7+9rg9H5l~Td@+q?N&_INH+1C zBz50Q{jZIBQ!(9pdwk6gD*Io`eBl2|nHvt&h}BO3%W@FYMSOjPZ#({jlRRqDS+BD2 zyaj8U1sF-=43{>wtp5jxS-mc4yfFZQAaBC_rY(=Sm7$P`vm`k_AAH-d+k!}0E><0P z2pijU#-l0LUN88_BtHLqge)AD_vDd`IrT1 zd6t>X16$t&ZC&?SsF;}qQ%siT9L^#sy**Ek>OthdGJGDgXhBS$9k&Tb>JvQ?X~F8f zbceo&C=Y>f3P4j;qpLwg)~VaFTmFNLAL5VQQF3cn8dD?mDj!xqyhltnHusrZ_nOMAm;Kh0OPLnC!FE?E)5b?vLT{d)XVRS{pg zWNn*6v}j{L!Sv(9@iWa~&y(pteb=+tCfm&THR}sKRcY4YGGo_GdQ}p0Bjr0n{l?oE z!lEQryX>aZ(D#@!WuI!`!qer*zEt{o~gSw3P!!PAH3?<#=KwDcQr6| z>v4NqCh};MvA|g7WyE{i`{^{#6tw!z^*04IpNQP1+8-XvMb+%jm`v-=H5PT&f7GqP z2qwHotB~PoBSX%h=*N*8>3}_4j@ zCqy=oUHhe=<;W9@jvZK!YQ{Lhpe-9#j+|(X>pICl0d{5IiV|+P?rDE1?PVM~*-w3t zB>5`^CSjSw9jSMwcY2Mg8NQ=;mjYp6mu0p@PBR82?4U^S4P35j(3%o4xo_`Qy4?CR zNK^ej%Su1TMPCjop$9f9;CrlUQ}qmfvknfx|$Q=FcZHP%ckMmO|JWZ9rH?tQ6dwM7)PXiEFQOr39k zcoLBk7T01qEZRO?^qU!Jtw)l6uy-hU8kk$C8n`@V$)K-e*j7fbS+7m8#7Z#hcSaW> z4)zM(;k<+HUlCsmi`W?h??LG0gFnJx$)HoEIICl;9_|Sxuyla;!V7tQyLH&?zxbKC zZ8sp!W{e6tSd38!cq%DxF*&QQp%~oDMd!0Bt4XuZL&m#wMy+6af6CUV4*_d)&hrz^Q@q!J4NTJqBueZWS!ej<#t@y!-Bu-f!KGL z6)B>2fmQrf;J^1Vf6Vw-M$CsPZ&{);HLEb4F~0YF381dy6euzC35+MUa!3z6_jJ`I z(7`y{YG&i!3Cr6wEB@fl0~oHF)dU=7yX@3+dLmWz^`~L~;?&Q_=jKjq=SwR-kIQ}Q zjnS2vX58bU^P*T8G`l_dS|vNFw)|Tso7+!u;m1qMF`tWEqp?H5{E=hr?Q4a3Xu2E1 zvEGkl$ZRS&-J93GQ8(Q7{z{owg*3fmLE+5}0-Ygtn4dQTwqj^l00pe$UGn6dFBN#A z_o<|Af(MZ%DZ0ykDoxlzlJ#~^MroaSTchmA-eokkFdfm#cvwd7DEKyR@s5l~KVi5H zHwrYpg+MM}x(dy=9w^YyMjw>qDfm~*gE+{!yu->Uc*8X^OGWQ4E)+6pVBCa$SnJrHV@UcPdXbSgrKlw5rV2S%7}*p3QmR3kZ^T zL9@ki0v8QhE8L68JnecEdKgDUr6@EG8&oD#{>FkC6@pH?_R3d=N48e+6K`;%dPM8J zszJz80?(%+>79R6sd@vgGKK}z7t2&mXF98m2{$cnKcf&fJ`$(2)ry9*2h*XdGfgKvIL922rZ~VDAi!9J8beK4CT{!&oq_ zt?iMQR*^j z9LzS=@W+VOSa0B*#R~3Ti&<3bJQ5SPm#=B}kFLP;n8CP4B+reCkLg-v>qc8Ru@Kc5 z0QaHgyoM%4Maoi_AFRACG$wj2WqVx6)=~LY?6c5mo(ag6=UzlofT5-AgKm$M=QUAckU5aR?+;W7cAD)V;aoTJ1mwD94+Q zt6CR4{X|=eko$oN%(Ad&;_l9u-rEK_;eOD$_U16YrI=6U%pwgzaYioZAMtg3THpyN zGt-IS029Vvdn)IX$%k_ig@10>QX20JHT^!UsfYuv( zbpOpThg@xl@2hbKU)UM5_E@^fr#hc9Jf9bQjg8}MMe)#(<5Dsa?;y!GnB-_4mAjS) z@)eX*2>VlTnnVZl^fBkc-`*5t>6@f z&iFL8Dnf0C%#%c5{9>y*{J**Jpp6-`}yvT5H^09xA9sYiUCL zE@s26Q03~Nd-d@`o5td#4ao)%4CLvkgRWhan2y?qzcDKL*=Xh7gKGpkF_(B~C?z)E zKmN}$dwuc0ne66G{{I`y#rk^Oq`BJWA%pT6Y;?Y3s6FU?mT22W_ir@w3I0DgX`KDz z_r%#p>F4sc$EEp7;|m=>#wpdkhPWmricZWQ2A;GY_SZE$qM{{01AFSkm-%qXTLUBf z|KLtC z3|B$s_fHi^D>baR|G_!W$E^<8_B7=?SO~T)K;~j6Y0i(EDSQ-M!fjgFb*Ejb9i&DO zjBKyiHNV@*7MVcH!| z-84$JY%{VUENjkg8Su7pFel~D%aC=j7aOkc#eBI6h&h1GVieE(O?FjJ^wuOh>x$3kX!`KbCmpItsM`O09cNaJQW~;P?Uep8a<3owPjM{4t zF*SAT`??Bpcr5&KmkCBqyG;Dz69qe_|E=LD>|l3X$jatf?@-bpWmb>4vhkZ9J+}3i zddmH+^ohdCO4(?y&-X&zhQnxQ2K5bviH`REr8q2&cbElo?P%-wy4n(mCqZYtnoB!= z_j%go9!Q@?DV|R{5FnS$epn9mfD=`+tDdGT)nb2olXD&4|1C6XE)Hp4-cP9OoTiuy z&TeB6oPoOT;u)vBVNY|n2&g!uN>UN0wwuejYQzRwJCu7hjZU%V&w;seLPU~8A zbWq))WW!Hg_>qm}j~4%)6M)m9O6grDaA)nIh#pxvCQ_xep~$gJ=?Vrb^ej6!Vjtop znVOxxQQWuY-A_zf+acTY;gV;bOJk+Zg}2jbNN3XP39{Dr?r9|;tv}FiJQPh6(Lcbs$Z#^K zk@`871CS{>kR&u-T8(l9Uk?9m>4NYTn&r8(<}r=6;f3Z-9qOVT!nfYdRwgh<{;V*&{lH$C55BLM~75KPiQLsqOAn~?#m#Nocj zTEcV>T)$RxHx?@+IDC%GMoCn=v`4o|Y0ZRjb&y>Jpst7e9BJ{eO=p7@k7d8Js0Sh}I1w4bdu{lvn786zpNRUW>TIyR1;A7R({~gZ%es1{?>O-%FkS! zNafgKp8h?mn8z!CtO5-c3#+MA-iFp-+^u@%BxjVvO~2B;0HbdaEK-_3Xz#|$f~NZ1|Nq&tAx;tl*! zDudQTnD9Dl1g-fe#jDcIj!VFz9)C-t1yUtrvy=LDZP_>Wq(=SN4`lBBjxHZ+%(B+1 z4$7tSR-ZN6!I-&Q;R3%;isBhi|F%oUTe->L1Ku_5?MI>c@l$fcvc6RYm6;jNC+2!{ z@y(0?RFjn||MLW>rOjb9$y6>DtBOnOz0mJQ26}}{$L|3oOk4AI8ehr~mdXRqe$+SzXXy`{=%@CVt6-*7r8SR%Fknl7NSyarvRuNU#6k@)M5$ zK;q1*YQ8E)eZzLmxDC?Ax{qWB#Mrm2Qe!L9r__pwYBG$7Fx5&xz|3LC%QuhDw&!+j zys<3A!;HKhCw8%G7oWu`6WhX+`{$HZxD=Gy z_|=BSX8ga=OfIwO49m~46RwWT{N~)0J!R+b8)%@qrNfoj)V!L6iN{ydojV2S0JSC0 zdw}Qwy$KOZBu-0yeB&HGXT+p;EGP>cT}ksO$me(DaMu;Zq|KPUKDx zo@S^!b0U#^)OMPctK|7!k_#n#{9%lVVyI(=X)HzQeBT8ZCF_~lDwGxd@Ov8$^jF+< zG71nP(YXH8>^^f{4WLeO?p<`MDC?o|fzSK;Ms?|wA%GgkJ@zknHyDb4tf3zYJ#dH& z+QrRE-PSnAoQ(RQ|MA-h9fobgDUvBTILqZV(&aOz%ZJ3i9xm}tced|v{0!wX8~t1t z`}r&84-C_kzFG9LRD0vQb!fUe7rL^iNMhW3XL=x>>JqB^?L^Sqr)9r}w+^k!iMI!Y z%+>W#C@1^M>E6^W^~#P^(=6DElV72_OQS0NoxWQ%e2+&`Ezusgu~pzTxxIdMS{}GN z!yZiN()nsNk=Y_N>YnW`sdsj^7wV?|GooUzz51y4_Y< zaHMKQIQSvNVytSRI?DX@vy0N{6B{0$*!QghQ^ggL8?|#|op$|sF?+Bo*U(7(deM7< zihcJzFNAST5gXy z*@nd1U-MeJNG5d^%)E%}_KSAyEIA!_t(^J89_s#Ugp@#%w>Moya-8<)cqmYB0XFkZ!AKB$#I0=nA z=Wy zV=MI@bBsgzQ7oOoRM@)z3ZVyaDmU3v*D7gHC*PS@x=%U^6@nXEte5`^%|_2oTN3%!DtoH+cvFo; zqtkI=aGciOcz&Efz<$}Y7rkHPwb=1UTol5aOHKX^1^ODvqfl8`doRmF29bU$i}^Rd z;H_vZB%w`jPKfDmX0y4L=FFTR_Ba`mOuf>lQq0-reE9l6b+|K!2o~Y)g+N=XbGg9w z<`rpFv3(pmlxe|1$y=p83R4z03h-AZ2m7G{@JDT7S?iVOd0nWGLritIrN&5WtV7+( z`9t}1@cq1eRrboAtlU|sEjIKfMIjH)oXpx{XS`}UAPZ-Fa1RPExu$icvl|aTbdzA# z*hs{a+v<%BlUpWJls9((5o4NZ+~7Aw|-HDtT6toCO`b$+~cQ|lVYQKrgGYE ztkIJ6j%ia`^M%)0<_VR3aDg%v0#M&>)ai*P6$jqhA#z_iUpnM6364buA!8WVS?cf5 z54H>^#`h@c@IZKG!r$WJ9B2%*tT1XSKnZ=FE6KWz|33f$LH@pe-sA-V zna}x!OP_DLDJ~Y(2PpfZEn*kQ?453_c;+*Ja0IS1Xm~E2o6mM~AkCvAEg!K^c4N&f z<@d^U=1NWFlE?~a7F6dshpwJzBs6QFLq=vxA#o7I0ejo6uc9pqd5yco zlHvgTVxmbmVUSqxe^|a{h+!3wInsegQ3DRM(AIoldyUsi8OLYFv1*)FCS?^48>h-d zrzi7kL9Wl4)XifbyWULL;oU~{bPa4OvcCqz;KZ=Xjm2aQA~yl(^kTPW&!k7R^LOzJj^u9%%BbqPC>5;`KLW*zZ9WdnK9d8$X{sr3n5JZsx0U+iJD4`G(RFnD?X}tEt$zmAEmH+XC0QjiOKIkld62Glr&DfR)>q`qVEq=x9T0rZ zbDNtlg5N$(t+NW%nwAa8g~PVXm7x}& zL0haG$F*a3rP0~2-m5bYRjdy+lo6P&ce9SnxqOGUWNWqZSjj)qSK2ybwhe_Nrp49)@#Tt~>Kt-Z)2{p4wIFWnv zx|5*SqB8;BQV)``*-+c$_a-fGdUmfQO>SbTr>)X&COJIZT-3BO-E~{E(K*Dq(R5l( z0J*xZ%^V@*IXN8g>OjF84xLtpCnKEF*ZP5Ox>qreX)3w+2r+g zyk+KEE_fqfqRQHHWEsAthf9pV;FBGe)+>hA^&MLzx!s)t!dmuP;Wjg)SolO^JcTmVZN{{O=wWTqIQ`3{!D`)H%B&#B*<)sLEi}S9n|~&L>aw*p_cz^`;hsR|xvp#Y)@Ad|1K}x* ztT=AdHP4yXX{&5oxtZlr5ahmuGRp*W)4WvEPR#Jn1M{*$;yhMU9Ikwiw2Y|HEi9-h zPE|=HMbS~@r=oU5d6{>6NF359=|%ljAhL@pM^qpc$E=R;xh^Lj&(@A;0`2Xj?5=gL zr~`EkJSYR3{{U|lNq74SLtWsg6~>$)K8cPND9o5wR15i_jTDy-CtM^CHi#kKuhN>E z49Eq4nv;_pK?9PLM^!H8?o>IcIuz}seuTjnUz$?OQXhcZs) zo3DRAH6bY?=&?z~&%s$sg^%_n!7;eq{k1OaIaB*K_9W|HhqS9yr1rhZ9?-fEYl$E) z$tg<{wLE;%BzJphzp961>$~@=NOizkvboXMQ}OV}y|T{X9lCp#w7gX`?DgbIr*C#w zbM_+2i7#spk9}it(=ENqh#pEtXP&oB$0$=M^lj7jvMNdLe<+)rFVP2u$DT`}*KqSd zEWI)xtv2yn#Ywhrn5^X^fffp7?6NR7FB{e();Y&P^eb;`C{x<1vNw_FvK>}9_;vh> z{^#!e$*ExLn(2d;s2Q!*F_$lrg;irxuKXIw?@->_vH6qO%r{K0j*2aie`Bk1z6atoN$?8#<0_T;3o(sb)O?05|xp z2=Tfy=NWw#M5e{*SZvv&b2`0g%ROBO6Kui6`xcc=bWt#dgDj5q0_VQAroH)M7Y-Q? zi*^m3n|2LjOfMQAByBP5In~F1LPehKF0)h8R8)faqaG{O)8Mo;;jJ;;-;X-mikh04 zng+xzuBs+BEuRngQKoe!IfX>y#r83dB!Ai}7lmI%_+=S(w+|Mv`x@Op{$ing>38Ff zDGV*{5QHm8LJ)uugdhYV2m_&B&tk(qD>I$QODEBiHRC!J?6y2#51e?^ANM0%op;fC z-v<8xR}K7NTX5NjQM_Jyg2s&B){^VJv4%3>D z>6_k~O+W-2A=bIc?n0cx-BD-@3AZTiIV+zfDpav|`&9HtMEddH%`}niA8KkxB+~<> zlKNBR5(NOy5#j6APFB6F%sGU?8Yu^Z2%Ck5tHgoK;i+( z>Ew-qU6U_QD#6Mo5oYp7^pyfS zlr-kEoPu>u&j*U>1fD@FTjnR3A(zYQK>*{;V+`aN6%4w6f}8MagXG6+-lwCz$(FgU z>?Gl+RRj=8Y4cOu_kLwA?AqVZKpi_sIlg{We@P-ZxphXVPek}~dy?s&I(PYr?2{+~ z_jUUUbj#CsWkV(SZSG1GSK-g)bilTO1CnIxuQY;3%0Jwe@C|iMj{21bmNX4j1boZK z>`>#w?o=Lh(wv~ZmAxC_1C&8ZCWM(L~?*Kp_>*OFsg+Wn*1{5nnDRx=Tl_Ti=mNf^8i zIkY&g(KcBltfr&FbL5W?Wo71jKa|~ng5yB^Db%#|QP9FFUndmv#3YhWa?-F|Z2ARW z-eE7NsQVBqs%u0>NM)XvcNr^zw3z*5^zuVfH1!lRw$TG7?|CQP7n_zyaM=Wx5>7Z6 z$7r&}K^x4H;^ptDY<7vU!@$I9wv2|RwU3aE+zcDGNB1SH_eRG(tPcD#7Ud-^W-?@M z6@=n7f-$QoX&o~ozu*wH>Kf=}nwnUqhIpjix*3n8WQ$W~6|~R6CWGvE#wsMJ-ZHXz zK0-Cin1{(~$hi@^+Pb zn{5owwUb?C9DCB&SSai4y!vqN{p`Fm9XAxD9h*XSO-;+ zr$x_av5w5_Du~fy9F|tOp-ej~W%f>XD(xxm{@w`F$t4-dnPkd*mLd6-mj>#kLo*xf zRvTv7WBfIDxXP(xE1RE0c7F{fxDjh7&owg$w6&@v%GWiIT&ZSpd3&A1b+=V3 zi-TPLH?DlI^kDQ;6=_^DP>7g4~*R*0I|1ekqT(&Dfuvp=?7d zqi+vIs@FN$&Q5DIQgOAux>kAE`<<*Rk}N|MqotcHkxf47?SJ0Z?$~VR3l7bUOAo@} zrK@dJOlIKvH{LDkTR6ieHxsX%#K|NJtF?uV*x2(puzYqbhx)0OShHHWYgYNOS0!Q} zATXO~PHS8#k*&{Na4M`@45=|yHfZ2*9+2(_EmYZ6M3sgqT+YLepJgln=M#(Z)dX^_W@)5lj)0o}(uv6AuZ3qH?dm76Iu#uHdY8_9gQ zT~l+y^X(rbyik?l+1lW$I)^X;mqUcO*M6c{2ssN}KR=R)o{bA5Ij*oZiVPYi^0_+Vkdx zCrcyNOjzjO^AhbK6S<{-1kX#U;>*S0pu@7MBQIr$laWdGx}cprQX>8evb!~umj<_* z2_&?fw^B8-w>sLAq1^q*1{_u|(3`p`HbkW|aw$74%A?I=C((~*=1e8SGn5x)cYRh+ z3W0KqBw5*omK`1kC6u<})>7yFekiYLScyV7C>|wtY8Pb zS=nFF+jYoco5P3oBiCUQ*K2CT&EpFh1Bl#|4r^0i1-z3b#t-AuHOiS#x=YSz@Y znx6fD{{Tj~E_kURyEwc27h4;Pdq)&)W^un)Rm18f=e60 z+qWggek&1kgC5x(ZCKYX%sV|EIWrwqD}*t}qhOP^y4}7m9&*6j~9wu?5YD-v-7TQ-9ukfRe?`N@al^=Fo)T1-)`5xRKDk)ETPd3`H( zz_hfE5;FUiRpMiV)*<=p;ibjfWk5?Z{{YEs;r{^niPz1CAik0C)fr~kP%!G@hOxix z>KDz&Mcq!=VR-dOLJ+M12toit5P%SbAOqPe+H7#O6xsVf7?S@0=0?0%NQC_&55vY;6n7F^2WreQS?S#W`*qlu9+ zIN9ouvgoV-08YP)TmGg^`DBV``jMSiajw1_1dWZ6g9K%9iytF^*5t0803Q*jk;2=^ z_oS%m81(Gth9G&ly;n*t)m%+%>|>#j21w5pcvFKOqJ09hO;e<&V0rbK&`R zi(<2pf<8)7J`q#HEh~hA-S#fbIYZA(-0Znn>`bAlqsEItY;VafPr5Fo1&(xbHeM2Q zv1yWgO77>qJSnwVj7}VwRLR7~Zr^e3N%m`@50E?2_7=lPkmk4aSXLHu*`z?q!0S2w zx^cES>41Kb$rJOl+P1`TJ}W)BTh*Nsq@@C5nqD)Q6YowLTJByJBW@2y_?f$OlQ~D4Or(SA%DHh*Os;sAgLy&Wm7x5^+7n+_N-7csrxWs5vMe@14ND01( zBgc|`3J?goz@H6LxM9iQhxQ%pP42bHC;;^KtU6nz?6T-Q5vwCW38do%JU6v>wKuX=|4!ngD->TPi-0Cpq54n(Gt>L#utrcN3o8 zyp*)`vO07@11D8k+v^XdF3({RdS}Mg@wx5|ZT!uX1pffr>q^C~TGSYYHY-6DZ6n@k zQX@}tqL|bpCT@yIvxr5235AB1 zxM;DPCO{{WXRv>6i4>MyQg>tAo1Mje;*c`wpE8hS>Uf{@DYj=nFi$cx?X3ZxNIcZ% z7EMKojB-yky7N!H@BHdB= z17C7aP(zDcz^O(xOe5tw2S;gp~@iW2=t@{88|BV!WMVH9{hB$7n@ zMUvIjJ%dk+{mp#B!O}2+>Q4Vk}B(ImD4Qj+1x0$tN`A#jBp+_D>ziBQLv}mb%sM;>Mr$ zUN+$1!we2%-A{*8jo2~$)=$1lxIYLO#U3fOm35T#m9&C)?*w&_ZugHK_1M97!L`(N zF~f(x3i?`UBxDducT*1pQR9_3j?H3KSj|5EI7nqA^FU)25_znvU2NA{>*;*zG6)g2 z#B@!~xW6Tp_K>p9C9eaS=C#S)Ys*E@=4Wdh*!Onh@Uq#47S+%QYAYvTifBzdZPk{M zwoNme`bEu#vwt;H_dC0icX6YC6j9<4$O|0yYhbx+ z8ri+O99oC9^$&A+D6Ev`Nn(FLs3LS4R@Q zMtc^eG*s`LHl}UNH|?&PxvZV*rL)QRU1jl5(dgRH{N~#0)llS%I=X(=V0@NF^;kz$ zkan%+v9r>}W^v7B2Ekx!x~p$wteyDm%tz9)dlVk3oZW1Voi!Xi-bm8LFsmzW#3;qw zc$kan%^ij(udaY#7L59$R@;Lj8sDU;Hot4OjX(|!H%;N%%(%fRyyI)=DTmnPvFbm zS`s;~E&%DG(U|eDthwwQ(Cq$JTCa0U-J){dt#>xzV6}_#lWpSIaI>{o!+CuQ;l=SB zdtqT~$?6ZiY*QBrTW)*B9B=eyNp;a>f?LcR-+x6`cogn>t(uYs2!FjX5MGdB&$isTl?3sv&6M{Re|V{XdvhlEg;)Zr5R1S zC*~ISG4VG)RYk2W%+5+YN)Bg&-^zky4{>)Pa=UmgAjoQgn~s&>wylHjLtWzFyq0V4 zTa=L!#;Ou;q5Wwhn8FQ3O#+=COpZ9PBIFV-&)pW_D{7 zyUD1-;xB#v=^vu}>%?NV4~rog_kF(wo;z(V@<*Ysb~lq%0T*i`*S~-kQ+If3wsSVj z>;sYHy^q26KFlL(=^}PkQesXt^$p%?!u@xP!r9}#R?IO>V0P?r9L={)K?*Wab$*_6 z10{Pb1A(y!<`%UUB-~#Lpv0rl)zdOUEp9S>C)TzGYYeNAui&J#a7RugIJj`28B%ib zC#RBWdxC0RIwxnwJyZ={`*^4@d8qFoWpL?bRwKMsB@P^1l)2e_kaDDSC^TGKHT~&0W@eXF zt<;{__au~+9TlEIL%RyZ`=s{Nx!F}X_SEGd>D)*l@hJhPsZ?EebKp|r!Y;%nQ0C?w zl%C%Q)R-<&rIRAc-a#&9$-C52bxUDpH$P7=1*=zPzK4uo<6rkvEvHApqSvXgeGa~i z)oJJGrd6_8vu2NhPehx-9e)G`6_Q40Tbg-|tWOs6#Q{q!!N8e^a%0ERhvfv_88Z$@ zEz(AhHAx!f>&Z5f=jXXf-je-plWft#N7AKCjpf15rIp`8FZHNBtlssI9t&?jt4uNv zm6O_kD!mR>jh>IU^{a0OK07J0s-oaUvid&-VC$dPNLC4D4Kj#}9tLj$`G zo;?;!2WO57`kYr4sAWxFM>~AeEAn{m<6Jrld`oLFx}17CXey$le&gcRGGAMGtt&~? zrtaP)O8Sf})M51yOD=y#_DH$(_;pLjE?~?#YPy*9Q}D{#EDLAp*#&KE!g&N%YZ?b% zsd|S|v9dcg-dYb4Jr*~wFzo5`&MNv`+&d3!5tfmy`xjkCLNevD%-FJwtUN1?UyegX zTq#2&l0a@4z?M4c9J8KsTbEI^?PhO#3pa&Wbvyt#bZ zro7kV6_q8{WY&$N`8zA#u^hF-hHW$d0A}j}ik>$(HH>_^f;`r)8AdS(>60IDj zYblzpNa@>5#s@~bTRTkm*GIc^jBv8!GUK*uMdDtqvDTR8Tl*f_sAb2nd0g@+>KQy` z{Ou^e=3bPWn+4{uIR!@6Z7jn`*w|sPH{#4zd{1g{tSlDKQs>Lnkvmm*?dQz@0M9p- zlAgaW`+m=kd^eKqwWM+Dhcy2H{Y66gr-Jss3HZx#&7`KPWHLk>L>b0ASDJTU=y%k- zQuOi6O(J2#k|r-PAqYaYVF*G1LJ)uugdhXS-o@=UEP+W@;QlttcDMR0UM%;$i`nd9 zKNYAS%W3{>Ym=<{Pg~&M>R@eAV1T!?V6_hmazE57V`|3oN+vXLW{qNYj&bu*(R~r| zPxUq#SkU*p3r1IBfHk;fIPWknJ2EielIvmG(#Oj?6m?F1p3KkUa99kihQ5k709g0( zwbo~L-d}5VT-;gLmW`*k@#y&d%aSX!>h8mu*z#7+`=XB$!psu7!f0$B3gclF4{bB3 zXLqNimPQ}I=DS#YoEw7c2u}+<7ZVqXJTDoe#W>pw-MOj!Fce|(wXs?2^|4uq$qw8N zh2tf-yWl4yXA(DcDQRfq`RZhZLO`~+Ejlc2a6KRNES_DN9aPrJ-Qf&>thS(-@7P(9 z_OZ|J3stfSLs&`40LUhiJ%61|*lUYi=SnhLn%*m2#k*d=Wv7lvaCu^PqF|Aq?N_N_XaF|L#_Zv9 zaC|TpN5P2H=fCr-*}2v{J}c3l*PoNQkUL!*o{DdjaW|5ncx;muM{nEQrP-`+bi=r8 zrN=XPkPYVVJZR1ANzQjto~)&7o%N}|71eg+_LV1+pnO?+*$G^DBfOCpcif+O zHoLTuML{3To^LRXT6%9w`lM}i!5e2l?0((~i0*e32j0a9O@)&$K1xSpG8*DL1yQcqq~&m+ zG-x-0Cs??R6=%+*gkt=HEtqPg^W(avw=1|UbOE98Q+^LFYTPbIu`X(ioH$OM5L|Qo zq4wP;b}pF)_S5M~#957%Nbf{!pmv44Q*hoe^VC@&`FFw-jYiwnF!2a!XxPF>XZNo2 z@~jic|3?L#>}8$s3(U*O1d3;OijKS+zl97%iYbT2A>f?o1X&9tHGJ={gl;%LKB; zAfBFA#Vlt@Bj~*z&fqwv+Rs16@mb=grEQxuz{#7hhMVrf$M~ z9#i8W#`?!oiDGn4AWKnDf9~R0OIp5PT}Lh(SyMw%BP4tiNda_n`ZwsXMjYpd-q-U< zjSOgJU~J&$z4{9c7f%Vo>ajYADJY?I^>cS4vahwBz1q=1Eljae(*}HMq0z$(V^2vU z`hM8Q76q|Xdm~3P%LERZXNM3AW4QX|CSU57Eri&*{4X4-#xZ(k(o|BgHjW+U@Z9~= zPK%3=;tj1NX|iE#F+1nzU_=3V$D?y)Rm5V z3+_7rm7?boUR`YcEUKe#wTK%HIj^$(6=9Bk2rHyynOz*wL@&VoV?H4gwv@z*w^!3u2a$6Zw3ODe(^Mya!_9hus)1EC8Gd8~uQ zVP~U`&4JHFd^hN^H0rXP*>7|^D`BpQy4T_NBpcwbDQmb8u*TiGDsaoq0Cy~yc3pZY z0N>3^pTu?MsjhXoq2AS7C^&EwoZd3)A;ab)hW)f5P1EaL8YXHSx$(C`y7U7yt@fxn z_I4xS79J~~R_nQ|b;ZG-HFB!n(BqhP)XO|>WUsSBe3r3zaapPyUCql5Z)$aQ0hc$I zlE&e}>yC>jMGn!*p_frzvDrER^`4$7C8~lZv^cs=+Zi7qv9K0_o1*F9O)%{~1tWx3lIo^)_S#HJ1-*ZlhJ__J!q=K@lSMw2ikl^*y-3O&w{(;EN?SL#;kT zz{x)NzB!51{C2*gYgvwe086LE#!eTPH#oRWPVNeL+#i|EW#nn-^^+37t1xJ=*(;+F zHxZ@Z!>Z}*egpP@9*!!8{`01Bnxij#M!tu%xNTO{QPon#8(A$oH}tLt?yNs2^{sOC zHKt8mbir(u+3}XT&C7A)%{|@5i!^dI@#YOV14CP{LbD1pEfqyuTu$asNX5}xFwv;( zU8=Z<-m^8-29aT+S`n&d%w`Ua?KiQLT~>NWIytGy9huC(LepzYoucaD7<=&w*rDz{ z#jby}D6*^E`gT7~$`6B$l%a5I-|;Zv;dg;5`Nk~bT@lvIje2dS$D51S#vzL(G!dAg zX7gR#YsFVoweww|U)Zw697}xj#TXs(n)v>7z%6I7V&8t>uvqti^j%IiY{9oA+QXS! zj+M<1gfk{Ucsv(3c_RhbcPyKPrn41mqmh90}%@#)9rHH3V``HI34E z$m4c$LQ>@>#HwSdBG*kSWpX(hBbTGHn?D@W3{W21bG%M@G?oKh#_C#9M1Lk9y45fE?9u zBC{JoS53qEV)eizTw8<__T<3N7r55}e z#d-6HbZGHPihLfTw;HEp52i28l-x+rye=FaidS#yS~rfg(pYtnE?(2)c;+>WK?PK< zrlN>vl9hty{{VBnKoN>LqOnTh&Uqn2n zIT?Vy7^IRm)VqBkYs7iiEsx!|C@sIPMVD6|bK6d%{%^!{1=udLc7~O<4sYA)boy7xhb8KucM3ftaI0DaP)o`eL9-U zqqQ-URfp;S09w&&fHIpcji+m!j8L!*OqrH8z5BLmd_vEruDEKyiQE3Bz;iZTY(7G0 zgV;=idGd>r!^@B8U2HXt6bDW%=QWp6+Q+BvX5k{;<;%r+!T$hjgZsj|ozGA%9?`}k z!ew@MhnXDyenoQO?sVVT=%=(8nQ%JqO_qE@f;?Xhl9z#n&AVSGugPPtV0}#OZzq>N z-d9eBqVYMWNt@ugGEJ*HRrDPs##}xex!4U$s_>}WGp#Kn#4j(CO;+oJ+}33uhPl;j zZWpx7stt*hn3tn@CxSPwi=15S<(h-lYmzzjRpVZ|+SRidbDzZCp}r;# z#i1Q9Wt{U^#%Gb5_D()uw~}Zx%ZuKdj;-Rd2;tYNo7*oR*UbZEY2=2qH=>Oi{{SVE z+JV68u?xGx_E{Ty49ZCtWzPZuIDE??ovZmN7P5LEaBOM5PDmU+Vt&qONF5@crsY3%)fh z1n3_B0CIf7UBAHmih#d=IJC#K`vvXk06Dgh(S8nwP^NaE$!^Q4j%vQFr-EKbq>XbHY%estP>Aoin` zu7+@tZi=-9*=R}LX)?fjlW`f&qncK+0dD^QzRK+*-KaMT4``NSL!`3^YgC+AtIhxfx9DZsb;3>mnxEsf8;{1I&%`*lNxS7qvg+jx6Y zCPqpcZVEx}F}4vb<|cMybL_?}Waj?>%`h`Kk_D9Ndp4<|6Hd}in!(KUUticv8{#-; z*%#mAc#-sWH_00CJ0*a-6{@DDFAX&gE_35Oh8-8!Bew00jfIi5#jKB?Gs$IpEzH_F z_hGv?Bby`HJ!hbYcPAtFMe~P&lmW&7upUd(?S>-ijCbOp_NT+(+%WwA0J^U)e4q}i zmVMjes|?YGMoXALzeVOAPVnCOY!`bFkP1+9cJ;dR=Se+_s}E}|ozCvW;f}^O-vOYu zW9lb6`A z;6BPyjVvW^`@tC}&s100`N~%A<$Dj`UH#xnK3tY+=5FgNKkYOB0C*OlF1DTvI`+2w zQCjC6<@s*)T`XFtH)e3UTHLmS_eagE-erE_Xdj|}C0ifSMc;Pi9JCTVI<3Af3{ zx2qd52X8qlQ)?2LQ)hNQ(6UCcD`FRp-lofXte$HSb&ALq7OT|9W@hvHR#BVR_uXM> z*8LUcH|MICWmavM+^O92T`tS~g0|k=N?QgL@|^zwJuJQ|a|WQ6*COWKpQ%XvH9%#3 zf&e2_o5?1e-GrL#pdn20aXp8k>(MhwJ$o)(4LP%NU5Y*^NN)?1pLTKV-UF7 zRvVZAboCc*t?ssGJF4^5kIgHbqAGa3nlIJ=076HRPTakT1zb1e&oY*0X3h@2C>)UT zM-kMZr?rAg$YPPvxsS}l)n%i{A)u|KscjVVx|(R_%YD{;*yg$NzKb^UIiH)!>TO82{MgfkMupNK&dTRkfYd||ir z9vY~<<|CT3#W6lseBTXgaH%2`<11M6aC_x@>S~rvx~Qgkb6V@P_*;=)B3O>_n9aja zFjr3jt1-&@cN?|dk(w_vG;Qj7QCh`0tH^Ec0x(>8)59L_j=V`MZ9L<5SpNVg(!Afs z8yi3_8C}|9`(87GGih)c@TWU8`GmBNzLC6}FNr!iV46rKjnK~08u;DP{{Z=~Po>M^ zW7X$%6yn=K7@EdrYmAI~jHbyr1FJdoNW55^E|(i}D4IhZ*jv=q9~6&v$nrbxjv;fR zc0ya=yEqojV%tkwH7*j$Q#Cs`k{RkZd$jJVHEL^jF@xJ7aqrzd1((08_%ePAMHP0{ zZB`$L!uJ4K3tdw!ytyw5=pubXqNSQzh8JXtP2Gdan$1P6W)|@|WiYwtS6O;09fri` zqWIl)GoXOzEN>xIQ$s_9yL95>_VUun?wwv^c0u9*`wGnq92h)27jjHOj-t_uR=zNK zZvIVj%q6T23^{BQ4U8tW*mfZmKrJPsboN{2G+$%c&xBkKu9lXI5;c@H1JK1R(dUkT zFjvI`WHM)KSF70^A86#pC@N`id_mAfG*dQzi{*{}o0;6p~+b@PlW8J={CsetfuJ!U9pIyDntQR$Xnoqdk?dXBU*=^Im7r*nR z)7+{^G+h~ye(GmbcA8Fzc2>8^QdYQ1q+fGCf|2aW?M=qx-lXQs)fG~o$yT>h*Lh>@ zQ_mTo7|}bh?q5Q@N;jB}9w*s#QCZms?ay zr3WuAN&~YiColQx4_)yRVgPs)=_-E-1^4>am%C&d2%q(JQ=!J|aGR(Fb4suEnxmrJzs_eDULSlugd_@&$xo5-l*2h9&< z`dwISa`*%dPQ)8(q`X^H^5$4W19EO{#0Slx76aN$zR#9AU}lITT( z#0yN1&(iV~b0cYSnppQWqbuJ305!QC1n*(=VEfm0I#C!l4cDMz+if|xb?$s}qADB) z;aTq2mzIuMB;Bmc*-Rjox%6gEmzJtq*?IvBK*|GFK^uVK4OFPF4=y%RIrfQ|oo#5A zmYJ@6G%aTA2j5e55#nfhIYeQA-B9by)iKZA^a3>0$I zJ`mYAfzcgFT2n07*m!XBUk4aFBH5SMKF~V29FA%ECNn_gr-1Ez)U|J*u9kd4h0_Xu zk1>Ivra^q?$$A~8taLbi76XNbimHIvql_Puj1NCz+hlY*5wmSMcaLe*<+G-j_6s}A zPyQOkA|cn@+WKjAZ5JAq!N86`O;GmY)a@`%-T8I(i1h_`bBhf@zcrscN$|U9q1ICA z2ZF@3BEs?NS_&EnYT$+ov5lV1f@|@==v~UJ z)sVU=laEp8>yf|glle3KmV$o%pj z6|;!deTSxvu6%Bqc4cEvRnnrRWNmAjbh@c<8fv-CMDoqOG3#!tm!B3Lo;EyF=j`X; zQ8BSGnY}5qouBk7sf=QkZH=-yjE&uX=C@mcLdWEirf0;?Y+I4T6*fjjG7kl;Ve;Xg zPPV@ARP^!Fvm;#hi}s{hAC$)L4yu~WqsOQT45QU=_knQ1+0zt-AgOkC$l7Lo2tp-;#NmdARYMbPv$FbrYI>{x?|vUj?;sx;7BBGTom)Xx%ASATK@pO zv2_cq)1|zX)6m zGjB7N#O>O}MnB|w2M1Z-5~tVtrEg%CH?i#Jp;=zOt36JaHnUqZ;<$V9EFyRqNSqz* zKEHI0Y2dhoSe_LO#jIsV$jW?PR{b4Aq>RPJ9$R*LPOFk)b{Dm8r)e#v#be(>I_Fi> z&ouDY@f;qi+v?X zkgCq_^iZpwT;nNi@)fTOn*2`{aeSGb@o5g9$t?2ch+0OyX&vaaH}-AE;<%7ulRF<9 z#Gd8uVmYH0-!M%ce`Gyw|x=3>#7u<+x?|00yzZ8?l$P?h&fhsbr$)lyPBjL zd!F>HEy)N35paa4aJk;}^QgAG^!k;zuRYpIEc$4hLmj1%ZYK-4zBHXlCR{{V6VNe*?c zo1JY+GjQLhG`j%-NYs=hl%*xQBR07{q>Zz5PcK9od4%1?>`DIsCGPyld$PVyY64tX z?3v03A?;OtbBFuXICjuT=$XrY$6iS3?@0Dfu~eB6Z=p$OE>ESIWR7l%V3PZJCO8hB zDfc^ic&IttQ$jCc8}xw(=R!=r25jekn|Am{@y5atc~JBFn8Yd zKs?+w=z*c_{YVOWB~S&e$RoMS_Ohp6HyWKB6>t}QN|5G`6tg+}Jl2*YiN}UENcU{2 zt;xJ)BRikYC1F=DX=&Y2h3!3QsB|vDu=ptA1H9^sU7uL`SI%ni%u1JM>FVa7o+@hE zjP$cf@^6iL8tiWs_?=ZQC4>P^{7ID)OwPmK96~7K9?}BS+H7JvtP+Nj8o3|wdW*1c zeH$ZB8-0B*F-X?MC@wvnIjj$;FPuy{tdDtPU7^uyjR5jpHA5_b5M0B-We?&c^YB|S zwZ@D(`mt-Zxuv)$N?+UU-&C092YN_+Z{ma~KULg$Buv1Y;$tmg_Ye{J41YU@)T-M?mR=Yg3j*`WXkU7k7ZhvCdE^UDv zmT8QcPaW2*ry~QN{(p2>QP*Efm5WZnF6{RgC|GHGTrBl+z4I42+UL1bML|=F*3)5h zb~P2VG6uH&PM@83W3IJvTHdGIJ`8Zz&}LJKe-la@DEJyZ->qWq=yWXdL*%*#tiqZgsCxFBZJlUk}Xv zpQnz@I?L5`{jBG?%sFI{`rYSTmsl^L_AK=hWvOZ2TmrS-paDaCcJ!zneA5F>;i3OaS5Y6sfsP z)|>FI^(;W;?eknZPU`d!Si*g%lv=DcM$8|#Rp+W+=Qu9ybF;)W(7k!--I~fFraxvb ziKJ6jqUf={H_R^3&w9ygf$dmn<<93m-zTae$JXZX@wM59Jn|NrpUX!|DOisrm_z3~O@s_16|`-=EWY=F|)XbK{Nj6CyM!$^zuhD;e0YhBODm^crHw_#Jlih<~-hy3#}NH zEK(Op*Nt9$7mxTxz#{>hMNG#G@@}iz)_Oeu0DKFjh1PwKt89dV!uz>;EJF~(@ca_0 zddV9l9I-wC*K>G~tnl8{zQ>ZB$CKdK%WZW)*F(z7W@s4{O||%#GO+bFTCO==!o9lL z<=VQai!iwSpmJu9lJ;*ZdfY*#Y|rG~z}w3AdAgPG`FH9N(Eu8wLN zsi^B1_DaELHu}8TEl+2x#rEeH#$$ax`Lq;II>k!M$tUxYuOTjA95{%#AQpI~Y>p$I zPb8`%%;pfme>AIIM$8O-oK3!!u;#e)=Cqmvc=B}cTd}^!FRoK1Q@eF2%sFds74BE>0b#Ii+p5M#6(Ig)9=u`A{rL-VGSzs&rJ9Npe_RzXVsX(%3P4r)ji<4-yg zftM>d0%s+&AfKOfkZL3cIA*vfvI>E4G5|ntWu)q_IVujW=z}siQaN=+hl;Hb5^Z#? z*-qUqm7Dtn5j&DQDcIZRDbqK-Fh@3J2b+DLom0C9*rmeGvNkX{oIKQ?VLaM$NVVLp z!jUl-TzMqrPUo+J$HSM6iIF<)QcJtMDvn&r4qT`NbnSc8Yj$PrrdsRpy+f_1f@zZB zXwm-wLQX9i(BZ?z^*No+`uk8xcAN-0@OKk)oX$31(eg_zv=&StIN2~A%T$Qc%3at# z#1UUJRz5acm{~25Tg_u9mqe-&acw*mWH;oNt_v$+bB^_zGe)$k9Ul+hI%wmF`o@rf0B|jZ3k+25Gr$uoSBh=#jLb{&{mlLdI1uRfQzRN3j zuRqnUmdsb2PiI|;RMFGY22GHdnRwmFYE|s!GmJT~<9ka)>^diBf5oBQ8!>ZdkZmZtbQqoxIQS}?EAQVe`5B#BaBvKm=DJ5AZsL!LkX3-?`_p(k|vYHwXAa-y6uRL zL0FFcKh9ap2)=HfDG)}0*-t)8h(LRo%D4@NoK>=CM9upKRzD{Y1$f3%zisO4>T4?BM;$A- zRPi)qEF@}4UanWMtvQHqxp`b_7%QY>DP&_InrPiyx&ZuOC%2m78*)}uZ3z?<6&Awj z!v$6#?j8PKgTu_N=<%#3;*OsXif6>zwXv7TN6@$xCG~Ocot~s+&7Gy)SQfLi2@pIIj$u3S^IJ(rB$$j9cX6g` zH*a8Buv&7;mbeWjjdy2>ld2mKp}Si0{{Wt|X1jR0ruf-L(X>vPf2rK^Yo!0rpMYE_P)(@BRpP6CGrI#_=0KANEz( z%2?`s=hU;yQD68IKfINB<==zp)#Y^`R>25D*@!|AfDnWr1R)3nc{|v>=EneVYMcK634ix- zF9>-%*uCDzW%~zJnC1QQ{HOZ3*B4#%UcbSA)kBet#s)hhn%lNlXa2MHD>J#DX-jDf zV#FwAJ+}!|u-_o*b$C5kYR|9#08wRfD|-v#bgc1O37ZP!K5b1q~ATRTL0t~`CtyIHY>kn9$L&9(k36lHC* zHQrZ0XO3;2rxHF)%`#;EZFJefU4Qe|dHdzthv}1@@oK>%S#d7|$5gSp7vdOTWFs|Q zDc(~${ZLpZrV+|GNZ|`>52=yS#_3$m;|^Ch*DDCNw%O@mpBELe*`L zf~~$xP{hf~pCvbIIQb`RqRj{e!@=OEr@0Sv`qpo6Fr0N z{K(lKD}hprly{QU-l<-(GjRT*9p7 zD~oeg0It^YXsYera_WvQ$DbuO1Ch~4A3{CpgY!Z!sLOw)0Nc+!xK#8~!d$@Tb1Lt} zo3Ati@kOuRLOLK34L%M`ojIT$>Iy(#G1W;T&+<>QQ|O9h9-v%GRr;j-am|In@vFMxwx2g!&}w>yzA_ypdxm14z_w7oWu_t0R(lDPheW ze1d$@i%%!=cKh1&9rdkKMIB&c3#y@edlORB?&S8UIQD$^5X15LsKo_EH^s$Ff?&$2 zZ6udoK6f?lA+tXA$o6>^_e>%h93r9BG}MvDBO-I8m$xR49t+`2r!c_@&(*^J0MQ?z zX^pF0Ma|Wb!TcOjYU~U6E#$GRsMH?8jiyG%K z@;U8`c+Bo+%0}LcU`WU*B8o<5V3TZ`&&tO*a}6YWf=cl?d)<&^aALSzwRd$M zBTG0Sci<7t5x@1TmxD_G0ExZ=TpddwW3$O&duqG2d#XGmXQ*Sl%{3W&-g@s3$*vyFm-S-ooAbF((#a&cK)%6;21ajvw4vNybQV)EFG!lFkzHv#fb530$_ zYc!tXT>JeC=-&ibQGPF7v=V|M!{hk04!_;xzvjQvzH;K`W*fH`5<^(sIKurAv)Dh{ z=F8#OFA0_)XQ^`>Tpv61{{Rni>dQLS%?_g&12Tc278)$En@ZQTa+2!^<(JJyd#IOu{81Ja>x`q5?OaD;mfL%+f>lj z`70yMXw(Cksy{#8qq(o`qLmzO%hgcLbT>W1Om}10sV;>f%3G@RFx*7fI{a#&9}mIgTFC1)wSLbQgwn|JfBB!=!jR$YqF;`ar{lGheW8_@@+u@*?Cs2cz>g6>xf zPKAUSnBp{W3w4e3d6Ys!t18ZO!PRLUuMgrE+a|2!KPwAp$m{{u}=Q-YX7k6`r_X5uY$&^qr&Ah^!qJ-;0(Av^ZFe zIThr#(+Lm%0G1+i^Sja2HJ%@QUcW>-HoiAQP}1n8Zb!2AxLM3|95ly$Czr?`&J5lw zm9`k9wL3e9VefR?p;lzq*u5qzhRcT6%Shn!X8_mVxn<+Fq{$hi1LU`INVCDj-P@AU zIGktHVZ&x*rxd~1lk0bksRr32-F}tMlO@lB%+@*W*O!S{WR1Xc=Dj++d!T4v`*l-c zdt54bb3~5hvQz>KU8&wNG@K4;bV1DyYet}puFfNg(_%C*{AKkYWNFSuKi7?L3xVnM zs>xtOhQ7pwS>xe(1aJY#Z?s*x9L}pI0f*4yHFDEb#!ON+&2wbenu+fnM6nlH?S4al z6vIYH*fXk)_i^iV>YN0u%F)e38I)#sVF9|wSZB}40h!2ayjC+i7({(+Y!=yLT=^YL z_}=Jb`A@znI=-LqLykJL1*zHDrO#1^TBe&Y{{X9=+Yi6;ub_qk7w23L8mZZhqoKwj zh-Rme##q@W%13WXzeULSooOLAIAzK1O(y=Ac33nvxUHy#3zATvLKLDt^H^7|7F%rby2 z?Lt`1%6T|%(QdaAgTaMwHU`^(G#^=JWMp$Fh*U={CexdfrTkXT>ikY^{i{CYb^NO&Yy-s* zsH;%G$Be)^uJTmcKM=RFc!a}zN>dAnYR62-+FO?GaI?p(xLEc8Vc9B-D*~es{AyM< zOpmZ*I-jX}e2R!@7v!8w#GF2RKFdRf?r?Y>+KgtqGp49I7+@FFd2$QCv@p?Ong#sGnru~= zv{+3YJf=D}JO?^iEzFX9{MVq5Xd*P<7^r4fv>OI}(0buS*hORB9d}fg%GMTUE@o?| zB;YjNzIizonB8-^=uG?EtrHM2muH}074Le4tjoP#7rHU-y44~=Hgx# zq4qC#v4DMtocI1T{J-epTwQt&^zaVGZMh&-1@T<(k1E1LM+Bx^0yXuRxw&Wn1Nv+WGR9|?C96(T=L z>|Gn>cx!qtPS1>#_3d|Zv;OIHWu7R<8AfXQop`P3RBd@?M)9$Vqm)5W9KMe(ej*cs zXzbU;Zr>W2TGIF0`f;v#heiy(7EV`ht=J=3q2g4>g5k2Z=?PDW}2r zL2dbjWz|R=9fSnCqDIy#{1WJ#Diqwe_oUZnXSogM!R}9@Wn}<5cDg6c{`7(eG3`?Z zp{0>=bsAgTtb>!l0n&TWZo=&$Q<%H9Kg!Nfoq$znQE5yc$%rL;pCcwoBI@L zllJgH;cL_0Bna{0e# zP&#Hvj~4r$k>#gpG7Rj6Tv=_IOM5yhJWkahS|mAX{>?F)g-iKs^`fCf2PbZ+7W3kN z(v34Bz&F)LL}t-a0!w{WE^y|pOTJA3J)Y7#pSOZDW_L6lav&a={pv<{_}x6t9-|bV zN`QYP8{dJCONpn!4zr!e9a2d*G7oFEhZ}e$#hC_|HO}K98Z}V)iDlD71UT^KLxq}| z^6ad988|t4Ad(A*W1o^{#ZG51^VB0PhD#p>e4reuWp@UOoy|@7ZloC1CX(RSJWg_W+%@Zwn?7OubhUR>4|-J;p($}w76{(91K*{rO#)Zoo~n&$l>FDmLT{Q zRGFCJrQ?Z-hF3_~$s=|aCkDwXnTMr5Yic?d%NNF2OpIilX3IuRc}7;Tsv`l;7v*Dr zp*eeJ*s@ayckF!cvl{+8`JkSvH^^&V$IEjSDY+A5&k+q1(Qe}JzJtfdsY zLyO2rjrG*=W?{By?r-&3X;HdiRV`&vk*=H4Ie_)*xMsd?>f6$+QmitHIAeDR?XNiJ z2RII-a$9wBzNO{my4zK%{LHs*Lgx?~)1%%ORy=yu%aYq!?LG^zR^nSw>`n2Xis13@ z_)f2zUEZHxxqXW>?(-oe^FC{nv$zo1t)8aAqY0IdwH+(E6#5CJ1f@hY+1I$8`HNm zU)?SQkmb*FYp9F)x~X47i&_gKaKBZnO<2K$3NvOkl^gjU@!R{~=UpoJ+9^x&$(rGL zz4;V^5^orG@pfUJVa=P}P(L+8Uh`}7TQWSD*vI$ztZ~!J8EcDp-R7pL-jR*xk!;Gg z)HJGZB>=QHRQV~FR9TUyRkG8~YPDx!(PMXaPiAw~W*t@)m@Fmg<796&mA!?9zQvI8 zv)+eVoTTvNNI!+1x*F@bmOxMqav8}1qfJ!lZiq^d#^!C3b*`H;Wj@5!%dJat8Ik;J ztC^-2crINla~~a7QcJQTeEVu8AB&e(?jqj$#(c8Upm~a^jU*fTMlPe-XZ}U4yI(n*Cy8y2+WS^I zjcMNQY`D+w<(tiJ|t(bd*&BU7fCy`AE<`YhGXy>&~wJ&wOL ztR$4>$p_cbq(fTU2k3*B&+1QI=fCr&9DSq14k?Gm_($)$VjmDEw%@(4lw(+N#W34M zb2XNdG9%-$>b~OH9NRgBhXZkA$#@;G!K0+C6>-NKsOmS5*SR8zoo&oIF<);(;`e(T zCCMWk03fW)d{Xep!pA$9UYi%eOR7FSPR204PfZE?qSJ?GsO6+(LC-t`{&L9saDO(s zYnrZXn6+^vrj`%^X=vVdC0WyH4H+Cxo(mJqZGc8w#k}pMedJBQBC2?^ zM#%?W+AcO|gTgq)y~}!vZOfr;xJPYs%(+eP)5T_u{hL35JBIv*H%Q?ln8Dr)?4Jd- zl{I?=*s5L$!|NrXiOm+^5s5!K`0nO6zzbPo!>ao)!G#OxJ`ZT5oufV>Q6*{3>L2`< zHdWWT>vU8vb|IPsvI{I*9$wOS^F@)WKwOi}OP!a-_Dmf(Qs4u-^&lvVCDX-DR=1*M z&Az&&_<-iLI@ZqQoIF`%w6{cQ#{7C^|j$s|&a+lu4 zAP*C{q%W7s=)bW=vpL!(1No`xs%Nv?_a)xl|*n+6D?L#>w6zEvN9L8Irn4Ih+O91*T}Y88E>kr9Ipfo zL9k9I%;F{Behx6$D(Gvms;Huxw|}|L_Gicd9ewM!w3z({1G}h}lAdf-Fqm7qB)7*_ zUcqf)*a5>fqH5YYh@+sZX)?jP*Lk45*E46Zud=&UisLn{61J9kDQTj&0OQoFnTeiN z6pwa%Cu!z&Y&4j@5hfh!i|!;XdszE);~dwj-Q^@6V@2jM`5lhqn0^mVcb^uOl@&4` z%QQCko37nXIfqhXabeQVMD+xLZp&TIQliV6OmN-GdM4Hobx6q3$XqOY!*i~gmVAhY zYXQ?miSq_>V~>i1D_RND=vs5v)6)#oJTr#&BFLL6E6aO-otI(uXt6p+Sdd6#dX|mH-@+ z8d(?eO4=pCizj@;GC!hI%a?@;AbY8fc~NWk(j541ihwfco%p@T8Uz~!rI1M@3K>}JNYhgc`mW-De60(o-Ws(+R=M*{_<78UA?GiW+ekH z#M*X;`*)JAAmkTj52sg;)O||?Aq!?92toit5P%SbAOp$X#qPE;-(l)W=kbX$`*K9Q zFGqV9yx5K`E_NQ3GCTc9mlwo7gVp#y`lxAbD_JD4UC$%qTgA&4ZEP>r^2ZmXT}`CF z#wg2Pc;@E0mAM%kCCCHV@}Eg>?Nyh=zP+1+BcC2yTfi)oZTI=o5C@kBMHVfF z$pd7_?AzGBWADuZj+xpRnV-O{v{E`Mi7DQ7cQqHCZM9yfNq-w1u-)hB>l<9`HPSJS ztE8StYFX`v{{XVPk>?K37p^wY(~LU4EN64Qgt|YBF}-ckb!4J}`6h%38s?D6SpNW& zT{$Pjt!(kK;+$8uI~7TeI-D+|JC?&!Pb1&F=jm6_!QIrB!#S1A&}*7fKOh3T3551^rz7ZK8QJc<2dtB?iMQs z$H`HVPd5(>xD#(ba-M2z1=Fxf{%B1rXJH`b@F$;CnUpu@DIvi1Bem~U^B#V+J)o&W zuN~Ds{fj1}vV%ACDJ8A6Rn@#mNpwm+$^E<&2F=UJDew9J0E%3g4h{;sra6ylTA&|y z-jL|vjIPUjA8n9;re?Uc)PbTc!*rdLcCBP;XMCpN0`0IROZ>u4=cSy0ZF6#tBofw+ zU<8kUg*@Coe2^7no5>`!LOEAN%1Jo0zCu0CR?^5zHVH}IBjKIkKl?a8h@-SBU&EEfc^!}+9(@Q zvsH14ay{}zkn^&3H_0oQBbn`J)vW`UlJq+#LmhT8hfznJvsP6$P4WAl?oH&M-7hOE zn%M>4^z4Qm7bwY2%sc&C}=i{W;XPqyab z;;(%MB^G8z9cQz5x+Xu)ypGS{7_K>86cjWvRZW%dlOsc%3}g;xL8)6iXO9ef6ozQ& z+Y}VkjfyL4ytumh55U_X!8v`v|$F{6_#vA##lT=%%=k)_Wc(fYJvQo!BmHsAp?y+t-5hQWYQVMXQcw39fP`)`n2@>yzPRc3iO zwS1D^MjdY**3&5{sHh{Xb@%UtgPn0^l3Ay8$BpjhvDehz*7UWSGqt`p`WLzQGQb;M zip!7HHNO|bcqv%;>}8(c_hQHBUP_k^n-s+;uzDQssH`lHG47jsMfY4k4}%QCsW8eg zTTf2Y8!xVR{qbGx>15ou6WsUv)1`7f*1hSJFhiC zv{g72cgFBmHilW9mROl3*#7`}s>h{upHtOh6jgX$Ia@=B)_iuMyQ$w%>+csksY<74 z=h_@%Tu!1086>7M@lUO{TCH;XJPh2IG}qSc+h(RSF^-Me@w?HkR?cCcW%i1WiQvAR zNG7S*?osplzbfcr&(BX61+vJp>}_pD3B+AZgUMR@hD8}`q%p?G{{Wm_n0p*uPkToZ zY>cazIk{XPAv*P3XB`#F`^n*C2G#Y$!sv_wOC2#(QLDl#?M2ivtV-ftc~ofP3p3+ z=&*YD+2fBfwn6kHUzFLV!EIA+ol8-fzLBlrT*nu0Kcr;&>w*hDyNafYd0E8lyvjN8I@~@AHaJNH8>?%^vpZMG!I8(oXfo`QCQ3|ie`Ir8 zvQ$e{=02hPO^h)#O87w7)~G^{3~Lnd2`_$n@zT6q}PgPD$R z(ib$karF5t{T*B!E2SFP5B~skt#fZ37mttOLuH2I8rR|!l@Y?$OPY^|f;+EKL5X45 zr8%j>tKqGu4K8z|e-jmO^Y2-!Y0dBmJRPuyGr%cn9W0wTWO*$GYT^`8VmN(86pkY~ zv~Ry*>pq@Iy6(T46%UkD)BIkdXlISgmN~LXZxzj`ib_eoHAL6vwVe(AQGEw&aIrlz z@tBzR&rctxYfs$$b>qv)c9I-`^9u`3lI)~-wMNdp*uF03;MInU5S_9YM=V~3sCdg| z=8V-FHMP<@u7*4|tR3WVJ-jW^cmBlBUioFAb*m$bdP}6ew|>>vs>Nuw{{RJ_2E?09 zO^ifKY3g3gjt`Gj(Oi{rX2)u{`$d68wODW2d_3-}qHbD<+DX#>E9PeRAcr)L2eta- zy7ur#i)_9w+&>YbbDZbq&u$5rx3PR11;%HZNNMDws&E1FnQvir)mu5AI~|<%vX>mq zJh?2=Q%MV_rk=)ln{o!WD+}BSI*v<9*qsPvZgSu_F1A@>(HC?d1|Nh(;=JWw)MZrxQRU50(}eb-?zOdd$4*{m+EO1UW69ZPB@8@=#9C`#nd zUpAEXdgkVE?B!Ik@mnv{t0>Ep$zs(?cs_5`lgAdJ4Ca7Z5Q1IX`qjUZGih}|KeARg z7T--10@3^b05TfWab^;v9%GlE5;GTf$Veo4`;`Dn9M^RPH)m`7)L0&hLXRan`6Hrz zPyx%;1l!uAo2Bz~_8=slBx+swX}LjZwXCeg(mXuQh?()z!M~}MkVE&$oNe^31$NnN z{S%8DQ0mHt+tJcTsyLZ0d3N2SGo1&TZH`wp&N&*^cI1)SGB2Ig{3O;n=j?S95J#oo zBRJQYtHm+QXpvb}JdTuFBCun_Us~W;+*ym4-QIOt|NxT7T;Mmn3(qa`<_*18i z)Zjhlt%fofSIVKopF70HXGfEif<@88@a#4!+9@ikXR)BU=R0lmh0?+H(+b3c z;i-yTKDI90FJs-QAz&*4*p9ESyN-PGN_KWlA)QQo;exf!F90EL#{@NO_i!d zOy^}p5C;Xvc&vj~q1jk2Tr83B#t3jZPt8W{rNPIEOtKiY3?-%3{1q*#W4jH{;l!q9 z6&03pGVwLQJEscsxQ+*iHo5f}E-M`ws&L*l{ZC6S)Upe4Tzf*(sjj7`W_jg`HpQ-D z>o_8|j#U+(!Q=ivNrt|!3fbw+Rb#WZw;7Ov%6|q2`1vk26N=GcbDUBrs&PC`_GK&% z<0aB}J)K;mvkuQZhZ*bNm2WFukRZ@PvVDov&E9Ecb96VjPfjmUHug|qO||!>aM9a9;u;_*hh@x_{%Uq^en}2V5aMr$ zL2$P;?2&W*bOZn`$skhF$nQBbE}g%rDG3ogj}=FnnOSHgHafE0kshG={xa4_j#jrg z$)9$xMCKC5WjTu2#YvK`rc-x~^3jUVIXKGCHGNM{7h}%tU;QUff8ed>{N$^IyL(N; zi9>JT?f&vb#2lA)AEyr=sQR`DLKdt-5QG4PApju=KnK0-Ugu)}0O+awJ~ICR?&Dq< z@^`U&or`0gg-^l5@t5)c0750j*Zmi(@PGAC)7k>pR^idNwY`%%#bWlkpxBeGy{fUo z>2{8S7L9a$y~p$^Bv_uD)9JpAQSlG;R$_uo@kV@>W`bS^i`KjV#W9KcbT?TDyhK~4 z=3Cpf$y)lI+}p-9>CIbNahBc-9B%Xh{c<19t}!~L;3uo1GW7lXf_dB%s8rhB)PKMX+6{ ze{^zFYVa{$*z#>wN!u1FL`<&C*SB1r3yXluBr{ZCvp70v0DKvTZHuE#FU9J&U=tY^ z$h5YOj;0wS#VJl|iY{RH*q={sE#cYS*JG}1UN$j^7fDL;&NsP)NAC;hbdol4ODAi8 zNX*~PU3~OZ!1_kZPWiVSX=Sijf zx}*>8e(%h$s)J`Y!In(hv-Ktu-$!j)U9jdMAqh8Djs+T7N{n*P^`~nDJH-S$z^Y70 zB}0{zhcpro7ri$+?#__mWs!Ec{mn8Jq z9E0!gPqb3f*FZMAg-(tgh|0X$-3{h|mvFUX?6ZmeJXHsaXp@@Y;w*3Cg;XBaz6zU` z?#`r_3+h;?cK-mS`P8W+vI$;)Z0cQ4fl)YT(yUmY=9hdMGkM@HyoTQ5bkM^V7F>mU;-V1^#k`$aH?B~;$5sybyHVELS#9F4P``(Jwt8!SI}vhE)(#7wE~^d&psg7 zU@gy+cNok89>>Vh{U!4pE>cF7k@twSg z%kYV`W>PNNp}V+VW%SlzvxhE=+im?FMHb#;j(lLUvC&M+f-mTb@-oT+uss&FwYkN#MXu+WGP!_g`-PfFt-%`xR_T8QH0*VbU3BQW z9#f@@VGz+!(Nr>K%4BB~NYXXKu^KJhK(tgjnHti=&emGQ5DmX7brV3sFZC_Pb@r`L z*u%IaxLYyvS!8!~c4u!jkXd7IWGtZQx!&G3+!8U6Rk_yI7wEaMPF&ccb9)cZoG!H+ z<8(C;&3{PTg>xNCl51uTHdR?JryZ?o+O4N$xplgx0+x+*=(3hJ>TK<)4kvXjR$I-k z<<{y#sKw*}b0Ccos?QawbTiSoG#R0aGsdw{N*PaU*^PCU?mEb8rG|D(=?qz4b*VuV zfPtvGt9H1nTUR#ELrEh8PZNcYk0q98#$y>8?AOxLrAFzl(9qUhmg7@hJdZAXrMzbR zE1uPK*1m2fM2#*5tBYFhAm1g|pNhcvE-iLl_yz3`dFoeAI{KWy61KQKEh$*$H&$6^ zqdS_W$<>dw!f~=j${sZ9qPU~p7};hu`ilk8XUo^Q=qmA9YpG#mfvgdp2NR;vp?+#$ zPos6Yg}a7ONmS;=HZw;_6SX8nWmqJlmkP$Ku=(ECz6~8Q79hy6*3U;KOm^*LEOSM; z0~LqZ7nAg?GP&7FZkJhEna(=%^IUd&y)JFB>#KCc_*s0Ug3S6A?EVh$sVMPTE2f!| zj6#@3*cleOd9NM7s5bWbug_#TVX z*Wh#;OGeuKG&X}0dAt=-cbtCbBJxho2@a2R@GcvEOS7}skHsovf%0UIcaqHGfsb69 z&27xPZAi6whZh*e8CA2gQsUII{hW$y)Wzd=BPUr`F9OCP!m(&-XAw-%tKoRI^2@XE zud}djV8^N09QMf_JwR_Y^5#Ew_Q=Myj))iN7pI0dqs_@(CzsGR%VgxPsBSBUOu)&G zcgE=ZG6m=BwoTMgQ|~cBB-2BjM+9DuHS0DbYH+x!Ag9M?5zw&lMJUi8HK&W?*gIcW z78|;bkW{tt=N5cy``XsKRfdnAw#+52v2#ExGbb^(A<%_0N^0>59^8!+KUI)6G1z`_ z(QQ;L8mhlV4(*L6qQGG+8jdx)22&l&K9zGo`66j!A93FZ4Mvv&O^=H2?Cv=>2aaL* zynJq$lOtySZ^d%jmXCJ(SMYbk z4@)Dkbx$ttT#`1@17bWDFa}?8%rBAtQt4P(Jmm-q;lFib13_?|v_fDW<5cy^s@_R* zNDKKSIU`GTNaiVmCx?Zpo-e^zT~|-P+!~1Yhq%JI&Dsbj#9c#%z{;wIzayVCo4DAN zM9FgwwtJ4#K9qy`YF8H*u9FL(H5IsvV$AzRO-)b6^{G#YWA$`S#AvpDn9#ANXF8^< z(mkJi-G!`Tl z{sJPrCT}wMuH4X9;hSM294hK)>hC=<&N4?B=jOC$riTlliS^Z0F=AB>-fm8wk9@w_ zh+tS&F4%>2DVuep9@z^&BKX$b;Pm@Di_1?$$B5j}#<9=N3l`DD`xHf`z@-sAu}35F zSOI03weN(+V=_+2_!t(GDV}5BwfWf2sb-Q#2IuBb-m#`0X? z>z8uz3uX*Ds&{sM>#v64o42*kXBhBPlGW9@K`FFsP+t-I#a4%6_s| zuGP;qF393?!SaQTj9a?bkUu)dvGmcmWN7KHeblot-|0)g{pH%4k_w6`X{BxAnmmp^ zC3DvPYl`tNC$soHZ4S)QMM)HmZ0r)3WwZRW`WBRxazR-mC@9%gSDPbqKH2p1T{^1D zjg#0%!||Q{Q!Psa*%!&V{Ipkwnk|Rf@mY#Y4P`@fWe&|Ww)>dzSI+)TJ-ppLpT!wC zn-7-{G&R)Lbg|{Ra6LgB*ImP>?1l=$5~4O3gSIQ^rl#2DD=DIy$X0jM4)Mbe?# zSn4Q?aXN8FHfynw9p})ZW@31fn#|8HN@g#FI6rlD+x>= zO;rz{8iwR&D=TZP)CIRav?Wn)YZI&1AVKY{fbrPqkXUY31!h~&GnGC)usDPJ_*7o4M*@d99^zb|Ft|f6dxI+Df>ilI!gY z-un1Uq|f`^y8i%KBIGXIKTaMmQT1#Pge_QvAqW8oLI6S#fI54Zy4bkygw-2?dWjju z_z^D)`WLy_(8GhzoA_Lx-Nd-M{{W)({tN!D7%?}rZJr8Ub~7_%x9#j)_dSe`Hb~}n zK-bu_ZA)ZsHo)64{{R-w&#iMA2_(BS!@QMrzeaz7INYaOqN=+ zm&V$8P3+0~t@Z|%MBc;3i%VJ0O1kko_ndx@P1?4RnAYUV-s*}K? zyE0&uKQrDY$meOEMbo93m6WvZlr_PiI5XGQ>qa@O;7=B!Eu4WDJ8s$e^|*Agx{{n>iGHM~kZpNQa$H|8Fpxv%*XXyYE$A-M@@ z9F3JTx9?XkF_W}%Uz(6|#yTaL%^W3U>!Qdpfp+G%ABuc#XIqsIcsj_-s=cM!+THx+G-6A-ZIoCHP>JD4<&Vna$9>oW@@BHbTBsCW8 z>Y0!|%c&Y!4s-i@=Sj>C(Fsm&4r-j@0(#}_C_Rvb*++$`adz0L97!oT{5dCNoZkNc z)|I#~Z7zc+IQ3FM0P|0f22Z1vmMy% zod91e+ezY^Y3n4gc1PWhUDL=62-(Rcdl+i*2@Bsf`1fnU?7j@#V-}6iv&Y7Z zS!30GeV{Rgjbv?Y%UQegT-TpTwr)+&jsE~Du ztVlQ2V{7zRZqNGZ8^G;1!J}(L*p3HVh)Yy><)x{3lK%jKD&kZ87;OagSaE&hrJq^l zUS_>-qukV`E`wXkBU}B=>xJga^BvqUs=#w6}n2-BS#9PY?#$H z@w&!jcNgCZF`RNtLK8w<3m}|G`CQ|kMbx0DsDi$pX=jHk+aoOi@<0v0e#Muat;4G@ z`lmB+_tKCAa>E^$PfwF)jqxmXu21dux$#WaS2k&Q%nTCxMUEFnND}&3n*RW5r_;*V z9VxkPe3uI?H6<-mWEE4$+rP0MtF7cZ7;XS-s#wTk2R4k|=$;|7b5X?Vhf6C%d>N|r zyCI8UG!?MVQ;5@3#RDXaZ{+lgF4XP*30sF&;dpg5MR==^C&s6D#p7q-1(l~K+UUnh z@y(w)dq8-~Jk`h9_bgc%n}h|Cos{h8>FcXIM>UhFSliWRZ)srlv9mP(bl;;-l9sH4 zsvY(14sKCo%eYjBczsHaU)snOGs!l&#Qy+_Ts~h?uv(3l3xPaZEYz%M%I1zQC5yfF zErRwqk48sgbx z@zKiUH<90lv6nOvnO$soVz!S{l`o^6@%Ivu(Yhu`9t@Iq56P?(Ntw>SQORWlJ|k(a z{{YInD_6zjxA!fnU5^F4A*Yxi6|&hSeA~&Se6HQ@^So%csHm_E>==eIQG41(M@u&) ztppKNViO4E$qQaG?>q6L$6n`7JC>gIt2K*m?B%GXrfVT*AhQ?-<;NwsOqz6Fc1P0m zIqQ!euTQhMT(ic?w>9mFj60v6y|o+;h0w8bsILtTAo(E5b_|~N*rTY9XqsblTnN$j zUVkxbIr^-VmUeae`_*+w_Q^pu3)QQ{kzhJ%ng^@NsSlffBy0tOe!^~qlN`KO*j73Y6Dv}Aq;RG z^JVocGQ8pSP}C8XfyXgf_V*OQFluT{Mc6F{CyG@cLi&bpBWNF$Y0~7hUsQD%>!%-s z<4$W{c{SJe6pLGXIimi>nrWXbuXFNebHFWU$(4w^HmlS3dDa2iTottxQq8D|@(zHV zR=XN3=JhMK#|nB`17nF^t2T)S5mebnW2b8?hD3rURm;&o*S`T zFCt8&q;0yYc$^voGF%B5^Y=x}k(z7Cbc^3J%iYH#daWv#HO_fsG6V(~<$d*VKIOk1 zL!_dTH@U&US*~c~V&xkP>NHysoU%3Se*lw>J6B_??jHvmNd2L~D`{&gWT?bw9iKeU z<9r8^Uc6{m!M0Cm8?zfzLy5~MZ5_;23_bYXEOf zwqiO3O=OanWQ@3ujTc-x?W)76$z>x=e5YK)(Xn}KOCH4WP2(i0FhcIcRNjp^h?P$e z_H}sf5koU#sjXvWJeeGM#_!~3;8^N*&8%zVr^2FOwvLjb%g#$q>N$jR zQaTVjgGIkdhQT#c+SWfK&6yN`C%j8oFA`p(48~){U^3G(?_uL(7I`A5ncKMQT?DM{ zweT)>5aEW_)5zFm+&R&;#II$z5WIlUa+_u)IIKx?GUT?2?_e2XkoTMl)t6*2+3{$x zX1b<|xvnmhQA=h`{O5}FEnpmlmAWUEi#4wGl}C|jGVnV`6(RUX!x@deg9>y_bY@3z zX4P$Ne%I4FkL+d;=<27cVU6yk7vSbuADZ?R*mWK)LTK?SR#d=w2Xh~Sw6M*Z!1jJe z&xT=bigGL@k>&4b@L?-o5;zsb5S^L8zQAn!RFjsPsR^m6bZ^i}*2}Ar!Pe@mK1WDh zY{T&Ks|-Bb+F4Arim|zXH-u#Ye2d{uhK^0Cj;ZC%k+g6ee&L)jM|`)LYNE{78MP;O4eU{gs{aI2mECdmcxK zWPhc4t@{8ME9bi@hfT9sJoGQB6V=q!wyDxJ{0+bUORY6sM2CuZWcDt4`EdxD=grf_ z+lS&5a#3P2iDH$}kr;myU(tDJ@SHaepFR^$@o5O*o_BBR5Bgt|TZQe;96%282?tmJ z27}3MQ8)78r5+nY4DwGKA0A_w2EoTE)SXp2;8{txp6=+g8%le8`|1Dy zX&6;;)dkOOxC)aXdWDSJIZQZ#(Mz2Bc&b1SEod&|TIIP94@a$wv^UG@SRCI^4xc9? zt%CAoZLOk3zE&xLpwUZozp+92MyrJ=>6=c*iuOei}lu-13%^(`kd zVcA8PIw>ugED_lm$mE&glQMzC-*N;ja^m-@Jhf6!6W^U#>YOQDdhj2fpWQX_Qd|*W z-4U@>Z3f(4^;-F?Z7hE#4|S98XK1>9kS;Ht{Sjc!=NGY6o%h78$IGHxs9fdjA-{r{ z;mC`dBuRC&W6BQ={!ZzKXW;Qt9NV*A26!h`D~IN&@JwH}kwGA%=ly9H4BYii!QIv= zGABdewK11l43OKc*3<3Z_uX^xmj+?-W*X)S=~JzCv&Au`tuD-TddB&;KvS;_mX~v$Q=snW3oDG%4ffMtvh>s z{!&HB9D?*P{Wy5tMD3Q+5QHsQ1R)3k2toit5P(OreV?Iw&5Iymk~Od6HBaF2^l>i+ zdoK2Vh3_^o?rs+|L~!X;{x>r3`8byk#D0U<_%HgXVZ_-K+f>F*_lS)Kr`))ZQACmr38|EU7#BeYRv;np5_C1-glZ5 z;bTB-tUmCwx>vpId&&2e=VWf=;^6&^o!@k83;w0pd26L}ncobMeJh=bvweiu7PFLg zTW~*lK}kQaOCR@1{f#j9GDh1>(!q8I+%37=k=wlbk4Chfa@_dnqI^-ZmW;iPR(AC^ zwObpzd=l@f3v#+gohy(n$I51kY$M7j2fd$jrGu1f^oE`jmqkI@dg!z;d|n)L1Ej^E8C@etoq$+JIo3tK&LBeVn(JrG&yyj~Za!(d zw2&HJ$j~H69Ft1=d7~qHI-x|?>zdko5aX5HLsVIu%3-Im^(iHQ+gnR3ZTEiV3?c^h)jn!-X~`YmSqNAe zo%2)7PN$lZj)+>VmxUM1r{{fX-p)+SyEi^))aCk+T3B)yAUm#!)PUoEwNFc@e$rRb zNHSVFizQ&Fl1<8+A6Tj(t@XNXe-J&yj~5D{3yz9Rt*2!%$w{y`DRE`Ys-bOZCcz`b zIdGndk*B>P6Ost)?m;~A`?W)?=XQPE(g=2r%&VDY)W4bbBd5Ivk)R5jsnfWPT2gCz zDngssOR?BbEz!|P1GtM@yo|hFN{2lXT0^^;{F3{hyYnLL$TRqLOq|Z`>a8Kn*M&}N zsv^ZpU71N8__HY|$C_c?Qsu&fD~`5B{d4U>*MX_#eeU!IJ7pGAn=74={R)B8Dhc`! z66ZC|NcNAlABLmX&XF6rg^x#tVLoqp%4qNg@a531^kIhuF{ zy^6bC^!r*V=O?@Kp(VwcQMHuk1r2rIr?~)IjrSaC8Ud4f_h<7|a^_0Tw`mq=d4NpX z$3(+lmPTrV*BkJZY)0lkpw)7=mS)3%RL1E`J~GYQJQqy5HnyTkot7w?A19Le#?#}1 zvUj<}Zrf%xmQFoKSDg+rF|fC|IV~EfoX5Tw0iAWQxbM7?&E99UM$3~{?9rn2>L4rU12w>bGdvJ}}$srPj7v2V2jQ=+eSB z?GABfcbL<pUk^)I6B0ChIY(8TMo#-Up1Y) zW%lS674CI)A8TFu1MFQ$2KJrw#m{zbt?jO94mTp@b+B4IMy^Tc!rsPIQk?n0T^8+f z*S+*@g^Dk+?x}^cQ@)?j2xmNT{{SexTNu{2Nc0^SlGu98R#9W^X>r`?xx z^oQzRyt|I>nBbX4Fbhv1!PdM%&HlC&wrYh@i(exuzlzd z$U3V~ID&d}O;0Vhjcl{w89>b1YM<`{^RYdl>|^^rOVe$ZRyPBX5vRu?5B~r|`WKsU zX?9@SE?nO4L#FIusTm=4ox|N+Q;OnLEpsVq<&G~=x-Q*KolYBWB6+VLih>^-$Q-UN z7X3Nqx1r6M@0MpiR|98>FKd;B?{i6M8jlrHyh#55$QB!m^j?i#RoQbiACngMC@yok zzh7#4T?duXsmj5)Xj$9IVq-b+EU}x}XJ>8(!+8~zr&WMD+N^;2tSt5MS)6kHyp;~B zMX%9YO~zZPcT~f&o2St%uFKdzLM@m#MJ-tymg$r0sUrOl(ARPZ)RY}z;I^P(b;{Jv z+}tZ_2>@;LKR1dsQ?S=aAZwfQT-KFQYg$^e$3E${b9h1UT2so$TKs8EMRjPr>K46O zJBQntS)Y(;Z~z?E2{9^4Du|4L%t7?u+{0%LLd^ubxZcdH zet7a~hgJ!hE`09J;gEyaSfg;teVVS<$oh6#Gpl}#G)#s?D0BI-J^ zMEQO%@v~3BWLmLFBo1quau$s}s%`33ZLOZxGIw|K{L3q1^il>3yV$iTDp^xZXUV0^ zVQ;c6>~clp9leXq$z5K(ZRvZQH{%mwbWh#OD}FB?ETaByA*MQEeNDH5Gw&#DfQdwGV;Ol)WEN6E1KHU}u_0uBA(XVUTtU8go zq*}`i>}~U9Q%WR}jLQ+Z@Czi9LIiD>c>Mj0nkWu?&lfd0tin~zcDIF_!W9;mWwpv- zw%V4837~Uhd2`F$@46N0u)VLvtD$8Z@d@`a!eVSfal0&DI?c9Loa=W0nXJW!UF3VU zm9f^#t)D<;6Xt7L2=saf+mqLBl99229b6R@uPiwoBz9xhk)p**WR{w;q9P>u8~xFD zBgfwp4K$g98_qc*vX4zlcC*ubS{jja5zZORtP|{F2p!>c!Bj3yg>x6-L=o}k2UOY=ek-5oLzUfh0b?) zu45=Bu3?e#%NtnS?PL8T82CJ#6bCl!n>bE@#J~&28u>@H4D+7>tG)A)^kB&u&&d z{FtlR z>#({%u~d>r4MCDw26?Jm9iJz;Y1HiI4_8`iDzNA(>L1pnqDCvNr|~_au=xHLhS%*4 zWR1fp=AKs#T-E~}*Ri7bFPxWsmc|+ephZa)pY2~lIm~7@UO1X>k~WqF1P)dRn@c^M zoHu5$JQNRzVT=!L{VhW`i>oW&IU-j&K+~&SZc=gJ)2f#^-&DJa4j1COoX&CTsFeiV zU!q|e+opRY?%DRL`TDG9kO&|+UEq_tT^Y1Uy6)jJai$15>l=V~MDvI6{&YK1q>d0vhby2mHQF$$X!M)`K^$lH>a1$* z8NBp}TG}oZwZ1;ZjoEH`tbxpLf@Q&rWXS&j1(BxZOK)o`%yXc??JMYzZ$#tO-nvj{ zbKH6yG|!miOmadLQahdAnaQ8YHXU>+c3tEUMa{mu)sgE*bvd*-^$2NTcO8%wnZ7D? z03bBv9x1m%fHM@FY&AT6P+H)O);9GK{{XbcglK&tf=6!pEQGnt*RZjdJDbT&ko@-I zL3r>(`5=6u_o*=b8doQ1MX>iCc9+3*vvA#VHjrn-JafG|cO708v~3xKv*ZHG+f4&S zqk=Xw$SsFzMvDZ}Y9cLvysmp&)by)YmdCOh=u100gKzYbu3GEu2mJ1rhbQl5{{VR^ z zHkvRilCjvjl@PGGvwUtEZ}sG50s$$>e=20i)Oq*Iv=jtxF5Bxcd*fi{`*=l7(>$$NKAYi(e)ns1IX zUzMa=a%$q{ElK?qZW${dllR8q{{Yr2qdPVp;u*xV;gw~QOBmBUnVwvRv_2q;N(iRL zXz3($giR%zr$sYfT|GZj7%wp_+dW#%m)e=|$z>2>7^}S--PwWRd-BIb;~cFma5f^` ziuukVLnb$bNr%g&R1OYfucq+xUaw^F=Is{G#Z@b^VibS9>)UM}S*&s|M-EROpZi>Y z66w4=n^U&V*e!FqCu5oVBo3M+OFO)h?RmPdhbNMYX~|Pvl&B)t@=s*1uL_%sb_J8~ zaNQjgC;&4ojdoQHR^DgWm=@7h+}7r66rM`0#QiuB0nAzI1Q&*v`6;keUF#qtODk#g zp8Zrg++6ifHxK4i4nCg6T@nSYa(TFX`5-FB=xeh#H;RMFRm+@>M+3>J_OAZ`6r66v z7iM{V?rx+WsIl!^-i-iAg+wzoy>ole0$1bxyioKQVxT!S%5?SqwA-(G=m36X{JqHo zm~f*^*;ImP;mWIry~zn#0QKw59a7LEPb{`nMSHiZR?N)36Cn&ilUr^<4ZfLDEYp^$ zlnzCPRP;%?5uFM54QTB-09_nOmvM2R2Dz@~^&>H|o}H9(Kr^G9-boEw6HnmeB{6|zHv@A73&dx0Dl?)^%f+?;k*0SG{FuR=TI|f>wiI8uI_x)45Yh_0GvG;_95K;>Krc@yYnXJ2gsN#+!s@y zPKeEw9iWX+Z_Y1!q0QFW(AIPT8Ll)4Szm+p@I!|*eBclAXw7aH9Rdw)99)zZx7HR^ zTfo3mcRzBHbFt0Y+1kkEFKeF7+&MZ(eJc4=2*mLK_~dR!KTM&0A8MZG;Y=e^A1MpK zS74M3bb>a%IUAsRHCKz>Rj$pM;e1q%Xlr9*8R)|T^HaL+aPSLmu9xCa=7xD(-R7Cv z0_PIq%XG5dtt{Gs^z5aTl0qKm_8hgE%*D4L7Y#|#Z&Xb9aJXVDX7W+IxjbvyY~`@ zq>??@bIxXUHnP(V=26s7G0ZAyB^YxlorcESb|v_?q+W|-qsxclGCN)Dk-_yYPA!IG zSa-#nh|br=E3CrGo$jl*v(dIJ5|PE%eBPbwe4VWD_dUMOg4pqSIhkwYEFXN`#JfSZ zxEiir0@5%#P+!F?l20K1wRJCL%PGm+%-vpnsg7gz>ajK1+x+2H*R`RXdU+|7)sR_U zQ^TU0*%o74$s8@2oX52d?1wo+Mu$au=l7u89j|WsmkDcuEqzSvHvVcQ<-jqJ*Nu9w zOSTLr4#5LJeX$8Yx?X5H^y193nz^!fyKr03(yOp=c9(k>m&G#Wj1Jr6Uaqmb%2zmY zEM7YjlRUs@;A+>UR&LfB3^uzKsgj!xpsBB%GkoS!$GyoK)iJr!i1!t2l)EeA_`9#{ zwfV29{0>qW>2`w^-W=|dIvAV}?c~0q>}q-nTB`c0iQNq)GwNQ^A=R z^2=PuFbLT+&JD`uHYe~u=|hbiLRhLkF%49DWFQ@U7wFxGq{Qg9Rw-X4M3{wikHl(- zox~SN2ZynBF)TKd9j0{#Hp&XPaO^~^v!>*|Cj=vTE0BfrR#-eT1 z44$G-z0<_^mAw`jjX&hDOioAnQb<>OX8sdjvUnXX5f09|@EMuO!i;xUl^9%Sxx>6TN1+Yd?GeK6~XJMV}6Zv z&C%zEM_$v3Gts*o)!!(wZQ9ci=BwM+3}t%QeEQ=hxA{n9mfI*ojfsKd9a zuLkDZnx_1b_I_jt%#fJ_UgF>gBUCVg;%*mv&asj}{!iSq#@kamRtW76TWFL-?=&_m zw}$M^EoKi(Up6ZGdW!kvik6-z$K3sN!_TsyYGr^(2+VZo7oeMD>#*!Clg)_GzGp$b zG;BVRtP7J+8w(|(ni$zr48D=x(7TasbyQegO(ZyV3u>l^;?Jync9U?RIBqx2UC6C_ zJ2s#!&3~j113;T8`_Ia(y%5EHo3-I0QNIX9JgF4joT4y)DBK?O{;l9rhn6vW$k z=De=Y!f{IKUGwh*S>%z{@9zB?@9exV(Cqyrd)9nrR=?vx!>;vk$oqv{bHT-Rm$7!x(bHjsMAsUZ9RuIP^sPJ#ADXKh zjtS&~(o2`ozU#)*M_q_cA*O7z%sUah@GnP&U^3FzQ&m>J0VO{hA&1vdd9=(4*0C>d zElyY1g68_gX~|sIW@dL;z15-vg|8!>Zn@I~hz^|XZ#8o=&L$b%Stl^&W$rC^zdM77 z2?u3spP$>RNZ@RKNfZ;JhZ`{XSvaa@Ny9}h{{U0wD}QRs9&5J#x-|maT#^L^L!3C? zs%0cjcLfKKO-s96X>1ZWPiZa}ai(39izqNzhD<2(ZCX8>GWChl2})}g(ifKF>Jp!zoSS0^u_D{yAsAEiVcka%5S zbp;)e_xBb@-rn^CvvoqCXtK53D+%Cf;N-Fvh68y9g$gEQe0FuMWtHyAGssjloSb(f z%~M5=O!>-1sf>gWvlGo?9J#E4*G9^P8(C3ch14Ccz2JkqxhX;)s# zVR~Ip7njzg*fZbxmD?$|Bp3&){{Sj>(#czmmq64Y9=){n9BOWpOB!>2L<0uF?Z~UM zC$Oc%lE|}5yJ#>AlH{0SNyXf~L_ine`qZ5Yw1;m`1cMWwkX;7sXR$WlIOoYjEphBf zD6>_=+KF;dHKm%#BJIc98Lg`G`&jSZF$TZo9<-%>OQXySxtap8yx4QRh(&dKP)TqW=J-DZlLP{_<7E9D?la7ySO4{?6a;C0t?1FHaBChl`);NJ0>_WDtZP z1R)3k2toinoV~upaMH~7jz5fZx6F-rgUQR<>|gxGt2bkMf8336b^icG>wF*mOd}ru z0NP3d!@JJW9(AI}gFG3CjfUD^lHb}_i1Dm4K<**DF4bvCtEt_7`pXB=tE;T~_WuB% z;gm_~8N;u&O;ej_-1nXr?-pr9o09EwtaC=$X(~YEV3aDGIURTdT@W_yn=H%?(15hC z`M3CGG~O}fTTgCh7kJ%q6tg9d2()bT&y(Z#qns| z_8j}Sv7Gmc@%Gtx{Wf(b&MxDB6|PAW5G{E7V|Vgu-)yGHbEGuyYz<|%nZwjOEoN}r zvd%zphr7vZ3C|2%x1F%F7c}bkeq=Ga+DUUQ_qC^ryDl2{<<81e9Yv#AoHt^`YKoZO zQHRY3E#*9;`LyHRgtsL-vmx+t9*^3vGNUdjM=w3yO*#JnYO&K!Dq>{BTYAWk(zNkO zcN8v{zQEZ&qN^Qix2UZ4Sk)fxrl!6yH3 zwDGmY&5^`vETlWF*Ou6wns-uEU;4??Wj1GT?YvV@OkH@!T^$pHJ_ z#aV$+PYW-}R%bifq}em;dnt9V zW8juy=9^DZ$x#+zZZ%i=-&gn~9cNzYDGRb$vne+6Pd63Q2b~~Kk^{2!Kyz}Y1+=nY z=I$wANw?7nUlDQxxO|lRl{Ly&!il#ufw;P!8-L`i->RgU%nn^bjNCbVlLv~)XVC{! zcO&dlJ6`2va)aOZE4HCxF4E;BkPZ9i*0Dd3y2v|Y z+xgZq<}ri9$OA`>5bkPR=WHTW* zRZa!YJr{dw=X_Q2&33Z#WHt-QPg^M^^2f*5cC^Om$J*1yUK<1ekS_e=Rm-p~AiNC- zC3UFk4r;bJo7~asygSRSN}658VU5itjD4~N(8l(9?UmU|%FHga9iAMSDdwGyaj}7x zK9lmVr`BWpL5J-Y34&5#q|v@8Z1+XHW9{;f-e1_hV@2?ni&Jdp*au-)bd(Oe9Oef{ zE0|^MXXSpEwZJ(yXE3pWvz-%y7$qccRuJ3thP;`?5mu`*QpubB0yZVzgBo`ghV+#S6KQz9&hwZOIl=Mqvi3#7 zSmA})Tx6CA#mMk0t0!wbUhkq|^oEXtii-DrJv?x~+*Z$M`%|cXdZ}FIlE-Fm)>b^% z$#u@g{mjEQW8$)3Q{iQenqBtOs=r(I=$cmC*7H<3T3e1GX;E6N!j919t%{1>X*Xx{CUW8%^9SJTKp(M-H-&k{sP z94D5Gnm0C_%&uvgKQ<&ypzp5&e!={er4I(Dsx@2yFpD5 zIiH3~S(};2H;b9F74%QpXr`MI!(fTkQxI>4=+I$!hBPKGE$X@tWq=ygr07os_JO8mTzrj_lNt?JFHN!)+B@ z44Ms+#iohk;pUml2ifGhn+cC#dozvH;uyshWkk`(yQ2_68_aLz;yN!?i2OCm{pZ-6 z5XC#5GE~;pT(E);v5(TXtZK#b*2^_MQ3K_H&1hj6!F9Rv_pCgL;&JiJ{K=Q*A+LCR zgo0dMtLy;$%Wn_DaXeT~aQYgGp-&!pjC`2SHKR72fEo)e`by(L0FCn2{8iFtG|^Q) z7?1d^7d6bv9buSVq#J^_u!`@oIKCf>7G0DTaMYId%GobqlB(9Jt2It@{xK_~ZOa)Y zL*&WtT}bdbB&UvJQyrfk^CJTFUkeaIHnuvLc+Fi4WpvjivXLyH5>N7bzjc?H+4_b; zX45e47mt%ktvi|NF#1|ZWpnFT*%);%lXkTxtELSU<;B6BhXu1+g;rv+*VfXQWNsf# zzL~qr$OiO-@7L;Hc;5O19j&Xc4kJw%d!%%aZ>hRnY&tg7)59jLfznG8Oh=;f1Zi>L zy*>qs;qg<)Lx@38`%NK*@s5&AKEHPfr-@4DR9W? z+qu};4U?$aY)S@1z#(Yg%Pac~k9%d-_)5cY{5KlGFpM^eI3E=WGrgKf{pT&`*YvNd z?CuK&&*72baRZo0C#{}@o`jBQRM`{m>JuvqXdrrG_el*NW(ZEaA{Q&%*yPx0ol*8KBTaSw-WHqT;v zEsPvD6l5)w#k^zS8c7<}wL7p_;}N*jim6{D-0d3cZPp~*S8p+zh~J(K@P;Q5ZV1BV z)YQG=Hi-#rEHUa=U)qSTsixrg-@G7e&&_3)zFDbvFK_gha*qwC#I|c_>j=G74J|!P zF80f5e=75KV$6y1=lxc#kOk(bGLV8AY$l(-&tW#Vz;{UpS};< z+?y?B1=e-{0N++`mnV{YB-@(Zk8*d*)lP1<3Ad55qdtn%-M(q`;`gMJDJ9WA(u)I7 z>k*aBZbICyXRqX|m_Y{VSl>0rFnKV#_r%veNJtKe_tzrRqpg<@sfwzWOGzHK9plk` z3mn5nCx+z(pBR9LvGQ`s_qFqz81joqK>&jFhDhRF_;0j%r)@SqmlC38)NJ%Fbau^K z1Z?Ix4cujX#JIhHmj?nl-F?et@ncI~X(f_D6o)Ki9e0E7Ys>r~Y(sGQB*yT_r+p*d z1x!sl(#QSrZ-c4kc(a#3PsD8xoiLK))pjuLrLV!AdKnlWc?o;t-elEq=4S3!HN+e1 z?MG>vi|V}y^*EVK^3LfemBsSN{O)=Cq>Co;q82tdqhMjt{UlmoA1m9E&N5t=S^jCI z1?|h>r#0{X3agtYGhKtScEI|b-Blaia#+LG%=@>QybRp10vU4ucKbn&(qU(%ObcJkhb`?PLDwd;Z$5BN1t1n{G-(ZDU+o zz|i4m(wC>cFdv(jwzvPVN(O29~Y5?k(zzl2obl(;q<_DQ+R8Y6UWU=h7} ztUgF71hq|eMmf13{NnZdENh;~aLgv9@2nK!X(DXIE-a4RJ&pbD&QDI-j3Kg9*2O0% zWZuTGKC^hoT2?wWv;dGA=(UMeV`qx356;C8h6}YsLI^0dBgLJa< z{{RZ!9zIIOH0B~{533A&#ofa8a~Z{AZA_8Jhf?%)POpFUYu4e|CKZNAUq?mh$@y7M zc^5#PIEf(hC#oiY%PF_`X<^u87*#8xfzmi%iPCr0_akpKzYE@lNe2DiNo96hR^qxw8@6Sim>= z=@I34e`wONS@9PX>OR)B<+}v!$4z zyMrM1A;pB}2niPQPrlT%c`4G}5EKTvQ_fh+@=Gc0*xSW6o@fU4TH$2pbs0D;vJAFK zO6TH%@@LuklmTaUHCKGDK`plKd#tiIHeRb9ZXS9oX&F!@L$dVA4cC&E*sy9Im=|tm z@Ohz2Ypvb4P2yrh(Li&#-46Nw^dWh);7s<9wL#^oZQ|{AlZ76ce38cX9(O=JRM>EG z;6P+PNoVDf;UF|r-e@$C5#8c?2u->4dzgIE1bZz~@pj})9vi84sq7fv*w4FEU6Gpf zMTcWlyZ-+G&X84sHt4*@)xGU)5q~+Kyk4AUxbgR|CAIFkqm8fU9I|>vtv#2Ay})@c zHaAJq9{E2?g3%e|0J_(7xk$~;a_hC7d931X5zSps=T6`6C0udIb@qYnePupPJp+Hd zm2w9q>0|AA89Rayg=h#u5CRZ{0E8g`9!~ZzXR(=^MONm&Q!ZS;=$DK=?_&0w9hlM0 zmzTy4Z)Ql>A6@ibx52;FK-$N>wKTvu{I*VOO1;f&5;48J>|48BU-3peC&;^bZ*tX< zfz4!NKnV+*ruAW~v#<2^GTM?SlHkG3#bSw}&4_yB6_A#(rGcL1Z5Lx+&R*2*>2a0{ zOn69+-z8I0QA?8U8VS{Pe5bvT4&@wJiEZ^<1N%yYI^xs7H_oWjp7eOoGw!;0CP zt=AonY1(0S-{UkZv|b4fcW&#D_Ty1RbV7RJ^+hVh=h#fmo7incp6Y#(%uC&1@E%sn()C*@ktK1r~*vL3+` zS>9k&z}C#tdN@W(VV7oBg${yNKaNx3beUbFg-IlId0pFNvPU8QwP(aFS4S%i?&yea zzAF_o43)K@>f-pM{;pV7#L>ve$(fta6|8si&R*vUo_dB*OEb&lmkf-_uiXmhRMSUY zPWnmRX2{^+`{>86F3!r=VR&e^SD!(m^bI!mi`jH##kE{>YgXGnTU6SdBNvLX@d%kC z@>FU5y82cfSlZYu){yYirI#;g@ThAkB%A_VNRD%Vl#lO=%xvBzQ-)VbNn0?H>~-VM z-(trOPJK3d(^~a7xrfoM!_ zf~db1i4%8QsYi87uVl|t4r99{DeIYAudY*-V>zuNlVxr5B;S+weq_%z7vkmr0FtDi zWxW#|l-#2?3X`#pR!cV*G+oB+)jY24Gu)2Qr6Z8agW2Lszvp#Cfo6pMdZMx0yOSak zZneJY?^1f@_ajdPT;}sZmSb$p_JoNc+A>8)qKAz+Bog7<_b7KDvK}VsakhPO`T=`q7oBZ`wLHe1M z7ka9Dns_6p2f1dYab-r03XrKs-9uPjYzI9OvT&Q!!aQ6*Dg)=6QzZ#W3a^8zfYnNkVDPL2JNe*x) zsil{2>1ExqY2)yS@o5_7wZ**~CaVtc)X~$@z5_F3ic{#jd$6{4iiMPT%jv_~#{62C zJ&m=#No%*Mo~}c3=f72yIiZ|Hk7-z($24nX^0~Z~)Y%^#I^ByUJz=AhG;uIpUX2=Xkz?&6HcPr7?b`C$$ZH+_$a_8$hb zO3kLMqjj=W(#rQX+V3OOesrym(#vPlz~U{kwgZq`lENLu%xba+XK=}?2z~VO+BRa zn=>+3tzIe?|8mf#`W{S{LPit@{dK&ditB;Or!$E#-65H zN68FTRg}!0Op?ACFPw$c-iai(@%eXmR{S=GDmOm5DJ5{{Z@I1T)URz?v^X}v94ZQ| zPaeb_RQKg|B`ghmfO~ATvDa*yL=f!d9wi%?bI(0%#~<>0wacq(TPSQ%Zkuik^;q{7 z(a#O=UDb(l+S?r^Elwj?+8jQfYPy$b*kEPceZh1q@OZH5H@-|>mRjaZyZEIbGGz1K zF6}nmNkg&m;Fv}kPel1?zAaZ&UBx-}FCb!UZE=a9000^)s$GWH;f&bk;n2~8iPX=Y zrlIWYN4&7z{Q+s<*w!V0Vo~BaWk%w5w<*jx9M7Ms=kT8d0?~anNIiqFId-dOt9FYG zjj>izP9wxXI03W>2jOXg$@b!5{r z2zPNc{mB0JqEz#U=FUaR!s1A84p7|`*jY*KF4M6|;i9jG338g4L=unW?zpxd3XSsQ z>3gJz7WW5|nGd6RvrdPirEs%*I~d|fCds9isesnKjThF|vi3VAgX6fBP^!VCriJ)> zSR|;PUrD``A4wYV5j-@U><_rqFQEJuV)S&Fwku7E;tqUzLwbE zN!r|J>`u#LxS-*FnoIQ_}$*^VGa<nJ$jm`oM=f*c={n14!#ZLBOmZDmjB$}zso@rbh z`P@1E3lywl%QHsH_yKz?+o<YbrUI4s{{U=uu&90%pn^#N|CRY3)e3cokOF09%Xp@m8gw zx8g`Ug}3b_N1zBM-qgkI#F0EG3{sr2yn|vn736li3pAC35@m%vSw5p~ax6xz=2V^@r0Dz!gB}2p{{VBkheega zyx-!x7)XvR|^Rq2-vSzcdev2VwQ8By1TbrA2tNqHuYM4m+Iba$v z`bh4*kHK`Ip9pmEv<3-jC1rr~ULGok!+4-(>@Qca)s2tg9|0_F#`v<|&H}l!SIM?N zXWUz@ui&cbJA*TQM06{f8W3(#!iyop)4-Bic-h3n_M7kK~XuV0}f57h9^JHPSVV zIl6kuY-HoW^qr|Z(U&g@jT*$_#znmfo~tKls67$NAr48yP?VgJ?m?tGGkM)2*JT4g z)|p5pz&(puuKoDof4FZJ!E0XEhYN+Q<9tSKe&Zkg@+3AI?K?ba3+MSlnRbu$)M&?8 zGRZ&$vFu6rw;k@2-!U7IXFw)~W$Y_y%>3p}d8uM;IT_B~5E&W5 z(QinkJJEJJAdKrF>vRDp2J^YiRoWlL$w|@NN#$tlazJGx=~gwpmKNmTaa&6!;Bxi~PtV^4 z0iLtHs0MO7wb(~ZQQq@JeZPO^KrRm?w7+O8WN&qcRwb>FX&RB=P%OX`cWWbg`K11d z1cqsExuw%oW?*&fGAcYQvp$ppE_P1^&ERHnsI5#8N*|X zqTY(5i0tA)##T45k)_jj%7N8u$ukh{^OmioL zHMr^8{{Z%qE@JMdYlkOrLJ+N(LJ)uugdhYV2m_&B%VWjpCTacEh2q)QGLg+N zxU};nadf{%9iJ2b08wVd&E((ZH;Xe%S}*mjV`(LjX}n_2z}CHKYPgte9gD}E`CBY| zxcrvvO)O~qg=*Hx98i30w~m$ORk|_3`=;*N6|Dvm?_-(<{UY_^>=_q^*;u!6 z;-fZl+2g46Yud)(a<~zp=(}#?$jTjZ(#DrL#1H@gLI1vd*M!=P4bi$eD9fS@c4}E0 z-2P2_kk+-?tfqQaRKq1a>@I=li`ckwR?%&$*Qd?lTbGyFY;?#4B~zn~=Yi$p{i5~m z4hGEx0C{*XnqpKHRG5I8k*)asGqb)c-{UM^zh?1xv5Y!16q%=EF6iAQ-o??2C3074 zy8664$BS2GnvX}X?V>Nmmv^Uzh;v*rG3rgOJ&C-t($>*r7VRu;56Pwem0-1_o{Dx7 zqhoQ^RlOyM>-o}a?ZcHWVP3%VaCxg!*eM+WQV5%rvWGh}Sevbx?D~>Azuo!KW2_9k zIh8nNBqe=v{YeWTES?)FCyM=21BWY>Y3qGR43^>dqT|&609X7JTR#nwIu2cxM7Fyq z_0g_=+6eTI_NnbD3cG&y^&k_UPH8sHQsiwWV7E4VXCB2(78X!jA9!{Vel8wp*fQT- zzfwEC^(1f}4J@hcc5}pjgh3s$@(F>fy{Zd1xQEoAx3TO%)m%;DvM*%2xozZ(tyuMmRq|py2N{4DF#Q29!h)Y$!>||{!sw4cGAhkWQSqOn#W&2Pz@~He9+eB zU`4}6Gy}_+c`9>UAE?zV$HgLYF_{LP6%hgCi@ztiEZ)TOmNeU*N8BpOz`%SIndQ5dMmTR{apYb< zD#BhZdn~cJ?JgosK^moN8|T&1y~b#oOpjzOk>GXotIgsMjqH3Iv%k*0&LxGqmkrtq z$*lIs%2rdb{q8A5vi?Q$DP}V`)CPl~)Gcww%h~j=fu>Pa?QMU@1w63BhCQr~W`e@! z)Hhvx>^$Z;-t7D6zma*b7$nNZ`Bzf}Mksi);m>zcU85wngOa<4_kLwo8Hi|cll2gY0 z=bG4NKTjh`5SCx1(Y2a*b#q3~RgO=MXi10E3{Ikq#Utg0IJcX%>D!D@NC;?<`uXBq z@3OSxX)!vvE=13dBmDPB+R3&$xe{TO5phWaghRiXVUmH(?ZkEQU|#jRL5Jlmj+DZm zLY(o{Ht|~BRs#H;jSyd(Q}m$PTTC~*7mZw88hGFS)qL(dK0Nw!Uqjjfn`H6pbNe27 ze>%JniR3w&g7TtU(#(`}&wQ+z?qhPt*!$weicZ;H$|CYak>{NM04BGiiLg?K%I}h9 zc{gjy{AKmHld7fy?|3FTI!3g{&deBt2@j|Z)aq8OQ*NXrn=$=vx^>Mlwf4SI;JMPa zJo$p^t(g>qdQR=Kljf<^&u13!4N(Nw4C=aZ7@bd@&t_|?4l#|!JvCT}w?0d1q3z1% z9^HaN52!d}F)$T(^Gnm%4 zOCOV1Pc!W(0SH0>RUB@XRxzEjbh?X=6`qn~O<5e=jArNp9FC`&N4Gg>85S3S<`$3$ zBf(Z+(K9`351~QiQsG-mW_p=wrV>i`Iqhp2(C6p(t%@4cPFT=dEw3DC!*GmC8Lf_o z45WQkT%2My9Jv;yO)S*2%S}-eqnanl3*$W6_{O0nI~a>$_?U2vws_eTl19&yTsYWd zaF3a_ipx8t&m?Y;KG)>3I-FC|iR79$8DG0(EIeqcSl=YEmK^qfJ_QlPS_Rwy<)Yes zD=E%t*}HY^l0~h&bj7W22|X^TF}U33b-n9ij+xaJEQCrU4+hUeA=5vA(RVO9IO;JN zsoYr%4tWolDambBO8TD9XLe2qB4n+PGu%tq_s6RAlELv-yLeg!?`~(B>(ZFy!)WG= zG)Fv9xq+*Rwat<|4qe=XO?R znrhm88X=N5C8BYeaq9?73^e)eQLvM!y`Z4)Evi=ZASSuSY>A-^Q=XXZ(cvASJ3 zpfV4XKGXSC56q#Q(_rD`s4J27Ad-Zy!{yB)BcojBCI)6S9YTkW2^9ly)04QGoGqxr zg>D)v7%f*%qlrDXFO+RoU$9Vykk&S+FS|BJHNdbIxug(564*4(zG{W?BQM-B8@V;YjN=gk;5y}&p2thDwHYn^wodKGY7R;Wmc{0+815(Oet=aj^o{l_D11I`Yy!#;yd0i%oigQg=!pBP#%$ban z%`4YxuCLM63^7zo8FjLfK7yk+u2(Z>amVd80TwkSGbySjo>=CMog`shLCZzQt8cV% zINLwemwVi+nekKCmqj)p`&-_VzDyp7Hr@|t{HcrI`Aa4f*CV+lnZ#Yml$~qZ=rDPd zoNcRhMfkfY?*zh2ydIK6kWv9m!@Y?RZ*KBBXoK^8$`XQr?Gv(s?Js>*dQ6M1py-De zIsX7P1mA@)k{rVC6*&TBz}x4jkc@)<2^Oj?dC2=8p+lRdWby|d&D2|5sgkeeRyT1b zZD6F>`J-f|&9F(?8QdJx1)d2rqn;8p4j*bkyn|CZi>6tW6|T{esmx;}(K?1wa*HQo=+e!VnIEECv*D@$%1(TjQIJ27L$_y=PH;TPMQme) z{qyQiI#>21iSNmmRU|E^C0vgK(&nkIAodk(4V=|CCA3pw$klOgH7KZCJ?; z1zWDul&K|y#n&QElFa9mMJ-@wXe!KY&d4*!0q|3y9Ti^B>}1tTU%d~pzr6uK>*kB` zSx*NRMEzfH=S&^5bO{d9tf#>)i3AJf89Pctk4r1&LdF=}nf#DpCl@&Qr*X+nZVR4V z)a-0^69_5fsFW85FkZ{&wUsi|*2y!+q?O}%y*}5}T8=tbHtv_VaJ-3VGG_xg@?8<> zuF8ZwW*rv1u{Gt5Zh>vQkWonkWRp1OCW|e#t6J6Pwt(lH?D2WCDi4kZ@%4XBRS z20JllX&H`xtwhZSJAQCkSGju?9Gm<)k>&pYDF#QqZ1Q${c2_?JHo)mVYourURlLyc zG&V*~=UzU>Y}?=iwdl2r+(mu_Vh?w@~ z&GLx{S+~#Tt(BUUM{x~2t-Yh3EdKz_tnb~HWdLc;>sJwJG*trm3jtfvU97a1$ntde ztJ$8djhL&Nn-#_Bi$mKjJaSom2uT~FjnO}W?T_eQ2L`BM+Gt{AjAW9sR!6)%m$#z< zw6L^tYV4bBTG_*uoxhn?hZie_J>7g0E_PDYoU_@^#wcXOplhRy$u%o8zzO4j@@vFY z!&^mEF`P2ONS*uThri&ym6u)z@dKe=cO0XRneW7*gg7*0oOcHE?u(XU*sZl*uS3*x z9u7xRgBPU6sF`0x<7Tw7NWSRDt=$W)=DZAY9hk(1IYM0QDrfHM;$)l+^1AmBR7F!q z9ZexJMhD)CQ`6fG^_Er(wmmz3Nyn=)a=24w{VJLn$ww|$TatX!x$;ok zSXnlfxwi_5R_?Vd!1yMHliBp1z@!W2Z#1vP*+)cX(>?s|nJ2ofLq&zN+@R&Xv)kUJ z&7oD4Hr7nHLLFsVnvZ8xSPtrv>uY?T^;hCaB+@f>LU$JC61%O;{VI!}d$^x^wFbGY zeflJH=irxR$zMev?W&;cy5vi*4g8QTeuxa2GU;V4XA_-osVffvk@-K{!2y!j(#ous zU2MRXzG&8=W1fjPH`Y*Fr$tWH*>0Fu8&)^myR)4aY9!~IG-(kuaSv)|x9?Cbn#d=K z=oLR*EQ2+yhS|;;j|y64L9aEn>Z#7*DHn0^vpQfK1VU2TEOXybj>iz_i*S6INHOj_ zwMPbS&?$KC2B(|5)4@G0sN1cI9G4m+yMd;){djXvhS z2nX1^{1YdG#>!4{tJW&Y$ng4h)yghG$qBd0NQF2%SF};#(?y0crN(1-KK5TebdkCB z4tz%=zDEB5b6p*zE)@{GjM6!>K1l~#E+H0h(RAUBYEHJ#RlbW6ixJ7C6*P`_vGK_t z=v-i2$l4!mSReESmYQg(=qg$yyz;&#N2lD@qmE~AIaq8qPCI70sN}u4ukKofjssf{ zYAg>>euOJ#_V|<92i&#Hr<5aM zwVZ~{lyV2$vI*RKPH(h@xlyy2#XH9P2E^mPjX05LNljBu;Mu9Fp>fbUNMwwswMRB= zz`<2j6*-ZyHg87xq;Fw+ZGfaKs>dt$yY{gBN-234-&sDZFP_uCG@;A{U)3w?dlCTH z+&We^;&)We;p>4dzcSAzx}S+>qZi11>I;TuTx7jv%jCMv%Iff>^&n=Ee2{DY3n*-iEg+oc5O($Y2dEDp}b zWOkY@hxQx6rPkGE)FivL&3d{jZ;kvI;*ZE=_@*HpQ$4vO5`9))QQA4f!>adtKP@E> z!S*ET*O#`jvPjsv{pK*4JRc_emh2I^l+sM*NM7k9h8X_%R*Yn|jK44k7j@BW^~y z@>m{dE_0i3O_UJe3w8D=Hd4d8efjSeH?)94$Xvq=jOn~k_ctlGg0eXaTuYnd$zvx& zYc0ao@0$=|;y#UPy}2ZF2Xjwih&y||mceZ{7qZe~bv44eN6i3^o*GE>lE?0y7ZV!C zTZ!Y<_?#4Gjg?c0+Yf@{*mwlm!slfc9ydm#X=SI}$x_DE5Xke{@^~!fyLD3OsM#cK zYwr$zi&erv?c48}pL0No#FFAP>vd#uNhI<&pM zg6lk;t#S80#j@tJ?0AgE1Py$-ZTGd<#32&X$kN+qV&QDne&owU<~CTObZ^#AN$Cpj zRJctOva=&^-&~RG>&x!c*=U^B;!@fBx9;I9(CSaMb1*iR;jfdk6tyxIe^$C#LQuke z$-GABaKAoj_kGC&WQhBzgJX2Bt(4p~*|{nT9iMW1(&uL;4^#soRh0LTESOpOGx#Zw zlz+4+uunPXq5>Q^N3mqHo!aJDu}P$F_A4M*=$@v$*VSrbG*RL>bhJ{20^m1d`e$2r zxYbV)7Qa6WsgElNerv|CX|PO6N;k2_F(8gN-^p{ugYV6K+iy00mlmLQBKVqe5N5gQ z>#vPsSQT~|BV9X$u;?35!=YVNzdlSaPHfbQq0A!b68T7Wp<~E5V79~_y%o{P9Cab? zWNu>)^CXL*nYS}Q@cKeSdR?XT&oVTzVzk_*tQX7VOPE1v{XohAODz5uF=wIRzgBQ$5wYNe~*kmYPPl`MC&N z-wR+28)ux>mhP*kCCojBST0Zh03)Xyc|KO++{L-{FX*@2?DY2Sviz4Z=Olvt0_n!m z`WFsmg>7Wj^JQ22z4*q2|IRp34crvCtuHi9hW+nV_1yq_t{ z{1?3}aC1SvUin;h_gs6cHf1&dsygJlk;w*m$nZ+S)-fD9^J431*?2S_HWfdUrRD~AGRrYjJ z?Dx~3L~M3ToaVc+s!ny)NahDWE_{k?6XY?w_WBg}{MEaQn-sfI!^RbTsY{&0pH%ET z5a(xiH4f#f2;a$TG>?o-_B?!|*mh;E4-=n%x+NizjC_2DB@O|%&?jTyJ;`R`x^@QV zTW4D+L}EJKOTIoU90?eMb)~jbcA# zaY^Rn7&5cox$Qa5bf20c8=r}y!`!S4qTb~4Wcymtt2;rwM83}pqe~y7@wr%Oj(LNe zY`0C^N{pjECC0r1_9@!FcIzoSdv-{asoL-h6r&p8IeOm+} z3sxZrLI6S#fDnWr1?jdqx$3H!n)#{7$>Xd`%$4bOO5#}@%iIZX_!fn8^i|mi_>cx@$0pNQTJ9ZC$Faqc zwc<{xXy3vLwnc>TI%+B5d1RMmts06qwe(Pzao#wOwNoECYoi8BTkI{wiDYLPgv#A;{nbftm6E&}H4uq+4DTIFQqHJNwxb3zQ6wBIUekdD7UT> zvwWZlh)S+~~S^m#j=l#2+frSa^Xido z$Dc&xa)vuWW4rbz@`r&0tlTOe#myXC?fFs+=n=Q5)La^FhUwn-qq*)&zx#Nm0Xk(_ z7&YXvlay!ZgX{?#D;pt|p`emT_pdRE*8FO&IGLOX-XLQRo5?=-yBM`>bW|~$gDm7R znFfTfEfl|FC_Xybw{l6mr=?@OzE(uxRj%(pv;Z=_q0ZuDd}VRvA*_S}KfUCIO$<=(zI7BTM5ilQp#qrm3}F)w?~j)R;rxRfRgEB}t|gY^vRF9t{5g zsakPtTvd_FG%T7bc0VR*CEjFSqi4j@Y-SlpRs^*5432D`Jl9$ZpNQbKG!$_%nh9jy zKX<;;M68zw2G~p?)ZZ4X$7t#5@53cU2pPxoiykHLZHrNZA;BqYX%88zp{Xur@7}r) zwnI@Eh;iGbi`HSUmKFy?EU}V#$0ol@n^g9Ex{`vLggbLiVU|bT%yWTWn+mR@rKFZQ zr!h@4;*sK5{^$24>Z_^Z#Nn%+x-mQ39(`I(p1h4kEi6tVo{~6YxU_Mpt!r-O*3R`N zCml%3NsBSZ)P_@UsYP{Evf(wNqFG!SO(c$NvKxEXf~#S3-0_+2j9r<9*K-K2uYLoG z!HGUfm$kA-M>FK~l1G1&Q)*Z34~B5Kqv(t(yJk^KbmCz_M-mg!dZ2ex$EfnEjrTHW3$TgH`463W+c& z<&v8zmZjUx%f_qGusyL1g4Xh0YiOiDWSAtAG*H3l<6-$Vc$(eagAt*|Y28IvM#_q3 zJLF8abRz!%bCGiKJOdSV1LVW;7vnf(>{!V?G(VYn)>gHd9UH@3)!3lK>!*%7xauT^ zv661y=p@zu0L~TBs~4S*G=q4^-*PW@8-oNC3w3xi~6lRz{nef@0#~F>;dmk+kvMlkE0_Krm02aOZE$XaJx~mVTqLv`o zp>9a>FGGs#<_SxQO%5Bil{HlH5gQ~B=Cf_6xLlcV_?YrztCFRM?vf|sG{c73Ev;NZ za%|iC0acPvFO}9^;^_-A=5|BU=x8qLb@Nfd&i2?R5$jaB3<>OS~=7Z#)j6PBR=N0f& z2HeLW4@bo64aV(ua<(qUiQ4Y7#&te2zENMyx4yGgYzsh0`E9a$7F z$oXAR$gJ-RNvhT%uN+MuLZH?$!Nl0NlWx|2P>&foJ`w5k*}02+9pktJF~1k3q=Nj~ zDw`yS&nsjfk!HbmF0Q$i6Vuhc3F(?;jtHVANh~h0%ZfS-0kA_$8>%6H%VrIK)VWe) z7^#aV#+yvvS`oVoZMN-scj@hh+T?w{Ux7W8!!~k9;uSL*(GV`E-W<7`b7r>pBHTH1 zT#mQZe0vh8!Q-lXsUmZuY05^UccSD}Vz{Ky232DCokVxNq^*#%>s;^rQX1*1%3ePQFqBq%#5=0RdjMkh)Yh! zTxYX2`Vy@}7JFuCHWuo-bgX;JU(PtZuLOxwquP0p&j zkG1s8ilc+mz1mbsOBC;oYBDd&;wZi0CzR=d>?7?EFOLAb8qS8W?7@%bB%i% z8s=8enwX?y+r1t#=(zIFhYsvC@jTw=137S@UD9bDx+g}iZU`-hHr)wbCY@GPw$x>o zIJW~RK-A{?(aP6Tz~S2;O3|72U?IG;O2)7PGxcfu($fBE zgvjhIWF9AG>Xq)EmQ2a~QN69;xL2Eqk>atFrzKpPmc*;~8SGC#RJnxP&DppTG}(ph zYnaEgFl(9PV!myR;lE-lekGZYYg``_-fU!I`bRqeH97(2ypGsoID5V+K^zj#Q51lK zW4mO3wUdaIM0vhNv=BCv6mgC`t#oloa=DP`ZQ*6u+DFQ3Vc#>AIJ|3>9C=&M#X z$=oGv*&u(t1ok!S`IR_ug&DYb&Z|T{j=6Ub?4fsxi7_ zhS$|mO9Yn8+|fsWYWdd674+2}jqRBHn)i@mSSC3_;f6&NCKDihH`2=s zMAq9h$7jzmN<&LiJaLln$4QmsthBZ?lE&^pu9iB$$F#ih+mT$_H^$b<6Q+*YHCpVy zx$b@kq_tMkK>l&X2+85Ql!f%WTv>d-;GS1~vtux{lG(7qE&Mlg0KTD@Daz%?Zsk=@ zc4Cq`DZZ#BBtW+$C7A(5Pav7UM6ct?APR%2_aiwewbA z$f-DQHZo2(wP|cKH>mtXS=BooYREv>eWk-^i_RZB~ z=z~6QPlykg#Tny2`Kz|Ngb|M4A7LQf0BHJ>ZWy z#ubg780y)Djcvuvxh$jT7%Q*7nuyn)AZFsgTN&f(4XZMn?IynXCw!OJ= zT0#E+!ZZ8XSDhS!^zi*UyndtV*dYj7un0mB0uY1%gdqTO2iUz9%QOiKi-ogD->Mbo zf5CcPnK@d|NLhK0`;o4Gr|G-?9sZ`TWcCwLL4JGqS*NrwC4mqytf26*@BE9_%5U*P z@%LuQZ+h~W0B_iwjkB^y{O-S!^15%QXTR5X)pdn}NgZ+4`mIS^0qib?SRz(xay@AQ zsJ~@(W3z)J3!30GZhv|ti+bN1s(W0}9c^r%Y-ldE+0M~$-A-)D9$vFlwXSe^IWoF6 zH3K^ghq@D}CG=UFql-(`ZL)QGsU5t}!IL{qp7kR`l}jWN#>~v^wmlHeK=`g3_d9Xe z^RzcaHt)^oqrY+TN~Afj1Ho6NG35^|QY^!KyhZvm#I2w=(J|uX%ssV&Ho1g2zRL&# zVA2cO?Fe((wHO)W)ac-OEo?S39vsM;NMjr$N(yrfq3$C%*FcsYMKiGo9L&X&*))pS z1F5EqE<-CzbNfR278O?7$|_k{{UwSwXZDriWsp2Hlj!fOF1-%OOC$DU58rC|W|9dH z^{c-JW1BZ?(KWeGg1pUlu&Cl-&ETu8kmXVA_WuAX$J*>HoRVgtW)klZ?_%a+*n4p* zT!q*JP+P$0W*PH_dgjBI`g?0` z*U;9O`rJI%-RyE0S^>!=*`1}L%y~h5fxDNC*}P(W5R4xebL67WlAfS^oH~4+g7&4d zHO^rUY>hT>Wx)k{Qy+C-J(C@=+glkNes=um4hO{Z+e#k zU1MviZR~PgIXggp-Bg&-{C3c#Z5fy(Ea&#p(%hAD7uEi!Re4R+7ipG7MZ7k$k{0qp zE}`6u8TnDLJ{+Ags?|)K@B4K_?Ykc2%|W_$xDlDR<`fLv`m4KxgK`wbiQFUALG4MV ze7kXSF3-L*uO4{Ju5ED#C2xOt#AHz0wi;pT(Jb6V&HrIWb5@&uc9 z+1jVeL;|qv>X%=70XH0y2P*~ium}piZfWV{f;DnYcYRO?iz+Rc48aGG31;E?)Pc+? zcO_07F7_0h?jC4>cGoSv$pMo zT~8CdQzI;6Gm8(QKG8*vT>G?u(^RYmiMUbX*O-}QBXyLLSIEq5sq+Aq}n6Qr1%Btk6H_+aO`&+p@KRp9A>Hrn|<9oPX_IJdbz3J zLr+rUk@XFY^09}}=SE8=%@_b=*}5+EHBMMs_nyMwQb`<@jAU(+P#@Z4Pmui=UV@+E z^sEM;xrP1L!y?kQWxH|W)O9UAhci{=s~B599){t1=w*UTEz>v$HS8H$?giv(?R?ff zIxHu-zBiYhnQbnaGX7=TqZ#Po;mXU&{pnmvxj~jkImCe5*mF8BVkvfJni@!Iw&I4G zXGY0POr&$z1e)a!Czn6awTpUHdc2O>Hda#MCQ~KD<>%AUE$@TIf5`Z)?BLu&J2S`8 zl)extXgO?g>JaCA^%rsI6kGs+$mblLY_Q46Sg>{N)njvuY|Q!I zilK$xKE)lD@hdm}nuoaN=VbLJN_SqS09&2g#`W_H=M>L$G@!k?9?bXp0{SctE~<|w z4-mJ~zHyAm)?KZ3my@5dPQIp<^t$*CBFf6BXsSyaIMjd^JW7UER?8fXenV^6a$Y^t zIJKZ>89^3jCARvys``kkE2WxuwD3t~)8Vw)nzIO!oB|GJzfVS1#>|jDGU79aOBn=o zHqmFJ#hPPe6-ArJ>c@q>4LfP2X^J;BvOhj!@@oFnH8#qsS}nE39fwL`fJ(>28ZY-a zzcCAt-KEAD4eA)-;P}?=*kO`T;?UH)SgRn8K=Li*xDNn0lhIXuncLmfhiEYaP&d*x zNRI~Wv!c%%+V%s~3oa|-4F%m7PL<>^xAG{?^!^!=waKlUPIoi!R9lqlldpEEwVlaw zTW8VMz$TX$m(q^+xd*YQV3uAisqEljro-x;PfTQ|ENr)EGdZF6HZL|02InbSP3C3fS@X@1 zg8`w%pnlQfGU3op(q0M5;KA}&WslQhp3)o=3|6S&6|JtqA(gwSS~9q}fpMC`{?**u z{Bs2xTTw-Uv8FBLd)k0qDUwo2k=m1X0c)ODUUz8XiMW;lJ{|z4mkFYhp{(p@`=>RO zPx)zDxRmo@wRH?-O?=dp*#-Ae^ia$?NgZal5l` zQ=-S&W5#u1z>aEy-P$+tNZciTJ1N~Qjjf1E`dliqrWP>C3=b^~9A{PWnn#%;Xr5O( zN3aaz*uKe#vw4GJG54PUdl$zk&6yi_ni4wsDuEXCx!B0hi&M5nZugAfdgoL?*p7C- z!TncD90mA=F^hxeu5`YRS9);gi8p-LRan`nFa#8xd+E(=RK+W0EjKS73tjOMp|Cvl zS|PQE7=(b97l-;bTkc_ceUKtter7%?By->!$qzN;DJ7#a4dkqUjl*yGSE<=bn5prn zJUB{35=KNX1!ac;_>{c=gh}ReK(2^;avtTzx61SJ4XPr1Dx0V#f*_*pis_3vb0z;PhyzB%E5nXEHaw}qdYPBs?=3i zC~!GF%1gL2`_X)j>kTTbQ+Mm9>UU*~36%N1DR}9M>>q8hNY9ZEEPHHiZUecABi#%F@!4 zSzsLXQHIEDS1!)Xc-9zi^VU{3i1{gbWPd0?@w&|!90McPcC$*=S;gFGse2^ra>L0D-gn$yc0St`DbIht+*s1R)D&I6@GB5QHEEAqW9_EtqekzjxzW z{{W(1be#(H`#c=l7+u{pvbX)5OP{IwZtsVGsjJw^_Qu+Ik8(zzt$CaVGY%5igV-}l z@c#gzdRerk4&Y`>epTi6dNAAyo#MgImO%dip?N(w)3fM4A>USN#%6$DORXkrW`WIh zr(<1C@418NF1b!ObDq|5bz=HAkh?~YK1*vjmN^2?a+Ara zzb<#X@~I(Zz)P*1Uz#7!+?jS&Ah3Hqs4;x54+k-f-r;d^3Mnb&`y)noKn>+Yciw0I zQFaD=sc__Lj~%th7dC7=I(lBF*fMQbnwAP&LXZgq9URQF!#Ox33B_tQagpH|^+xjy zk)}Et@4Wv2Ch)T2RByuNbx4mj9KE7@k|EJjO-T073nZeQo{$|ZJQi3pTMwq)uXCxv zPOle>i{0wvk99NSc1AspEptfJ6)kp`3(H}cq?$SK?{)D=5JsK}HP<>a$PT-2&gcw>DSll1Z%NrlM7r6@+cPYHx8wXij!NXnz9sUyO7bBHi~SeJB!6jn~{dfl)IZ1 z0Bv%fxqZnFX*s!vX$e<%gRqy))7Y8S$UrWNb8x(aqOM^}-FAol3DlFOQ;~>$_09FG zbF|K}jT|k|DGGL5@ZQS{pLIY8+7#!rbSczB5f*+;6cb=9vOkr+=lPa5yIpywDPwj= z9IG3L7F`0e?urLI{`5*ljdzkA#>5WRWjVZ+n6SO<6zJA;&?>f;NIx_As3m;uP}f_M z$CwRlsjlh~Qc$y`0ot^X0`eHmYh|men|mAK5(YJ&$*)&A__Q-h=$&Yq3$)}H&hfgv z#u8a8cwW&Pw|s)A?`@67sH%~&KB`td&$eeYi*nU{CuVSZd;v(buYR$?@f%`3?fGH&AbFgUrgN^V@^a(q=zPf1xd4QLM|M)-x#f(F)NRWd&# z$)9$@#&#BZfJ|^yQ;*9exDwfRn8o`mX~5x&5*IA42I=<{2F`?n**b%#h{9+ zqM@ygf$ovTtdEyJ1>ovG=^C8<=Pt{qbaYhFO8yv_y0Lcpk&*V?Hop#%mn|;p2Cx$7 za)`@3Zrv^IT2a?S1~DURBx9QEG8r89@Sd%=FuqNJ;cmuv4UV!nStVqYO)Y5A`>pNQ zZX7I`lx29pF>d;dy?O3>^nR7^Yigg9uBreo$KneMUOYkPQy0{Qs-M#vwBWSLEAgH z$JD8$+TbmF>aE3u=iP(`S3AXEaOkOyvF)sGC@>R zcj2$(TiLBePYgxo*}T?DI=Z-GEZ#ZrN7xc~6xCclJ9FMGhh{LgMw6BQ0Ff0#(Cqa# z3sl#^j!9KD1V&4`IV|?B9yx+XhE>SyI-+XaIgbIg5=UpTil`~%bdQ=RJ~^Q6w2n*A zVVH$h8#}678*@3C9@$yEJGDC&ws^Lk>qGaEzWS+ij76co^~Bb?}?4WY8?IM z?mL=!7oEiDD)8rStAHT(C26xHR;abAzl}ItxGl)egf3hS&wTnHHPnn{Ey%FS_dXqy zCQntFIIYn&F6^p2z3VrsT@dsR(tV{3WM$${qFvP}3^iuZJ5Fns)32KA%M)Z4?zw5t zN4joi&B5Zg$7hG}EIBQ0s?+8}KuQ{Esw8Y|06F7J*=^C`a#hUM0P8#**ko(fHJE11 zMq1e0QHVI-cf7Vxwb|lnYbyo8>G0+@y0}yaH0Nw=i;dxWI-Dk$<4e1@wCG1a-^S>u$yQB`2F(!}PS&4f;Gq+`aBuU(4QMNKek znkCNXh76rnloa%}6ivja;&s~w{6oC^npMb~SJdS(%o8|C=^YoO_N6@dReTPlmZlfX z&cIx#b4|2W)cISUSY!<`jaI0_u_rmSjis9IZl8N*i*7X>?A@ZJG}}#u(>9%x8j7gn z4Up@7^7dG+&0yHgJg<)qWhDNPvZ9+_K7NrbGX-r9B^6yn%$BAYw`{TO3$Da=YzI5^ zw>9T=Jyo{;+qVx*&3#XqV;BY}vlCLfrLnoSUXq%ko?TwKay6Asc&W}@dk$#0Ut`*A z8|>G?gW&0VRQS3(QhMP7I165AON(Bi?2tf%i`0UICEmseJ`r)SHeTfV8S+( znFWk=_=Df+8P$=<7t>^k@joeRZ*tIDEvo#!9iA}}erC89vE_Yl;MZ%-VUuU^YK9t% zlZVtw@09*c88PwdXG{JP`W|b$#Xgov&AY7roX3Jkj23vVc7r~h5_fGky6k?u`6+)i z>||Yjse@!@IeE$Sspb;cmfxO?-FIm;*rPfOUodlTz_J2JZQadaeX=_K3czk=`qx1& z`HHKR4K2GkE#QHZ%j#39oPfR>hPKXo;(u@2z9~%0WN78X`2zcFE-ZN<6T54Up4IV) zDICdzUMyn`A5dFBp4lplGCKKVbk$N*HJ$bqurNF}Mw``F${IKXZsfYOH12$QyznZm zkYSQE%@LG4jPB*RQO((G*JjV)^%57&hKhsh%_8q?<^!=4;ti+7>G1eR+~8vbf=Bf? zv07ByTSp678@6K$o@O4?%%7YsH)AfTo8z?jT?GtmcL=23N>8~|Oig*%ZCBW&*=!05 zHVA3uF_&d)SbJYm`QFqvmXi{zriLd&xDj3{oMm%2k$XzhlNZHa_P65>qmiu6-P=TW zS`Vo>o-4Vn#P_q750xTGB^U5jTEtt*IBQ!(Pn^8wCil9YT&&jCS{PIBio|_lKPu_H z@IGfjD@JF58+BZ&0Aa);E`CygH>obO=Ge@K8`qnh8)vVh^H zinCu^C~)LFl1UE6o6cXEOa4>M8QkPBoY@8JgxH=7!@Au>ZFW(o2ZC=6$n64gjTvFU zv@~!Y2b|}s1Mja?^AH8EAGu>BKer;2s~`>KZ^)xJ8~jq|p56)Y-^utDrB-*i&&Ms zlJ+J_&6)bAn}JVf$L1?%XE@i`kOkddI1*@XZb>=Fy8vU;fUxYY;6`spodvh%i!ktg zNd*wwpGFkBE^Si|&CN#+ZZsNR{w%8vTQgD38SNH>s?6{+DYw!QUrD}qH58Nt(><@r z6F^`EY{d~QXxBF-+}e1E!<#5+v@Ysb8ZaKm0!O_WJ9c$puaL^;HSfr8%^=4|As71A z!$2o4g)x2|S0$|L;fc;9opeJS;O9M1V?&HI1=>S5|CTl>>DY;Pa0y?L#jxxu0b zUMKK)=)E~<_@7?b{Hx00vbsDb81JLn{{Zho@_K2umaqK$UgyO9s_4Dhk3VT#(&qeO z&wCcYmowN#o{?ddtrBVvCB0sL)v*|uUv{1_R5T0f&YemC!azO0%*bRdcntR|_`Hp2 zF8in6)w8osK@@VAmikaWQEoYnaLXezvBf7w8p$Utk><-Jmbr6#J}Kzy%#&C#_@LLzY+6NUwgGFC2^7LCyTzMdR&f8isWdKr-+xc z(k%+PUGe%k8`4Q&S>zXJxahU&U1-bM+lF}RBmV$Ow8p~KZaI#0L=L=`?h7c39;J!y z^fMVFT5OzdtPX&wrl|P7B}*^f-nPSUQ#_roq*6#-OAFoPvNJ|E*tIa{<)MrYg>If| zt?uHn>el!vDYu!of*qFUDiDj1G#kHimmV$!MZA9XBeCvDdYYGOWbNdk&h>~?N)3(C zx;MnhB9!ENAM$5a=c;MW5l{dCQA#^(u*)a%i_o>r-ZL-$NlMWrJEDASbW+F1yepGF zJ)PYTS#FyD0PS(hsVZsYqpN|nR1=%JDGrU3?~6)0s-22-Y^{=POJ^i^1xqxNoc{nQ zvQEcg6?>_lnvO^MDP%pLo;D|BIj@E) zn51N|$;SljA1me*ThZIedB2HQ>}1cV!eSVv%u6O`Q;9c^q?7qFyHqvwn5G!Y`U%-J zH+oBG$v>1UzTcX!otp7)Q+F}HMLHxL9CQUR4o=s;%19BSuKu1Y8-Ln$RNe*CocGe{X1_D7lfJjI8VK=XIRxirZ$1F4Hc2>cq+Ix+sTdAx zxI@zyZmbqb_xh0jdZrDf-XwXdFKHZQNNq-(GxL4O1n%B`o+xv5@F7ju*TUU1s%x+0 zP@>{!>Zp%gXZI<1^5~0sBx-MGj_5qfK<8>Y9}6W`WFMKx&%t#7r;_@3rma~m(MDlw z>Xu;t01p&vC+*2H;gI%%gV-ML$eW*#U*4yOmBK|3JFNGpcO_1B&B}o5cq9R{ih}p$ zjNJz_2lZ-P?jAL1LCh4pvi3atQz6&nv6&rYY!d5|rNe;-irKYTk6`-{l|Qko{*;{V zr;-84SoS`{#Z9ej{ktYZx$gYQm+)OuoB5<=n=f{}lJd)JNVu`G_@~SdJLYJ{;HGk&rI(g;yP|>8QkU_v5&nUl)bc*mO_4 z5s|CElv~tzAjUCjX=-GUQPW;&EOmR=A9NtbpHA23V^_A>_XCEuPR4oib5%a6^twDh z2f4RAnWYYRV{;NtO?=iyWf1nYSX^!a@>yikHnl}q*^Tb>x*HYEmQRaUOeASzpFEGr zWz!AjPJEv+aq(;pnYfHtoK!ifxjq;p!Lx(^0K_LLYg}pM&O(3fJ9fQ>Ymht;;4Nz@xW6>*;HK5}FgH6fO6_+b zhd8+0-AjRCv)EYl85i|uBo9jcK?*9NpEmz@EMbT>vxe=EAq4g+0yLqW^ zMC>ow<5KR5fmdxPZ$y}dP5na@LOUs;`xLA<G4!cD6w!DM{aX&dN+?cZA2bz;PYnGij-zlO_CEdh$IEb+EY<2;u?6n05%$LQ|1 zqkuyIW%(N?_NCCmu^MRhuM2ckY=#$4xSBD|`_u6x+>zt6Gr~fz$v@CqRrsjR;g)7yDq&`n}STra@p2cJ^I^YYJHUbsyQ(YR+kmixJ$Fz zNR7Rq1{9j9X3Z^M>Ly#^F_tM86lEcGv;IGmm==Y*Gj_>ZSw*b zK6^X*YF5>B%sC}{3-pb~KdoJySp2uu0o(eQp6PQIM#pwBz;@T0k||2`)l;R&c4$?=W~th&;D>a zhv~z}>b>RfcKc+6SYc2=~ z5i(7e!D#E?Y_Lg$(?d}ky4oRe^)JuZ#vJSmXt5k9z3z1lL!xPE?g;|l75VhbnLS^j z>MU>RmX!0UogKoJk{p6AgCgwqat{}4Qil_k=^jcBWbc*9-A8=`k~Sq1WIE-%F3Rs+ zK{iQ)hcXS2Xfz7*9E%RQ61vFYfD3@o+WE&}LD4Fy2m*O!=&af^c4+%xHZ zc^68Q2?31fcTE$AHQuWW$F>^^j6p8VRA+d;XHxuR5%@;yZm({ii_`sw!!Tx3vR_6w z<(XJN2KHVaNu0{ZHKdK<*4@R|*;m!O8lWz7m`?TXA2Q2Hn5B6t)0ul(t&6Y3C1p&J zVXzHJrirDXj|UOk_pcqcGMHOKg9cH?Xn=EDPRqUCz`oZ6jh3D{7;e`zI3FSx$3777 z=KY#&Q=8k*7;apyEzKqDdh=6y#eHzo9PK8(@Y33N^MJ#d3 zW!`WR1d<&WZxg17(YQ?r$O(LwlgWKg1+1O8R6?D?D6<(d#0VVxE~43Zo*f!<9K4pn z>|I6|P|Rx;h(j!Q6mb*A@h9Cby~B8b<(Q>+T)(f1rk7{T+pJ=FvN+*ab-rR&;!@Hy z;7y_0D>KceZ+d!i(MEpnbq;rm0CT#Ouf&eak(s%H&(}PZ#{r>=+BF>gopV*0gK3q;Qw$r982}iJEw5nE<%xGAJ&0 z^b;Q@&NWtAhs^qso!NPmcO$=wBeCW6BB>7J?e7o0EAZ#CMcISfg^WJn zti0V#s$|^SERA!C$*Ptg4oGHad8@EfTpipCE%~fXbIf=0R_<-~sZpH2wUrdJSu45D z@$*OxEY~XHbMwESi9>rlT)flG?Ln6gRPws%aOG5Ze(0GKa~5geR9GyZY;{YgqezL| zF20FKGU%z+x}9CClL>N8JjqM4I6|8XBY@GyBHv;2!+vK!=3Fd3(?$q6FW^_EsbQ9u zT)^8XE6ibX0T%7gX9J$ZvVAwD(t9>t9l)_J_pD|KGUx)^4eVWQQ!x6glF;qfhaJr^ zKP-XFf3*ORLv8cyy(1ur+RFfV@+)3k78!JgCO64XnQI@5<=bVZCrA(QDE|Pwm3h_c z{t$5aaQtS97nVFegi6BCQ+rYR3i1os!Sw3+-lloWX@GElsE7eCYq8ui8X+!0b zk?oDr681a6c_&lFhsfGjxsH*5MIhjkBl(6?D6QeSoX_PY@NTkt#-5s`Dq#;ep%vomnGjgYVh&f)bBv<>s{4g zc#w>p)lo~7S&uwQo*3u^ZyGx6-_<~DvAAa4 zy`c>3#fMB?hSQlOv)ItdHC0g%b8lj9=)#Ig8&54%1+rw`XJ_@R9bpl|UyxjjE$QCM z-H)K*6Sh%X5q-A?H{1ExmsFdzo(s-w+>Mer=4SJES4+ol1?XLJ-$`w6&2N8q7Eb0; zb2qY5IkSFL!>(==kTmfB0L^D+Ws&)~$1fy^;u?KP05s4j&~}p&Ru;8|?3l9%>%L9e_O>NN^EIVO+=$0b1Lf;qd(H)6Xn zRw?S|v6h^VK{rloR?^|qHj=bQEN>sZ>MzXw?Q|(;G}0TK%nafAig4%G(`Rp4(bFV& z_>+Te6d3H!rKtvs8EDG-NsdD2^Ym-3=-k)6ua8!Eh0VrrIt+fFcUuXHsk~8C$LQpZ z{`I3tj#pt-P|$5;U^Z9oW5wh7IS)AZgXvy|J69vanAPY@&yr4c*r+mC+Q9HQv}>Co z7Ff%lYwDJ%SsVvWznM0;9XhCOx+>3hSs-q9UvHX3N0X(JYpgt$M1qU8MbI4i0s+Q`|xBBPS1G z4HnU!`+zDZaN%mtczyc2j;NTza7fq4G?&xh$4%A@m`| z`FSLhHE$2?{{WhuNa&=vSvL`U`BO7=oiA@7jqhCLLm!*1)9>@^`OpCDdzAohWd+wt z!?SO4I3x)jyXFviq32JOQz+s(c&bAXv$J2SlbpAz%KP7eU?YTQ2^vo|iQH_--&qTk z7kH{cJ>HP|=fy>tp4QPa^3ly1b+_k1>a4`{1gM^PX=x;@s+qAc)Jzf6!rZaO-iyuG#OzxYrNUs5(eK~8k;HOm-6UL|CySF>zK5m3 zUY7;Bi}xaj4s^IQnEbAAe6=D7Snm5Rtc%rPj&Z`~rzMVKD&>8ZZ47K?%TG^E(#m+g zF9dOu%gHN&km6H28{{a60Wz+b)Y?&>R+cyU_XN$C@px@8hs>>R&3~?8{lD|Wv)lYM5KbYZVrqe-X*{5@(kUA`) zL)dW_Tv#WLV#%ZI$lI>uQMyw0#@O$#9E+lsV`pL(vT4~X$b5}takb9SF5GcREMd0} zc1?9vhtfh0@@Y$B%ci{-QktR}C1a@^)|d;1XET;|T|PKWM>6xco*7j!(igv7=L-Y> z04nqH(M=6qoo(S~8(eM*`fe93T@60!f|45O0kL#X5f=MF=DfbqHmbg^da9Trrj$nZ z7PZ-(W^0!HZm`>k<*Y=+y#5`w7|st(4Kysn>LG-=k+x_7b1n1Q;1`s_F72v~+(K`P zy`Zq%n^|vGLio&#bH(j#O47oEhR}y+;K)56(6q;Y^0;~+?J|8zUD)>^J+5feqE0+X zPjeGe1-S%?wxtKMP=I;rr?%Xv%;u-jDI|-3n1=z$*7H`R8~5|E3W00)J7~-8M{{2V zHV8=*VRn0$hTBGe%Q-)jviEL3F?fBlXZ)rd&%MU9$J}o$`EpFs&QYz|8qACi?EpgO zOftyeIoR26*1wbTaB8)(s*FJID`okHHMdPEnwx!jH*o^eq0l;d$t26@u6t{>fY3oz zi_y``kV5C@coOTXE!w?yvt|qmc(GV0%RMBUv7$Do4T<=vZ7XGwt)ZrojvC~Aeu_oC zi()WEid5p%^#DgnByvL5cchQ+e@g7W4W8R<0!(g7Mw!_jd4nEH<9+#EVd~pwL{;+_ zxy^VD8@s4%?`uZ!puguaZd6f*w7l-)0OobNX>z-GtpwXSMGYM*12H)SZk|xfWFY*S z(`I}$aMJjaro`*3UmG7&S2!8WZD#bh>0NlM zDXHYkRq11mvN`PC1#QcFsUmis*X3au}n|OE`A<2bk2xA z@rMB09;+j3NQzSDU9BAMr&iVLGF5@Ku{y&ntUrJj?G#S0v!HHLdj;oqhT;!!;F4x% z`O8BQ#A+KfTbV#^@5i=}38&1mYT1xV#)meNq0b`f;is*hR!0UNUnAaF#t9ZWD!+`x zT;SHa{B~Uix>{jLTKOY+Wo#_mpOn%LfSkAvuEBY>zxk$@W(dkhmIY7=)8ai zLM+!iPD|*22`>X{vAGL!wyJhGkTqijOTob@jOA>Z3)a}&Jw{7px2e5{P`;^>T$TnK ztQB~Cu)Xeu*Kj559M?vgLmWA?NXPy~f%ESr4tVF{mdLZ!$FvYrd|skcnY0Y|;%PopMc&!!NHK`(C9ize zt?QcAv)8~~y!oJhb+t_xFvK%(G;Z`*A&(%B))5@*W+EZs%fKXFHdm+iy3tjfHwDG3 z^DvrvXUstR;D{CZ@(Ot;p=~nSc)k09zOMuefz{d#zsw*hrmI@Po5$h#bwVif4H;G5P^t zc)v9Bd#4|1lXG&F{E>AbV$cxO)aA|5A(%V0!lc1ErcV+>weM0!gGE6u_AHI%*jSE@ z9TSb(AZ*QdB<>}TH^Nh`$xSCQ$#G`471`HHy#PEZljN~A+$o3fe}Z(j)!Civ#hJ4w zZXQYmoPDsJyVm!u8H~Uue4~jM;Zd72y{b)D_9t_fDwlS9Nq2qf&xMT=zKU}M@7hSX zGH#Mi{j^KEmZlxTIVA3AaMeSe8mtqYW?efX>lt=|;Ua@BaOAO`L0gWi2{t+HstC`| z_pB}~@>EWqNoPNNchZ)j1Y5kN!@ir{kgR0!rW9PdlS_vR`uX7Wjncq5oaK{3u2RMC-_vG7pGaE76y zC`!SRqeV?N9kq$B>J~w3aP#PxWRHWjqPvBNyajoLzKik0_ zczwvtm8c3mgzgmQZ|qVob*%Dopm4TZGEEud`qke|>MY+ssUl=pj|wluk#`p`fRoEU zZ9G)x@+x0%EcQ&E9RBnv4#?(c0kOLBO<Ib@E=u zlpW03dt)R1wd3lK@0obdqiE*5Zi2qMK8xdDO27KF>^E-ECf8`ozeKxDc|&h~J8RXy zYv(cdIuJyCQ4Ny5zdWP$h;TAU`7g=QXzJEc0gA-;&xa$=%t>Tm>^8GPLhw zy}7SiM-kG*mEiDcL~oWt??)WWFFrBZd%_z8j*mD6t|LX&KBpE+`jpqP-IQenj*26_ zy&aZNa&|q-CM-u-$L->ynJUQ8GTfFi>a{BO7;xf#aj#U=kOyre!=FDss0zE;+g38V zS)qLc{Q_BdrR z@fQ*o3cm=e!|K_LZ2R)oFj}IC-HGG=ZFkn&S6e(AS6@re`&2#GzJ6<;h2u1s!(@se zVylPcsOA@t4>iAh-L76LxYa8zZoNI~p6luPRAwVysTWvq6s!~-pLyU_XZ#h29v%)$ zAusd#f5jkS$G|BEPDspLZlLmDPf*F-x00gn0u(o~^rjGOnZD_5d{SuOvWxYyMZ>Xi z>_BHPYa5;NZtc}EVBFpH0P`UI3F-<&$$v@mp8KPDf7|?2wd8U(Pcw&tVU6w#Zhr(F zE`aR8?C$ciO}>9NDK$CVKb0$bMtf9;jS^w7@<3$FY^yVTRy^KG=FNR>fMkw#PqXbq zuiMp4?0}+pti@T6F!TF+mOU(sc_6I5_DuR+EXLe|o9mMP|ZPCDz)&1hue{YknU_@Ih;YA0+^Q@1>ic;&A&uNxU8)5u|lCTDxzK23Oh zLb|JLaTa0NV_eKOncLSm^KrMzDH^JIYd#RMAx%mfO@z`m;zMJVpR8V%QB6fmC}oJG&A`AwPUwI`;2y zinyN7Mp>P5Hh*^GF>Rxe)5ZB0TzkB_yPU^6rEVXbvNYVPX=rmx?~s)Ou2we3OG@fE z>K_Sz8{Zn|(^E+3_X2I}@^-@7sg%BL?YOKmESO-=ip0~W438IF_4QfRUrshEShqxh zlalm!dkAx~^VZ9UOwjqrC%Qi(_AqSjGH7C&pA0n(mAUhYVh_6Oh;q-UI}nh{Y2kZ! zP5CxmdVCsZUEhSd|lC6U7rj@)>NB7J1UXHo+(J(e~ z1B?{$xvZKj?Kac@0N+k$nC4nmym`Z?h0?}p-6aKWTVi{Qy(3ydJx;A$Y)1qVwx#c^ zbwlKHgWT2zfa?I}y4@_h*kGrciZdKhKsn@sTLJVcr>3P8vKnmpT=xgL(h^?bp(VtV z(M_w(Vj%Y7W%2A{jqthPvqR>*oR`_k$qcfF!+RWNcS9E*}s>)^`_&@l`R?~`MaxEIB~E}++31Kv}V*Khy)YSE8qHRTs?5i$moMS z+A4W#j#Rj9-oW8sBtTfMJYC8p!!6psA9c4bFU=L#o}9sf>xv ze1^>gkUWCwwU6#;KB{L=9~)z9BqijP(UsFu)3#<1*F5lb3$opA$?v<-M$KzmICU76W26zt=^qq)qw-FJ6{y1}o%FIf zyXIt-v5j83P;90+`iE1T2BLZM=*oE_lb1eM@Jg#;_PY;Yl6{%QV{0_c9Wa>RmrJVV zrOm3;h3%*hZH8CN02cmmh4u}q+PohPrp4ly4i$Bk63k+nNc|XOj3zsk@p@*N;+2_8 zUyz2i=SDn@7qG?Wixs3}w|S$QINT%hC1sL5O|j24aqvB*#qdW|oI13?>Y)z!-?n1v zv}&puRaYdne02n85*}epcx`=MTdAmM>MLbn`8Z<|7}n3&ddTKv71TA9Pm|=t%nGe) zm#L>EW1KF-xhpjpn|9~1vNR7z>|2e(SalD2%N`!c!F+Q`!U(uP<7SvHwns%Hf1E{R zpC5ceq9XAVH*CmPQmUL{RGH)5!#oF!$I0u4*`qkcIfbub-QC&#_?=U$J4HPlalOyo zGx3CNy+U?V!K~gI5(+v*DbQS z#i52wnl7tpE9&HNf)gX2cb<%OSgG)8rvofh@;ERHA0<^o1u={l86COGZJktAame>H zhl`8ZDJiG;%c=e@=e>i8msuGR53^%yLp8oc_F7B8es+*E>(83sp~d8)hIj#GraA*< ztt7HijowB(pxzacxTKWyRdnp4Xf-EyzLA}UHVy0=uj4p{WR`q+H${PO;*OK-Y%YN2 znkJABxpH=QH^r*lIcHtBm%bOoFU@6=zP0Z4SWYC&PKG*&-VH!;WU)V2u7GZL7XV8e zE@yrLUo(mG($4u{A~)LE*a4Ak;~Q04+#*~l(uPkt$uVf--Sb=*=`CwL96eQLIhQYL zF^1#2L04HDpYdp2mYt`b?lts(g8Ure`!hZ>EMb)xy+z~9%Z9=GU3|-C@E2_!JxhbI zIgyjSs+ESuIO86Y%k&I^jSOTgEruw|VPQA)ar9lb*Bxt0xG!%O`$@wSq>?CD4rd&o zd6n>;y~U%(w&xJ3g|>naDB&@UPVId&Zg#1=FM{r=oL!66wn(9CMv*Xm(R@NUfPgi! zwZk_qk9yk-O?_5pY5X4N;HL_0M%KR&bw)#nQ|4q=`AzIbCH1kOUK`-E2Kc7V)#DPv z_S9l>WQp(l!uJ=uR#|P$g)8Y=P9;D&k10LjPHi*`8m*DXDAgi!KG`myn>pvI9CiIE zf(KCBDZdIYV4_DmmVHn_*{y#h+H<$Hbq{ulUiziQLt^|_vQ{8+wfvSlX6YeH!rX$O z%w)cP4%Tz^uadHzkO&7In>4@FHY-g4B&(bssoUu0`=mbO}_$1O2*Y~M4vqRzMBw;aBi1ew?@ zdM$iGf$_L|mMksd%m8?hwyHoZdA0a@EqUe>9#(w6ZNr@uQvCSKhxMx_8tgVaGLn{t zkV7Of?&Om`vjrPqbBb6aa|7QrQIF?0t6vDk+8~DuF;c@3^pO~uk?w!7b9FWJyD`JB zapJOEwW$&SwyPF>co!B7wym{RTI~&h=W@DN?{)D=Y6giki(D^7$;%)hqcFEMAls5| zAfVZ8Zkna1uAmlj+IRJ?|Z=#!noa=lpxI^)tL#ztA1 z-(EcG+zmR5~ZJyh3Z>~vRroxriNUudCA$(dV4#~Q@bt-@?|t&-kas5Pf4y6>?%#e&95rKgLCW0ejhQ;5{ltkyj$GLg zYS%CA;F0Y9-U&Eo;O46{a@_#!oa9n97f#wKzfhPB8F-NAWM{E5M*HSpu(6UuZ1MCb zP?4NRpIsAZv!2B^^3^7st_fHMlIZ&K)pItAoXLj0)%F=EwdyB+UJho=BqUS#)>af|^*AT8R3 z&%)Q0ijt+Z)LZuqk7Su+1BntLc{eV!LDG z$iTU-pqy6%YCxs8qik!k$8R7G8b0<|9hg5mI;o55R%4nDVevWF3vlotqOFWefmkeP_u5=d+x9_Fm0?IlwzOg*;hx(DEN5nJa^m+UgWbRws znbD+XQ<67>%HB$0RT-@8zbLGpY6u(NJ1TB|_cckgD0{Q#-be38caoMQKp^MsrWEFz z*o{~7*A`eM!(L@>V?^ihbjZ8!z51+9XaF-VVCHn@ zS1xX!Z&S0S>#x&W{jP01kBPb3NNfDLuB25BdC~0Wb;zoqn-6raqi4n#INb~Sr%xmD zwn$t-JjJ=F$JBU!n>~EpHZHE7CNFhj+dRxpSSs-9kBMUuKQwg>)-(K^iZI-D^|h_S z@meV`%w$EEcIdZkm-(=|5Y;wOlQrH}ELRDj#_9Jp<3^q2b2GNbuG-|;;N`_?TU$5t zT$|h<1oIymK9%O-#wzeh;ls9>?Q{j%BE{o2j!5lz^M&Z;jnM$y&AYA|=E-96uU18E z6<^YFeg6QOSo4F)JNX4QL5FF{H6VEtW@fuvgzdn6pP6FQKTdz0F`16@R4TXj z3deS|WYfr?UpMV_4*RA1NH$R8mfEOo-EKZ=Lx(q7-qg7`cMusmD=!!7u{EarzT|%) zO{CvWYDsMw-*5+ltl3^N-s=``OPtwLPD^+q10~AD<~u(nEhFxO+jU{wH_!WfQK&0= zJqDbk^%W1-Bh^oXR@rvnu6Uxd-(Y# zl)olhXR^Tl&n}B8aV!g7M+AaR@7H*f24daWBFxU`0jdK`k_ehE=NmK*rFlK7#*IV1 z!QnQW<1dMl%-K2h>a8tYXA+xeaY*)m26^3)a$DGt+ePVUDJbwPG74%(HTjz@<|j!4 z#e`vz?Cu!Yw~cjdtRh)NdVe<>9X9p(q<+q$)X$B_bm)UcL^U8S;EDROK_}p^*P0XFG>(1ai2__XcIk z*{;l&UIGRYsAqpbzJ;=tEvuk)6N`gmHjg)g^eawi;O5b1KL^7osOsgaiUMj}+?&$* zAC;C~&a!D~fR>&INhz~Snl1<7S*wQnF;6MU!~?CEtdL`_-c1n`u{^J3?Qs{@8aLF|MCclAx;*nQo!3g! zjZ#Y3?Puf~e43j1N!wY5>3z+|GM5*wf#BDnH$8y~1nPIpv;85}v2A3NTe8sxH; z^5OR&A89>Whil%tG8@?di+H%x=I%G8n0FB8W>l2BGp*Hdwuaxmk6gS9xL!PUUVm!~ zn-vR5wtehl=u@j&yfd8YXSw+~G+c$(gAaZuL0H33$Qam|-12f-7=&4>Ugxv6x{wFS zBN*WF9_Z{!>ibT;&uLj#EW1&KZ8TB3Rx;*o&Y2`Gy7SJKA%)Y?)Cy?oX{%zXb!^gn zqb=B8<775F2gE)M@l0NU)%11j-v(4Rs!?#kalvpcZzb{y`R08?rJi@oG^R;kB%I{B z=B7EDYUzvCud-~W(o(Y#sEU&d*{bs?JGMuO#~X$FjBJABFIkV`SfxJCRa8Z?xb_)U zy4G5H$Xyf%tAkl7y}z4Zm?aUswXSO{(QO-bOp-=3BPW@RCzEA(ZPu}hA&ljVPcK6y zL+dJ~s(a;o=5WuwKXkI(qo=5@__iNUoIb9lkj77pfUYeajT1o@bDv-bg8DDPjv4Wt zrL4v$a1_{F0?!?c^7HzZSB@ivQaPR-9iznP_6C8t9?wGqYeY<*S*KwEg8F}0xmXs` zRBbHsZ2mjD-%S*bf_U4z&h_T;s`HHE^|+ITzBMDuZTGSkgcH=#R#MhcI5M)HR!vTQ zXLMr5Kiu}~(f*&0*xSPg0EuwaK_ooxfE1LFCzk^vj?2nw0tTi;SK02I48CzDz?;~OHTP4kGk85AZ z-C?MWvB2Db2*J^eOchL-aKh+}1jgvg86o?fv{*5RQ&UY@@ivi4$&7UDX0`!E1yo-X zk`|kd*F~d=%N(q0B$_h7!}%4}ovQ2Mbk7)79ATDonPsnD)kXIpxYMwKmfMJX?T6GvdP?qzRKViLzp@*H8zGm9=+W2dMMe`LpH9o8#)TQxN?QbWI$?8*p@ zm*r*UbI8o{7C$@PcQcnEs?UkyCc3g|L-JCcSkEQj*!&^_YH`d`c%Y=ECMJhJw;|`M z)?>q}DPI!W)$~t;%mLU21t$5I#OvLjav8?f54rx{D|2eL#)o7e-4=@cR#t~YO4gBY zrT)TFPe@+Dhp@QRn6_o=Ev5o>^ZcvdrO~^11omeXBfJ_Vrz+S*0h4 zY}VCQ;`p5PwU3rs+LuV;T<*#G7h7gFc3r8)nTONOEOdIls-`o%F-CiqTH8CbRhv~> zX($_(2;6=#SGxu{8LgMyu-q<(1H$3MF!p4E5P00uUgzCjT$UlU z6OkvEj%q-$(aJ~@VvspcH95IxrLS;fJXC6?T*EUoPc~E7&!SegigRhnX{j=Ap2-8) zeIPeqKE~mFKGRf4=%p=|D4xyg_l|ys&t6Y$;)*9yRyD)Y@I4=ZsqDm#X3^lqt!4f> z3!85O(ig1TV&S#51?K*aH!%8^E5>a8c=4Jn_kK$FLx0j0?)LST+89m#QkXX1(kaco z&MWG0X)`&^;^?|~yZ5*aOB~$o0Ke*7dPg~=pD)b2bt5(pTF!qD} zOMerX2xMt(%bS-eUSnY=l6TUv&dPo-ytlP%ZO+n1v)Fm7Y(erh&d4M-XC83}0D!ES7}EsSkjnONEw;ICx4 z;A2im{{Wm^{i<#t>}qeaZxYT%M>rn9J;jCN(CDP`ekI?bs`&mKDhpa1P35@ntLPVx z!K)1hA~QTPl2_hlS$h!d#kTD@>KB=4(p^(uC0uqsrH~VRo%Mj1k!5Z6F8o&7t}K<} zS%J8}M2D;OEMU9MJFWF*$QZ7_@w7>C?_Ga0$PJIGWwBk$^HOE6=+lspSr1Y|vyxa6b^tW~>b zP0iT(iL`LH*rC3V_V1A_tv&FpGFUV$f!g1wP+6a%eAKOxqs#WPtqQ|oyXDjKEQQZ; zKQT>CVPHGM>RB3f(P0e$TSa#S_Wq;|m6%&UPZg5yzY_|@8}m0puGi!dv98%rNbpga znQzezcY;L7ZscZbU#BFj8>Nw{Zhc-54*XX`wc@`tySMMATuIXY zMyt_5Ar5Wb#<}y?XQ$K8F!a>Y0vI!ZR(8B)vjDe+?z!}DaEuK09!qu3a4j8IG(%~h zH_v_*oqT%>KmL}_@9GzVUhm;ZpR;&9#lPgZ{{Z@mh2aABu>Cr|e?Qcp{DdJ3Mj;47 z074Le5QHEFmM0CwjVlt*PpJd>LHQL|xIT-sbN>LyvAxaC8Aq2Q^E*PvHyoXX_p>5< z7oypR2jNuv!)@g=#;eb5C8ovOJ;7_>iHz#Jj*i;(mVHmetG7iCZ9B_GS7@`ia|=qt zD?>onlG$v#!b_L6n!j`9Yh|!VD%~l5X1lO{_Nno?%0_^@ z42{hk04?Si;-_V<3;wmJJ9)@kG3ag{rrNcmAZ}*zjzxe!b5RtmisCo;t%%~w9&fEg zp|4|@@uiB9cT^nDEq6m@j;@|Mswp9#NZ!sLri|&WP=DaGIe5 zjU`mUlSDE^@!ySax@e@EaMrtd%0YFbR~u?WV`HxNjOFo_w@FzoLnfztZ&wlHj`{+x zC#%gpjI8H&^C`4{C!)m3V|zrfnHe8V;>2bF%x;{NR;Aq9c3?%8o8Np!oHv}*`?vo9 zD7U3$*jp=qrn$I;@zcvl=McdQ@2WBPGi=nj#@xE(W22MOea}Viu$d0xq9%`%IqmOX zKdE#wQ#J3kofVg|*||&NU~{`r{{VKoadxoI@3)DhbXHB{`9%Xx#|PfiHgS{B#Y2=i z+((j!afgL>Iq&H|Vx+SC7Dk}6@n1LHJXG~neyUj0rym`X2kdeB5u9H6#zY3@>7q5V z2}B)vs?TTNqMk1gtv2({Iv^1p%*g|OT+=!--d~v`cC`5*CQN{5BSaC*SvTZk^zl&F z7dOX510|$7=c?t^VT9C*x-uClXB>UUuB(B*ODtqvybBE7J#62m>TQDCRmX;{va&() zGq7Foi0@_7j&}!`q-kMiqc8Q=D#|w0fL`+)m*ADY3!NLMrV+u2S{EBINdCju9@#Lx z=(Y~Nyicai>$i0j@>0|_vr^O$$>4j4y7Mih#I{B+jp5C9BY<1eQ#@}UOn;Lru>{ga zSSFRSNB2juZAU*4bP_qTIzA@@Vh^=?6v_EsFICcC4C^VO#303}8(%>?sww-$;Kb&8 z)^V2C=(t#h1o*3d%p&I_J$r?CbSK^wcc-Ln97w8>$ex;hKV1oDWSS0aQNp5qDi$SqqM1={~htkAPUo${HV{d9yz`QloL| zezlFqni}SV(>hY{J5!S0NPx)l1If=XK586!u=9GHxjRuur{2PMA-#Tt>JNnUZ@oSo zzG?x_Ges?aZ=Jq7#GcO+{L4obk$DNc) z<9Qmb&bz>S?oNx&Z8p<01cXOREwM-OZyYVSRjOF_pJ>~Kwe&O(5>`#Z^6pHs$FrCi zz-ZfDUh^g+QyyH7kB$ic0AR4-J3saqza7V0C&ypKPZZvgMggYsLb?xgs-=9=hvw>h z)>*Sx9bNqwNo@E30BW5qlAYwbNd9eG6!eahERsbd8|tM`N4zb2nVqM(WmwiJ_7e~I z>mu~h%ekj%8W}tDARKq>{C-k zLrD!CEJipXCo6T)>z{$)KVqpKYEJVKtm3Mb-LqxV<*M{GeC*q6Yzu;RM|&z6tdaYW zlZC`h6POvJfy%tS6{$9!osDR;xS);W`jzQ#$D9D!KqkNQ&voZ(v&FPU%)bRpPyYaF zoGOm|PV`PZ%WSx^xIRMeJp$@iO8DSxZ+=lB&bd7RE1y4evki4(bWC%kabR8CIuOi0 zN4eZpbrDDX1;%b?I2N64aJ?CU?=;lV)5|d}&$@}3-ypg%RXMHcWT&TOn11s7dHzjr z;qv@mNW@lX&(tWv@KcMQi`3$<&^4TIrgH-(9&C@GUZW4$EIEyAjEfejeeNc6nGko; zW!)Btuak~qXWi4InAJwm{I1M{599@EMTTM&^)E5hnpvdCULuXsw6tf_F<@vsUJENq@y8Ok;`PzO;x<}RTE{rM zI~oPOy6U{_RnHK*M$8?N!Zyew=DkdZ9*UAeD&cVqcN6KJuN7QOWzz?C4)f|?M5@4XOr#t#d!Es= z9e<#&D~n+BL`!9*sB5LrG0X>f^eOQpwn`!rNx3@R%`Z&oO4g&4)KIb6O@Pai%R5KU zO_htdhj!ETlJ6iUPS3ecYrBO|wr`k$(E%=QW@hc^uP>JZmiBMtjJ`+;ZgSqK9Hri> zck5(_Z}#y*QtbIM{Y!_mr2JZpi8pyCkm$RXxLj?bh|Nt&W?cMWJU+^rQRDGwSlFpu zq-@=8gVyaRY|}F!7m&ueSe_sxy*o{!iTsKAMZZNTXlEWn9A{OvYw0h&_YZ^YwO0J zO8U%DjhFZuYn`QDIQ{vyqSG7y0CX3G*sY&COSE)YTUbRXkjYY5?73lQ3&8f07pwSF z#VTuY%6eu3F!&-S5YfO%TsgewhojMB-z-bP$X%F+yOWkY#jg(r&mB>wXIsS_)bRSM z$ED~tb{Q*nQx&6*#NpBkh~j^7k}hD<#B~}j{{X?eHOc1TdmeyycV}l1$L{CcQU*_ zG93UK4K7xRGK>6T2{ICH_xl%jIS$Z}w6P~Vh#1?JZ_1$U*4LS1ju$^uDUw3Dc$-dR z_MxwveuTBw<3=jO3fPaM-W(aFnIwyZXK z2%KYyh9~Y`T-FIcqF1!|cBmBCrW;1WU6z@*Xm#JtQ6JU{^4Ke4IJORDjwxFFMv^%X z^@Vr-9I7LeZ0VqolGv%ToB5U>&a#f_RC_*gkBSmY7K8E_Wxve2%nB)y^QB()>}8W%F|CC(Zutyo&ZWG-MGXL+SJY%IG)}v>y3xjz1GV7 z8r9*`6;jL^eYov=lSx$dHNWO=+GMSx5=J#O^`qb7v z&!1^|%4S{da_hP6W*=1N4n5SDTsWl-CqE^#@t2t28PT~$@i>I??0g^8I-ai%hk16n zk}>|#WxceOVY0p%03>Ja8)wmQc2|1JygFdUhQM_V60u(~lO@?r9Fi8q#ztk?||HEU;O zPABmQ+yk4-SDxmnIqotL$7UJtZv~dVOPhJTefM%U+ynt(UyV9Oe!E~ykOYds^ZH{W!sO{4{~hnTBO;hqEOVsRZhv^c@ep~ zU$_%+vW!_Yv1F$3rk8kdEB=zg*Ieb!RfmrS-?q*jRel_)+;}Owt*JLdg0!mbzP-N$ zUD-P-T;S2Fmp#pG&=zE7XV{Gt=L~Y3`J2rgSMPmk1%qdg6@<7ozT^T5Gj<(xz;pE^ zpQS^j$m`^hP%qP;(y@~8Jl1vC8=q$LDLMM*Plo)BmNFhX6@H+R+78d}Qe=La3BR=f z48cT>(Nam)9Cy$pL%aOba604%2!qHu{|LOaO6%=*;^H#a3c z?_C9`ExMNsrsGUq-|6_)vqR^HwV1XjGfyGt#u5;8yQrd^xZrOxp~ zou?W4(PAfS%{<2G9KKgbaRHa|Dyfr)4-bO9H>E)2)lGJp&{RI0!n?aFmvG+w6TYod zY6kqZSDT5PXClS;ehPsZ&=x?pwpnhlwcJ^F{{YddZxBseEw0f}RrM-y|N z{%AHr=ZBoX(?R(^cji#RWZRjcKxHl^`p8N^=4xEcl;%#yRzU2oPVaXCxmfe6&@(%l zZR|#>TLX(ShkXcZfqM^9wW_PAu=`72UrhsjcRzUl0Htvqw-`Wpj)}GPuV*-^pce?& zWW65rFbw1mdNSuZcpQFvZoJcRy{E)?O`^fzq-*reRW~)vsi(xM=F5t0Gu`X5h;S;c zEB71NRpJ!bd`^edJ1`#~g8Gm~1) z7R31MvANEILe~zY>bY}G@rhjNp69%EwyJisO&O`M>e-kRI=IJx1SaBMbPT`Ww zjh)F9w$AOOZY{%aB&%y1UMJp972Kyen9$uER}e(zJ&xwO*nG|48s_p-k=4^%$={}t z;s(9Eyq0=;-Q%}JM`rf)TC}3{t^ysPYS>BaQ^`6YFCV2z8|Mo&FA`-{{Yk>2wJfSLJ$HFgaCvg04$LUwohWl zvs1S*;_N3-`VPuJcZN}x8wpz@2TroCX4AFShC(=40nWEJDr~XRTSm5_`8st|kG9w> z%wtGp!`F#VPgk?-Gyec{pr8G(AnsnpO*vdrbI+)z+HiZ9)7rk5#a7;?^G_bDE2O)7 zS}iDF#!EunFCpRVzcuA$$E}{HPi?BkC2ni>9=73L@TxFeSm5tt)M6Bmed;KtFw{dC%FkV9W3tn8(%nh}o!YqOvzu!zG9*tG zLQU6K7s=eXr{4tIScS#ZctMVG3^ z1)S8wxW}*UNgxq?y*w1=b4Qwacr$q<=Xc(O6o-yRU1KGWcTH0-^F`X;K8lR&GV%(X z>z{g#iRsA$-6U{n;IYXZRRFeD=V9gtRgwH}Wx^ZcZl@+X+qtGY+McSpE~l%bepay6 zK=l@8oYdjdvqJ#MygIPICf zYg{@0*)FT$GakG?aOYu|%;LOZc=Te9vBNbq(Do|5%eA9iOPpFC%pEMXt7xe4dM}CB z7E2U|N1a~?Txjt+t(cLNc;n(fuL0KpyYAP^nMrTctjAt9(@p~^5jcq+vC0gtgW?_7fkYsbu%Aazo)Hn8%YJSGNQQ@AN zx$*8@nmc5Z`8A<}?EDxb#wCixCd7{uY2Btzp=ZNz$hK}r)LE67)Vexh!pKMRYdb^b zFPc}rS>Mb(VVkI~KTTerMeyrow$|-ai|VI*(!3Wxv>(p>O4+BPadRZ7j`1FB`{K<7 zHQLw79G3MxMUNH5C@?59;umd0zD@?|B!OXv4YFHnJG!2>oi%(MEcF$XxMd8ugfE>7(<1hzXLoH~3=)&$HIdjo#L2s2^*be4=(eUzk(l8$^FBvK+H7nh*IX(&Cc|To zcf5*Nw9nyX*4emmXHQXxVN`NWQxo@Y4YLE!@`Rpirxje8EcRG7&$k$>rN?ne>Z&D= z($mExoG}tQ1?p=YX`#-`0yMcR#6^wmMiwtN0N6p*`>-6>A11Wl>s!%n%}WUtm_WLPmc=bc*w3v)Fq=>_T z9Sy%RD@$lFsw(_4Z;a8)P|(A6Q-Qp2@NN38O)e!vMP>;OU^U*%x^e9#8)G}n+8*ng z{{YBV+g9<#oc5&Fd8_4EjV8}gxv^m4rIi`R_ByB|X<+w&w1MO7$hY>+zK*MGsjF$4 z8rfod3CLLISaZL*bBmeX)CG-p;&@HH%>19ZPG<4t&Xt^=y@ViU(I$_X^d+ubxsD3>)6M4PhqcW z_V%xxnviMPPg{}Cjg2M#t1gZQh1X*k zq%>G`G1N~Zi$hC**SctT}546=bn7e07sY9 zUA$tW<8q8g5UHtlEl}X*w7f@>Fuc7(^)?pKbI+f<==u(qO6@-E4!Xv8iB|q)A?LOpjTkEahdRiAdudQJpyYs??ZfpLSX^g@$VB7{MDwpX^&@j;LX4 zop#?{S29{jY1~@)+zKnIEW>j5aUP3qiafPV>(OgN+qXm2bzr7^?_~Syy`6chvlx2a zlYV`y+0b~~HX#mnpTR1A8D=l|L8y-QEMtd;gaWW^t#r5^H%E&wMI&jiAZ)I)03zJi zBWWsYc86%{@j2paUsWTrwkC2977Gf`pDvk=V~3d_fn%qUS(#HK8<#eo#hQ9&#NFhK z$#tqUBL4uDbUF1W5>9swN0P|MB$8tkP0t|EDiMO_wXJ*H{{S`GqJgwD4y>9TT+Q1H z;!|sCs?~Td6%3V`s$*k=Phv&&93OcO8$nM5rGl=CN9ABKjp6cNJHd|bDP_N8626y7 z9L$3VjwZ9w%e#%h`L8Fgy|{Y4B`Y58mKZ9nBeUCml;zAhCVNNP zvAk)Y>rzlhu(7ym6OilrRwp<&!7v=_3)v?Oo=j5bC~?UCF=CiZgxDdjJEkdnbLayv z>`>Q-o?O)0rL#51bru}0^(=Y8>VQ-2Et$8RJd}b%i7x0b^sITb4oDzV$)C z!IWd2Fj{%@3sO9D(LONA8K$tMOp1~_M7aLOb`3pEWiZ#bPR zs^QBaY)zXlA6+gKNajhsk_ev^4|I|>uN{ci8+kgcqV`F}Bqu9~GBJ5Mu>SyvRPLLf zI05W3bGr3mhk2mtxwx$>r=|1_^s(`a_t>+&TH?u~Hg3E{IHYs3K`Zzz+FKg<>2c<#p3uC+4nycghW6R@Si82eWydkfyBzF+#Eyw)eti1A zPvsUfYrBg+sA$ud)R0hjEfQ<2+bAD1+@EzEnw;~@l(YH$N*wF^68ooZ2?gVsSo3i7 z-YPCRxhZqFK2w1*Cjp<{r(b$Ac%%ki0FW|xcoraS?Di*{wZNo{b7hrPJ0yW_K~l$? zPBi_>i(#dZ9mms}S)9YA?hsveWNqveB(i4E4N^Mf%7*|72R=V~utPU-#Cs4q2L&$d z>YL5;A2bFyi7YNR?W?gK3mjvIE=-E_Jre}(0mXg<+zGmZ<_2qTo}Kcb9~Z8qhVh)= z%4&}CN0w%H5CzAs5^cYePkHl_&Vb0@!px~-8Cu>2MczscP2#tjLE2qN?W(?BHK18K ze}bU?Jn9MOmGhwo=w+U{ z%+$w5-Bv%d7`01-Xs`*G?nX-4Vu^tow0a1^-Z)ytP;8E1a~WcJXL&2kOzok0aGw>! zu;%^Ev=Esrxs_D3^N&kah)pB=Vp@rJYI&;sD_QF5am*@>uK30y3j;cdH;a=t+Rz5t zj*hmVdhd^Q8sNi0OHA)Y6m9$wWwIM>OPhZirEImT>xsHC{C2umig;*f;~j_8dR4s~ z(gtU%uMjKe3?rR)|rW|r_* zGuay~K?BS!XVx{tByqj(wyRB9?%Z@`q>EhnsV`$s2w@(@tW9i^+{Ya=Ir>DOK<6CQ z5(&CpffdvVDq(Z3(jV1jq>y}IX0v$JMI1rgzO^>cf^VW$?QMqI+2|?eERbbz<6_<} zaRhJsytAFha<`lEZ5~ULC0@@vL&*Fho8q`{{eXYe(W zO+xZ3*1`1Z`M#&>*dYj7un0mB0uY1%gdqSPt7<4^__q8;az1d&+eNCf#7kRi47sjN zl2vQ8@b=pp;RFTaPfvBTi^Ly8Qv**+Ee(%8idg(7=)3Z@vQ#>q;M*{a{VT-HZF-%b zZPLd5C1LZBLz>gjgqrK>5Wwa*vHiG+W6*{gaYQ7Tn@bX%w4YIjzm*xfKi$LlxH@N3-b}BK*1FjS=cUTij%P(AZ_km8?f(Ea ztk<=Xh7#TTPomJKVT!Hv)){-6Emz|a$QbjTw(7A}R|$SDL$W#t>8B-C$8W`l zk5^_{WrW0GX84IN0#)MFuZB0A?tF0r{b^c)vPWHyb3d#Kr+Z!_7O>7#&Nb}o%}*hX z)eMY{Zm>|Cwatu2+Z(k3<0*ETFRN^@NasZ)a-Mmk{OH5nEc#6ozA-^fDIC~XwnMIN zEV=(f9x-O3$?4PjqJ+y;K6Ta%B-)^*3UM?W zenbyQuo`?f8Oujf=;n#f0fFZ3W~=9Kghuw&(K@1;j3JDcDSSfh>9f~Arq4I4_-(My zrS)gL#7J{P3Nx|J;Pi{E!y41^j3X3?54{LvT?lrQ0F-tk=~>?6em(nZE_ZA&&%jk0lz0OZPoai4t5?<`=R7xW)STzCOA}`;d_xhV!eJ9)HE~2s zGshcWynKk&O@m>ry&}-Yam+gczsBS*sAD)GY?je^s=chm@v|*1%+fxIoc=I1kTdzk zf`bTw(n&nS?3C|3i{yPfAN^;_s@k>gX^$PUTUxQq{A+8+#%roZ9fEeo_4jB!cX9pK zRn(yr)Ua-FXk(_QdAq7yc;@h1E~a#o3F{^^%6JY~_iS(VYcx?hrG?FV<7K;fFJ;M- zskOZ|dssdnj~#qW?MgaWndo3+bR13^XuA~DZezoXL#1moz0L%dBCe+o!DtM%vbLHA z9suBEnZbGaW5l+$H}Ja)z@+R(Kr_x$$J71RW!C&lZ$>XoTQlQtsIM4q&#=|j8*i#f z-9r!ci#`v6!-dtpvZi?}u}A48T)bt!&Dn2LQ`1qvX{g|i8gfYti<7;}KBq4cvg&x2 zw!x>F>(r|awu%F@IXkw=g&{K1G(hd}T|gx+PogZ;1MghjaPikT-HaZ4R~H{lj2mcJ&{iArM!9K9B84Qj;e~9vGkPR z9Fi>_#|Y2*H4_!GqO%VC_SdH{!D&&n~i)bdoi|Fw8R6BVbbGS<&mO-MNc?Dt9pb zk)*<8@?MA2}cJM#f za0;zjz=s0qkALAD&m{J-pwQ zXR7RnYUHz8Pc%PQd(yvir-B)qTb0foyD4#VN_XK>PKr$XPRyH2ds&imobIWc<^8-A zgK0^^;TeKQF#Hu;C0ES$wCc`3%D!P;VD_`6#-8Q$qBuiyd?r)2o}z`4zB4l^$&u{@68`{t z`NZU3g^Sy5_6@^XY!Aad-_+)D;rfyLlhFVo6uVm{)FpqQ|7aJ`IinB16ONww5x19d@@@06kT;Pg7k?e|uszl-`csjzyKG z&Fj$qSE(B>w6A&iy&VNpS@$+oa!#`Z+j^$%+p;shHnSy~<<5s|wvGnI8;eHp-sJRA z5W7_W013NE6I$m|VDoj%`fvW~%hg|XPeGgTdC7hc_U5eTe$CY}zsgKMO3z2|TeOnO z#?;eCO5>x0rrnkAnY9~6c4O?|`w-A1-R^$JAIrU7HxSz$r>zCG7{P`iZ0w__+$ZB? zx3fC@J0#DkRhvD7Y~vd)BJJy(ZonQuA$eN5r`6OtS8%kB7RS!%jIEr@#l3fKV<3Es z3F0<9?bT^nvugBp#`KsSK4wO5pEJ&@=#7(ePZOHBR3@@mU)so9Uj$d-uVHxk$?JF^RZ`)VXThisv zUs;~gLfL$lBQ#>!-aeGsD_+>%*Di-Y21({pb;EKvTil=>Mq~m!5xFRvzuHzivGzY& z44FEpCq@KSByJnaCW{mNGud6*EI_itMn<`V-l!9g4tp$bHX16smN^I=QV5yZm`^GY00mjEna4}C3;WhK<#Wf% zSs+Nc5N!h}|u{kj)YNB%<+M0KmrMP|u)sx~#4rv7*xQ@fiviuTU`02QH&;u~F!Z8?&rFN$GNjIDsT zCD^`!v&NN`am40EA8Te2*>SdlsuyEbGKQBMjKwQWtqpKPR+|QvW^uWViX)$o+O?Z~ z(_L*yx~Jl@%+@f;cC&*a=(V+wTFaiiSJ~5hOJdpIp2!bt8XOsGYwuV|2Ib%?Y=9fw zC$lF57NvC^U=1OV)IQPt$ra&Pkf5p(6KLgmWW5(svYI-|DQVnDGDl|n7npQ&QqL<3 z10L7wWrj?AyKvu_;$KE_4{$N)*AhOpjqT3t%agM>nXaTXGDu9(dPdv78tpr^eCv~K zF4k-0*LI^&oAa~f0Up&aW>*ecENp8sWR5!zAiWw}YV6>=Yh{Ur_)YqxMwWZhE_q|` zbuV`{NLhO`J-R1;KQ$zjvovRaPc)Qa)&oT?c0nJKE^VsEcQE!5RH$VHc_||$o5=)> z)>FxkeXM}C@VBQ~-IdZ!{sHwR@3S0|VG$B<& z7~e+4X^Z7aML`GUA@};!2L}#n+zBci>ow1FgKx`t^-34IFW&3owWh75gueAmci?(O zt0px7ZQzEgU+VX0)H+4Q!#WGH=(zG?m2YeEQNvE&;GSLVi&mnm5Hm53#j-FSHbDwC zUbcEy=3zP8BYzF0bLYnJic;||CrH_SM$2X89Z4MRKN#Lr?>~f3D#;9cq61@PHz--pSj{6>1Qx}>RsIUYN27hC}Ip7*=FPNffiQotVjcoMVT zwpWDfzJ~hZTSGhjCuR}4N*Ya_q;6=belaTtIbXahm1#8&u=ZFifs#AFkuMQC(c6AG z9BpH1>De1^$gtUH&52e{(8($uT04hTuF7sK?sCbx%c1%d>^7qi8rU_#{{TEEXP!fn z$j0;vnEtm@s=QCNi*_$;!Bb?Y%Sq_Z|4?3 z=5DWYZQvHX)%3K|hVMal%r-+7!&*Sike_lzq`trsbXrDQm+sgp0}rnv1QSdxJwyKh z0x`NvMy<&z7}j5S%QLCuwEoI9$M>x?^ABHkva*VrC+{PG2mSIvWtT?%VC6(UJ8|_z<+rRox5B~t=IQ0E$n4}){BH?t7Arlqnpws(wKQ{vT(1ZeFwTCH`teM_mdaplHjzhYi8xg2H7==waHVXNc1?0z3n zYOVdFbi;C+bV;c?*0SEtHp^<{5;UG`qZMGcrDEcZL3fhM`plOMe;09ZX2a@q~!oJ;CUa;#B-QIife^$XYY? zR>|jKYaHue!ELpzVRUoT>|gN zisIR%^8`1o?zR~@c1LNL{VP8XziWRM&!cSA#-a!3d|x5FK9P6FWZ8?z?3GUPNSk)q z?3O&1UbwqE3(r1kCamtr*B14%oXv31>Fq(#lwH|!U1X9u!{3o(7U^Y?!u_v$hdTV! zgmM?mK7g44yd6=mZ(nL|ad!eX1YLJL_^P?TMLCJ^RNSh8SX<2lD@c8kCyOgo_jE#3 za}C%k9h)LaNx@qKxn>5&bnNe*00#4@jpk-(+lTRPcu^tcsK8+3_ z_C|_c@*5$0@&Ii2snsthiPh1?wH2~s^cD3Dia6gx6*OW? z5oA!oPrHSTT@CeC+T(9&sodeTZM~y6%W%D{ZH_8P>8WCDRH43(CL4gYuco2rh7GiG zQ!<*X5vIVXV>`D)PcIPuv20On#tVncWfbz&OZV!Ri3;kBow)2Y<}_CHwo=^r14}cU zhn#J3Dl-soa^vC<-q`l313_T3wQFwSTQ#dFnLINx9o!N~+?kmj){Ys5)Zlnu#H3_Z zQAqIlghtQNb#wZ!RvT_Xp5=|OYfnqR2gGtxeO{-M_`t%YbN6hh!Y3IfhGy>sD`Kx_ zFv_^wSw!bjJ;y!B-bPoWm66nvWnp=CqU5hPE)Q9N&gz^NqEkxk9Z$+ed)86CU6Iyw z*=?>$v?qe1f;^bM7fp*&GtvBRngPFISYz4xOm-K^fMVvY+>I@0$o6^YyO@5_{9w4p zQ0JC#Irro}s}3WFVHm^RBVvk@W7w9SES3v;byHh^ae2NO6Y9k;GeHhFhT;#Urw_w% z2EO8*&jGU^Fc)?$v8|wxQseX@M}SW9GkJc6j<&B56oQW*f(%ZUCVD!Uj}!}c1H`GZ z%q~g{RsmZSGG>X>N5{M7x_oV`v&pwllD5{*M~Br@Vz7td)k3MD`be7N8{_uIvR%Lf z_1Sp({f%oR-(fXU($uhKV40wi{c1kiF-$U|LylqcRL1Td>linReKze(;K^67h}$-u z5HhYc7SmwW&ub#Bju$(*QsElviDP>tB1TBow?71lGt$hO`pS=H-?t^srNl*4j3OpA zvJ0>+(Dsgu`Vp#iWj$57%)WEUXwP3s1bLr1bNyIj-YrRSs@I3Ig9n-6_sK0u-A0$C zrEyx$z+`~gu@dh97M>-HVYo{Gt*!<`{{U8m86;eaiXEe@l1A3zH1tt}*`ytP>kJzy zgwxDjGbXE>m#2R5Wp1M#U3BPj+wf`B?ZzXB%kfMWnmT5`hkD0}HTEf_**RpWHTav0 zv-h0aU*5eru8NWu$4?X#(H3%JO{}p+4P9iX;_y!+U8eMllCZZ|Z~p)tUXCAyR<+wS zuo@~#YCN{h6FMJ99BSI>s)>q}2}?W0+qNpII35W1I~T=cbia6w`Skat7C(>TVa?h6 zAk$NWc2?Ir>fNmChWRbEm6NT((|U1LzA)&h;$=;BTuo~@-z@IkkEL>7w6fxEeJ;$? z)Ys+L&Bbu#hAhT+Uq&)d)oON=QtaZP02;T1HnN#Lea`P+1~WJ z=IWDO!`u4R0u@;*9nvXjDnsM$(uO9Amx9LD*CobDWn-o;2xy|eVD zm5*Tk3G?=&?Isyz-Na>gAZ}Nlsu^is-dX|mF18^kbJ)^23gu4cif0>}tS7zOhQ5|O zJ)*95u-J_2(=nhy8$DIRz)1Tf_JVWn_l#Zl3lGS;BCK-R!`cySKtDeQ;x*RUD!Qs% zPBu|bxO|P0nZP#r*f|x;$60E|gQGGS)@&k2K_Hc`%Ja;4r;ggnw%WSBw@Cb6T3U%^ z#HuARwE7_kX}an+2bJ+P=Ax!I6Pe8cpP_j?18F3U!LM-Lv>e;b8t-EE5o46^j6U!H zdYLl*Riwm8PC1D3h9_Wd%r8=9xpB0yw2gnDv}txwMMn&Im~sH%TE=l7p>-dR(l$3q zy#z2^h8CSZlu_d}zYwM_E(F2})5%V?nJq2HvrXGJ(9+jg;PYr}T0Wq)&dn24>ouK# zGUqnR?qlj*VT!{mxLyN6(#nNpII5BR%!ILl&38t$IoZF~L_~AsG`IM2W!ZPU+(S(x zoz2n!ZS^cCWH-z^$k`DZfXuGf-WRBCTo%$^ULdUPa~*Qh({5xHeiTbNjeiHjcJpT6 zhv5}XjFBCf!JU`rwA@-`anGY~`B%I6NUx@w0mSJT9Ov%xhX&rywu{2cmD0bs3y}eWG7B~CcQ!=-0Pfe!tIzL;voCplLUJ1fy8X%P<<-s2 zJO2O=^D60Wvs%|%Ft?do4dhn4R>L_Jwcf8z*v-Vxn6k0pH<(yk&x-b0n&;C`*Fi92zS2zxHUsof4BKZVEh=9J)@L?-ivrxv;+e?(pes;c3pYjaBZnj>eP@k;G%g*&I)95xo6Vv~QH`M*l8-sRL!6y@}+T(s6= zMkaa)+R9dZz+6|#_KD7Xukp^lhgBeDJzL#wDddybzH_t(F?c-!So_~Sk~oJi2#NC5 z$mq^|k*?sPs5fYB?a^S_U>a-PCI01+cbeF&1N92BbsD+<0H>{-$56`^+mkr{OfD5@ zm6(NYeh0+O+V!stE@q3$Vnmv}UCbOl7Ec~+m5&a#aLvbS!DozXWrINFo<7RxnRH?E zvp5&i#bz8%FLC;oHuEbm=CHM%#wwU;%W?Tt$bWmvbA8DEM539@b=dyba21v|+~&{T z=Avxrd(28$V)#6Q48WOcV;@@ZFFZ|eCF(J%()=oljAYFaGCltQKI_ZBEya?EWsaOf zUBS-h;IZY*a*l2VWp<;3>PdmdSp7`pXva5e*zDy!>yB2~vNLh~n)fv^z0=|{_xDCm zV)C0J#+fk^S^oexrOv%`nk1Vrw-igs>+kDv=*icK3fj1p{OB0BD zxoDpR$xjpJAcmH+*t!(74K8sdl9n>oSZT2FG$Kiu34h8jONLU!+G7q(jB`UQh^IAW z&ojft;t+0XOJ2;UsAA_r=P`w{O!;{DUiIkls&P!_f#H)vy!4C>Ia|TeR99&^^s46F z6S(kMsp(xVNgXR8zj08YW}|)2$x2%OPk?x_V08c!QdF~ai>_U=CQdtWaWZ+{S zn)PFbOwv2>*4chQ*A}>Wk!8hX(h%Zbm!*kZs;!}%IndHohMvKmBNEc8t{)T9_RzYZ zx6r{cA2p}*EU$d9Hqx=tTh`CoB4~c7h6xbtB^3ffc^rydpljY zmGrJGFw5B^?~8{uIGvu1PVvjozcZQxdaYAy4y&TjZbN$jtxCo=H*l-zvi-JmW~&Fg z>Q3d#ELv=*GVRsM&6{3oKz42qsZHILD}yDi=@gBIW)9QDZbOax7S5s1(>3kyP0n-9 zYuyIC!?r!QPyq5vc+82p&b^6Lk`Mi?rF>)s?5?%48!k6{yMAhOWoBTwbsJ~1a2?siXPLvE>YPa! z`qqo~*^@E<029J1D!gAagmI(8C#rL@mV#~VRU0IzeW8X|p9YJs811dv6C)iCA4yKY zZhY4|rhTHsV{pVVY4;=VR$|jy{liz%CZ(#0x2T2C-?zWb7v@}QtbYcjZKlQOT_>vy zo5kT9fkSfXGd;(?=){*>FyU0uIPT)gJ#nI+?bTisyRO@;DWS}#rmd?sy@X;o(;G)D zvIa7ikT3!tX?L{`&!or=67Y<8U{#P37zi09`YrrHqcCC zX6l+Yn{tv+x$I+X9eopPONV7gjyyWIpNP~*IIA9Wa$_RhEn$%7zG-vz^Sw)$?Q*b$ zHaR5VM~F48Sp@BkzKWVLe*~nis&=OA_LYo6PPxL7PHmw^+Yd=LT8CQCSeV?vIpAB^ zwj9uJX6x-)40b0cE=bf`%|^oayNqgitA+<=yMTFHEsHN{P#JqVDYP^3EX3FwZpzNc zqjAjVXjC*iO%_HxfaZ&%QLN~J{G4bqVh*2%DB_48lz+-C;O35ZZ?vg> z+&D$bHd9<-!ebe#neXY4g|h^4)5YjxV@H5CQW?9yMU;yk!TMD0gn~o4o=O8Ui+h%4 zi?K|=7TV)f1ctP9u~O`>c2du!Sa3Rn=9XS7C~HC|RU+9v-R=oddIa4mltak$4+Szy+wwOzO~Yv^(|-~N-K{{ZFj{{X)-^9$1L zq>YyoqH}qCMnCT*UTJq=`gM8zPu8$P5VdoJAqW8oLI6S#fDa}i=y)9lJ*-b8O3mnO9^A6WR&uJb&i$Ccd3dm&ZgeVt!-}9U=lf%_=P+4 zu+GPCIWI|4Tk*ILan1h#F?p;#kuz$mBZ{I5h)X+gb}YRObBly;Zm-D2;`O!u^Xz^T zKlIS^8&w|ezM0uR=Prwc`(IlX>bAX^84RSnG)r>zeAsM&^kvu`T=p<(&(#2kh49Q;17k?)O0qx zy(WvW%4onWVI+H2Mnjd^EW%EUmeyOH9v_nK&(_N;;F87d-TweKwq&V>D6_s;!1F5r zs&tZ{i^B5XUFAi+O{*gY*+67DWhap4wkD?qyV|OqJP2B|)xL7dXhRzm zow4^sR;lq?GTKS47J&A`&qY@x7IaP{cdfxm!YW7}*ntPwu&@$uBP43wn`UP*(mHb+ z4VWX7c5bz)Tm>7Oz`!}%lAN!eOE$%f`jIeba|mY>I+W|_4eTng;Z=gJHiwu-@$9$C zFLh0{ZZJbD@LWPzWjVyOyO}TjQu*8x2#$Fh%0=xkENYgY3#O#4sNCfF2j0=Ep4HZ_ z$l9C;R0c~?RY1e{Oh%SS^j!*i{5q?1xy3N~bNaP6T$kc_T&`rUsbr^^v<5|`TNcjB z`3&?_&bOp55Z!WYJU6R!6FHg8B)8XVjEh`q-`l}?D5)^YSp(@Nu84!qI=NGBAzw>o zQ{&T0_I4w#riN7bsPLYw8@K!v7n^ckYCWdJm~zV=16X=mJ<{4{(h%Zh!6tpa=}B6a zgGX)7(CPH64i{Wuw75$i-;Mlsg5Sa^_n+LYhGUo{nR0Co9NTqt+qGUAb##0|QJaI0 zMRqNSmRNz$Av!4`@X5QD;NIHkmaNQWak~aZgba@5#(?O}wFlmr4QR|X9?nW^H7n`l zjLKYX#8bPKRB~Dab>?=n6ra%GSaYLwO!H)rHcMT1F&sc)m~`{G*HA7f=6%h z`P+GFA0z4WY3Tm=s-?5JhGDSbI9zlv%4887@;>@K{wr{CH^RwEc$=FnqIyb!AiY&LFc&Q0TSo&VZ9Mci!yC^xqmt{;rROdK{ z-S_aiUK^tyRg)iWo@P3It8m@Jf>J`)a+&g4KgyTd)kAl$tDFj_$(+9rlI&n!mBG34 z*kx6ju5V}j6wPfNt-fKF*4ocK79)@0t#8LDonH{we8zFzZqsc>7grnD>a$2&+KQ{H z>JnTD1cTxf)WuC$9@?rpN%Ly(V7t~tu}M`!SioK|>X`b67|26KC~Ko^ zF*U9|h)1Jb**04XE_~FltfiaAo=-+ryqh(OhlbJPf=G^;YTB~5Pd}N_kFV)1?7d}B zTu;|8Itc-iU?I4NUx1Ai{rFbMWc0Ul$$SN9}ow6cn zx!vGc^xgMKV*9yQn|($l9%j_xSM`07^39B81$}85mA(3pT;nIebW24}=q{Qhvg8U5 z;p~)tSTmK289|Eb*zup2a3l-2foQ?jni4tc(m<+^w|tzzB=>U{B73ZyA%ehd3s<&e zv=4c5Z;$ZqdF3PWBeP<$pxbFVz7h*gLO*Q=cpQYES(B0`f|~!)sH?s<7m&Nc*K;Bo zE3AG)KtdQXA!o&8)}=+xraVHS>$M|jj~ETL*dIvmGz&{7s`t28jy*5os4R$c6Xh-t z`^MwMRTrIG#4iOD&0d7Xdd$KdJB7s+m;Ig+&dWjuf8Hz)*FoCni-1!t(Qem|4SG?AIr-#Z`Mm ztnYpDhNjG)Ng3SDnUFPVX>YF8_}hir(9?i5zt+h))VjK$Mj9C8@M>tZ3xi|hY(f`L z+{)O4R8?3|rqp4!Gfi*D-88#Q1l_7s^}K$RBx)fE)~}rzp(zio8M5Fn#?`koiyQgtX)I%*-&m3 z{QAB23k1)xyaNOZ`?|x4w*!!Bx0VXUyvXBoJ*{iV;2O|FsG~yhP^qRT@6p zyUV&tC1or3E#cQa{kpSqrJe;+zthY|||C6}@4Btw~yo&uhYtm?QoaRdAaCRGffJM}?5 zs2#z$g@N4QWMWfD`)Em=L;e*Qd~w3j(|gQXbWbWAsnj{erYo(yj{ISIzqg6o=y%Op za8Fn#t*AV$eJuY*bPD&D&{0npYOBxrdBgd7(K{S9JkB18W4x9s3Aa&e5aV2YGk8_s zv#VWpa5tecI~$&&5gXLZu}9lkXj!ZkV|q)Zq_R zMMta2Rev`PpK1vyu`vqNv2hS^k7UlsZPcf{wYk)|;tkz)AFsQe=QDWUZRVm+t*7`1 zHk6yte!9cqDO;Ah{;7o|lM@abKADMHdfIV#bKjD$fbljYczB?P^D68-H1qz0;TQ>~ zT`P67HrKnJ_wru%Np?IW%x!Tpw@Fhi0UB${QBO^+kv5JN{C|pQ?MYHD%1=23=jyw9 z)&gNyBUj=z0x58r5vm={MW<^3>ZY0kgj-t0wvI6GI3CaI z7}->pDkA(6^y2S^HdV~|@1hR&7cGiPs=xtKwuh#RPNr_?^)6O(I&%8Dj>3)$d@3*&y(em_sSc(!|Af5K=Q1(n%&%Y#CPVmYP8rXhF&pso0jK3 z0{I-Cg%YI|RLYfA6H2BoT%g)-9DIlY_`8LUR|hQEcr14~p>9nk+JlKiwtjI!Fv7Is z?cx*jfN`Z~#vz7FeQWy4r6ERAyER?(s}-TW8l#Y(&gZs<6U{aKO?_=vbl--URX-7h zcA?fL#<=z^FRt$tGJgA2>Yd$M?-E;9?5z;a_*U=LcB3C_jv*N{idc4H!+a%n_+^4n^jz~g3kqeaE&;Ch3w=<$E%8S z2h{Vz1^sY;UJ^Q+9(u0O*t23gh?YKuJjDRY*C3&#>Rgftk4;X_fi`3JqGN9snclVU z<7|(+hbS-EG*a%II(AbO7%DX7<-Q)quqGw$>n9WBhX_b-<+m5G6JiU+q8FZxiB}MK z=+WZ@t#-P8$NCh1n%SVXD5sS-3H#7$xL4*0`}u3bA{13tlyNT9;?G{VE(63qX}WH< zy!T9zTAOt?IH?cQ$T67`5+m>RBBF*@EaRJJVtU>%yV!503u zjvq6e+jYD@&Q>2`4YO5%Tu=^=Ckclv%J6A34EPog->2_xYIeP@w}?0%V9{z4Z#}$W zeiW5Xke3J4u(`sps&Sx6D=DL?TEmxeBmNc*-v%3Bp zp#F#jQJ}$+MsPdC{AVFY=l0BExJ`VSX%qGEIt#5G(UY~Y1>SVN&ET7)y;=G=9R>wi zNy1KF2KkeOf^@Z>Q@I=QZr8DOIO<_Xjo!&^MB$%iO#Q+-$7zjR=hcR&W&C-!&%e!T z{Tfb}O?moNI@tXM2USv0SO*==6^j&`yE13Pm;OZ?& z)K!?f<7RMLU`|qXzAdEb;nZO6Q~Z^fW;D)E=y5Nx)D}w2bq(|93=M^0Qfr=Y+-X7V z;Cri5^O*i&iu1|m0k5UD-|wRFGwydZ0pJe$FBM70Jbq;b8bkLe}2nyj)+v{9P~ z7QS|7NB)uB55qGt8|g~y_liS+=pN~qC+{g85>!LxbG{UtdOxoaUy{M<~+cv+MNUcaAp zWE_YgZ(0bL{KRZDDN8}@KJ2V8wUNEdi}Hf_;7`{*Az8A4c;bi!?~j~3uCjV685FWA z?S7}$O+xE{<+Z>M3v-wEzeyVcT`xAhihs81E=)<3pIg@OpVtzDR+gVe8ixRHv zdtF0eR2rtN*|B^(u10BLxkRNScZ9@kU6QGTR8)ITjo*yd-t}ovxUL^KZq!U|P(M{4 zq<;GDUwJtmjhewS_MP-GlDH>pYsV_UzyHjqY56C6ad#~oSg(qj%~KQ)MhStMg|*Jv z1e?uS8T@)py5731qQE?N%cnZrIKTS~mN66``Pj8HBZ93Cgqe2BFDvQi93lt*sLSZe zl)d$AzMz43*9rbub|H@m2m;0`fsva@q@kM!8dvPQ7Q8)|{ftn|6Q?Yv{!md5d zY{SwSL#$IMarW#>eRz08;Tc~pC0pT-QJRh17>fW!g8fWzK~9L&!YJ8n6JTx5F|#Gz z)eZ=nn?XFio7?M&n%O_)Fe+)(myDFt-p#`f_sEI~JMcY}SB55CFxeEYstM)ta_Cr$ zC++i8w!AaI#>E`mqj%}DoR(LYTG}Fe`~b3vES-vW^t5Va)7 z?_*!l_h~+1ZL4}BnWK;9wJFy@t&T(?sYLhP;Qnd&S~u-N&1mC0Pexd~n6cvTxQu2j zzBFst%jV`Q#DUGz-TZJXcbKZO^eK(}To zGCFCQLxczKH*(w;5ll8e;Mr)xx6IFLjkry~C#v-)fBLj}y;^g`m=Yf?ij-#NvaD}V zMw*m%>DJhxMU8f1C`JV~$R6|X-spWQ&2d>WTf%8B9*TvTurkRvHxwV}@Sc#CVmnn^ ze{=q1!hbCrdT(8uKn%Ev_e%On9OPU=boMLLtc5;~8-GA6mv(a*em=si$1Th2$R)$C ztt>MgB^a90F;|hqw@;C*$W~oaoLXos1a4ht|E17}T?_N4xgk96G7rG3>tr->(~&-f zL=$j2VKc<}9PlcKC3bX7CF97#33*}Cl*iLutiefv7fh_P{i`$-^b}&?upLE~9gh>~ zPkl~kup<~;b!Sg|XdJNMQa7r=eK&6Pt}la2Rtwu1=X~7hzFXIRwht6Oi1JKwoViMG zc^e<&qbBPZFRHjT1=FWyv)yRqbL(ejDv2)23sY;gy7UkCCka!1trB~7%R$`SmS>{5 z9Ex_Y&l6V>7L$y6dY$-ZK)-FZaf1GjF{C=U7-`c^=bJX+?j@3982c^Q$V)LnjO>c&9%F$RVzzxYkM2dpKyqIIyPtyE2ZcQg4x+w>dLv zRHRzOTbitA_Gq;ufpJ0Fa`1U9W}EZV+K+7zyRHMNG{9oY$V2n{Bt3^|cRX6q>rYDx zT-gOZ>c?qan04M<(%1kO|J`6{ng2!~tvZROO`lUu;MtVvOaFg}>w{m@IkgK2hYodkp0Q%7rXlDQJ1Eo9zKVZ>-HEOxCz2aD;S{1Ljw+qM1jTekPMyD94Ku!J@|{ zQ)ajkGR~jsI+%3l1;jea`ijSTdv^K;Sjb`&@$6!|KP-tFH@Og=w|uYCRE@N57GdVc zj27+YrAyMjk4Tzp`<(6i($v~|27-N%aZsQm=?)-*CkI{e6fNS4g&&Ak!ql{`kz=k>g57kXC?Y zmiaT0zNh!^sU9X5Z`RsoHys+Y#(A)}>27L~jv5I#>spp%ivZ7IBYQU)l+zcPKWbt$ z_^2{krJmm7JM-$sk5?e)MJ>kZPxgYZD8QAHz2FyNiHXZ5Q*At|(WEfKQrf}uVcz}T zn!fTOmvD8W@#c)p@PRh(msN7E7ee!CJu};9`c{od2i8?&><+~v9Ej77Vbi9!t&MI8 zbXf@h{O}Gg`T0(L0ClR!Ber_9-RA+6>LQz!XJG=bV|vvWHQU~k%>KFgLaQTOp+|hg zq6C&CGP+t}pm5Dj@}?qiYh{VN_0I$7)POyB?((R+CF0oijPhAXFIGBPE^n>P$1A4% zvmUl%TmCG_jRh8Tg77s)@}!xQqeM56cQUC+j^8Fk-G0v>;?%m-5?DF9Is2TDL$)Q; z`p5$Az0Y$L#)U=UaslQcQrSo1${T-luB<;2-#=@iv18U1@(c*kzU{BA?xU@Ah`K97 z*Y573d18o#PHlFMY1tvzT%%9wdbHQDdw#4lFmYO9Kw}-ir@hP_U@7IYZ09-8@|mb% z+U0v4v2ZZF45ByUnkw__ljE3#fQWb+L45)0$Cf=^q`TD&gDo}00F zT^;LuVLnhWX+b#XZd+bescw%@a4WXGaPZ^Sv4>By*l`!Pzeh9?Zuo|2rA)cHekjzZ zobnT7QbI)TGl6rmDmQ~_dZNrbC5f8({H~jFrbe?11bPX(-o(jrr}W$EUi#=f`KGc` zeH=O`Ak{Nf^S#!duT&pJ&}_EX3_{g|X+45a-v6Mjr>vPmxW(&OZSMV;ri0+Wi+ z)lH;D?@(+8sr1p#gxSc#S%)CdLx$WSwQ+|qb&fx@Ampa(c(rbaly!mf4NKM0B*YHG zy>0#SmDHohV_I&`kym^IiFaCOxNR(L<@|#*mE{8Jk$uKd)*W>5ZrEh9R?@`!4|nkcP(5PcP+$+53P7Zd&`Z&fH~gK-X(h9mgVX z7Ob3(n_rR=>W#V z$<6Ob`>51AcHQYyV^y6ng@-@4AS_i8ju6wJPk&MnPm z=dWipFG95Ie0iDDnCIM&HSNI$n3*}@ak)RFX>>g3+~|tUruYIlKUSd?cI#r6vzJr8 z)NR21OUM}biq-Vr1{5lt{@B6+=-N1HXtr)kqhLSI+_R>IL zDVI)m6;7A&#(Qj@DmWz zgsLkNNYS_{pS@~53thBPm=dvOt`mR7UJbxe^Tv(OgjJI1A*b88A^xztpJ(cqrmQ2B zMg8l{AuY@k7fxazD7m$36hlNpn!ervp5Q=*l6towQ%(fiuI`74Xwt0g&o0 Ypq0 zO&Pz+LzHM^ihs!U%n2P5=}E)5!oo)6`qmiAFBEh3q`{76D5Tomu zFO^B2{PeM5D~8cEb)#!sxK*Pnwtau3Ke5+6^#XUSr4}}frq*4Kwv3KhZxRRwE?S(| z;|t_Lc4xY!^~6zxUgb7ytJ;8;9us$)o?yt|eUyzjiaKhe)~}=pW*hV@S(&mCc1pev zHG_TB#NuYUS~lG?_i{e3nsuP6#$4tcZ;%5F!q!pJH&b0gb>B_X&z|RrH%>`%sQXyi z^o>rGL)wN$I$16WLIg6C1S}P_URyjp*8N;wER%*lpe5O88Zbbne?1&V-tfI6s!`B* zVf0T@2Wgq&V^Bt1lLVP_3XA0)*$eD>I<*OLtqnFuF%IkQQGU~Lz)2^h%jd0cE zfd-7Oy<^uY+<;!3?8MreP|w@MxkHsK=YZ`UH8k=YCvBqEJw5Z)3LO!Pe6S0-M=DJ^ zy3buTP)RY%HJU9kw0b4F&-{*j>bQ@)(y_O;&AQ@<#x>&hh322x#MEpeW+Q3PWJx5T z@|keCQ^zWrFWsmQGzUwBc+^(o;5LE8^X)QEIxV)U<<*ksm~eV@;;U;)32t?w*XVga zcY|Z#zbE-~QdrI+J?0w1*1s&oJvC^rg|pePb5Gdj`0lSV6+!g;$$E<9ah!7exKBjNY1nlck4=6 zpKoz7AoQn><0G-7d!Os@V%yX|&ZFcC&XU%=f9`xDcE3@SDW<&ugTZjmm36gdM74Ra zJ#tFZH+Ppt5)}dr&ohp^lV{VARZTML$FWPi>eKvx7W(N!T)D%lKs#hlwVpBCs!(6W zGK9V+75@=Sm*pL6#>k=7M?#f+D6`%LrnYt@cR||-SGouMtV+5amf@+ z%8bMy=z=pbnLO(FB3otZ`yt_#Bam)BHDNcOi0cHu^a{H@TBx7*OP08X5o<+5pirda zER_qS=v7>oj+bj?+o5`$vC@z07__$7`uBiW-hg<(W*T)`=gZ&R@YrPGxvlx80z>Rw ze(+CtNma5b>QBfoGuRmS0$t(@=~~u;_niDaML569n{Tb!zPw=ZB1R9Si~V8wQ*r!L zPePy*BiwSRG{~7>%Ql!l6X6%v{l(}|zNBv>3}K6#IJAnYsZzfit+P}aOpcBsrCG%{ z5Vf}Z4DLwLd0v)yqsaZelx4%CcxcP-)a%o{F&A)q7HD@BRZ6V4So8qOwtN8XhapeJ z+x4#RGz}I2OM>4wY7n*0zynBwcUiv3tm%0CcBA#eDf+(1;?fA=h!fcHqXj6B z=~C%*Bo%Ky*&x^O>(SB?sDau#eVN%i6S^QC^G83Kj^wXj72)4yMT|x7k@H_65mrOT z3`%TOCxZgZ_c;%sGR0h=I`(b=75?t=1)f%qMVCFfdfGEo?vF$4t>q^R`XK`S0s*#b z#lbiCv<70)D{uPUPr|r6+E$gJoy;^3psYT4z^Dp$^Hdo7lwH+$>A)C=o6rcsnNLOs zT^dd$TUVN9i?+nq9U6U`Z1dlzyDhU+$Ot$t`qRq_81@z#>CrUMiAH^iT}?u3mEP?| z3z-JF{dTi!ngM}O-K~?l38qgF22fD-wprE=Q4o5^zg(s+dJau+oO6d(rQcrE!c@C# za9{!+Iv5;v1593+9vj&j>O@!@3arrlu1gc(56`=%$yD$Zngga33 zIUuawpG>nK*kz~u;s24{@aimX7-K){0VJuhWs(YKZywyx3lzKPqS*+7fomT%_wJAh3SB%}Bx=_X^Lue!Q4Vv^4qNNu)@tGyZFID6u@GFgQYypw0Rg^$TV zYRY5Rl^&h#$XcQ7jc&|k)-GHcJeoG>xcdFTuJVkz>R2#{Qb$^1*&L|Nd;L9+h^*zU zw*py{h5gp0EN9f#uexA|j!{i#hd@eiVin7^$^6|c!e zXm{u8G|!ZQWbclOs*oynB%t0yvAP_X`4Y{4KDhw2!y+3&4L zY7tf>HBOLEWeuC=wuI!;DQfcmj=hl5mgk*p3p!K!$Y;QN?;lb!Yavl+6Kl*lzrO?S z48;9smvy`F6nu8QWH%hwO0YZ@x^L{}PqZhZB8x7lqj?1A(s@G=C=^R`KCgKY=Yd@8xe?k<0w-nv^sX=1_d1p>F z%_s_TVG+_%d33oNj&Rf`y_f9cb=(?=GBEpb^6EySZ=Y$e;q^?@}++K&}!$&)8s#{{>4-+LU#Cw3X_;hQMb@amHTEcrX7~C=f$i&CA>r&dEDM8^q}x6^eVDT%hHj-m~`9+Y15wn-&|w>G45YNV!#St%>el zu7f9iyLoPSkm~1U7>Dcw=;FEeYwr$A zEBm>r)#1F(SNTq~@qGRU^(86z@zeZam`)4Bay}!!iCW@UL~=D3epPd^Z*6TEv7p~w z;CZ7esyq#_$;|RLTi z8J?KbIZ$z8M5ae&Nc!c4H($q^Pu~+&AO<0hn|H#Bc1ZoBsh{4&Q@}TZcwI+hQf;ET5*cwu=6P!@WD@#vbOQ@VAY zo8i(l{RD%|uun9!h*EoU&3*>kqIvGRGzWIj=UFH6Y;P3?6BLtKTTT9rRUsN`{Azu+5SVV5R0Mo+a zy|hF)Ci*_x%L%HOe=iHD=bgZd-s646Bo$R6j7G^vzgbFz{325bqsG>EgyQp}SCrwy zem!tw`f6>>*}#-2FSM(#3pFIi+=50<3S;%BTa9!+Ou-gaV=rn;R65Y6eO zr`dovr-;MhPR<_XQTS9<^)`ier6F7aZ)%)^40~5%UNP1{K6)kGa&BuVynU-qtL;;r z0itj+=bF4ED^81MPC(goI~n^2kizam;d)*2j}GzSaB0(r6AH6i@uxOe>s5lFU*G4>-ijAcE}=<{xWwv z)!Ra>>p|F(&!`8v#87dJ_p0OK!=4k$wAQc| zCBg>&fjR5qSyu}p=%XQwq5WpI>!(HN@&#Y-z{q-=@q5fQ{Nn~f8*!0?g*p2k-+DQt zYTnw;TZkn22oRVSBeiwS2726flIUY_g;h9+GcPQXjs&Rm^_W6ket6>jUy9|j=~a7c zWIupJA3%!HJ&LVK0_SbJWq2uWn zkY#w3Q zT-N<*-)7D0M=8*wkD{}s2v26|xNFZQwZr({IjlPj`g-QFeWEGJHo8xMQqLEyY`yD4 zu1rEV)kOaxrNye&AB{C1E@*t;ocs+^tr84Owacp0ZB-K_FSwyn) z@-`s9PVr*uZO62UWs98+4HN)eGlIMj`%BSE4tr|7$ewCP01^gaGB+@O$^HyVdfQg2;DU4(_W4%eMGLOzg}<27~UXi?e@iH zIsr<*Gur$NiFUkiHwZHKpd^)geD-xkk;1ZW{^tG39jT~x!?81N89&X$_P~@z`o}sn zEsVOd!)HVT#ALl+aaKylTOPB=&x^KWsg$gLgzA>#AgI_e_G(ockMjY_#G8wx)!pgF zj}TosEbY|l1={1hgqxP;1t+FzDU4WeuznCdcd@$>lY$~*pt>dLw?Y9^x z#fn*u|B+7Cu6^LZD7oCyN0>6N;@`essV-x1_O|3kqs0yxk<(P;9|XO7yIiJYe~&hT z!chevnUuHFNQ5Y+?Ty!E6=qPtJH}1u(s~|l&gJk`_u|wuRok|~qgWq}D}o|G&He@7 zfxgYgqL1LT{;mPv=6jyG?M*`7ZXVau*jo5KapM(m-e{RW_JVO*^GH~;Ri!3HzQ(je+WV`GwO+F$qLyeoIlngUlW%z#2avS2K=8@?1PiI3&QS< zMX%$yx~zI$jM-_Oxi2V1jjIfHx9!HW&k}d1$LQPEVnwBCD72lvw@2^!(2~c3!P&tv zSrKjrq=iS)4d%^0uggvxH?EMGrAjTq_u%lsQS$a+m?I!zLh6TN$5#ISsHy$#Gm#yQ zS#@=J!(01Xp7B0GI;;&H5}THI0=^u~>+kIT0zqpgjqgt^uqmII6JZpQ%c;NCRK#Ot zu1=WbOgZ~_-}bVP&OD`n~brS>l zrMk~8J3?E*MbWIk=&1#Drw_15j1Cbn;MC-_OtCfpQ2-K6uAwndAt&F?EAVDLvS*U4 zYg?}xj?HRqXUan5G|XjSmwQdZ6$$@gtZCwS%7FPJ9hqU%xYCH{Dv_F*&0bq)-=lN4 zVF~RY>GH;!tov39wxJ!L&)p|T1G5qqq;xgJ5!X9(wwwYG5?pUk%~gq$9#98Jthb1P z6YR$K051YcCpL?BUL|?VXPLC1ja@nuVrk^xeX}f-3{Pzo)l&+nA+gF|i%bfX5GK7n zI@Hobeo}#&r%&bF#jTOpTz1L-?V@Tr|31swE~3f^#Gli3)_U`!hOEL}M|WDD+eIv~ ze}lCcxe1>ZJw>qoH8n&m)HL4z%ta1~mZ)&;X4}9{r>tw9kvIMdcqWSdq1L#A?T>B; zC7Hxv8g5yp@21Q0CMqj{m8@`nnR(S809q4x7GlZKF>&{FQ&b>+9edn(!zQ_{2EJg$ zVaZPu+gj6rBl-c3?3rloo&?jpr=N0 z&z|xMPmdX0zwM@u=bKA1Ig=p0j3{)GT*<=)Y&v5ARt8Rj%qF>gkDaCuyhjuC4Psnf zb@b+D@s*xoUy|L$k3t#Q>qXhE(Yo5&l^^?!-mLcc z>h1fRI-OR)HILy?F<8Stx5p?d&xNUy zHx7eOz)$aJfxha#AXh~48E}kai3RwPS)RnCrZCB9T!e7dF4I1>eEvY;!rh|X zGW;aDeCbZba(GE^81lztrKUc2ohpZN5Li4&y1&5hs|MkW97DJF0aVlAd+=AQ79Vbr zYZNM!P;i|}AE(n1F`0uGYdLb`qV+G;j1X3nh1X<7ML`^Lz5y$j0VE9fAI1`nRF=wq zNUM^2`KaS5+1m$|ZL0@yHNvs#q~IE(_2kY41ugL*1Yc;Fq2;`R5KaoRFB7<+j* zWvE1ED4Wyw>EAfN6yE04gnX$vZU>ZNkXGukhV~JFO>(IIaonQK>tC0eSzz2f$gWzaPVuqI7wV9NOqP~J0H051{VFe6KlI+rP`9`)%fk86^bUGNM|7$4j|G4? z2pUtJ{uh-ptjr3wxEQS@oEnHDy7vIa7hv573jB7`T#k5mm)Pc z+pY=&x;MJ2rPE?(-^o2ZnyLXnNC&_gaT*oeKjOgEAQaofgKq><*fqCz^^N_VTZWFoBzSdt_1?JJ^fH~VT_qJ^Pk{z(B zsNIEW>;Pa%MwlPkXNT|DucJo zetrN|F5jNtGf^JjgzAuC`+>ulTT!m>LvA$=Sq%Vt9k8)QFLu(uBmpPuCSWyzuJy43 zj*=F?RmDNAY$AtU7TYw&L>)rzpa;wh|Ezq`6&bLo+W*Xe6|KW<=(Jo=*iZHqyj9>< z#TV@a?essU2bct@?GS(001)}2z?Z`$Z*aB<4J9O4Gt$58e~du<$IizFjB0vb2XvIJ z$V6a&1n(Tsbh?AAC&OHsp(Q>zSCqgR8W<1Q^LV09_!4>V%>QNS6y4e9DcUv=-II{( z`nA}ycFS=1J{VvM=&T*UsFH`Gz{|ux9Kv{PEhOc=V%fWMpm3|by<;FQiZT;ge*hej z0VC&AM2`d2Y1}`Q`!0h0eoe%2dvmRIDw-r&0;j--9N+=edf(YM2M?eDTA*j8yRhk{ zZOhMnXYIh^?gbq4dW%_ccUrar7Yvu;9R^-y*N^f$8FhpjRq%AD&_E0P8=77gOu)H9 zgI~121`5bhmckoJOta$+RzMx?ZZq7dkNicF(Eohg6#K8Y57AV&{4KW!I?S5^=~F-L z?+VYe+02!=B6gBFmgY1uS1=djS`ZmL#LI zcR8ysezh%t_tqYMeq>!$RCs(Vy%;2X9&=Qj(|ft?BBu383p4kFt(2+xc8h`U7iS0? zkbN^eF7~&`Q%msMF4~b?cF@>7_h{S?j$}eXC7jC{VGiwLF z@;EdY=-hfIR}XK4FF}|jr{`qOeb*ew9kvr(kb2hxL=&O}wJ7B?FlkR+JH2vbdsAqC z?}nD+ily>i|JH*nXhP((e*YG5kq`s;|3R`v|PQC5)i7G>q7+jCHYPJMk)_#G$TwM;SI;T0XdyJ&(XeF@t zqn|fukCY5P_07A0LO0Jw{%hMHU#_Dm)(k|+ia}?c+gdT;F{;zn8f<^mrFDyYMlSlp zJG}s5uzcfvwjT>U9uzyt^R1vV1#m!sF%?YkBJ>Xw;!bqJLUCOr`axvsm~~B8@I>AB zn|BY+1{K3DRO1S1AaqA(aL@VT-g3EEa+dJ{w3-mOu7EJUrJ7qpy_XI2WgPh(0dK;% zj>o=NOV6NU@3=wlyG@@&Jb>ayMEU>*$Ltg(b=$+elxe*-r~ZGKt0XYh_y3+L$-im( zZ|?o~KK*}_NF1&IeT_7b|CWOPmiPbGZ2#8b|3)kS=isvcIjP#FU4&m#TL5$1pWQ1QQEo}HrqgM*C0|Lsg;5_pOeeIZ(O_W)w0sk(+) zCv4z{CrPizi=0GD-N=fe^!cREtg(l(+SFMTihNgfw?U&Mf0JKO@U`&+anit@HQ`X8 z|5-!vap?I<(zhMfM?d9rwg2uRPS`+D4&)e>mKH&t)}JQKIX-|ko--! z8R!oddO_;-Uq5?ic}TJw@sq}WMAhe!t)~0yj$e=R{*LSi>kw8tN3Azn3B`GW_CM(A zpAnzg{%y@Xfb&Gt{T0{M-=T2-Xwr4h4N$ZKz|g)e}*Fa`y&{R z9lr=EpJECB9qP%yyZTGLf3Ma5ZLurVb!Y+w&W?()q&h|k@oK^M3_*H$vNaWz(Ql( z)hB!{Lg7wSWJ8CSP2@u!gNLu294K7gM9^#xAfbx`ZEtt83Q99`ik$geDMIQaCF?C; zzO$S=7*}*Dj#Dw_e|qYOA(Mv{h&8{@QVM2F3K3`s);j5b%S@*mfZkM-Q}cPCeH+Dt zFKKD$;@n}y-B~WvT@Jvq|He*+Guz7uR>M)3kH9 z7F%))wXXOZbt-65Xj)mwEc0mb231DXC_c@})QqZk?(3a{P3Gw@<1SdTP1c-Jw8xE6 z=B7Bg7i3|6A{UNXvkUa(s%uKhajHZO%49U1UhQDh#bx?q|MxysnvpJ(GT5KiFkwc! zW4@uju^B;Yb?Ps#lMRGa@22X1jo4vm512cpLbx;6gQtk>iRv+2md^l7=cDD=qW%NH zMaqfQBg+b6dAqA~%jhZFtk?53h^LE^S2YNX4x@zZYv3UEFWiQz7FC!^DvElX3pKREW0z zwObNAY9q`?cFa2Lkhq2VW8W@qUU+!gr`cVzlp0BS<(?C%D}klp%;}o6&*aU9zK}J%tRE-kYQD`ZD#b6&@zrP$s%oINz&6`|dHJZZ zayj7sm6y)HTB%^KG4FzX20GTf?DSB{4CG}MDa5%cfRy6OOYbf_8mnI0GdG$p+4rOP z!9$eJC>&_%o?b@YvfAA|ndE zlvz@|hXm2&(>?lgz*;(TrnsXpa*>R*yDkfstf(u>gjHIn;76g<{HhnIF`a|U|pTj^s7Zn&0P+=v$VDRX*Zl(&J&$um>$h(Mh7oh98pAT)_t z%L5`kxD_vg&fkXnCq?>PVc;Sch*rtIM?-47;>aJ=)g^w%%tITxXLs^^>bvO{DW-z@ zWQUBgN$N>Rz!IMgF@I`)qa{o5V96=+~R=t`+#M<8LsI{C;uL^l1IQ@-dXi9MudJsfqB*EHc3!$V%PwcSf-mxC-(s0F6S(l^q!=s9A+C#j zHe!Uoaq!et5(UBlHX=75kMgr?+h4|&+yB5uP}?|h_G=pNH+1vd21&f?+Dj?Kl7C90+!QFaXLb22twI@b{*8j5tSpNE%W|N3L;@QfFZ z6{Xl9pf@k=l`ynkmmZtV$v-)33)~s|z4-R($$!>H`S;6<{|^hIUB<9p0*czhKx=%* z-8>I1UHn8QrOnoGUTf{P)2^-U-gK1#8& zdDW5GL!}ls66t@gzSJpJRq4cqp%SF z_ehck`xqM`f2PFa-@5JMDWi!EHS0m{d9vS(CR`lV#($6ZXfTP<72v}5{Tv68So9E$IZ?ax1YBlPW&(@g@&1#oo(0e5$jG+q6r{SnhME9P;yrxar^dY?BBzu+$HriWJvy^@9@ZA- z;iI3F_~FJW_cGejvTLkP8Hpu00~WkY*QmkRC_2^WBP_k617Y5uO|O#|Zp^ctJ(9uU zreOk0zrM*+JAvOj41#5=Tyt{0y0QwBa97&K?aq=^y_KQsq-AHu51=-`_22tvY)YYO z-ezZZ1<9BmUj}=#miRMvw`VaTq{naX{gRSP1I!ec>tjNJ zaY`02tQlGWpkfW;i|X|(mWkGHdd@HYL23<~ih0zgSt@4NNqKD|l-5wjlta_Ql-nNU z)tHN&>Si0F_G#aZcPB0s<3lRj`JO0_uq*+oeTNdD(W28W=D~qa&V?VwI?;-v8Tg!| zcQ4nTRsL%~V^Z?d+{yQHG*%BoE!L4KZUMT^s;IQ;ryNchR!!3M$GCbnwVpj}0z1VHKFl#F0L-ayky12unGvTzkPn;@~`|GD|OF z=1vXY*O|CIed!>!T~q)2aL3i*uMWMk2>;g9e`PyzZ9iUmgGv{=nz}8~1J)SScR`jB zA$#%jB=3ev)k1GB)1XMgZX$6xL@JABQ@2Q|T1XuSK%S%OgvsnaZbe4#k6J~H0@U@?KSvd(S$M|@=%@{s7foe&#K z!H=%Y@9Z#+Dve7xW1Ny1Nbj@8zk{-u?NsS=sNkr~EgPll9gUQK|L--tmGp zEph3E!J6Ubv{T|Y1iroP#78u?dm!`2MkhiqmsJJWaJ{<_V3Bm+ns+LW$L+xE4%}Hm zU>ptvzyKeI_}NNeF@796zqz0Cg8iE+w!_Cm!)2`MMw`vuTNR@U&eTVVZeM(Bgyval z6X9w28_Z#{5N`g#`P{5yNTvZdJV|p|L9b9a|6mVYfc-VCr>>IHFmp26HC2KAA2Mh^ zME=U`|G3sj)qzH$mMHtHel~rYpHpzGXYUd_$iBhiG)Lc7bUzcGl(9uY83K1o(m^$; z(&^S+HY`U>Lwv9WIgbydD%F1y>d)Z@BKm9_*8tmGC*Fx+G|x&!Qqwt|=%7fa{Z^d3 zRM*`xqzqa7&a{w2-9|qCP#m+#5UP{zx98OA%jat3TzlBn7|=3?Y;-hakA};-?h}__ z@2@IuGm;-B5X(j6O_AHj@9Wt4L5bNjC4Co^3}lu7`?Z%Vebj;Z!?1r7(_(qE!_%Pz z)&1V(m0+}`OW5hx0x)*dw#Ug{QU>s`lbw^u*<)13`T?r6PEE$UF4IPy`jkqOI6`GysucA* z#}M-u^!yz^-M|0JUK?I59XC zT$oOqc>1=<`ZFXA`+@_S`ezKnh&GF2%p_4v#pF9R%j2Oa*~OzXrSE$GmQyf9yd0jfnu_Vd^yq3%^z*+vF#q>Gh~&vfhbRw49NMrbMjFcbx-yw z4{5-My|;j^6Ukx>kd^hcPOJKPEG`O%10r@+hbAzsZZ(i{GP`b~uQDFHA3;!FwMqg$ GkNpYXXq%t_ literal 0 HcmV?d00001 diff --git a/paper/figures/CollDetStick/GOPR2201_ImpCtrlv5_E055_part4_t036_bearb.pdf_tex b/paper/figures/CollDetStick/GOPR2201_ImpCtrlv5_E055_part4_t036_bearb.pdf_tex new file mode 100644 index 0000000..c57d22c --- /dev/null +++ b/paper/figures/CollDetStick/GOPR2201_ImpCtrlv5_E055_part4_t036_bearb.pdf_tex @@ -0,0 +1,61 @@ +%% Creator: Inkscape 0.48.3.1, www.inkscape.org +%% PDF/EPS/PS + LaTeX output extension by Johan Engelen, 2010 +%% Accompanies image file 'GOPR2201_ImpCtrlv5_E055_part4_t036_bearb.pdf' (pdf, eps, ps) +%% +%% To include the image in your LaTeX document, write +%% \input{.pdf_tex} +%% instead of +%% \includegraphics{.pdf} +%% To scale the image, write +%% \def\svgwidth{} +%% \input{.pdf_tex} +%% instead of +%% \includegraphics[width=]{.pdf} +%% +%% Images with a different path to the parent latex file can +%% be accessed with the `import' package (which may need to be +%% installed) using +%% \usepackage{import} +%% in the preamble, and then including the image with +%% \import{}{.pdf_tex} +%% Alternatively, one can specify +%% \graphicspath{{/}} +%% +%% For more information, please see info/svg-inkscape on CTAN: +%% http://tug.ctan.org/tex-archive/info/svg-inkscape +%% +\begingroup% + \makeatletter% + \providecommand\color[2][]{% + \errmessage{(Inkscape) Color is used for the text in Inkscape, but the package 'color.sty' is not loaded}% + \renewcommand\color[2][]{}% + }% + \providecommand\transparent[1]{% + \errmessage{(Inkscape) Transparency is used (non-zero) for the text in Inkscape, but the package 'transparent.sty' is not loaded}% + \renewcommand\transparent[1]{}% + }% + \providecommand\rotatebox[2]{#2}% + \ifx\svgwidth\undefined% + \setlength{\unitlength}{243.7795166bp}% + \ifx\svgscale\undefined% + \relax% + \else% + \setlength{\unitlength}{\unitlength * \real{\svgscale}}% + \fi% + \else% + \setlength{\unitlength}{\svgwidth}% + \fi% + \global\let\svgwidth\undefined% + \global\let\svgscale\undefined% + \makeatother% + \begin{picture}(1,0.58139534)% + \put(0,0){\includegraphics[width=\unitlength]{figures/CollDetStick/GOPR2201_ImpCtrlv5_E055_part4_t036_bearb_small.pdf}}% + \put(0.11350025,0.1860528){\color[rgb]{0,0,0}\makebox(0,0)[lb]{\smash{$q_{4}$}}}% + \put(0.11586437,0.01200456){\color[rgb]{0,0,0}\makebox(0,0)[lb]{\smash{$q_{6}$}}}% + \put(0.83721833,0.12809527){\color[rgb]{0,0,0}\makebox(0,0)[lb]{\smash{$q_{3}$}}}% + \put(0.22940213,0.51317985){\color[rgb]{0,0,0}\makebox(0,0)[lb]{\smash{$q_{1}$}}}% + \put(0.74390376,0.37527207){\color[rgb]{0,0,0}\makebox(0,0)[lb]{\smash{$q_{2}$}}}% + \put(0.30021948,0.09932552){\color[rgb]{0,0,0}\makebox(0,0)[lb]{\smash{$q_{5}$}}}% + \put(0.81594486,0.02836957){\color[rgb]{0,0,0}\makebox(0,0)[lb]{\smash{$q_{7}$}}}% + \end{picture}% +\endgroup% diff --git a/paper/figures/CollDetStick/GOPR2201_ImpCtrlv5_E055_part4_t036_bearb.svg b/paper/figures/CollDetStick/GOPR2201_ImpCtrlv5_E055_part4_t036_bearb.svg new file mode 100644 index 0000000..1b9b60e --- /dev/null +++ b/paper/figures/CollDetStick/GOPR2201_ImpCtrlv5_E055_part4_t036_bearb.svg @@ -0,0 +1,511 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + image/svg+xml + + + + + + + + + + $q_{4}$ + + $q_{6}$ + + $q_{3}$ + + $q_{1}$ + + $q_{2}$ + + + $q_{5}$ + + $q_{7}$ + + + + + + + + + diff --git a/paper/figures/CollDetStick/GOPR2201_ImpCtrlv5_E055_part4_t036_bearb_small.pdf b/paper/figures/CollDetStick/GOPR2201_ImpCtrlv5_E055_part4_t036_bearb_small.pdf new file mode 100644 index 0000000000000000000000000000000000000000..744c9fe0d4a2fa13fc10d9fea724873eebbf449c GIT binary patch literal 186980 zcmbTdcUTi&yEZx@Kp=F93ep870qK!m5|9>ZLetog9#nc0L;_gzqe_pI00~X80)mL3 zQdJ}b1gR<@5Rs;IDc|_M@Ba4Q*LD6l=gf5tBv~_S)-$u#Q||koBaSC5R5Vo4@FN{R zQ%m5-Wz}T^J^bN@hHAFn0lr~=vfAJ;1T_oNr7-UhSv8AG7s9+xczXtVc^ezUL&HM6 zFI{9}2h zvA5w3o6O27n+}ejmb3z^=2y}m^**4)rjF?l_>cd3VZhHh{v~0T-z3>Tm1Un!3=P0t4dVHBjGqGrMHdVvT0Y%2ez7@Jv1@vMJ^tmB%6WfGkI->SOdOdF-0BVGWqq}i@u+|91SP}2kVBg`Xm?n*;{KOnc8 z7XDne59(evBHTF;i}Anu;%S8z=P7itE0+k;qY()0ztk)teR0@xZf>T#gY%zLBU|k^ zMI-{aetM2R)wcbD#GMxSk(5=7bBFWT2;`+#Z;96r8$Z_Ki5`#rB4@h-`JGzB_3~M= zbdb#J5aGvz?avBswwnK}$%%Q(o6$y6C22WK*)(FB9)H~oe7O#ZK{y5ie8P*Lf5vxe zB02BEr*t;taKa11gbvJ~Qk{M*45D|tP!AA#tyTXf!bVgg>-Y?{3A4C zul@O=OoEpiGD0_!ur9~jDOw(ln=r7Ide_>_e}n&m8&HPKqCI=ZqNXbn{zt+R0OkPz>HFj=j?>m9B}@D2?O5ApO41wDadNT8>aci3q) z&{xQ+SziYGG6PRAj|#JN3IqLttlq!RIqBfx@9h~TtMRvc0vvP@YG#1}VPLPJvVR@R zzkd490RLX*-;PFB?e7R>|24!=Sv4DySE%f1_+JAE@UyaD58>dbH2(JXpHnsd@2USe z)9gang-e0H|JB8REU@zqyWj=3$ZGsO;eTFR=YMzb--f`|931UrHH?k_bEUs_{dZrtBnaw#yxDd>Wyx7rEs2$H8a z!O|42=0@@Yovnthjs{%K%A4ft_xCm)*M_T^lEOkAy+h0bF9!t%{Cz;Wa5Zc2riKIs z{`JMOVIkq(@c;N{wG(E}|8~y*<-Ij@wa}WH#>W4dFngc(763skIBUECF96&idn14u zAPDCZ;Nuk(;1>`U5)?V0aPR;Eap0J&+#vi_e$*8+&}aLU3Qppe4=hX@2J z0@-T?WWX_ULH@P<9q-=_!U5&v;)e0?!uh}hYJ~v~2o%b}3FYGAJ-xhreEmrNp<&?>kx^Ho6R+R6dF%Ea%H532tn8fJJZecPol#a^ zQCao$Sxs%-^ZJGtZ{D`HwRd!Oy<_$De;OG4JT&}mVsh&H^vo>#$MUb=E30ek8=G5y z?ScT%f13sV{eQGe1hk8TlM~7b`)e13Bl54|BAi@u8r=J^c-Vzt(ZibYJP6bD;wP_p z<+TV)`#nN>;Rh7Z-;ON*HSJ%P{l7CT;s2Lq|JShpwrd#RheE)I2NeNKfN#hWiU%B7 zLWYm_K1Qz_Z4Zd=0p#+HqK}VzaIZvNS*Q-8i`~#wSBYeQTwBer3*1 zKFRgGh*eU;yWrp6q=D*bn%K8Y5qm>!qg%(%b=8fXIU3^Xko~kGWmI8j!L2_7aQA&o zO98rxS+Khb@Gr5ME^#?VAxd8tl9bN+599XlAbLtPbC4V zOO-tAL@NtRBKHYP@oscdp#FV|4me{(;6WSZ;F9?%g-oT5zSKk}b9gz}!YBV6m& zJOL|q3EWkxCUL(mxPYcbl%?D(7;k8CvSd*qBdi>>Hb-G*L)pw=GftlcOvewz+q4^1 zK>T_Tgjf{i%^H2zxv8Q!$>17VFc+OSU4Y@W^tTPQ8IFhf!-&WqNU_i@UxrjgI~O+@ zI*_vBhy-91-kEB#*EHYp>p(PIs~Ztf1{qH3wTdP{uCyWW6hMC&!^Y5!{2=zB6s>tn ze+^6m#jG2-S{fv(%P32<^gqy|<}WCKxS7j+g+Z66>I?b--6}eUj=Xe@ey7mg!OiUo zXnGrfoHK`3(0im;fQD)E*cG<*7j(@fAeuEbktR*jL`Ek_qRh2^F?ytskNJi(Xwzxb zGXh^`29j?Y>fB9^367PQ>S3!h3k)%xK)3Qt@< z>g_MC8d5EK@MY-X^a(|es+~_Q(ba(ggF>>7#rQ~#3)G=YhwU`c7t^HP(J$5)HW!?X z(0^F%$$z2r#`n)K+p3-EZXYYJOB}jJSykQ1pPv*2a4ck_y)g#Qj`-@1SYd%Ned9vy#wGEcF;m>LP(6tx~%@OZwh zvs?72OIC1+v^ItE(7kKR5xeX7b{BeT#L1%1@=Sx0{tTjiaya!3#Yc{6-(TO!DCR*K zgj&Z_^qCs=emw&eEeo<7W1Y^C(oZ&EtiEPg9Wd7%qg!M-A(gOs*Sg_f z30e(s#IKg5^ykXXZ{RJo#wmaSL0Vrj7NwDHPvex%qnj}Fsrrr(Dr~8DIAtaGtsVyj z2bl!j1b#RtqYr&E9%lQ85Jp=mm0r0iRk2E2rDae&gjeZ3;4B)8w*q!o`Hw-%gox+g zCFMuZJK2kMWZ{f26oc&{TK*1_hE3o3GLQj7)Ql#D(Jpk@ldNXS=gei%z%8*Je{N$U zun0D9G{XTQtd$+oGj+FCP7ho*ydBX(L<7g5=y)4P{!}6tG%36+wP7O;=fNc}Z&EEg zDbAQNQH`zS-Tg7ibkuMlVp)mi98gx`07aiFc5@GCi6d&Ir(Iix#t$yj@)NGmip9vS zMLE+COrgz@9!me=P3h&D!#QOHC)SV^NE? zO2Mx0zAkA{F5nx>qiIShLPQ}cJA22BbrS#8bp+2XG(6a;KGaTjRS^x~G2#m*`dZ*a z!2fH9uq|SniAWmPyUAB1?IMR6^P}AQaNt})6fGop-ol|)(o+l#1St5Ti^+zG)=Yfj zY@8Ah@=83o=b;~GKHLYpQVL~}r5gF#6rHFV<^Te3fmy_G$;l7oSM@N12}&|i|*rbnqPgu6p)`@uZrTUtdlVIim6)GRg@HQ_SrmcCHN)%+oiZK zzI#A5UjC{NJRvVxnR)IE-Mw z_#`DGu%Rrg+FnyMpIed2^XJpiarN^3;;_JP&QPlksY;%}CWn#VP8e6oNZJXn(A{o% z{{AG*k-D897v_I4nIgh*O~3khM>-9jI6Ypk=nR;lib8Vr+DUY&((eZTrZjkRrr^Xs z)7?7??~|5>G6%$sYoOMH zO-Q2(pr@7-zdcLCQnf6=(8Uikv(O|N;F(NFI>jK^dXvE9SflmD!Fg9`rWw|0=Hj$` zIJfR<*$hSFcUWnvKcLTwTr1tUvIiLAi`JTZzGL7u*O#&AJQ`O|_dM1x8b6%C^V1LD zk=_JCCCY`D!y^9Sq2C){|d zY}1o8Bwo#VRy&_fJNbL#*mQP8%8`A^jZb*rA9vHZYxSCwf8KlTVM_0#<0{wQ{XA{8 zZ>+aS$y(fmVb19~=z8;FV^&g^!aYxz0MjLOzo(8(J>|XA&C|JF*<$N~CvPqLet-Dv zb$Uau_p20x6*w5I7O|7PL<;cT@=l1>}czb7Zc9DJ)8B zuI;FC;O{xi+a|G6ba98zhPQSvZ+D{pqy5c5ZZ=nN8QF5FddF& zRMG)Im?3M0PP>rmFXXR+`XVQi-Y6Cc#(QpGM>I`>E`5Z4%X83Ns5T9f+vU9?~_? z!u}vG6%L41G!xk&0si5R{_ww;mX<{}ONZB^Xno9@`0NaL|Ycuv#OcNX6y zs9ViZBE=+AiKa;TS8<2bO&YhHg!`D2)dK4dWhM-i-lDY?G--_%gD=#7_`{Uj*q>8Q z>`c<+cw(Qp;UQpBmf)Gx=gGf=(y}+MNlc(Q(>(YIGT%0zVFha7CbyQ$$l0B)sQ1tBH3-yuyRmuRjW!5P>$)I%v>-eLp{QCqG;|D?s< z?drdbGC+y{`P9txdHT}gMh(gVkGP|FeuInT5TrXfoO{h>$KO>(W2^tNYYXYz=P81x z-%7d2NUiufU5+NYeU$1{XJ_!e)X)i;^l);3Dq3z*jkD12?WjH|a^Clk*_@ST+)lWj z#Lck=y8CIv)pgo2Q;3nqCd;SHs|#GzBn-l9c_5y@8*w3iE0Qi<)bGgAYn^6EBm!W0 z1EAE6P<}M1;xHLvD7sRT3jViiWj!T;~ro;X&znc9e+x<`ur3XhbiC`{O_Rk_cN?1j0)4g_-9lH zESI_mt-meBJ(JmeCGoGYb%~#On93~{c78)Z_g63uJAW!(S`UbP@TX^E_i^ABiP|eG z%!O~VZ7Pk_kqF)cfJ)VS>*>X?cOeGyPPm6bKzZ@!DFdaYYs={C0gkWloZ0!xQ&CoH z5ZqXN!y@|XtD5VFt~mXgipwX66y*+-L*)TSZ0DSV`~cOm8a{Ct{#KmGV|buv#({4R z>(qAg;R#qn+0);<-G(V&St6L*Lw4#9{Rs^#w2B@E4oQAA_PQ*|GjXf`yTkc@CwNh` zhnzfu)vV>ru=;^24vjAw$Rgj8<)3LnSG33BorGRW81MLNY9xJ1x)?Mx;<%&~q9;TA z2PSg^K*7opUx)NyU7^`;P>pjA>YA7wvkk1)6#aUZBnkS>eQ;n9CueI;wji2l%3q2ZDkt@4DBRL z4rLYCbs#3KIMU#HMh90JAMK<2_LBvXicLp@t}tjGy9fe-2`NOP2|+0J0~Gt1Ra&2L z4FON#R#BAl>qbe2(KtI0u}DR#!33HAw*^v)#M=T^Gjv6c1XyrK6If;>r1VG9O!vWv z_{9yTohnl7x>u-mT_!;qjCou5LX)A=Z4wgVOo$C#w4s>#L9C}UY7vlb4i3v|*%m1- zRXeE)ZmDKC(H2kT7N5=r8-W_aHH07-915D@_Q5tq{(!+Mqx+~|x9mZ5xDiRq1_N87 zp4$VW@1`WgQ=0sCW!|JohT7A_$Wt-Q;NSR;S``jN1{H^$!S6P7G_2BH#t%P^V)`kNiuU$k^zOP9($lOp(6sTN2)4~X-|e+sPGA;!AQ_>7L&(Oi5yp5zBey}Gn(dY^r$;aLN#?_FK8 z%7V7lY<;BV=E=uvE$ms;SZeWXp3m^9ywu9+jNz=Di%+4Q3UN5&ntQTbuncSonIAu# zMDVQBrE^SDkXyYQPQWZ!XR<`CfYp+C8_Y=z%-u2FQKg96huo*CnjmSR8v47Ckd(nAa* zQWNU-xn>nbyv-`zghdwo^E8$u1otxt{fN?C>jq%)i{_j&`7G%gfFP2d((gOnajmAQ zlAJ3=qIV_dPe{PrIuG&c(EQiDr<@5US?CD$5T0OUM?8jKT;H3 z(RAX#aAYB4Ed>c_X{%xn^mBXnVP1njMs+?hN%bQA>DE6R z&47!|=&jOD@FBa7#au4=YHm){)>68Q54r!MD#_h5KSj`wPrVd@x5Z+}!KM zL+zX*+H7l?E6t7O+aj7L6*CjHF27m1@HDIXzACj*T)K#4=*`f?eQbQbAnDX+ZzVz) z|FNLi+

5BP$pyF4|@le_)&A@fzWn_kE9U`u-?H^2KY7G!PS3cQhddExBcxG#u} zh3e__bjkKT;P=P#S$lv|eh@&18xoXsfiJe~=DnE}ck>@|`C{BN+v9RTexCza0uYVm_~rk!=en7wSEfp_>(_Qj zqbE)WcdVAB=~dpobh#|O5G)s=4I+?x8xH6<&1xS^^m7xL8I%hyl1?JL_{K-*BtXji zq|(W7Bmct^QZeCl&BG8Q5;^#_NrAmfZi<}+M*h*9t=EYVhbGg5aO3m$II8vUKCrMe z1r#~%LO7P^Ex5HP=`PO}?UYmEstKcRa@i*6V+Lf>N%Nu&k^OU#z)snjxEPt-+39MVOJQ z5Oa@9x9nS@Nv@O{_w(?s(&AHby68liWWd0PWCzC4Yng!LM2ZoKcZQ6e6*Ofr^v2yc#PMb8^2 zCR>sAv0S1*7!n!`8#FTJcf{2>yh8(MJBbR+a(A*g~U9a)@y~L$RSG zqxl<#&q^Op(P#sp4Dm?@Hw6%k37fY-&Rh9GNL6PJs5%#na_t@>o_|9Y%*TI>^+SaC zfwS7ckwXSYv<1UCR@acKg)t1af(}!VWf~wJm>+Cq`nyf4f{mTSw9z8zU26WL=sg2UiE;kdrxp_DW~tPm@c+jSfs(>;bP{1#AtC!qF2)QgbkRumnTre|6*3(vxKUHa1N)922_E{vJAKD#fp`rHQM{bT=W z(hi}_+cLDO=J|oT19k6{%-|0#*HZ;{E^4(sw+p1bv~GQFE4=U8@@+0Xw8T>U>rlGiwTi^!cP5;@2Lo?L<=Cri-oW+Zrryo| zJllFV@XWVQXN2rpSn%p{?H$dwoy#63)asL+l^)n4e|$e7IMrWojjmyd#n1#vubOdO z7y1ikd(bs4NP0_~irj5|LNDm34B}e+0%~$gH{yC2>Tr}>HJA%wxHEQs5Y518YNhot zrngWRj2=j_Yhie6rW3G*FCuESiPNBWQ5qjnp@lVh^j4J7tYR%9_jQ>@FvaYn2G$4_ zrJR);LC^)|TO6l{-9aKoLHRk$k zjr$Bk!fylv%zXLNU+{vp3T0bo%$Z>%6D@Q*x7p@$hCXSKspYz~NZJa6#@Qw{t4Oi! z`-?b(VQc)lOUXc_WKb{_`xA+&ME8%=BR%Zf0fEdo{J_32k#=hE>A8nA-kWXlGO&QbsjMQ zNzZW3<$;{ybvi5sB?m~6X~L2^?pPW@q|nH6gZUgexfs@d`aSJoh_{b&>LQ#nY2F-f z_G0*HM(Wt8Yxfeq@||r!yQ}NY@Iv|6OEsT&LLar~U6VJfLa(;bLsc#Y(V=|Y>lJyY z97dIl2I}H1P2ag>7Jh=;$fZ@v>-KOn`qhTcbSb^l+l*zGat7=k8oC(u{(EUMm8Q*n zA|ofW@F~XGhVHWqFf9#3DX-S73#IN<47a5m&~s@XFaMBd{Lx(1ZE2m+X{6yweHV1i zQ7rE1DjzoJpFf}J=PSotKHTVR4< zq2sySMziuo(S+b_i$WLx@QQCbv!rgnMtryMh3qf5Wuo+(c;JPnm5uEw(UOPPRxh4@ zjesA}O-MaIQ5kBLp(=IQmb>1sMakkzb6t%`oz-W4VfqT(fA9lVQE$EMYJ(pB6wX^- zl^yY67A9eS0ax$&F-mH#xXD8mQ9P3M?f$-R+D}|2C0)~^sXgD6JV&q99=v_2Rqn`-@^S^X+j(>4+fBCro+S%Jidw^{5 z9&lc0yZE8Ui)6sp63nN2T8p+gT{J%nKw2cK4DK8fyV{~-5JZXA68xlQ=8{LWnO>B7 zx@+tix3)ix7omI^-pY7ddL(xb5UvR4;#jmle|FvtH=`Ty$@RC)@S2(UdDQOt4XG1( z)dD`Z14PC(JsiCqA101nJfZF`9s-fLB~_&y#DBj&;4I_x7wRo*S@yf67O{d7lPnjV zsC$$9%g)Hl>_lIHO1+vl5i>%Cc5B^sm+ZrAVtT&W%T7`WnjnK!U_b$kYrf?>S~w7y zceT>49Hm;C{Om91^sLp9o-WVixxEMYuF{}IyG_|*6BF5|>Ili5-+|-? z@s&l};SS}DO;<8rK~7St`g5TYN@cCm?~U&6kDW==JbP{Btj%W|eYmfWD{*O~WFZq| z*$w{S;Y#6dAwlyZQBqZl@Xb@k=hvK|s}H9nf2WkxFY;6d3g_`|meiybwZ@;lEejZN zk?>6rxY2C46xaT=w~01Z0w|FEt8nK?`b|ZCb%b<8Be_!_#Syv1W|nDpEpY~f-e7JE z6ogGV+n$m7o5C&gb~hFkcN@Qber6!0AH-d#FxWyba|acqK>^HG7&ELiDohd0b7rku z91Tsk@O#YdH_u8dL^*KZgTQd-fYMq{&pP88G7>FHkyxO5h$6HufH{ba>Y~5SKBFE6 z7r>?(`}4l{A?t1W35S)CV^O@ibLQl8H&goa)=K-C94rXv?4*#uHgYzanxbPj_CYJ8|x9e5iMuqDE9TsnqKxqkO8{P?|e zimhjSsbTMUN`K3_eu7UD3+O>KbhaIV4x-ypVrbebT`~o^wu1tGpsHd~)*VDn)RYGW zBWRK(jzFmSI|`zJpIjW|gN7i{(;rFKz?9Y=L9}utN#~ZLAt@+;zzQ=$cB>y`W3~tp z6FEyXUK?ccg01rEdB)Z=sZMH?{tZJX#;z1I&*A4k8>bKDzkd z`=YrVm6MkGB%1sOBE>zV+4t%dgmzV5*m<``OVftB{E}=|GkAn%C|yfWk3H8JluZyJ z92Z|0Wkn~=I>>HK)b9bJLK}r&(yBt9==?b!H0W*t**Y}!(p)&F)eR?NjV#jAS$Et6 zlFjXsQCBS<-FS?CKWe=C=YrnI?i&{&Q6C3kp8l_|a(@^zz=ip59tlWp z1Uf7j*2$bNxbMbx?t~-hMkIcMfe2XG*Ti8@Kbc>Y^(V5AUA!$6oR9YXr3?gFyEi2?1*Mf?5d)@-p2OLx?eQ313KGVm zcp$>*Min$)c_TjnB+}ZDN7Fpf{5;)i{-imZLK0AOi@_O;ovBubGJ7{2V`n?A?xG(Y z5cWhkMqlGj1342I!54kqy~y9GKbCY7T28d}NP(S0Doo@8G^QX@9>K%YLSLj3aex3w zP;n#KZHQadM>$w{s=;qts1$P1PI4lNA_n=!I6V|>V>`H?$*Mt+J7^d2MIunIO)Xji!lQe6h^{NSi%$G5mx(9qdr~lnYur@K(Slu&6GU9U+p=9>9@-77 z=8#B$A>s~B?vT_qn1mHD(=A$5k>ivmVK<}LmHmbaLrBSo?(&?WT<;9QK!-DN4r339`swOs$;Bf}bS2CsX`{-7AWJdy6-vZIWB+^n z=j^dhR7ga6Ogi zX~tJXMVKs<4F^lIQW*v{4k*}Xl@SS7bD5RyAM)jen7q0@0A70rsw>Xmx8g@tJ;<>` z$UpIzGJHqd1HzRFJnqjiPDl2DCb`Wjp@o!{;uPZxtHs?_$r z1upUz`A6l|t%_APYK1i(yb1pb_mfqJR=fVeLd>`jyb*P{sy(1__~yzHY`VV!x2f^k z=){u%=S7aXhs%c{hq9Enbssd|&Q*tqH%!!(%Ud+PJ^s{T4>(6f6#1wBuCM6QojpJ; zRS-$+5qp?X*!pDZA!#a3z+AXpxAIB46?Ynmc6AIj6_;+4;>S^wC}=W<7`{3s4l{XU zl2_)k?+pb>DlKNg*-A*?H!4qk^Z0LU?9g?{&ATe&ujGQ3Y*kgmDTA6IMtx}`;ys{PBzxTfv!K20u{k7xFM z-mGGCUTA*dpKrEa9GrCAXQ*1?OezmY_VCz`sL$z1LQPC(CEYV|0ybiAW+E1;42`a2 zDk6jHj?>Qfst^k&gBPFHb*t`fkK_zLJl0KpC4${4t$1IQb-6b(?&Z`Tfcp^xZ&{-3 z&Ji*K$HQ&6z8?BAf7*HA&1u*-oIaCuQRB7{$XrW;JYFmk%;BXfphmO6xtcH#oc5*a z$NE7+E&LXDyASuebD(18=|?jU0p_&W-rX2S0m(z$a$mouew(wO2Vpo#2o^+RbIIWo zDPLw-nXB{;nPgefTD9-iyNED7M7x1rsqUh6A#(9G7|QerSLn0Xh?+tdKwVfGG!lxjm`vI>>5L4tJA!ngaEJ*be zIZc3yI9(A`Lhw!}^-^s?<`GrnlY<8GCMgl5mmmso2*CIIP|E>)`(hJzcZ~$RT(*F% zn;*5eAo&43;`3NtgyR?z5?cwG!zd!4iMG&MRJ-4{AB{^2SvFIPl&=NE8PYWb5FEyI zcrp-~GSRkNQY5$G48`GWvSUwW@k_P{}d=4-i3HX#;CCKuEIRO1mdSJ%k~& ztKYnBhYQ9dO)fSVdeK$(fMO?Yr3TJIL#XR`Gvl!Z&0z%9czk&-h;c;it=E zhFc}OFe~}~#pNG|+6#i$B2!phd27~ht#sc**loNgB^n!gH%=ygJFAQ8d^;(9uiJkh zBAz$#?TZjSLc1E8Y|t1W|I3r8u#VP%%$dv0`Wc~s&_Yxk5v382;l5T=a&I`Z$P)vR z^hDH*uS{YR?hPmX!Ovsf)^cv)UnG8EW4J(fie1+$Es7iXhn$CqWV~i$SIYpB0gDwu zgVsu65D_38lnX)Nix@DP?qAL$a*{%{UB>WP59d4=E6L@Kt<+m%Y?HKBX#mKCTLc*p zgt=r7N;Ts1!{;ocNgs_W_8kPF8&0@EsHJf~zrB9n6LSQ>3dTY~cEu+iq8lI}^=zw` ziWC#=)~Q7z$Sbeu9II?|SUlUx65S{41=mlp_Zu}bmuh13YgmA@uuP6Vor0TeLe1HA zT)Kw1iJF-%PW3lp3x-nM<#bIV18Zew7_diD29B2gZjTe2LU(?^6g;xi z9@_Iv$0x($pC8UZH*|Afm#gobx`qH{VPs({a(=_ncn{cIrJ2UHILukuUqM$%BteI% z2EMF#3RWtVibIiZ2TJbN{P6oz%EpKxfPzYFS1FkNm9P5!-YzYrym5>Zy;BzMk3_t1`7Le%yZzxUW2P{VDa% z;lnB8rQ&-8rTx$h3|Ei=CC#f4>B0%`oI4D8Y8;rIAto7QoY`pQZatkI!grYl3o)v+ zR$|nbKP8v5k}h9Tp9-(Mbf4d+J+?wKef<=vEyUa`NhHONC*s&hcA>@jjs14Vd=UJj zRXaaYT5n_uTaV4TmGNI5h5Wue)@By{xqHF)O7FbHW6}i1O{}ZUMK->mqnsGbng1!| z7RoD4=w0vz6Oj7x;%>B1i=zZz-wJ)=z_I-;Et{343SkwkKZV}C$0^8J67`5mtqr<= zMnR#aF57mW`>zpF%l#0UaLr370(Wrgn}k+1m`t*+db@sHqn%=5qrW3n?DZMVEdJ_s zi>Qji;jxd4a%cMMN3Sr3t=Zjv^j?+2X-|_+BKVDFwQtGDe}9z~b+cm}J=PHL(k1k% zQ9e$9lbn>)f9wG{fKa|O>Pmxw)up2~r?Bace^aG&>)U$SPP(wg>rTDZimJ6L4fF}g z-Jg<0>xC7AC(eHQpzz=)$jEA%{;!}dBcyjARFQro0hC+0fe`PRW%lVpsqkcG#`Ex& z^Pf<>KmAoDS`Ug{t*+q{h9=$o^JU;cewO&W3wpjy%{Nl6tl<)wCpEVg)YamzFpBMGn|9o_ljVI>5=G-oobv=>Xl=t~+BlSt(I69%h z3S;xxb=ey;x(IuF!x6bgU> z)Kx^7)NfD$Yd@V*Pyqo&OMkUa_{3Cy`;{;>(CqLg(K=%|JN`}!$kO$un7}>w3s<~S ztHo(M!x#jfs%49{Ghrn}fyA>%0x8(eFyB#`Z#-$TR;pqV10e3*)W^5$5N1->Nc=G3 znc$>gR$7L2Vf590AROU!TrnC&ZkR+v6Rn3c;=fRUpiL|BHs~D1ws$;@98QY~r)7*M z@aUGQx3np(PTWoUUDO^A7m%tj;sT~7(#p3 z^>8An{2@U41v4|DZBW7f8lN;#Dz}THXdJlMXu0Wt)r|!wwku>Iq8}U-jFKh3aofzXnT>na7Jx;h+m$|}N z#I#RRgm6M*2%q@TVBNCS(rPu`b(*Pr@3zSdE9sCRDAWWYZijE%U=}-%ZI7aZAFL)) zRy;Be=K^dS^P_?!0ImTR+^}kONK0u2ov})Xm?LhLgN1ud-YNrqtC9wQ3N`v66d9C0 zpw768*2Ntng0=fP&7;qH65X&$3!{nE^d>oC7qP}50EO_SoU0*+b^~J5IpE}_agN6N z(N;^cT5N;OL9v_%N9^n@a^~R`TG9$AF(4apsi0SATt=jqJ~_IE%b1VGXL^I+q&b|0 zpCXlGB7&ANoD^&+Lv)1*YFJryj87Eghts>-HR}5y^`p&1TcHg>(&;ikd1wJf z7sHtku^!Il%}Dw>!^&xr+f{;%ZL>85<~Im+3!zlrsqN+hz-zlCx3z`Fv_?B}NE_Gq zCQT$VS+PGbGH*fkEl=lbTG2-`uL)`*HxcdLJA(F|rgQM)Gk*9j{`M_LN67_Zdvmu%S7WkV#cSf()lH%nPyV31Q(TPqWw@-5= zAH|x)gyTFpeHRI0ul2e$Zqqg9@b(SfQd)Bad6cJ^t~~8%_BXMr$D4JDH|PbF(ZYB8 zQ;t14a?St6Oq!tE;rpgmrmuq{s5vBg#r^+`cI6$>t_xnbVsNgsPdc4Bs(M5&v~jvj zS)eJ7$eukp0F_afNk&(#Z~q9eyy_(OOZ&!J<+NBk;h=1va016y_fKTVYpGP?1MUvg ztWq}Z)`72A$4HES!c7VcOGVny$^k9hxmJyS4XIZobr{;S2qhuc$^9x%zd-^bBTMG7 zsnBPxuKnGa0~U%5U7HSEs(TMK^}C&1&U72e{fS{tpl<9Qh~He?3Q_ z4GuhgV7zuMvy^k;xLdH|^o0%9{epKPpClg~a~jZEyR9|YB^5Uw-SbmvnjUF)a3@4& zOVq{qO{3gWX+nAX8w&Ei>|aIKf9+9q*OR zMLR|EE8aa?uYC8Rv*GOZhtp^K85mv3Lj*lVguGm&Z$6>0oSUk$cJBZIZ44 zzP0!uWaxA1%kF_P&cxTc4;Z)W+N$KOH9jJ_oh~cV-=~v4!ccz#YqDD)TBSdQKyHmyWFNP5ZF$E^ zJ6qpog#Rdri1rdSjYc3ZX@cWR1!r3PIw@tXw_!~4uF3Ua{Jr<#j+h9^Fht1cG1~_Y za-VWG>Q)#S!xjrZuK80Fv+@U0#QIFeH>>m(AHwG?hug9&zA!H14yNz33}%$)Fixo& zdy1KCtP^KfKNwFb|Sny4eqBrp@FrF3NK+Vl#*w!CGy4gg@fJq|zCizmd+CcYvLq+kMxf~xT z`}d`ABO*#tm&#=0SDr!MbYRs07C!jt^sk~HJY?h#Z)wl012_sV_WF89Su(D7oEev1*3c0zjxFk z;OuzzNH?;ucWzH-`ryC-uM(ji=q{Vdax(%b>`WgGIrFXjx90x2uRx#o#Ud zxuq)m#}g8+bOZVs@(5_gq7CK-oxWb~k@n^;2=bEQLO5i3&|}EFWwgd{(r*lKn8L-$ zgis9}?G5lLeh_Y>izaTlBSZfCAW1_VAj#Z z+&;Yx*|})&W}u?yO4S4RV;`8r1dZGAU4cEDPDFp0d9A!litIk*C(je--ZjC#TPN{H zFIzfwOEfaaX(78hk3VS4Y5$09t5pT0oJ^Fj!Sh;Kp;W2eiM~J|#*5#~k!&;JqPH9PkH|U9pBh=g z{%dF-3b*7Qkl%}u*G24uv~fU_eq&1#2jXwYG3Xyn;DCuf(G0|cROPfl&=O>w-67WF z*4p*0WI>I2>n`cfj7})q z(jOxkHj(!GMdC2XCcCR%DFe$60a$zz(?Q|}0L;*)GZv-wN}*!3{9k?$K~2AT9QNql zG%oQ@w&gc#st3Q5)kiICyYZTdl4e7<0$R}|X0`O8os4R1g`%QDDBD?1h-hDuQ_CGM zpg8^Kv&p-(Lj9|+GQUQAjdn7ZMNH-sJSYNyjKiCI+a|YGz{Tj6AS58x>7b-C{e?`XBZLh5W;16E67(u^ zH}y6vwSG-!x~E0a0g-`tZryEV8Q1fLu14D1pB_f1{+>HET*C3B?%LMVUU{nk4=#_W zIULYV`rz!IF-ScqcDb9?Ff{l<99rLPlnDgATq`3xyx(M{IVT9%91`<9GiiXORbHSX z77U%pT$N{@$eN#$tk|UgX>rOsX!53=Y%dr`%;X0pav{!3W)T^G~p-T)sV2R`$ zKDp?8ru%8~52*f=H`MD%kBHC1Ofx%{)%+igELE4Rs9aJncC^xMgE#~iy`jUDJK}Jr zEsr}sjFCpYu$mZG&i;_fKW#btFCZREP8U5+08FZRKW93p9tj;8+^;~&p6fQcpnUjQ zY)^E$n_5e^WZP)A#tqJOqT<=!7i(=uS<%k&I;LQ7em~0J>%$EtPtJK)Xdo-|#)b78 z#wUNZCO%Jc68`F*ALBYG2B{Hc_GJo3bt^p@$8W)TUXQgMJSHZT=UO69>OpL$f00R+ zljr2nvi~M;yglu=2aK9*NqoW&SNrqTc|nWP_JG+y7fXM3O6PC?tCwInq!hC1e}#S_ z9PKr3tKCH|1f~p=XqL0Q`CdcKjO2Sj4Cr5@euDlO>usPNJf2ex%Xej?b?*AHtu~SBkkTr}p%Vb{$ zVeDgHQpr9-#!kf`Ez=nL(hwsv)+j|t3(CHarLt#DLb7G;zCPb`?%%n8e{`JF={Peo z@9Xt?E|0gJRILf2~f$ zUC7S2$$(>Qj)Q4dql{$JykXJXQ{COov|TKK&-zNRfJji+ zmS9n{U=63M5Qpd0u3zzYF&vqV=giHE3|~C|M)jM|(_PztJ4xIjl_~X$O6V150vDG} zO~tvDYRl9125;Nk&h^ul}qOj^VkrNjGGjmvIE5<~dv=lV#y0eRQh?WmD z1>Jar3SS`@<_jK%@*=nxM#(z+QG#ozW`uuyFc!$btDM)RO#x?((<4yF}q z&a2dj>Z2irY9c-|;6GbF_yPR%X#qBR#3V%w0O7l%SE+jpCWVBf5Mfs=nEnG7drj*U zqR$0si{Q!loum;`zd3MT+QJg$M$QEl3ZKFh^S*#hwoqUP9-oX;qM$F}i5BH(1UL{t zD-esS+lM}dHK<0gUa3kG1G7vQENkaMtsjzyGp2zxmVUreEQ%2de?}>mtTg9x+olo~ zWuZ*TJbjE<kPfh!wPOf7HPc2di)>9ZG@pNf07>0NEvr7A4S{$0~fv!{NXZ zrKWWqCz0)0>|}Ne)f&rN18C$oVDLl}yBUIrfiw;W;E62ocp?xUrN2czB?}0)T)Z}v zU3mCnB%5;-EH~;il3SoJ3t=w{;gdR}1psZ%d%aSpRfYTTS(UhGU95zh<+}3KkEzk2 zUzsQMb~L&6DBrIiNl%_l#2kNKyOJrQjQn32Lf@d~)cA@&RryWk2zBEYGk#HR_kk#* z$Zot*7(h$qb>akLQ?fTZbSix_i{H;au)KG)_d9vzu>BwKC;|K2ZOZt}_(>Hjq{^wn z!}}eUR!noRy$_%B_tk`?=nK#koSOk6i{qDZo|>mV&t{$S7IgmZ4E8%;N$8zu)4p+} z|J!*G3WZW>@@>M5jlq1nn3V7Um_TqRF1~Z8=S-+wEJzCNA6RxoGeqp)in9ES_EW^!ynQ5bZsg#P!{4mm3%OZVO7ylG#7yiaeZ?9=QEKx= z^2#is9i3%qE9e$21DW@Tz5t{TAeC2?nuYQraG32|CHt(IG@ciSdqgp8_=+o7lNsAZ z5Q>S*x`Ej7%(M|Appar9t+r(11BOU!7+`K#W`u}T=mQ7ZB``#nhr{fC6kSHMlaWEP z?KBy1NS(F~qYmgn*!ygBCHt*9sEd=yoW_jQtPLu#&)`Wfro#a%vMLyFUuN6~A~i#3 zvxtcnS*kbDl_@8UT>bIWU+X{}7O+PQdQ{{8z>36=XY&$(sje9Ys!~!`!}7Ywt`^+OY7G*2ik2m3m&R)VbQI~iPCyu@2w)H<3Q&O z3EU!>k5Ks+z;r3sLe|Gw<3{at;nOq834Ipn1d?^UE;9$92fqD9f5FiY=~yf+ca@qK zxom8xxj9QPWkl;)2c>yVp%vsbRc>)>SzFjJwa@A-- zB2z@m0DW>QZ!5s+&BcL!U9-K1(7hd z1rig};#SdpdjKD6QXI+|tZd`ADl>NJbbm4PQH>N8Iu>g|0)%9W>3&vDzaL~w5aCM4 z6{>B2!QYJNd@_`mw_FeIQ6O;u(?_=cLQ(m>c^0#&xIpf+v1#R?aP~m+XfE_05cxB~ zXW4Pz3_SAkB>w?=QN5MzcVsup?)ZU9z$>QzN9KptIMxtn{3_mEL{8+&ZP@L_Up;-# za@*bY`<-pom7U|SOD{N%*PU(PGoZU9oAq&t-JPF!|FGN&cVfAA<+yRs^g-v8-0)1N z0~yI#(jgpu>GN{OQx1xpr9U$_PUIaD5h?gB>o8sP;HuMT(dBWyIJ}ivxXY)M&o?Dw zW|u6|VSm2Ev~T*gFRGQK`IkT4Jb7MPS?7G-6vtxElcHvFK{(iI{w5dp#5Q17z#jH! z#Az^^v3c_JVsacRFS^7(G)OU8vN4t-+@L-m7UNF70T{MRSZ$eWsJN!ie&-$hw!I~DG% z4#>#0Mk(s`tIf|ce>#kxvKL(?ma$)4!!*XW3HY+P&{8obq?elOEru^L_NP?dqsslg zI4_?~=E&2qE1{j`6(g-waI*-u7K#Va5a|j>7q@-m&k8I%?{Q>Q)u}F+l41L$m!CiT zc3i5VZ=#p=rXm(2mNZi11$2I0DCt&Kkc-|5wn=&JWG*STBI4s=-}?PezB76siv;lf z{htYX1VmU*K(?|x3!d=aKocm66*?YRJa$R3QBilv_AB=&hUvZ=uLNDTV2CgLlICZ` zY4stO3-*H1yXBLji63hV+9lcl0e9~#S*=)q6;G;i?(dg`IvGj@IIbVXtPv;EYvfBp zNkMa=U05C?xaj-8{c_(rTfoj_YeWlF*qU5@Ph<&4#rMF0LN)p{hZYhxp<}s(<}`pm zSs2r)j;Nss}{9%KIn#{a7UK3No{Ln~yL(A+=3II_M0 zfLt~nJEW+>kM*1cdY~_yHLRmUfUv^cD2mHAO_G&x60~5$OKIBG>7U!6X&A&hBTZ(% zZ3E<3^oTK8DCkPUL6LyKGvuA*%U-Cx37k?INqY}(g{kcn)`-KX%NX6ZPSDs$kdDI} zT}!_g!-E9s7Scpzz8@ladzL6dnVP|7Fwx3UoyWz#hH%j}@6Bh^vTAVeT$|v&o*pip z3^9>>-vC1mtBi>i)73VVS=4H6jxw?tkA+l>Ss!8Q3t!Y{5z#!3`41fc_0rw+ZWPpEHno4sQqj% z`&RiC;$Zcg4&}N7B0|#tAYsz!|HU$Fn9e@wd73fYNr>*_Y=;QWU2xcS5dSWFY-{GH zGW|JoiRk35tX+kQ7XmKy4-X~1?NsLdzbs*oDo$4m)j5Yw#MXGcenGwRvFsfH_ zc%gJGWXbdhbw4f;F%Zbb>&t`3jPv|gi&QaDW~giy#ti{=M{8iJKfBGB18c9h zpl*cYskuCC+UfVELwcA_83~~al2DL_gk1`0wh$|>^Wd8gH9kK|_bb^4@uaDs^tSb} z4J?y?M=Mfy=?{ay<)SkmoA!@?fK~}jYKICQ&+J?z>-qOfNXY4QVATNiLR2olGsURp z!pX7CB86{iOUCA-_#Ml63(5Glo}(=Qu^Sau_yJT?VmQ?LCTW1-ZCjh7zgH~-g|zV=5Z z^Y7Hb88Ce_Ir{6iOVWxsd9ynn^4pih+`n9ML|S!}3goC=ZFswG-RToyO;G;Gb!;xBdg$&I~f zFEnr_Zwt;7XMD00#<-MD>{pN7esCqoRMl=iY`dh=BUS1OUQ#w|F~#BUhxGKjvmq3k z9tO?Flgr(l^1+%_UWv#)z6hu=;uAZyfAmIFj4Uc$3JKJCHRGD2-`PF2$725xr=Q9B zKHP3XO|wFMKyPIiqI$ID;Mw{6>rDOpI+-=9E>NBXrp{!s>co&T4bk2>)+mnA1yTTm zm46;pxOS(y@Juizg)gOfamn~SyTpw*@@=)K6j@9&`IEr;W|lZZ?j2pRp^x6W)la{1 z;5K|bE;|I3tbC|JCEWTog#GHaBEu*Vp#p5pDN{ARxKF1%>%2PTKm>(R#3NGrf}X?Q z9AbrfoRHd*J)0CM$~H*MQ*HO-=yS<}GO<6gdVrkL=(A%w>pYV+Ayl>I9okvK=V4^L zLFmJ??(>bPO;Q%ta@OWy7qHYmk&K&`Q&0t7tsEdXh(7`*$_kkkE94CoQs3E@cYjX( zHfF)GivC)re|K%odO>;)bFT<8Zm4qJ$A@DP>zBY$*8TkBYF(LTfo2UZB7{FY=(Aib zRPHEr;K7K4QfbxOs7)%7<$OR;0u*fcU|E<>)*!$IC%8p$n+mfshcU7w2q)6i3gOle zypePoDt#4NQnUan@*(|`E-P?jjkA1zA-H!Gz=EMw zujEro2EP<=x4EpXW2fMi@-m_s%xRmn71P$+Amau?gT@*aP+|Q%++x~8P&1Y`rr42W ztN|Cx53qB#c|S|XnN`}SuLk(-qlE)pA*Ms1D#Q*(CHkqaSwzgm#JExwmMtD;y279@ zpUu`ZHh=JKka(ApTj;LgoM|Zj7}I!c;w|w-iLZjAR>d1#%1?vKRzs@+mizC0-%v-A zo8D~e3;PQ_5Dy1<;M+&*r42|Y-wq+08oTu8KNc>&EAQe6ao`OcyFpUvYGBTg`Tas? z=vJXhpvgK*3fcMUC%m=d$MYffshkxjR;9&G*7^ZqZ)RIeElUP1-3z4W9q%Wc6w$rg zntYeK$aF5IdblUzq9bKR)V%HnGVY=}5;kQwE|9!`Fgy&2jq^?SyWpmCzxtUQ?{4b+J{2hy3aTp+jOkg>^t8-?DV+YM z@7-e-6Yj4c_Q!b?wb63|#!;r6sr{tfxVpWpjRV8_ZpU_L;qAJ}V5dH(m(MY)pksD% zvq#Lqy8~VLU=f#7w2iTMRnL@II$NhM_>S9LGxdA**wg+-b*sl{=kO=$v*GKH~WA%-5HO7+0QN z?{K=1>50~ZQ5(N1;qB1QSNXmb?&k)~&(w6j$Umtuc*e-(_p(!rftRKQ zvKbo7&>iAtCIh4ULT}-#gCqjK9+a46J~zQnk~NM{?l3r%Lgiw__K44USBOcXfMUAf z0>x6WI8b99&7Pl`r9Ct_Sb_ZM13|X{*8CI`kYxty`uybTm;``%wnA1Am22G(s9SrF zrm2Fo6{f|}ObVW8V=~Q5L2C4CEfM~UYlc&2VmXcTec2Y$z%`)w4Ngbh1ryQ%X~*mk)ly9 z0FU-{XIQsFkF)za3IS^;{r>{a94M_pmtF*EJ~*}P0N^?(vFxgV` zwk`DPu-@(;b>5X0$aVSODt4D8l-yQa zRKS6@I9!HeH~$hhjo*oOE>D*i=Bq#Sfl7+uEx8nRQ6y>*3m_y9PT2xY)(#sqm}uk^ zut!-rEL;hmDY`(kfFmh3#4n+tyWnw3k9i~4o`xr8k_4&SHKytoaoAbR_ap8fy zE<>x13JBKhDnK7TJ{;$Lx9dcGhP(a5egAIU>*G75Z)(S8iUwPy6p#HOd;=@laL_d44eYA(X<&z5(ysn+3l<2cA6z4i1CuHRjZ4ROK zi-&LPu!i4+SEPm`-BUh$B%G5mTlrPvZ@VS=aor}UKT}`oc5cEMJmW=Eir+~s7OblP z7|k1W`Nf&GqcBnw@B>pB6=xt%+7gW{-R;#{q7$x84yRBdb-_L2Vy+zMZey*F_cP!g zCp8Sjm;uF9W1R_S=-IkNo|#W!+-lkF^2M=h6nQ<@6{+oVDSMUxX_@)1JJkj4y{z1q zA&_A*#4o_Uh3~_!V}f$pek;4USncUZ4u!)35UB)N&Gxu)EDTK1Cc5*rKN;%}7;mmc z32+MxvS6KNZH`7%z{Xq1_ii~#JRJ^Ap*a6g`z(=}_Fj;xm(*YsWwve#;;z8YviB&# zvH~P2z@yWHcu_z-4fY<4AAX|?3bsYDB3Cf#4BqV+4q3kN10NXidTVmn{t!@oKRtv7 z`ZxOEUl2GfhK`w{*+HTW2~@h3(1Huepo1;OgRH0jh@@^(b@Sg3gr8$oYEgj0|zYHpphiG`lp$wjTuWX zkKvRrun1i^Ktft$CbnpxZk_HCWex4c8={v-33`hZJ>2b?G|3SH5IlvVf}IXs>W!42 zI_fNfI}?TxRJ|kAJ%XZ-OfHtk99)J)kcvtpqu()w1alx!hH+d9~3 zV7!a@mau=#)mnwJ0zxAK%YsAD;vBpP4T%AlE4TtWhCOu7-pN6Zyp3-Px@u*6VqDU8 zH+b33EJ(=XNi5%M|M8E_!$Q)-_E5RWp>eCT`UQ-w^7HCP+wtvb(DgX{(7ax3-l7lTAZKOPBomwldHz1mHq)x zf#~a}%J}$AA3c{x}#=T}>pZ8F|m7;ycy!73zD`jwM2M)S|J@vFTj|K{A**(_K0dbX|J z%#TcE4Wg#9o<*dP^71yRCjiz_e8z#V3rbXBd3&&AG>pL3A*%1VXP@^rpsKtDVa1hV zAmwO6)KHf#KD( zW&+^#9s5I15X-jW--^=6cr=yb&fA=s1~x}vV3c|^4v+qXa!aD0VLFkPi#2DBeK7bN zTy~7f3O0BSRnY$Q)^Ro?4T>amv^m?1q^ZFlAXfAt6Q$}LN-c-h^}8i3vCr9B%%dD%WjHs`_hDAGD36}%x}aTyay69L<);81T4 z_h!w$*CRap!H4-2uX8d}1nRWKZLe5Hnr1(s!=YdRqcee|tQsJ=_STXaqD6ztC2fdd zWdbhzH?)S zmfncv6%4P|>n|0s@Ee9}of(aa^&F9=?QSvOe87%JeO!_HzKHVO*`}(}wi2&q%iA=J&bWl(b4kAeh zJb$_h+A4JXY4N_#JnaoW*b5*jk40ylJ5{^9brLv{kw8k zJdakaorzLnDecUMELv!&M%JH_Q>YY+dBZ(o1c0w`puDk?)p*dcaS9@oEz=|E-Xw5AAOJ6lzHCC7-{4mi|t2$1Scl{@WH=Ui$j0E zS{VowfMIRy|NX;sI%CjBQr+zFMoe2*$bW5G%CDRB-@j!{@ne0r4q49TA3IRKX*wf} zef_d4Xoy6RHrcR`gM2(Jny^Z)kVmsxh09kONWPu(GYd156x9$ZH_;R0aJ*q`l{R|s zOl1mhXG#h91i!s%mq?IxxltQX@Y;8Z1N}Jnd&~p6!?EM*FEQOE7=w-G>Qfq~iGM|Npg($p=J-G6b_i0++BT9U3nwgW8 zFoAY|wR+}rsjHywe$C}$m3Q8ta}XbX)$aJt`6>gI&y{vEd<7nvY2R?sh~ebO>{k=Q zNHNK}Zj1ZW9_Q4Cv83CN5KM6iU+?rFXAdW1wtZVu^VeDJ>*?#(Ob_Q6hd zK0UPmTkaO;-=JPDnCw z6E;3Nb&I906{!(I@7p&dz!$;!h<#BanS>{rf!M)xHww-WHUWZn5sSa6e^iUo+EDeX zOXviEJmi*>Qmcuz;1$7Vnj6FI4=TJ zyW3FS!EVX9>n4%Q7-;w%yrD5j2eC@|^0%~ph9E4YxsWcrS=4Vi_=gIslvgIAb>Z19 zkP=8E1+rO`hT%Cu5Y6*}>6}*)zEe$Ih$VxYGB()!faO2CfCha;XC|ljv}XMV=cKM5 zINiPx3YfY*1%!PkZ_+l*JGM}=n;`bNQ`(Uy~kO4n|R zg+e6GmGMB`sm~M|&f`io<;Oah*QA=&+*Gad-({fX-E7lR)#mJ;?f?N!o-U%D$sOTI z6x>IpD-xJ{-I5+WcixXZ2|`x2pHvlpP*O^&Wj^S=a>RryGA7L5kU6S5qoB}8dm!7X zw*M?!*BZ)$GwapAAOV)iTi#I4xY3mL`jLQ|Ak8)KxyAez-L=wgc2?`Bgpk;Jt{s1n z=dom!08;pvRU9zA3bLG&50_{!={JrqF7Mhn0)d}4m#tE-kYzh|tLpB`zU03pQ*s~+ z<7{l)7T{Sco;QuHr7j;LdFINRoG|Tuc#Bl*YOkF`y$zP@xB?kx8;FZ-_`aXUvM`kn z(u-mQ!ZXv>&`OzYnhu#rxu$eNW9CA``x85TL>0lVQ~+8N+~YJ}^7@&KGyzxg{XPx{ zZ#<2&w8F4cDa_{qhWiM~E4%R&*!K!z5#s<^YR`zwtZ_cDTn@|c2$513w><_=^*fKj z$hIigi#E$9s;#mh7RsZ)5i*M^7TctWhTKI)z}e7|ixr~3<$>ouc>zK`P7IR3Oy@ zBpc?2Qd3q8?nCJ!r8p2Q8&)LN=eG|2Ht-^-ff36XmL4%w7!Bl1@MM)QA zFmjkrEy7Q~vzij6%X5KYYp}xCOw@n$bPy)U@6khEx=Hj%WbyEKvw zS!(rZfj`A@eAitfLYM=Cbv3bEIMumUIIkW9-QgbZH+LhNt zP>-k=(Tl@lqK4U&%w@E=&x`Fo?C8PV6LY7Ft7@rW!B?g>ldVAegHsg9%*tJ-XfXH) z_!U!35crFT>WXfsBEdSP2TQ0(@gQ4$Tu1~8M znnKEiFU!XW6yZf)P-(m>t)>IL08{**McSBfra#3xVEWr`x` zB%axMdZ0Y}s?S84q^P6+7e3KFHyv>FSa-Oj?3E`mVP^CX(2pv<`tq+;lg-Qx1GruC z|I0EK7>0PM zsKShtCt-_!?ei~u^}ibLA?5e;)5$y_O8RR3>*V&b};lXtd#LdZr{|hQc1%@8`!mLvzK(wV*}85$Lr! zp)^ZUaO~icvf3jrIkeD&o;9ljY8qM2$@pw9ekV~60vmalb=-02ml(7wjM`oh*Q$Q! z8AbA%Q}$g<(I3vzxgGk=mmXCva=m4}1xddbR~hZUR{oT`M%f5pt02m?B?YhS(qE|l zFwl@xMkC&Teln_zE=@VwA9^f%EVcXB*jv#C?5@XzONOY}Sp?Wr4F+FS>FAk9UoWaT zzflmkbuCNCh@V~9v)gs#`}_u?R;Ju|ZXnki2dYuNb6-cbMxWh2UVAnzg+h8Q)vZwd zYSlSQwZ$PBGxt0!&1CVNTk0jxjG(%6w6cBc=k+P+q8UluHTiJG2DNYJKTI_=@Dg8@ zN|biVLSi6xo%h=4uiBCw#7K8~EamLjh=w5hH|&o(zDL#n&ttyluydf>e?=whxZ&q{ zTaJ9WADy)07L!I%9uF5TxqQ#Mzc++$FTdDr7q;=1AUuEK47MJvW3q&5WX<6dKIon* zt@I~IZ40)9o)9~{&!qDx+`*q^^>to>n)c8sr52H@2Fg&Qyv}-2#q(!W(}%XwT2|+ z=p@R+=R%57Hbg4~HE^)&AT^4m53#a@ftiIqBf6gq-?!z@&rI%zMd=A!>QtckN0U#> zf<4Qx%rVCq-lHiNJ`-kc3vuY5KHyy8y5wGSLGUURHWWXarvo-gz?=5~ zAXJO*uFg|w12M^4zCffzF0X3Qsv4N-4W%he|7NEij{-?7I*jA~e-*L2!H+L0@BOPnVwN33k z_p7+xjp_6Apb16Zu0vVRGr@`L(Nvk?g9I<6=jjo#8+ShKyxn)J50*N=QIf2z{%WE6 zS}o3FGhTc#k{nyrSNvYhE+<2E z&swhPMl}#MQ(<(X*(Gg@rorbgZp!<1SPJ7rfar>qt!~l-p&MT&DKtP|-cFL`eJR&c z#T~)Yj+)VB3v48yp~SmC$Gd1Tup(0xx8jwoG&b%R(d=QAvQzHRJW9yyk;r)P^n_hH z&;5#<14g$>#wP3j0fz5H-Rs>CbS7>sI(9nrkBkh};G{P-UvygPGAhZIf|C6lp9e{g zRqxwY;WOb&tF@^IhSS4zpT)4-P182Hve`9 z$BE~$TLz{gK}9OMGI@N|x$BQo>j#@uMJDb}Z zg2ul&^VV*#iGxgdS6z&N0?|^nMI;H{k3q2Df+ijwl(=fF!=JQIFXVu4_%@v-sRGad ze(T7oF14PZIHs8h0UT&ZV7IQHidS)Y zdBGyuj;6uEE#qt6Htf@}>Fjz@jV4Ky|JDcR{x*{gfXyY=h$W11i#&W_G%ZzjvDO(O zZd{1Uc8y-eQD5HLGX2l{{OZ0DZ!RNpdr)7SxBcVJ@Fj|V>|D7!n1^yQCw?A!a=PZk zF8ca-@!K+hzoxQffn5%{Co>i_Jt@jZ%w3YGR|i?c+_p|><^JzdwTA($NM1=wnATF=0s)$|x{e8pAAL#={yWGP z)ToTdFoXO8wWej$vSrx6mZj&m4aC!$j+3xuZ4U z0-da#Z!)w=dSc*eaZ?Ak0&1%MZa8(8Xh)6lI_Rp4Oi zA>CEVY9|4eXS`ZH9nN}Vk`VMc&Duei`qFc(|Mp;CCxIs}?b#|-b%L~l;(Le&LkcE0 zU4=bDMRx|h8x+C?!R(4jCD)KI{p@;IX~U7QZk@?e$%*$Hwc4Al zF3CXo<%bHS?V>mRmS%%ZkXoMVgvMRnLtMHhpHkAb&E~HiJ>Xu$Yhq-R*~XeWZq_<< z(rt3_ zlRhi1(qbQ~xC3{mD22(#guF%AO2I2ER=CZZ+*Dw9yR}yo4L`}VF4*u3kE>nJDsIm> zM>ds*A#_4S8?11SSHfA%i+jC*3v#!g?IY6Kb{;*u{g6D|{uDjCuv=dqoCl4mp;WjD z1n{T{#i&=Q{N|8(nf3WH+q8GEwPC$fJm|&$ns&{T<=(Gh=2P*XunO~OI~G4kZqAV) ztz8{!>*V_!m>|l$CS31~`nWoO&Ua+>x2)cQ?Z!qnKaS z-r?Bd>k4@pw~Euob5HBa78FIra`V5JbFq0@^V(Ro%YS7}sCyXqsuTXg_ov_ebLVvh zwXt56j#d0r&iiiot;$!&9!Ds2KK$Yz1wVpP3S_x+rx{*pP!Sf{y0ieepEGzUU$p!F@%K5LA$(QJsOFohl1FdZ7y?U=S^MRw3cO|)&6%w=Gz zMNHGNj5vJ0uR@E;$K5R|4EhrX>p^Q?>@jjiOW)1KrIY7&iU>-{+E#z9cCCylh?b(XypI*Eq^Do4 z+A73ZqkWZH#C;X-mJ;e0lA3esVnEzaqkXLS zSLlAVw=mv}t2iNI>~Dmx^(Pq_@cxdvc~3Qt>Ddyi9iJ6DdjZqs90JpmoRE0o)pF+j zehuOkV8z9HZn1Q1t7x@Qa}aRDOdkx*d?rT?8pD>1On?Yi*dH3RfAc`DRo`w81phft zeZxX3EiKI|S#2)bmL3#kji61(Y?X#zEIC-BMP1xISki58U(idh?Y-=ZK zS=euqN2&|iIs6~F8*JKQp`}BB?@6r`aDomz@KLDxW;a z`o4mhefNs_`l7?*`X$MHH*=Y);H?5uSuG{4bd0Lgb+|uQ6#4d7{?E8tHRqJLVOBEeOy z$C$M~G|=(Qhc`b6RU2*zPFaV!#g}?^>*jbgf*sDiFlY#R_!DjK;NtZnL#%!jN1-Pk z&N_bzKhxc;b>uGH|J_1p>v^B>)wj-LOZ~i4CiZ$p`(qAUmEIQbZ~8~Iu0 zqH|+)oLAn~d_stH>}E4XR9^GqGKP|K?eqivNNV=&E12G^T@-fk>K^+dKY0Zc<0iFd z1dLjrGqY1ICQlhB@MI^3bNJ!(Wj9GX`|YxUIy=p6)e2Kf>Ge5l+gGAnG2xsTHsUmE zknL@XFTrrgFgbSMto@*=vB%*6St)5&;Pr_FW}nuX?~TIH47=xL_E_ZE+{T)qAic81 z)M33Xj*j~X&;8+%DPx**%fo;hO1y7N_N)FnXq38)xnK$$I;B;{`wp&;mlbRK>lR)- zV%Cvk7qWB~_MaFj6oU-b_(*gsu_U?0bzhk;PERK&bG(2l6~M~vhYJhh>{11SmYZ&U zFO7oND4MjxWV@_C1q>Q8L5*b?b+22=xQP-cARTa9q^OmP$VK$w8dn0PK?MN z;%~=cQH$*myrq2X%S8E`heqYNU}wy@Nj_5RRW!KBe<;77);U;Xb1HeHX?XZbVllIS z<#S)4cLkyF`Z&Oyckhel)2BU>WmQjtFHPono*5d;46XHX$~uZV9KO|C&vy)iMRNqf zT!9yQL+2Scot}GiM7kea4bYCxSTu^N;?WHiQ<*vI95830WgbC4u@jbMk=ns2T$NJ$ zVn=-_yisax{++?qc)8Zk{<}Z#9_Mr_RGKvWA|V*}R_RXJ^Q4WKsZf)dQPp|RL~D6A z=8}qIspC0jZ{^S?M z-OLl#9kQNw^^fWdL93EHoSWiZ2;V0RMebJlHak%ha1pdx2~RKuof4P)eP3mCyqr@u!+5X;s8eg)l%L(hQsOUMFHnF^UG8%7)`(7W-d z^LBzcyy{{R5J&;;)(lovD`NuB+Q`$pCo`svsWuM{k4@fgLU^Q{Ag5p;ytlA{_2{Ic|3bS?dFZ6n$PN?U;^Kji2=CBI({I&TXP|ai; zZ#DQ2h{sl+(|I?|$nkNE8yP8H77?$i1`B#g8tx5$O&0FIYs^#oj^A%6cW9&C8zMZ= zF#l}!UVCpO*k=##-`c4}zK7ZTRIrrD=r7){+X#$zuhggK zzuzx&9mtJOMAw%3$O)TAc1q>?uj#wzDlY^;j#gaM?b?OxF-dRQz#oARW6jjVIN-{# zb74l-%CW2UEHBkWe4QFODz(-v)bH+9vQ%Cf@H7c_zFwyICO=T&KqGCTbj~wa0v=@Q zYBO~3^;{eLv402w_NoEIU4*nED@EAPb2qPuws11i^`9JnwXqSyTT)cMVCxson&P6q zpp>zae4>~jMSbat4rncE3VO_&O@4<(ki$=16qLv{z# z@EfnEmQ9LLjh}@T#co?FP(S1^Qk#b zpT%Y2-Z*dukM`X3!`5*pYi~)Pjny!96}~tr0MAA@ZkJlJWc^LJa+7Q9+#_jrp*LO+ z`MXonjjzuv#I|w%wRzYi#|wG0MYG%0y_L0RpQM*urmNcse&_|;+eBoOe6Zi33lkRB z;e5P0hf#4Pe@C~a;KQlICqExnaJ!4*l5Sa^16A6{Wle_=ZFuCcwlb(GJN;ij`+r}* zezBpFmY}2G+m6%_m5!S_COqf))n^@nq*Gtw4YhG4-p$gLAj-oZH)|WEEjDu8f_F z)p)yDwZnDll01o|tQfh+7_X^9rb7srvwZ^R+&PLF1*SeLwGaPFl7&K@?321|>Ois) zd&V4_kdM7g_+;t%zbU$ct*o$-`$2_qkj)-N!!trKsk81n&c>+*^r8vv6aLRFmN;V? z%X&JG=DSXpHEKjKC|Jz87Xq3TjccyIm&DK4rsty7NdOW zmq;ZCcX>_p_3g6H`7uyNkv@6O8^i~eDW`S^g4cvGFA{CJI*mBTh-rp$m1xA#DOahy z=i%qizQlB>GAHHuE93-cg8#L1qp?jubHPjObmwjiC&Q)|V)g$E(IV8e0>X;NB8?uIu zgP~ZMRhvJy#F%WZ&8ps8i zm;K@}39{0L8|hEInlrnr>arQMb`oBl|65LfutJRc|FHF@@le0@K^S8nOC?(9k6s1XJ0R}MG%Zt}LdcdnYCxL}~iW9q&)?%uB}=Qnm=X8WUBs8NKeo=L!e#FKQwcS z3zWk^-K^c#_6&?_>Z>p9|81iHI@$b5u%=%^G!Jq;%%t;j(8*7S}%r z^;2uP(x_1!0GBb~EcfT>zzOfa30QG$vRGoF1x{`7`OnkH4c3S!ro7^m4LnE95jcY~ z+z4y>dEwPLeeu9m0>Du56{+wQ5<$SXFxkfp-E2p-+XI0_1#pKaxH!I8>_cdIj*f?~ z9wPno-qGL%LPPL8_qwBfTZzjUK%YVgmK#g}!j;I$`dy1;3ecX0SxSS?G_W=H$EYHS z0etgOUzRZ&8!H%A6UHd4DJbnTC-r}NkTF4D@~=5kcs*aAXQ7)v;Da6VBq0)b(X5W+ZWqon5U<~YI0i|Bu>i8E3nbw@zgWp&Gid-lp|B=Fe z^Y;>#`5YzF`b;1(tzuQu+h+6el5ObG@?N1E)*AObI{Y&=UwQbyS@W7=@OY$p+tq@{ z`5FXBhAmfmUm8mjo66Kw#gpzyxHw#kCBxcPSKq7NvzQ*Z}k##^)Wy=|z{rqKF zG>Y}ba<=;z+p1?J=49I|zo)KelDSjvrhV1zdf})aAW@g1Xgw~GB<2&Yw|;N30I}H{N69xdC$Vy{;+JN0Yt<=2n=>*fy|JN_wxJdnR$| zwvmJ%Qts=69TUIM&g1sQd$>2hnI9?TzBt$Mxx94g+zmgkLaS`yb7_v(J-Uahz<%XC zbK{=OHMIhcsM_3bhnp&=?@8WK#`(PXB*c8`!CSk?V|V{S!zngrdOy+&YWz|C4Z;o0 zgIVk?UOyCUUrNBEeb?+GV{&cVc1PlvRZm#7PgqXWb19B&p02$sAX8E+fmv9&@bkj% z1#oRCj=OfU|ECYEP33R}0`*S-K^rrdmlecVf=px7K=`5$ffzgMk3lvuD`A!oMh(e& zy#^&qn2Y~u$S|0FDJRAhcX&=TlQeI!#O)r1BcbHb!RprYyHQ)OU#SQdCNbm%7taWX z=5G)Bw?Z+hAXpegWAC%Y`-QF_EO9aWXl|kJQKTd9?eF3bW{jB=8}(3|qmeRd<}l1` z=)lgvXc9{*E(D36+9ff}1o!%DFA;ov4RB7U!80C#7D^Lpl7b=Bfs0M^$(PTD9 z3S}8Dt*`^`;gL|*Z6F9aCs1xUYYEc=|AwXEOr_xK-=;2q^4tMmc=8TiXsB*sm1G*7 z-i)(V=>zcq1Q;=OluYGUst^stL8Ao2E~!3X1nRGetBJkD=dq}ulH{?$x*kSz(MI3q zV)2Ax%Z?Jty9BlSgfk)EOf(|-LuN@gITW=E82{6r-q|56JQI$S&u`kcglYcXrQU)r zmwJSt219?T^<#6Js*MqpntkcpQ*M=vu1@`m7c@778hv-@)#`uz^#>bQ2c6IXJ&-GG z1&0u545f1~W1+h(%7F!J&uncNDPjHXK9bbij4JKGk|28J?hviMcf2NR%(pgx4dNL4 zPBe79Z4rgLyoe2gK1#&w4n7cQIIQvN+}nG{Z+>mK7{h$gq87!GR+t$>FLU98GXP;3 zF1m%NS~?xE<>3x5HSTaf`zg2~5DP{YA^*{P)a z!izT(-EvzzI}w`%?JUnJMfQ^OtX7en=UvHc&V|X!ZHtuVh?=xxp&*|!$Lps(mBcQ; zz$3Mjnl~#<&-xVqm!{DhdqI`u3~b-yh8k%$XzI8*6Kvgv`~D2!`{RVHhW^%WT{@^Z z^iyB%u?~LGKkIogWeLs|8aD%ZzH-K)cr;Ig{iHhvSO=m1^}1|O$UYkWB98qq^-TU& zw=d@bwf^HoZH-)ymk&%@oFn`*=V9lS%iHXPyZUuH_IAo$NH2zR(}JjU=b*C@-X3*E zD2}h+%W*76llN~q+*Q`ND9r5>HGeVV<_*aJ>1I@t7Jouk8N}=q%4St3iW%#A7q({M zB9l0A+lBdvPE1B=+vDrY?UmxLjcO;xw}Niwl+NOrPsDF1UOLuMvF$u*@~Bjlk?ZNZ z^PJG?jEa< zk&Qp-Zsn8}@LkikhV`-WS}7|XX>IZ3zQG;P_o>y+B9-6m!f^7b7b#tJYViuD*E(h& z*y#JPWnZI`)Wpi(iFDXSpm)9&lD&4)udM9cvgfnqKatE!o_am?^Qnv>mc#V&>cJ?b z`;pj94dnpjqT#9P-RCY=Gk-<&d5T_!M6?AOX&n@vvbFQ|lG##CVxkKxb4h7j9 z|GL%v<+K;%F^4u6`)&U>U#u3+wts$baO*W|fAuE?PW}1($=@X$rqc2(`!eKKhj(#j z^)K@47%m%lKmhvs@(gauskR>lL{&(IFj2T2eLX?#- zBqx)USqV4bucglTH#-xcx{gI%VRM7wqH*b^GDLU}=GgD`0+4~D54m(gvqVIb6w}M7 zq>D4unA;!O&Q56kO+nixRDNxq3<=&@VoMV_%WHQQ$Fn=Q${nnQG9HT|uX5TVK z1RS@4M2{bHP9(C?$OJiK`jJOJ%pa$-YiY%xirk#?#RegrDbRcjj*}*$4a)p@A5J=@ zrm`Ox7L{^;r^ZGP7{$5t9cs#EtDZN2mMyl3T&uDE2gLzO9TuRV8#;j2fP zi0ebOm`0I&ytG#pTXL+M)8oKrw})6U7N#oV6j>wImR&uvveDfw?vQe!*1f$5H;`nt zR;!D4Xt-3T^UWGl>B!mfgizLEit0Pcq&41onDz8qzr$ZQ?)p=2%{h$lZwoq3HLHj{ zIU$*1awXYS^kLfo5G=J`cJ+CWTVJuk#zg5GR3eCm;=Fyf{V(XH4aW@UUW$PWtB^9d znz%|wUkO3)4kzs($l0uAI5&a%J-6DDo>}d8@DDDAWp$uR4N%V zjN{qf&gQaNmo%C@#Vm@oX{UiO&p{aCiry4U%aCB0{^U;D(DGCsr@Wb=u~CHap9 zGJ^~A$M9w*lu#}64>}r|Gw3|Hy5;v%f~%S@Qa zgtIoL4puIkJXdo$f1jI|^(~cB6eBC|Sy0K7XL;Y4Ly-?Zl_;H-zjn%(e23AhC3=i| zxIsWp(_W|TR-?Pz#Kg(bxd-4K2Idg`cSxP!%T!v>Gz*m9q1fJJ)|RVQl0& zLuEM0HdE&DkiGiLS$s#jGXe-ORqWV?sKXD>ruDxxeW~YXUnnBj>X$XXt@Xp>=&SWR zzP>1_uCr{W+k2Hj7g~5oH!^JT$Nn*Ve(&tJ`yzizsJ0}%8)~=%nLw0V>3N3KyjLu06Bdo~!gqm(yt!|@#M~FO;Z&IXhcgn_hm*xz$dT-4 z-Fejqfb`9=Hznc84{4}v?_Hd_3%Xrcmea*da$auDN&$@HU@QAtG~Vyg8XlLR1*)x% z2KaK?R40)|gYi-qpo8Q6Atl&0#W{_vD|#iZPIXdN;rmWTea~T5p_TKrIg{l5*OrYa zQgtmw^js70tU8@$miFyK7bZCqkE1xG&>Tz%#`z>zdqkQ`Kb?zU)^vi)e+?T-Utmb( zAD+izM#6I z(jGAs3v_IfG=@07wt+9B2?gxqGB^lA;TJ^B<}j$e!RN|hH_M>?cfcIm%Ore3(SLWK zjU5X%H!3}hcgOliI{PZ6V5U+xfXg;_$OSO;?fi`>^3p`&-8aWylkbkXp`9XMz0Ryy z$HK)03G#%G>TbVV1z+kBwKrOM89lY`&}Ux3`DS?k7B(wC2_Hq=wg9LsMlU20qrr5f zG&HG6p?19pfGyb=Dt~B~)be%KkYc3}+tq!qq>=?1Bbzfy>+rS59?Sm80owHU>M=V* zRMEFUXF|Xy!;8=A-lI%*0ArC4y=*f5%l3Vp z+TFjsTI0Bdmb=VD5n>x;IEsV6!Z5@A!?THiCnXn7J=noIe8$;%--iub+pbU7FZRn- z0P@m&+Kcj2&!5!FjuN|yyggWCE^_Oas*le$bJws}Mv<Y(ZA#M zcA^A=9~W{Tt+#KyClK))z5NKqK;yew#)gHCX~t)qmC&K-#E-vz^7zFG-=sQ|uii~& z?0M~}SOH&%a&50>WLBV8)4B51yRYT1W2=wOMr{RIUH1BP!^bK`{h6ajI)(|uo&z&? zB;G#dDjafIc%(}!NX zxF;SIY3u&_hR7p$?VheD+T)XsF_2gh9y1>-UD*Hj(mdTs)#m+Xsh%jFA?2F4rKO8n zqT5H*ow7$!kB$mwd(EAZF0oEXq%P$I-E~_pQM%O2$7f$;KVmMh`?-wtqx#M9Xn753 zJBG&0lJS}|mWFZh6Csde15wWG;88>uOO%V`HZ5J#wn~2_Cq3@h?n=`m$F-0%-CCnn zT56 zhYXqPCC7Zp7WvmP?X$vv-`2SGTVAddfeV&#tu+q-%1S#Opr;q;IiZJ0Hbwu=d16@V z&VXS@fzFhZ572f|qzS5^%PhtCOX(lPP?#8@SrhAIF2dX11QgRbh$b{e-W}R|XB#-Z zY`kJB(J#vSyVe`&x=VMX!a56>_z)yx@_$kg%e-+wrgTm8a6(XnB#{HrQc!0ff~pEa zUStcv?`+3$I=H{zn2+Oac5DQ;@*JU>haKN3MNJT5A`?k;I#|Led!k$T?7|21^}$)* z1044!gdLYn7@aKdw| z;W1R`+n;^~gDL`nWzA?PT|08ey@+227~+>5%W>@`_?xXaU#A+p|Cl@GFY?#dTp|3PI6 zsK_R}H{|Z0t%{Wi5dosHDGsWQ8#lqY_1e0tu2*fPmG73noGXL9Z&f#p>-E?@;_*$&vrlXV ze>L-0)kIsDm`|!Y872V9gzo2WFZ9`AlTCiHb?a6QRO@nYl%IanV8BgV`Oso@7WfoA zf|x0pE$m1`rs_Yf-Dl`3`f{(IkA^%u<*4wc`SRSt_AM>58zj4M`naRll&sCyz|2dh zuAH+p9cEO->J%uNu~r`nj(a@6kF}Cbx%xV{3}CxR%GZ^i7KmP-dwVbzKALa-Qhw=~ zAni??7_#hZPRR!;nYqB)dQ!ms_68lZu8%oU_Cr58sh%)C81DtJ&CKO+7v%|832 z3j6%9_||cTeXq&I%TDysRl3o`2lI-er>qj*n_P-d@5z2(vuFI~f~9VRi+T6s*Kv;F zo1eaY*b;asBMRMkuIOP{^T;_cSW+=(_0)*8iw$~RpzSwq!q!;33&_APnd#KTk1EwP zDma9EfBHkqxo)^p^pVY#*&F%^gKGCt5rt30^a#PCcS54Efk{MJly&wV;aZE5(Jf^5 z%vU@@=dnxu|4|0LraG(tHXYh zfOYVFn;nJ}-)(FE5_`RSbr*hrxVFYJ@S56fqn4K8jCdxNrs7=B#(XiJuVPN>+uqq+ zE}8Sqkh)BB{*2j`rxc~i42=J4y^*J~BDiKZUNFi(&nG($4<+ND+kI`St$*?Bk8PKy zgY1KDl9TgTSv${V+c%^=^IKUqSLk}?HfC$b%r>7kTZHI+WS)(NX(bqneta(cVdKgZ z(mmhZ&spyS#!Rd&qE&v#TAGqO>=oiIN3&fX*qei*M2a=9?2Q;o{u=+A0V$@mS?7xG z>^C&IB)a~)?cZhIk4_9Me$o29dG4jx0lT~_e~SO3Ss}975(sYH+!9e}WyEhHvj8^9 zhttE>4y-S{-or%rFt~8!-70|CSas={WyLdV=JMCy(@-26Tu0ucgbvE1uGBk!yl(&4 zcgvmYw}GG(LVW>^ci{wsq&~?B@^5Xy1O)^yNO^*R0}`P0W?sojMgo)#+}UeJ-F!TR z*4`u@urEzk^gaB{E2v~3G*mp(gpGxcQ;)pwIp-LvJ4kgBMa^dCK5G~v{8cnATPBPUOwwID6cS322M&JLQ9q{U?@^OenBL%W>0KI)>o}` z>2|&ak|`%m6yZ=4*<|3jeR5e}0NKJfpPf3nJ6J!SH{|C1$&eU6xNffM@CYpkT)1lV zsr;tCN+xFci}($`ts*}3@i@T304Q(rg4Q_@P~D+$>f%0XIi#^E?At{Krg7(I3I-RD z7lxxbdm6P8u(2zqd@F_&DMq(i+znREwej!K{);$f`Vc5=a})?ZAX*Rx&CTw^VlYHfjk&T>11Iowg!z#SdGU1Pc+PGHOGOu)sg(6||ddil8zp7wipv_i^VFUpCoyhZ)eIT|AkJONQDIIC(98(_FJM7p`A!uu&QWx?w22N+#&#qKc}rRTL2ok*P);iqPz;N?-Nz0 zAg}=P(NlgtzCD;IxojdRC2(97cu+Od+$c?DZ3e?pKxp%gjQ?9mWKfjm=)X*p+MSQ7 zBLjq8GfszD!Kh>EU`gR{pg;$fsy`u({Q$Z^3LPc#5?&fo1s5V8dP;g=bx`=c8g5Y2 zcAEp7owPtuhXvE!Bq?wdhZwS27-Eb@QycNXhKS!PUNnZn!E)RmN@WtMi{YiANNWA6 zXy|&l)O$%9f@&-q&U(-81E9X1H4=wE6SGH}EVMs6a&-Lbl zGGF^9)&)HZ_%vR4{CuiaEf>AwvVi-#S#kEmkEfkwUDlW7gz+@e;HF=nVn(y)q=Mw> zimP_Cr#-TzS>-98Y&PB7z7gQF3i`X>Gx1lmj`Z0D6@NNmm2h>|?=f<#H0BkiQ;^AP z+os30KHPLc76l#o6T&wWz+t0fQU8R%^zI&dXgwz{_TdTAd=LA8eYE?b{gW#ya58}79|6Vqa>0ZP4Yh2# zO0Y)WuM}C^KD!quKA~P`YF^)?U+M^ooQz!iqR{v@5@-HVL+^AIni9W$?R74ncug)J zWj=(}#(!L2SFEk;$a~L&iuga8=3|?!XM>B=@3}mF^IK!{b1@g%qJ1_F_Snt7-AzZ0 z^;4#KLprWzok!>ywY2RbTWCK>Km;CT?P*gLxzkbdqIH(YQ@eU7+=y+bDFx~74qkeY zWM&(7gv>hq)^k#ENPmRQ45zX>`zmylPo)bY-IQmdXY??FKfvQq`9zo zNi-%Hf;H`whXXM#bE2GpJ@s2NE9>J?;GX@(!?eUMSv`rAAQJXW4Jco6v%<&<^3_-Kka)&%&R6ts(Z9F zYk;;J7s`r(SMn|EOSOaAourd2EJ+ zj<5SKo3wo{J%$M7g!)A<(4n^_iBsUZQ1COTd1h(GM{Bri2>haXu|sWnHMs`WAR1(e z6>1sef{}DMZ4Rx9kCWLahO#kyS~LbO-~K@?O(gQ4gC*Nz!0M&Y7&Oii2mse zNu0*!3>JysE%bwFKPJ9MF)O2H7F$m%D(Fj_;UJyxMeQ*^)m`vz!+`b)cjsN*-yKM% z6ebD(t==g8Q<_oWjB=YlAao&w(mqSlAhOr^_RxqkrRGiOK>t8Ht^jq>4e4_5EOXZ! zq4o}7hzxpg%~HHbA5(Wh)x9C^DDZU)uIH3*(t6Gh26kr%TnkXkF+X`6SeNZke`!6Z z74+JWM0hi;YcC>ADBB+s3%k;DAZZy>(AjbDI`3Q2w`oar^% z`??IM4&x`VgW>PNR9qMWJw9%3oKHcV3 z=O4txvRuRbvB-t{|Fau<((u1Y#!rcbKoIi3UO#UY_rovbb#Y$(_7B3~ z=KFN*Peh4cz_<8a>F9kIU9vXF^WTQ(zYDY?XC*}n$2C$^+c}ZVov8M`^qcrAOj-fd zCtV{=ug`>h45~UJ^y=KSVl%$uC}(;FHk%jjJ<)UKl5%H4DLuKLGh2?bfs#wML+G@x zMicsK+4CEzE>m@#3ka1`!xWB-^Xc)m;vLX&{H2p2y^2jQEhuk>2CBImQX*Ui(Ldea zH;Y62?ZZ^qsjLll(C)LezVD|!pJo{U5mMR;ek^vyC@$d_^JJy=ou0pjC$+@i+yZ;| z&yVQXn3Hzr$|bCg9!#fv<-VzZ+M4Z&sr1<8v&y{CmU_f_0gCn^m%r(?D6xB&sF(bc z-iLm^_27o9D@E?9_Gr(tHBb4OiGF=?+4}6;SOMy1gzOh}n}{TBL)0Dj8S#UqesP9I z&&Qn_tr8&9v43b)C#YZ|*XJRxfQ`}?d}-M4uPxbdc&8{4+yM)J9DD^it!x$d2{N74 zDC3QM)i+EGPY`WhAk&j$Fo<7=NX6Ma)vW@dK)R2C7uZ;{ngf8s7m~$RBl|dk*m0f?-Vi0{qcW8C*?Z&ad^-&^V zWNj6|kwL|9U~u_$5db3kS$-&C5wx?KHi*@JQ$G_mGQwPA*Ai;xE2R|Csr92uSV+h~ zWuX$zi(K+lJ0ewtcZzY;}4k~e`}iHO|Xm*!9;gzbMKF@u#4hE?kOqz$0zwodR$!AO3swy6HQpD-}> z)HMU3wVk3b!ScTsw@I5`q&xk!h2)h+Ne-bFiJ^fo7+(Qbv$;}~5w2N8sIg4-JxxV8 zY&)C)!DCE_9bZjxx!eapH>W4I_g@JILb(J8mWM?k^MCO} zj-}K31ZFk-fjb0>?=r*g;pLpTyS|V3 zQWPnjTj^Jg&dt%2P-_Wa4ki8?M>u5~WB1v8z5iq|e(|1BWKQ>HxpQ2u-;Jy}f7DJv zOUnC=g6$=zVwXyjx@^zl{i5D4q z;a_C|tp*tYP$%#Qw3SN9DQMcsj4R}&r%LqlJ?dS&`4KybyI0lr;3{|T2YugWJf~Uc z)hoDOtaYbWVAhr7UIJ}I%Gx`lM*nt3*rQWK@mN{D9i0+PMRV@N;Xeq+BAJRUMIgUQ zW!Fw)IR>a0|DOaSVGGk4Ar-Xi&!x~v943U;C)<#$lRBJPc{*foY@mHBP6WAtM5T7Z zntm`wzA`iH4jDyy?L>G$E?m-Ccyf2oJHXlST*;X)A{? z)Z=UnKy?DBjG=kjBst*lx?5@`-OC3g``%t%>kMC^V=HeQ4wk&&)*;-ty#^YEzF|*6(ae4 zu>!Let5hFvANmQI?hNbi4+Sz)C!j(HSe+8^9v(KI0YFrDREpd5&RH60W8oXc?a0#9 zWbmwV+(RD=OEoeC$^0tf$@SuWclC`TaS%G={kDQrFwB#ZM6%g>1p*qU=|*g9dk@y& zw)x1Kfd|(rh4ZtNj4AB)7YKduXl?EJjGB>yu+B}pYEYMV< zInnoMBK*NW-qA$hD9dUS@eGaOtRoRCqBNC)%@s@*QE>bp)LD{~r06ah%udp!XAu|R z01YT2^c6{-(#pW@G~P@j8laO{Mk(?mcJ$Pq^9_SsK9%o(giF_{3cTDNj1ONdg3K9? zw;2{4thJ>@pmUiRko?}iB82H_Y!($A}Rzix@2+WP8d$x_E9{TT6Mo03}R= z!^uKv#ct@j>n0r_d+poiE?Hl|NsZZxWYsRCQ|LA+&#$d|rbrr;S0y2OK>V*x$<(loSnBq>Z zxZ=QcQryZP$@A%sv49_(aQj36K1i^c|CvJ1Ty0NXF8IG10i!3sr_8Wfmx*k@Ncsxj zHH7~;$G@`CN3RKepr_s#vDbDo^&c%xD`T9Mso1>U>c-xSd_=R+3c9tjQ*Mm2cXh&A zFZCEDO}R@XpURPPb+uWzHMHte4BHAFWSGb3l<$=H9IV!$Rqn&&=t(S(?o;$GeQSlB zNTHHFjSR6K9gO~YwRq3N6^*CqFMvd|=~|^}GbLolU0me)>plAXO-~-1(Q#pEq=#7< zL+-^g$}vc?&+hIkS#fyM5@O4L-8wAp6Xv7<`H2@o86P1K0wx@0&!HBdeO(g9XlQ(GMpWj`yzAgN#L_uLa@+H-s7a@MQTgnl$I*2TTmncW_ zhzL?N7kdz^^eUB-sCJz5$(JDbv;{!IaI|yG7i7*n5prjUX6FS@jgF$bhH1FFh+Dya z*@`aLjp~V1Z^2;NJ}`t|*x{k@)^6Dlb!Bp9f&xp!l$?nn%RMa6M039Z@~6dUR*Sl? zA@F-^I^v){dQz-70{EMS(zsKC3!5cF0}-^-($d7B0%wYEs~jW>0uOb?&0=H*1rUxn zYM`wroC}GFqxg?3P#s$aCM!?CI26|J(B8Kx)cz`n#A$=7n$!;|puAHNjsx5>V@3$J zVw6`CHZT#(fX_=40xO_zsxAiQ^$&7GbHpdEg-2FOsWWdCA7PT}MA11L!OY)r8u%EB zXezGhyT45k2(c(|igGz|u0dhZOwi*zim8;mRV>dt7Ad@7wo#IoRpG#<^JHDqr*SZakA);gq5 zZdZQ2gH8xGbaS5+Ue)m7X#I42=+CVyPvSO@tHRN5xTMtv2Xj9jwzeXD741 zlylK|JgBdvicxU_{>z;Hli2D%#s#|+TZlShqj zw!TVyG`(W8h+#NSb`uV%1veBwek;MB*&{m~$5;9e{EV%31G;6WE1i1{Uw6urTLiY> zE`X$3byev}Wq)G`HkOAdf4ZCL$$ZY?mAVXFzIn{dRLMgBsKWaNp5RvAPFAE_lhr+> zu9VQtz!jH%ud3SS;V93wXOAL6ggfw)23ks@49{D_HV?Y)w;msm>>T&m^NPVe*_7RB#ze z1FR;v8ID=0m%ywrxKV12L=z)61rbG-nU$i8Se?M4CccGIq)Uz^q@joU9JchJ3L zBXB4){3(5#;cr3GMT=o_5|hYrxPXs_lsG!Ot|0NRKR|}-iLPjCre)t>ATgrJBo59x znmC_OTI~9oF6<(eplTb!w^j1I7;e}b;XRx*b+`CCSVxWhtRi{L*_{n{8t6hBrOCPP zua7PO}OF@yGILH>(dg^G6aFa2@TuDDX4h}XBQ+1$M zW7$CR2IniBj~_6LTjbGidMf}yFjzb0@x5ah-4)5N#67wu-ZuNIT@)9vq_ryHdn4cfVtlk0n?^rbR-?pHQm z+>ehk-NT)7g-Bre=&3b7!TN9v~a23f`!Cc!_T?@gT_i04B@dJ5c|MlU#k|sI2G>`*(^1 zcd&1tYj>Wi2D1kIA8M@X(Faxr=EftR?{uHjbWt9z7pYneeL+w7)T?{J_sd(tBSt6K zw&i>7=vY*el5u!fVCwpv^Q3_sC*%|9o4Zt-PW2(&4Z_f|0;|}Cc^=PLn?e_Y%99H} zs$OI`SWO3hb_%hr_G-1R&bvsxd_Eavno?!ShT&^f^MTK4rQ<3{-Cd-{x0_6U3UOt( zyJooVd1oaCc*M^s_qgZCh8zHmb}7<0p1VwTD|pd7@9fGExj&y8=Y@Y-x57LPn?(+O z^1HBA3k`iAfnml!`Wnk+s{1zFUp2b0@m4hF_hGf!q3Y!Xt3j3v^vxaD^WI4c_8oH> zGi5tXVAXI}chMmD*7akLfArtiqNgnYObGK@VIO&b|ZpkrgSG1yi$cNF(F-D`&+U$<9t#O{gWLh71PRHBF8?I7CB{`V*nGe;y% zig$)i*#WzIMilo%>Mt5-e!KIsanc0Kv~ZlD0Y`TN8H#fYdZH{OhoWD_@Bc$@>@Si7 zlwX}yp%pOpX@ydTihmC$0lL0m31!UUn|pC{Z=@~D$zSN)a^Jog{gCkqA_wAEVsG~6 zcYT%8A{;f`b;kj?KLlLNIlC4t)AL7C^P0*@1;-4>5WfJ9&21u$fkRJHlyDzb@(1%ih2UQ+MJbGB$bKs8kKN;1@zQPLp| zzKD?k3zzDsJM02|1s$cYhX2pNYf^JOu@dmHu$WLfEV-FBYJkEAIJWPa%L_`;iVK() z*1`t$ebo2q4=Z$-4=O)e2&S&DYU4Y<5tF-uUSgRE(+;~%YLr1IM(&k zjw|^S+rz!V8t#{Qw>k%~dNu;M8P&~J0yD!Z*eH~?8J@vt1nMa4)u}qO?+1|5!+scz0(%Ooc=JS+}`e4?PzrAXk`ds2XC4?Hy?@` zsCqoO=Dt}(c%m=n{)Z#<@ZCYE-N(PD?C;T2y_;;Wm?F@HXDF4X-~Z}4b7=mevBWJY z*tA@^9lyASdk#hX>N$ITPr`b{Pn%8QvdgO+jEm%!+x)i)8c75NPhPkF(`*o31Yb6g zPZt-n*Ss;ElsoS6Qs?*UBch30rn0t|&m3-Er3L3YNVAzF$0LxZEek9CsF!+S5I1FP zDEjjQ_5D}sjOh~9Hw9HI6ySoJP6HX+X1y5rixa zi{nY(%EmNg7M)KDw_2|>GX<+v*a%iHYQM12JvBDnk2;}CT0y_#Ui?%#dTs2?-w9(w zuB6BA+bI8?%RG6e14Gtvw^Piz!^4I?ITvxb3{%`&8(WT3OWnT~fbv2i-XzzA>e~pGYh;7W>k>Hrjl~NH5 zuCkeItxZm<4SYUkKyi?F@%G~6sdsrY;=w4_)R%rvt08;tZn)G)uhpF3r)F34&~;sA z#4RtxCX)3CjGpn|UM1WenxfO;U?YACQ2YZ5v_~mJO=UfbF$_uJQZuOUnQ(g2Q_+He zVv)bgxQmutx#cFJ?bF(8V5?9A2BR}bH!9||zQ$nxrWmnZ28TSG3v5_%7WC96rlTe+t&Dfy#i`_7qdKAK-~a(G zBp@BS3mjcqUbOv=Ux&l263OO^Rbj}2Eg*@$R7G9_Tpx7i|CScT{H5#)~Fa&|DwfnNKg|`K;SsV*YGGePX@N% zfYdLzXf|Gq9Er{zC2HMEqzURNP>P5eOri@18MIyehz^;&PO{v(ula5``_I%2Zz*|2 zEAdZp+gZ+1^vp&{lBz>QT7gT!emUhk*miTI!4@&){7~@T$X4kV`eV*|eyHC{A8&zf z^`C=D4@E9w454l&U2!27u{XYTNbhrmGL2)N@7yX{ zVz#M2Fn69~jXN{&*(*VM)zZy;L@e&cao5O`cg-hdQRU23`BRp)^HqVAR3&@W`dY1x z_y0fdzt`(J7<2!3TcH!$Q`Hs8sv`40;_CkYW0+Dnpf!sM8NK^gph@#mRZw-+Lx5OI z3iD3{xyApYB~$-RQbM+niXu!iLN}}$op!rb)U3o-c5Tvb!#)bddOdxFY>&7c)Y*ib zY4XFnJ+VHo$N!TtOTs4%A6=TF98~r|;)aon`b+$!zGxr5^tZRIuFRmm*-YaSo@@ou zYb|=j%Ey!cBwFBFC=q|xGUCzbFp3P;KZUhSe7iiCLr+t@{=V9Cf|B9!#56gBGh~K} z)Y^m5Q)w=+zo{0-SQex3>D~2uPQCTw^JNP1_zL;@qP=|NfewUHuWG*Adld$A8j;M^@8%4XE2>wa&Upy$p#kKWGxvx?&XHW>Azr0i;t?= zAM?jFvnj*hZ5HK(uhElWZG@1&1v+>3>PsU}I!q2{$MKHif*rHzQSqyqYs+S9Cc?po zXy5$xWxVKR5lGrkgHSMAiwiLS_^b)RTcnQfXW;H@5@bIIpgxdUFIgzoUt0y~0zVar zgMeez91GV>d(_;1sDWji`L;nDH=>t1U?vWD_mXr1>rru_Lt+ZqQCZROngU^q3F0=L%h7W;; z>Y#P(P;o#X`gq?&tLS|nPTFaMN@!+v^Dhk?AVupoThEE?@;gq08_cDkfHh3aT>IOEbmmrozfum3D3z; zBA1V}zk!G9>8OOZlQhOzbA>4FHg<)hLv#)Wqlu(D#ZahuXnv*0OtKM~)rqe#W|(xA z;doS!6kIluPBNxL@TlY-=^xT+_*4oQdmtZypOF(8Sn6{k^$>sufL^jDKY@1#?8F$q zC$Z|Ap##xGf6Sr@v0&FC>EoPQoNyepz}~3211yayJMJ9|RCjUjo*c^ur!%I`UREoE zJxAQ7lanWs!ux#>eT`kjMWP1Rta8iC+l7XvJKK~)`xR!Qa_$r`;HJDZm|$0;b#gdZ z#8-!z%fFu(m*6*=mA$^&5H&eh9+n{P@DH+hF^Ci>e;YAiuzo?~+TN?UfbVkpo}C1? zK-8~~TQ59;?a=pXe{zAZ^R)onl+?6NzOTutp@B=Zi*H`CR5@IGa8Fm1@6g(2 zo=a54;i63pH>vFg@Jkh&l(Zh7D60<CFCv;-r=b2s+hmJnzJ@FzcQB7KejY)W;aDu+uq;tVA?(WYbP`I{aR*0 zAkqnzKZj$1uTmjIx{SddGCNtJ{`3FG)|-Yy`N!|y*BBuQWfa*XOtOWHb%wq%cE(ny zgfK)HTVxM4ja~NLSc_7G5RxUb4N~@9$WCOL?oYqpaUb__{O|t*Pdpf7mg{yA2oWTC# ze-ILVS%E$EmWeGfrDSYeW+$IHgH`ie@r4WLnS4mx$0MdbwCqA>r5IM#>|IX^Zjwd7 zK9K1Jo5iqsh_Ji6!zoK0PEs3d&0S1h&ai}RT{b`d++AC2VuX@+sthRto={1O*LpSG zO7G55;324v94nXNib4+#%Xw@eFh0a^3g=yytlNHR>{vaGc zJV)M#b0(SH`~rr7k6L=NgAvmN)T2HY1n&zLqpkdh+M7H>sW;23tw!Xbb7LJrKU{Z* zEqhOoe;6C7h(FJ5=TUb2?X@iJnG72DC5sDYC8{q_@sN-%d;B$59)Irsz(_eO^v%qD z1x_AhK&jHB=?~R9>E7a}4oFwC*Q&6JGf&(qA)<6Q=S)%x1M{P9c$lUvtXqmEz>z-2 ziKPJXggZeKwXUOsY1?b%Dc)OEJ1_)Rx*Uov3Gkvz4hNYPa^TgnsRirZ{3{qb-xW<` zwPn#5F7P^XLceaxShL zZTnOIcMHLBro9U*MTfL3p9_xM_>f#WvEWwsCv%HAMu3N9`zOe-2G#n!-o zn7^b=h~CL=27;x{1p^*O70|y0%n<6VDTNi?v_YN$sN4_PWm2pZwvjMOSjIxiX+HlL z!2b9CMRG5< zOP)UkP1K)cnkics0XW)cvH)`M;wYqXuPtdW1D(NseZjf|TJydIRPI#}O3wb40Au0P zhW+scEtp;VINnCNbF}oKT1#2ZY^G`-g#$hxbymH1gRR~isr?I?jh$^2H!&(u`T9v} z^n)=&O9^;mvx=B8E0nmzI?-MBUUB9GF{|E@dp$veBtT0sxD{4_UwM*VthF*1b9{2; z+J~hh(W#QnH+e)cbsC~5=;Hg|A6gaQhWay*@)sHal*c|??d-${aRvunfZ6E%pI^NB z7o}2_y@SKpH2Oa*vzN(t)_r^W3wQeaG>UPe$jCeIwV`#g?bfT#+M}R@p)YDqy_Rf8 zsQmwEjDyw2zmy=}poA7zjNS&fUq);jz}~tYQ&+E}g5M_Z%6=0H|MPJhcRAr=ysDE1 z{i*iukfUO5AIN_;?S;k=El(8#qSeQvlT@1Wr{cOsw9p(Yrbk-W6z+Zf@uvbt?9Oj8 z17>#JCh4*N5B;nE!+GInOrDI`|Lma}r_x9AhQ~RtDLj0=4 z>Px|55F#%WO0w310=}6S@=Lmf_$yYSRQ~IU(HAJ=JUExyyJFVP82G|KchNwDXFlOC zWcM<7liKZ_;W1_u>pitO60Bf#ybLJEWNaS_q@yc0G3|SRG0u#BLiJ?QA1unV`JG2p*#z?kHzg~P zDJ~>U3bUk33pNZPr0wAb;J2Ityr^JJ zCKBkpx+mK7gbj*TG{^52fISX|$4`#i_WhV4@P4pGEC976hb3J$bvDBg#Z{pW&93wH zBrmi%9=_Zm^E+e&W%M<%AR3VJ{SVuw634ZQ|fKu#%Dln zozqZ@OO0cOtb#9icG&Jdj``*3XAoJrYBAXzW>hmt(mMM&B$3J^+CZsSvXx8-C~=bR z&}PG}oVnACFFqmkQd>%Mn({oQ^XkVZG<*y! zb)`;!p@^V;;$6v4=@rK%B}qGDKmJ1fUQ(NaC7nM%*sT6;wHR7MS1KbU^eUyahqdc$ ztXN(UiRM?GjATa8CnYBbz4(Jhu7L1dvEa!y=L^CHJ#`qn-g3qF^qXgH zbhso|y%e*I5+1dph{tniQ-6y#aT)BrL3NZ=X1}r6*V`4#ymo4VEs@to@Z8+R`KOaMMBGIt9-ZmIOmlTfon>bmRIq*e` zX{u4oZw;w_ov(j7{57#;ZZYqhXJl7Y25HsQ8eRWYaoF5PYNI#u>?rN>`J%5c%rk43 zRWoSWMNIKqFU5c8uNZASCUkQ-ZeiI|b>l=CNBvg+v}%@r$0r?lzwjxrNHN=tzOKYw z!Z{~>G2wRqMT)Xak)W{aT(ZpjHMOm1^QESu6);$X zmQH$`(OsOhN*03mI+?2o3;L(;I4LILpwlGirM2v|0hQM;}&`M|j8 zH@Ufou#F3cSHXEeN6APCh8v_ZMLAU~i6|cYqp1uWBn5}5i>fto%8DvjF=gOpb1x=v za&PbET)6gF1>9&H?yx5af4gt;nB_yu{>v&sJpWk?ZCLb7{SX%|jT)`>;qb$pajr7a zlg#(4ABtBC%S&$bS1isTe{5ffY~U+{>}E)tY0Q{a4L>8IZm9c>CU4PIED|4_`LmnH zu@&N6k7*-qxU22vj|4NtY&kYBX^kZFX+tMDev^gv3TD%!CxRKTtIZM>iI8Z10S8Z0 zD-DgCj8;gRm7603hC5-+J7{eSnV*4)>ESe|D?LP4h5){gN#A`U*?mO=^hWQ1M^k)U z8SG988>H9-Gi|PGNTG6UIeQVHq`;OLRzN;5bkoB!_#ca^I35^2QYmJ|fkSS->;*`M zlBR(l9H8=jOJh45yNC#sm0ot_h)mGCR1u3D*8*qV(KO6w<&yRS+U**n4A3vW%UR@p zS}?l4&vzPca51jrDSj%jGQ$Bhr*3dn9}Xs_USwrhEb_a@_c`c-`B zO1qWD&F%khqgJNpYqJ2(4!ZQzh~4DdZvX0|{{JQ&*!pd{r!s}|@MHg=pGd1e>$jOB z+zTq&f&wQGX#S@zAhInAf{RIdb2(rAo}Bbs{j+PPS>-I}WqAkpQwQI?LQ8ZP7yMH> z8^;aBlA@Cx%AQfAH4>yH0?CwX?D~p>xQ8R^v+E|rWoQhh@T%w9lN0}?0Bc}7KtC14h`!_3mur)of}M;U^&jp(3s-lm|Za{4GGjdmil8+Dilwea_Mnz z6}lzw#2Rf0rhw9yl6-!7L|L6G{uA~I3o}(kwO4_31+%L`%co6>Tdi+V*$wnLDh#z( zC%Vk(Cwjkq`0+)&DK4yAAsSY=2w(RE9Gv?l3@o>QkVOQS^r@a>oBM_|vspXoT0AB0 z?cLFp8OO_Xs5FN4R_FjM!gJ!j&mw{!S4zOla@-VD=q>1w`M_Q3-k}sA3fwSs^r3`7 z9BCE`GY6Ak-v`xfN_;H0=O0Jm*cL%V5X(e<8G=Fd2r1JlN|PdRm7rF@ zNmhAOD2%XA5b=_9y8ecHA^6df+8wtW!de#Iu=620dp984{bD}im6Ip;=RTDfMY`r%J`l#?6J&x8YXzlAH z$!^T|?QgN7+%^etO0vo(CKle?{f)F$S(zSbMd7I3Z51tyS)*jc624{SBaV@6u?cC? z80M(QU;21|ojlSPi~J@B4+z{2Rer0^-#%{2ckH)ZWts0l9_!3syuX#tK^0!Ixd|4om(eIfnXgQiI{<%GdKAId!bFj138632 zmWk8jeo7M3m*vFrxo<0}94qyhC)I<4DFR9JiSyA4f}2$Jd^c}P z897N8xz`Bsg(9hlFJvpRSj0tAX~M3E9A)CRW3^vd!=K^VXSt$A2$~#_O?G->_AQXN zZ*_6#3V&T=-Girv{Eu`hr`7mZ;UT*Zox&gM6@`UNkDfKya|QbVMh*?}mw7Db4GPDd z+$QkJn_sSc-#&M(ZP;iFt(qz3d~*QwNrF_awx$8inM=wIbvUQ{C;O&I-Lg@KZ6i*MA-qb*B0YPyTZUO%rn`kXhox_) z@-H6eeP;R0WGa68uGXeFHQBT6=9*h`#@riaCTh+Q0H}=b!!^hDc^!|Z1m|t|vI47e z9|>6uM^1m6jS#L2VIsVy-5etP`hM?Mz_NLYO8HaSASRXSXZPi~!o$NJ#jPnTdEo+s zsZN)FnN=)X{5trUg9+`Zc%DV`S|Da1!ML@gVLtQ8gK#@}hWHY}y%ZrkK9AJWJCcLb z6;;o%L^}=lj~)zP)JExRsV3{+ANLsGUK5Mr|3aTeZue^#%eBRa#o=GfSFP<4+@q7TRAUpATFvPktTZW6Qgq@B66w1a`m??Xz!wgp|+q{8boj z7uLpt${~eCRf@G#+MCeA`iSy5BkV&lhr)47Pur7ZDN4MF8(o>rVEU1AZxTcxWHXGS z{cyAN6QMAUyjiR+&J77Hn+3fM0#C681w44bTIC8hir2iC25a|&pBW&sGQfU`f_0lw zuitr+wXsB#BHPFZmQx1v%kgS$5*K^=CMD*|A9KIxIC9p!9+zM-@Kg!?*fjZg+IaBO z+daT5UI6rlO>z{}vfO~_;scvYle~=s3 zC!j=?9nc09?1o_FXvvLZGHzEv7FAQ82*_yqodkkyCU94UQ&;7cy$b{j_z%Z}E?j5z zDol7GyAIrlkpol$qc?1V@i&Gstogmi*mT0ivT{3#gC3n)V;11aAkAe%(0e9W4M#y zTClpVF}>0%4dYwIZI62K7bvq4uLCQKGV@N6KnyiZkHhTOWi^IL3hC_Rx>4tjg+a1P zMcq!0HND`scV6Lq4jpr|)IVkXz9R% z<_R}-2o-{YmI}3zaO%x}@||L(Tzp_Z-T#~HS}EuIzb+$TEZRRk2~pzTciH}}9(%KP zDR?+lXv&@1aPSwZljFT}Z(pEGRqPG^WR6IQ=GCip;<9==)xRB)gK)9wj$OojQ5{8 z=oGr1J2|X0*Mq+BUh`{SDSoNiAj)$6q4%-VsOORMTTP+r^O@rZICxFOF8QcL!##p5 z;NB_#7&KBcl;DZff_wBEn@h(?|HA=&rM0Dr#LT?dRz9B%a0w|znHEvK)Y(*)@FI2*+HF|1AUazO)uu$ zvCvKdpV!CG=t=K%YY`_a3NsyE$&kN^+dg_QXS2l}3$8@s0{IPyCOY?ZJ>!@Hr7iM_ zfJOi#>p>k3hQ*2k`R%koR4;EO`DnD^pnqp~CS;wGdeOW22;UA;JX)hz_w2S{=0wk& zehjP!4{PO|3G28RTw}{~gQvKg+jio~c{X&*0d9tL*asE}whbZ=Kaq|mqd5OKJweFP z*VyL_CN>?5QYE)n^qPSGY^nP^EXQ+Hb7SY9&B!4_cCs@VNOMM+MU({YfDyHU`6Fpe zc$@wNQiI|#j`Tljz~>jCqps07%zr7!mv!L#goKJvV>kF(V}e$+LcnlUvp0&Rj|W;Q zIMODMq}()~h(4m64JZMPC0}2k{R?$mWL2>BPH&tN{R>Trk?fTs(Q@8dmuP>IG&c;` zsIRR|!kj~v)UOrQAeUOPC)+1b#UZUIcB*7sM)Y?U5pR6=UL)UO@)hy)ERA9sWl5cI6LG$R;I#`0v6gS%TdL(<4^@e#q5`1`h!qRM+m-FV- z@kzm*(u2b1_rZr}HLBouo{QkSfREly@^3n$t0KkAdLsSZy=-V{=*7w7x0W8m)P-~k{5hK_3EWj zcmS#haq9QRN;?ZMmldr^gTK!ilsKLH?Q~O!65E~en5g=|aQw$GL-CDwFDaEZaxrxH zqyeof*n$*UP^aAU@h>z{e1D@YvIzTl)%Ew#Xnf&38#FdQ7qQyl% z8IF^CU+E~AncKx?1PLH|V{ryrH zfBNgk2Wxw0&xCHFT#*x>+gZBb^{v|u)hj)izUPch@st|PVA*H2GQ0Ll`O?c}y5&V& zrihoxJ;?f%rooh4cc{*+)6wJvVv9nzR!dz;Gru2Tr1E3zrc)MQ)f-|PS5*>&#?T}i z8hyLwWxuoHe_L>T%d8>qrt}c^ngKxfWjNNAKu<^I&Kk+B% z8|>H-Cu}kzFZ8C*NL~wHC`#Q{4-WJ#bzzCP8=NK$0=Qj#9p5~+>(BMNE8OAM%xT$AvCS8Hul^K0lP6{O%(UH%sk7_AWZN>gacJ&+9Oye?`4B9d1{zbG3~#1f z;<7qs32Lj&VtC+i*{$=D_0Z7Iz)MM-=SGc_wD?_V*A!y7kGlIK8}w#x3p{>TiV1PJ z8}C+6M;}huLH&g;#ymGc4Q48Me4T9;pF~H&3;l5w%_0@Mg$cbzy1y)lFrZbJ0n{2W z$-snzAsLN{@5gvd$F7{R(Mk9TW$^I@Dc0wSH=^kb5EO$l{huat+@XGhw5vv1S0kcd z#Scsn2hyl4(hC zzL1=RZ{Z_;KSuRHW1Yz~ManWwnyziM=u{u74H)I@N&P*(;u`)A8)T_f4M!lI-gqKH z14eF(hqjngVKH?YpzSHcD1>Ou^B3Y z1}pXVxwrC#Bbu1CRY82pXzw(GyLGzP4YYL+jh{6aW-!{YX0SM^ z%WRQwGqD*jz+0X2L*?*P|LP}L23L6x*H(&N08CSD)=#M9qz*B&8Z z3LRf^%IOX941Vu}cpZ7<&w%2106sB36)nOizk-3z)}O9qsnjLof0bnXs@J zi#BKD3Qomu>y^!QuM_{Z*f&!uy<+zFBl)(!1nmgFnx=dxITD?Ixmn?uN9_A5ng`_R ze?Kaq!<6Q#o~IuiZr2gC`0koYph>x#+4~Um3%4`x-g^INqF%{;<*c!x_$FSvwD!%M zcrEmn6q;AEWQl9LQa*D%i2Zgw-K8tAPteeH9VVA1+IzQBgD%fRe(Kdcw>BUv1UVp@ z)ReOmDQvMd?Ol|p+IhSnNlJMwa8-dE)&VbyeY`ZSTd{%W;(@mwgQkxbZSK>PN&c~x0bf~iF8d7)@Z=y{sUtO<- z)dA>#=PW2ZMl*uWO`>$%lBOU>&VW9HEI%TaUN#aUfGr%O?$P8T*!nhiC{yMf%4BCb zP)B&*9;KNV!I(e`FM(xz4dhuUV8CstZ%_r@3t|K(Oa|saCzgMl;E<(N9V!9}1IQRk z>`nm>fb%Nht}_!RWqtnOWhja90n4u-^QzNd7Lr|AI#2V9yg>w?oH91grT$(UoO*=l zC%FS7+5$H)SomE<=0txA4iIHspZQmA({_XYHIEVwhJmegBbb%!!>~~7iHnPFPR2`E zeT5vDd$o(We0~5(^OBedJ2|upy+KaQgmq2*2%CN8(>w+1kl+H{0|ER7?Eg3MVMBlO`1BR zD2OK791m=>^Z@Y`_Xs^s7RmO53>9XNcF0%Un{$afsC*G+Q)vNcCRw#I1E#i$GqfFD z$XD(kN$e96**G5Iz)@U4x6gcx2VU{@cs^XEn9BFt5#|RCPXB{O=n6R;r@0GeiNe$t ziB}uv`n1N^HQf7vvmp1i?cq5>b$F8GqLpmEUAT`qq3rR&jm`*DywKBVfm zZxIk8Gb=jpwM}CuA2vHDzZ*K8 zRq)VXpgn%xN>YL8YS%6;&h=}}jZQ(YLzZ919t-@9AJW-wL^s!<`cu z$Ni!cE8b8^&h(c%413Qq)^?IA6Sa7BFnGgi_2CcWzK*of|EeEdjNilAN4=NECYC!b zJYyyukUg$TPJ-Zc%4|s!*);a;MKNX4GV%O=iZLs7l~6aYR<~6)$)NFi=B5t(Fy)SEuQxyZ zfDQLzJj(8m^_-)HuM}v63%L04DsJ43ZIa-CesPQU^uTC#wUY>yu5sEjdAs3#rk6X{ z0r9L@E&Y4j9%OtZ%q$t_J&oT8rPLtul4;4wL95u zG}K>bUAB1Iei#LU8u@EEo#3lY zx!*E*XEQECW&Y~Ogbe9B6W*m*nfZfdf^ z(a%k3wVW@FYw!MJ8MqjkXMY*zaytVk$5nCpzOz?u-MU=^+9if{3P&Y!o#jS9z)|t6 zrqWw>F-um4ak1rX66Z^tR+U8rwQ{1yo@DkL9P)4CqDlX`@ZOVDR;+f<(<=UOnWssU zCO^;%c-t5(T)xXaQ(yF+8ws?bzuQ*fQf~n|LA46oYL%Mc_Y?^1v*)y2^X3M%z_RN$?o#pkyC#BmKmYi4M8dJq0w88o1 zH~fTSyG!@&&q$x;%=6U}j9|QVJrI~pUn@xnl4>ApJ9d?u=J`K2dAM5Ko`*z)o=Z~u z`Bmr4LEL{n_icVhRV)9%Y#~SieJpcGK())~#hp-~g@Oe1=C*a0)MpaycE~DDH*|we zUyX>1Gpc+m%;b6={n^Q0kfRXA#Nkke)lzb_z(=*_X}6q(S4HlX=F2->_xN$L+9`Y5 z0`95+>W5nOeax&UFTaat5u!2JWL)2|WGh^HcB))BHdP3kb2zN}vhO7r#QI&sb~5>j z!eO0S`AWIgT+)}l0@osD;etugO5PiY%KkP1GHPT}8;3tRyJRAu34DT}QT=A0p&y|0 zrNCCS0Js5>vQtoVD%ugjJrkk}h9(Q+GzPL1s+IO1y26I}gou;$uxurq5rYDYZZEz? zN^Hx%pLY%kV6vwA+$Wwt#VBywL<3V@74c*~z8B#N>C^ce>8xu3-KIg8jpg;M);=S% zLMu{vu1{LEF-l}s8v?O*fRv{s5%r}bk z;Z0-<(Y&sAFXYo&2}WQvdxI6=+$n_Uem$IEJj|aPWGQzr%s1>ZfV&BKf#R4cCo_4o> za9|)tAK7#?`HU=0`1Fralta)QSADMGJBNc-w{fri^a<<40D)X7maYR_SXO0N!m?;{ z``vT|)M)T2T6!c@0bl_@C<@|^Nu-*1qO}>oq02sIGl!0SAtbtTnvyn2DW?4y=z5v! zRSHd93+$-XAk-2vA%yn5&6;w_Q;Kr+nBpnzsk4Nri3R#&us?=e84VCcDA3$Qn>Hm@#dAXUZh>1JD7(Ms?*Ulf~ zgCV%3qBYQcY?(IfU9;B;9E?VUD+7g`#%8v)lWu-rlTJk)jt8!qQhd_+jS?jmE=FB2 z5T0>1<50hqSiPqShQ3TZ=X)CNijlAE=En!K)t4Q2Uf$8VraPnlm3=R$$#Fz$#emQS z@aVUH^zv4v_Vzg;&(fSHB@|v!AV}&ec&Ch z(BpYjlo$K5hVX$r6rXD^&Z%_jadWs(>itd$>`#2Snl-_ohlR)AZ_Gp%nr!P1 zhY-v8rZ3c*4#9m~G4-kSwbgF(J8~!4&0%>OtOQP0Zt-|>-YcHJ9HSIY`~;mG!&ZwdP# z=>XUaP+mgmv13y^kV1JA;c?j(m`6N{eJI2B!%Ap2dS`qrh@G!xucTcSoY^7yj{xa1 z=dNvlNF4#%NC{>l zw89JBG0I3XB-&0Btll5vgt|y_*axAMD#V#VLjw!Qs8vaIXT&N?^b}FCKNNFdPckCS z!qcuR+&$xD%(djA4JG~RD_ODHdNaYm!}X>t=*-)XFa6A8tC<@2x~)4{9-GB|XS;$L z@lX(7(c@-(ATXlL%r=tM{M_2Xi)o3p!$D4nYj42Tzy6jF!AG(Ts+cI*-pUu;gj2Kd zEeVER!dM1Dnhd3kO(S?KRqdnL0X#` zM^1^SSggFT!rsh_UmYdPj^BUPyEr6P4bqfb3!i+p3_C2_=camn)nJW(CmYW3;Pi#{ zj`iDX8DD1jm~t~_SB)6vo0_*_&G+`V@A%>Vvx(0=+x{fZ^6;}sS8WpKIO<(ry|l0E z&ds5eKkp}N9&cs@4D6H4(KFy|Smk8%O}tP{mCKp1AaAtO-nA?It}@eN9h?0a#*m7! ziwoT3YmMu6sC!rU?%g>b2k-HyuY(G=&oil%DyTg15jC8CX3uZ;o2Eet`1(UXAd+#8mE%j<_=Ldslatdz=N zVu@v@oGkes-9%l*-cxkJgMIyJ@p?75Hs;o>vs?SSvy3tA?8)xVmoj=?&ki7~3KHp!c;=B?{^-7*nWgoDE4#(3} zxuPo-t;$lK_^VIzkHfEsrEf;(3Y|I~OyVe16MG+cFKl4vWwPPjz#Z*2$kP! z<%`YjR3RY;RBdcvRr6c~R9)p2$TTSA5Fi)&$eF9RhA&lr9);fPFNt1s6_$)&c>SD# zm%HZ6sl$%ir6Ze~a~~pUE;&9s6*?c;eK1@w;dCLOWJ|KBI>vAP%vVA!VVIUcDV5uc zjD;^OIcGh&oIzDDA@^9Aa-VM@^v>2)8*;N=Li^m~%#GfTm$$9*lRbk^D@g2b62Bk* zQLq0$siNu!b`Hd;)t%Agx}+h)y3r1t*{Rs8<4!Iv(VgtJVw2YmJ}EvvpY~+SDs+yX?pMg&sgW$z~KH-{AH09&~mQW=eRBxS@ z0I{?s?#Q+&8O*9_ogSmRd~qxd=XOGdpK^m_ho>neNv~Qc1|((K-nEZz2<_6dh3VDMG4gmwd3B6Y7|Ag6Ch2$;la# zF$6~tR`m;amoQ<~vMhBsPVaQXf!T@MA7}IjS3|GXi@3l-6V@Ti&$Ky&S0ZQ|prZt4 zQo?e9=UykQmw5oAJ|x?^c@ZYG`2(|5{?_{enLO~~UvUXr2l5c$zro+ZwxYlv3`}G=`DJ`0 zJuIdkuhl`1Zc*cCrY@2BFA+L=Wm``N*H`4Y<;Bk8dkYMM7ZSX0Ncvsx2Ll6^?#-uF z5Ka1HzSgg{viDB+x-TzLROBD2!Y`OjnUWE7UK_viAwv=9T-=gfYOS0Fv_uFeljeP$ zr7Z=!ggc8hc|SO@?l5M89!~}r#!Cf`Q-qn0BuEo z$_-{HY|oMBCur+S$gCe&mL5CA0cUPVO-xUshkHh!)Z7IaYF)c#ov7ASa+ZmpGm^+n z7y&pOsby(Qvr6%L^$u{X7&6cw0;Zj$E1qG7OaoN;jD(eaiXBL%cd_Z#a7HyeMVBdW zoxXZ6Wz=yEooS-x>e1@W`uuxH%%=Hh@jv+k6Qi!2Oq`mJUDg?13H1S!?B zkJHcA-b=k(bXan8c>naq0Go9;C)#?N^CTjkamS>HPuO61EP8*lp&ywd-e;GB}SZ7)})IJiSKc7e^muDf} z?(q{vzp#oEg``0iOXFm#P6Q(ZSMV##w{kY`LTc{4Thb#XWNc%<5~_X1sTX8o-SrQ4CW)oH@kH6@)WH1`K+tfjfg=+E6> ziu0c354wbK-c^xzA&1`Z-P+GVn;ZLTK>)dc7Ae0w1_9suXC|2e0AFl=qS_ z0AWW26d4=%u$>Z|&v7c)-%yc?unFc#7~U)lrq`Bkm9&6xCwGtVxsUz?lNlKRAp=Kp z@F|0!EE&K_`nbbuNfT>Lq(#x3miOsOGpGmg!C-UQHq`Dy8f^CUihg^QY)m33SjW%{ z5|N7FQ199y%LJAp7FOFC+uw*b%%< zzXrPBbWiYzcI+K3$uqiwhBsY$MqL6WDNXZ^sP4UJ0@g3v!m5AJP(TKt^Sy6yFHSsR zI4z+_vCZi7rHL_wcQ~k7{(4%^#`mEU#(hGt z`ixWZf9FPpChRBoUNU88D=c2DeymO5aXOObxW)GHc=M(v2geeqz%ILZ6>Dc$$8qg^ zOri+^ohpbjgYWywwvd9cg&P_{1-IkO#UH3zyw`CB=i#1ACv5)3$+M8^!x#7h4?3q? z^}NBSQQRii;|%B6CM1aJZNz9n>UCi`2|jzZCSeXD*=KCj}@v8fazp);@ilX=YdKMbDH zTF{Ogg$b2oZw}F`4*k6T*^iF!d(R{sm zc-7Y*qw30%7$rLw#C75)8ls;z^i`i;dsS4E!24kMtxT|#OgJBzs!h?EPt;I)Eq(|><+vynVwR09>0<>IISOa`M*uN(BP+4r?A_{gRR`} zeI!f^M7O@%*X6XAX~gG0eJJ?HOufkY_1;Y%_Ro_`X%Sg-x4(Dfle9Rt*`quai-;Dd z_3S8%#O2{mQ@i^%uO_8!V->?k&0Uo7McVm2I_YLAfyNhEK0Exu`GqSChW0zU-E|C( zwtQ`Gh=07VJ*7=QB}PgAY{68on)~28^+@wz(DwGm&%^4Z>y4~uv_XHCMeyH9TQKa|d=|9AuM~LN-vG7|QrxfTAi+qaaH-0ys=B>UU&HJR?_(o7} zbKRGZ6r1rql1JX!!PK^TRA%>O8x``S2Lx3))bK24(;-Li@$cPU8nvEl8C&MWkxj3` z^M0ScxF{3a-j{~YSTA$bZMJDRGw?a#G??vvI*IK@j~&paH58lZ+S{f-P5d59LmhQWqG~78OqCt;A1Xl+6*>W zW^8qd@$(iJn2bNY7Z-S_bhFk3bS3GuH3Ix^h^Q9O6l z*KSgVX`PC~t`eu-Gf9s~{IkYq2KUP@zVh9@^tC6w`BI9L1NokfmBW6-!BV?L=f-DM z{jgIY-ji%zEPdb4J%$ zf$9gcg?C`&RbARe*)!d=MwnJa>LMl49iYeh9Se9IW!r>BW$nW-VXAG>JGNu}S|oJj z26@>LQE5fn+r4k3DL81pp2<3B<`POk6i$3$1rLCP+OiKY$kSyBy*vsj!^2xtSV>{Y-`fe6usVOdku$~Ecn;x_*@U7MJhBXk*-Zo-eC4BTcPjl>E#xJBIM>$nPGkh*6 zybLW}56+?K(v8x0LsBGuWcr69o2(CJ-WLDrsl2yRByX57apr%Zg5RPmfilba7c%)b z-u6>I;DOnoIm@Pqdm)*XML14c71_L+x~)QjRT zD=X@wu~&XEbSuuNv5iiI_w>IvMSm{KUefoZ8<%I|CcP+J+OK)%NajGz2V{9Lh*Yct!JzjNwzgzbq<*FqBx{uFfcnc88#is=cN2W|g zUaRj|*8U%^-aH)2_l?7zF&N3-RQ4sx3@OXV*azA7u~bO5Fv`9w3_?v~Ut$s?GuBjO zO(JDWmc~-qqX;4U?)%=qcRSwW{ln2ejv|lyx$f)wT<6)dK9pXq$E!wU-BG-muh{S= zT~c2>Tq3&BPM4*2piD4h^l>N*_huAaIDe{wWp}pN^BK;XQb)@*Jr;U}UgkDwR|ZSg z__`KqX5V&*AL>5+528~c`j6da5R_OR&*Nvmq`Dr%ZM6<}U)BYxxAV1QI9E}JWpEuV zABG_{kwM?#7%_PK&2f)5P1G6!#I9w1-?mg?)vsV_e$}dbzEU<~F7HGytdFUpz}Pr({|=$-+&yEg_Zmk0MPqW*!fvmLVx<4hWu z-caB?W`U+~jQAd1IMMef5!cFZpcO;Zj&3$8!4${JeL%EYb>FHKlh~qZhRuK5r~4;w zrnZs%^`jK>)^shHctvM<(Ss!1ED?f&b_5!!;Mi~y!Af}tgJsR7yu$hmT1Ef+r}gKt zamowp11kRdUYr7C0?fc1-CV{YHwM-+QNCEuTN{85@V(D-VFB9-_Am7<4d2Ekef&q! zru(ReQP`I6f?f7fL7M zST#17KoOv(vqEo(foyZJ{@>69v%|jc=~ue{v`govj|A1n&S-HNenW;H4o`YrS$m%$ zfkS1>bbb7CywmLemfGaKOu3OmHLbPzc61X{O{(tnlrmFUGwo!IAXzA@V;XW`lVywLzyva_!2~A=~Kn6|BU++AA^!p}dG`JYm`@AtLm7=hYjcfc8;X z+8GgDTIO-}`r-W1tG4_Xh6lB0w9pjtmk9&VFWo%OEKxPU`9(@8x=WTsSjelKYG>jJ ze^94%T(i7%oH!-(+BlkjTnqetCz^W)zmPkLUeGgW#W{-qLQ3n z)AaD7mQ?g(@?*>*KJYKH`ohPadYnDl=ltt2Vx=rBtrMNgC#3FKeUei${_|iQ_dwQR zgte20k1G8PA7D?PYqS(^l2uI(TnsdA6%;;`5sXytT)0 z#EbuRBjRz=b{H3c*gq^=s-2~$>mv7@w~J`@w_*$`6f03 zq~r}3KMjV0|FCnVq1wNYF6NNHYs+r>gD*q7axE~nv%$ANe`33IIyq{6db8raSc1gR z^L1yUqNljaIn(lhNC5Es{1UmbrttpL@tIhGBpdo2Pg;9L^^1zeP&d{)s^7gh&_mo^ zt&mdXu3t6%OSzwkA&u>au)4>!~jqSQzNHj{n zaKH3v#9C6}TN!U#kq66eb#x!K4#t|ETFZKG*4TO}v}7s&tu<=VA)Zi^!)Q60oY`tQ zk~~glb9pvOIMpnYCG-clb73^(k^z&9?5WxdcsyVYLD0ow^0lfnT(&;zkhD+B+Gt)i3p zc^3GGIs->2PCFcysvgY>!81n85jh=e=uuY72HMFirTyXsM*dV-L9;2FbI0oESk(wz zb{AsY-yl^Iwh9F8`gd{p1xd2`D9R~5@Tp1g)fAESUMX$=COA!7ZacwIbC^Ia*@bRuVPjG$~LXFmw}7N>>k}!5@3SLuI&%BwL#N> zTv=e{KgemZKPM2>*Q_OyzLgL#F4nyant(C>MsR0ryJQ?ra3gQ4^utVkGX{77kxOQ< zjCS;n2o1#)k*q5!9JstsPgge;b?{@lEDD6fQu^z(MLgiIpo?D3ns9~8BZ}g{9swk7 z*$9p%a`+p6*g=F8snL1k5Q|6(B-yjSSI;l7Ac9jw1}zGf<(JKR(d#vk2lu~IU0098 zXQ?WpMkQ$ns?#Ohf;kU9Uq%9Cq0n(=~)8W#|jx}I1| zT?FKR9~Ke7m&5l#kwz<%;}Y;))hHN$F*#gWbTrK8$k#Wrx=!=38I?3U?f4vh>0cFi z>73|SG&T#y{`4oz?%5nna(=!x=OZouBPWqH3|zh&u?Yxt1DP_ zd=ZySdR~S9KB8kdULs9?*`BiU^~$nit-CH;GGAc66hd^P-fLfe;Gx)o9A0ThVtBoFDH0K>~`AT290l5&o7A3BF=+!A~pkd@u>dGZ0}j6{4Hd(}!?YzHf77 z&sk+zMguU1UX0fct|D)(8kFPdyASUPnG&RZKD_^zJN#y=0;mWyWo%!wmC5=iZlvS_ z9<)u&_`Pcm$@&c&Q%lAJgZd`F1~~NaEV!_3$|fQaGh2z0RI^|ROv#O|6xyW-hk74I z0>2|(-_8R(p3{DTSXRx%g(IY7N;A>dD>Rx+K-7N$@6q<1vWjp2K$F>zF`N1c2A=N% zBUPN-F~6M&Lq>s@`A@qL^>RY6Y`!vBWnzb|S`(-^pZQgORSS9jo&ql}7P(}UrW7u) z+qaKcn0TNTykNS#i#rY~D%~IC!U<<`6fGF2L;?8T*YzsIq9=$#l|f2iwSsY2-f31O zSIIuz!ra6X_;v^|daQq+r#LwE1s<(pSq&M|8bGt2EtqyJ@^RlnjsxB-?N{Tp(hdn= z9T3AS;gTWCSm8~A7AdI$3va%x%cqW_u$}5Oy6fDzprx_NQNtEDffwbC|wVAzwp(9@s0Vq>3wLu8@9_b-qft-8Uh*=M%Y7zby*}$rd&h13I0Qn4? zg?^8g#1>UNL;E!09|~OL`a%I&VM$jciEmbup4EyuXrUo{1?N(^^z@L;tsJsQ2nSJ4 zf7h}jkPHb4Yv=oQ8_&s*$)SHR)S>Gi?2YG9A3DaVdRx`|xtG{Ej7{mk?U+-I8IG+R zxm8ZAEFbL&b*sD+7Ycjvn&6)vcDsMpGV-bEHyM`}1KOM1ZsFSvqhH?wq~H-!E8wOh zO8B!pxJ4;tF+V8!iXb_s*7;IExtn69<5#1J8Z^>Ms1qZ5ae-vgv1{xdzT zQd8EZB(42|Ux23zAV6x3yhuG|Ajs+*Ii5GD)mYJ>)96a#4zOyJrb=Cf0V-qwQe?7!*2q-$l(<^-{(?Ddjskqpcm!i$oYh#F zht+tkc7sHOP1mU%x3qpE_`vN?G>hqv}gdb%;m4^Q1xNoMy160gg;; z;tFWxytQP?IQy^k>fcXnXC#lvS{PBMV8Da!*?Jgy(GT_Fr|va{jPBL(L9?5Li9V#o z%GD~V$v>y&lul-?cJh|l;V&`X{@(Sug8xl)$jk3z3xA4@SFcoT(fV@n^y zmw!c#&8gfk9~!Gm6le-{<=LXVF?jxntnd0{r{YYX@Spo%|3b1ueBa))MK%Wi46N}d zlU3h2g&SNi$l=D#`pv5wA!ms!xU=kMPUwkzQfN206ZiGL)uk-Yx^%nq!{tI>f7Th~ z=brxY{g%B~NP$;Xh}`;%WZAB%W$T9TkF!CzyH^mVhbiN|7nKR}F#1t7FcS#OC<09W z4T_3K;pR`kbz>GzbjTYpGexxedfBPsf~j)R)97cV3*i0&RqsWFJSUtX;ru*{LDorG z0>`1x{Dd-%gJ7tudiO#$X~kk-B;XHzbeE0HVJ5PUfFr}O*NSn3r7rqTfQFWALI&tEUX<(%Co|X9baxs<@8d> z$1^17AO;@5tLMmm?5GcdNUE9@gR;Z(GkoW-5nZx3j00=*N!IBdDFU4rmg7Teua@)N zCdI`+CNp-+8_p{W4?UO;F0`~fZGHd!Pyl3UeW05myt`QF^EE%^l2b8xgI5kqVCxi@ zS(){tQRpvL|KBMuqbp^>q^zOvA;V^2NInU3vpEco89;Pt(1q57=mXbM<@ zM5iSW{cM`d5z~$tz@==LameD2kVsXWV90_Y(Q=S%!bDjciVAW9^thi>%!D(k9zuV9 z`S;V~KA;H-I>G^-q82LtSa#mx{Fdc=Ru8+{#Z;e+5ICLzOxlM|0RQO~cLgI+xg4c1 zrSr}4SOG{`*(K_i-n70};Gb3&T2fvK*8eG2JGFc8cv3WaZT`jQ!EbtFPyGQr=Kr=c z^Xp|TJqI}clGN|f`f1hb$w))RYz+@T(9$m zJ7SlZ2U?jsBCN&zTgCis+xDu^TEwJ=^X2cb5?(L9Gzj?Pa#_-_5^vbw4c|%cVPv~@ z=VBSIic!|e!l7*4I-@n%M{}y;VXkMPp8-bnXVNv?=jo&$lZ~4TR?@QJRgJmhb-+9L z!>gwJ{u)Xq-l|W%e0uquW2co%6o~R^_=~LGe`K4WRi1sZ<4)~Ztxe|an&zRdz2G;8 zWJ8~m$3WT}Wh2~{nxK(MC2GUkGIr^+=_mnFLEIIU{~-CB5WgrdX#W8k(7YLcHkU%% zNc2z|Z?CLS`bQZ0nL+ObU8E3!3QI5|ns|ta9eH9p(NCisX41Jll80QuiqK{U)1%FO z%k_Pcja~Zu?!5@01$imjUsaru)~kvi+y9#0Gc?G{{b44q|9?&xpt>bQSz=G*38OgA z<;kt?p6OaJ4uxXp*vpw9A~AktXE1 zHp5@d>U*8&lo;eHxLm)WH_k5~-RC*3U%=lp{30i;d1kQJ1l;pW5%7O#t z2;if)!gkN3=12bF;#c7}af?N=v9Oa~*`mx(t@p){1Ho z^$-xOMbr@H!G>0=?Au2?>MzHhglyf)rmAgs;1vL0V&oaYY^XuGnC-5J`GV0|!A%NN z*Vs2uBd7S_;TZ46BF{16C0NrYl~??gNIajqKX$W_kT?hbJ!aIIZ!cnp_~n6k{9%j? z@%w{nr&Kqk#sFw)p@+{C$Y;7Mk2Vz2de7H%l*82>!7ELrav^*ZtH(~HN| zPX6BxYO7;H50`5#Z~SOJeTOjg%IdQq+4ywR=QtOI*Ly}x*4;t4Vlih&m>Z`#OpUsJJNs3tem+`R8NL{?{3r!Z@=}}(tzr5 z6{0kG?g!I_1OC$79WHyl((Qdx=+z{eYtlE*{pPFI1bHpxW!tTjL(O6_qUDD_tZ`Bu z@g71Ge>0{Ivu&&1VES#l_M)HR8gg@eV!jTM;(Z81>BZLbRdde`Qy=AJOS!o`F8EpU z$nv2wG-fOn=^Rkznm3>S&N5#$%9_!|j3cCu1OK(-%OXQ9>xVC0UE&y_ChOL0+b#!b zD|gE#jphX+*6I6Ptf9rPVM181t!;nAGjqkf6zvB!=NadlFGn~DMj`%^f=X4nz|J84 zZr+ZUthLXFF)d!40=9j5{jkRWXi={O3S{jpI%^Y9nhOD| z&$wnLDD27CeH=t_%Ud%zA%^?WT5%Afr|xfwjf2FVDQ@t7o!T6z?HrYGwS?())SuGZ z54(kb`H~g)!pqJ}ro-vkKVo#nG0Qe*z0L00e-&3giDGN9@RB1z@Jg#mSa|k>4g>bOH-Ea4?p;QsYuvM z(AfgaP=SqdU4wZ(AuoEsHNDW^Auh}=W-NylmLBo%)Mef(ocOpB>^rl!`(jw9i#>z* zCiryuo+;y({&V;L=udbh@)Sv*rdm|X!UM_M!MJaxvT-@tiutH7=phVrcfmgWWXc)ZM# z`Xnstr(Z~2K8}>ijxS}mH>_`PY4NoDZPfTnWy^PIceqW9S0X_D&Y2h2_qBG)lsw4L z55@OiGdzWrEF1Kg*Q3L zF(xh`R=}*;hZOSMoWMTlMdY>?fro#Icmm!)$p_l43k29VKr_Xink2xIkJJ}hLRUaS z>rSvTMGHtI?vZ^k;xARLpen37^#B|3qy!P0_2Hq46&9ZI7WI*aUJ=sFItzu4W2tIL z!GY*^6(GYw^wbud_D}|4FJ4e}bA+rJKGY%IvtpJr6IwGoJXgxtXTjUr{nHf2=KOT72wn2~5M2GlhA19&A%nm-=yx*TlNS_GgJeG-+iEruzb z&Cfh5CsoG7<`gfe#8Cv@$wOow(R_9?we?rz@3AeKU~myZfebgoB1PiGfCt`J#fD;WtV zmPv!yz$ZrcXBzi(HIR=iQ@?{_fSRV{z@3lqE|Y78w^Ux;az7lsKK~9U7k&rW9o0nk zmt>qr=81%}wyr6=+y6mEt4D-_KK=wq5?18%7pZ`S`~O8Z3cBzr`NQ%Q&)suoixyVr!Fc$2^vQvjVs4)MmZHclwE!R$Q{)^{A|8 zoP=-u;PPtLWL!G_Df}@Qm5sb(vqlJJ-CbL{AvL9OBWg)-c>8nLi%(MTLp^Aw-o_t> zzGc4X-Zs5Ca6iq2LOL4%H}mw)`r?zsVV;`RyW)*85{(V^Hl)>w!@Dhihw+kwmoB?T z%7tAw%z4`)bM@w||8P?IAI!4{hs{!+A3VfDR^Y!&4Hh}qOMC_XU6-z(=nYKDW~e@W z9;|jnJbxQNqOviUU5zp1DF3K=NnMKl(^c*dYJp?uY^vPT^Jz-bNIT-{xi1}|Jbf+u zLf1)z#xBW`!uK`@Y^!bQ2D`Fb)|eX%+-~rhxE6Ded1M?z;M64j10U zKD>E46nPQVIfJNE+T4~=927oz@%EFW7tM~R3rbGQpy07YxW-oWu4#yRvhs>r5S2Mi zUtO~wQM3YrL0X#~cupaWEtQOP)uD$cT01b*y(-|Wp!ukm2{0a5sB#q5qLp^aCd%oM z{+@5Y_vwU4l4rjk6p^N_p~@{$%Gn#)x3Hx>%xD@yS~&Jj+LLTJ50rE0?L5SRo(WsutvYhzK- z*<*Hy0)1A9C?5mitT=)?OIGftXuEBJy6O-GB527&t#CVE8fGxCYYz{+d_qi2QQMxd z-&Bk^`V*h{Xhz=As+Yq&?SdH|5<(N5%Rob5e$1Y)nK4Cv6zGm8P~Lt*Qqk^duiqs7U{2ZMI9gl^k#n~?j0hbt#0)P7s&P^?FI&&XhF`I!q;re zsz6xiZ?mWW8QIkj|J}bpCXR5-vd zes1E?7G=r_B(3S_$luow`igJsQ^uWbgnvnU>UsTN)UDmq0im{5dd4w~Rb_L=;qN}| z3JzBsX&W#7@cHU@Ufflg16+KXY(7k6aM^e_X~b9Dfw-tUD2bX|3T>0xBneK6Ua)$dGDvxN6l7_v zk2I{ktk$@}UbLV1U~SLVN5P)IIHzZV6|*_^sBp-&aXrI7{O%9xl=M#;t zz3w=dE%muE%X(AB(tsurtZqZhz>Py*@`g&V8rSnUnx30y`yKC9r{HRRSoE#dtT|fc zMP8KN3*@3kEsx3{d96vR)#P({C5AiWhR~Yp+Fy;Df8pE3Jkk82Rts9C`9suf&G545 z#I@th$)Ow$jQciiFD`V<^jH1;0ok*D2sTIaDjJY!>w{S|2rD{4+?0BZ4Eg#U=)!RI z(k`I|NKFw547MsU-SitKeuhGWI>)GI0$r8KxM%0}^6|E19R^DdZ=Jf3QkhY>av5aqXl`b{P za=w$gf4=`#S)R%My*=94H!o#*?dT^t_KM_g`EuqXq2D#tV!7wCZe~WG(UX!0yx<%5 z^4s5h{=wyI)Ki^&;zN1|6$zh9hmhPk@mSO<3pHY+|XZ{cXwO?$HMFlc{sse z;^KL$UE)-2{>eY2Iwjc&J&qHk^lQhk(Rc0MmtfLKIV%-14mDLdebqnCa8xv?nVoTn zu8vMF?D(k8Z7|*%%i>EeaOitFLwIxa#Fi=V7hkM*@OB#9XhBa{G5rEh`?(cEaqrJl zvld^qw~7$BkaFnIxK$a7#cXJn{&e&SLhR94C9IP1ILL!eWo&Ji5&A=cX>5iZqLd{| zmcZ;rBqA=>pKQT_r>vR4DnLfxPV?~!9TJHm2Ljlu!(`B=1 zMt`!-Nano8@n&oWaF-?Z-!k&2{8CXg)dn7XJAvgRc|vTjJrRz3^9P zf(Pw_!N=~sw*v;tJEcCGiN297Nfv}(tnuCU58wNojgrznE7ZdJXfONx@di%EwI87N zX%erkmJY4yVE{ko0;7}VJKy6CTdDr*$)G6JKD8S?N=eHf5Nx}gc<_I;^3KrZxOh=9);c5d6)2Bv2 z*B|7YDle%o>Rs~eMC8s^s^sJ(@{ZTMo8QF?ylR#=Wc0Ymp^=%ODbCx=xY1o+fKLSx z{#%u@Q-c30QnnpSa!+^lJYZ0UEg5Ef+mGH_d^^=0dD{X8B-{<_9iY4x@eA7+mP@VPH{Sh4;^f!wU!MIGsSEr-Fr0?y9e9#Y!arqsE zH@Jr#yl+cgkCd`72%cD)%*;x5KF``Y*Red-SmYt;vV43A)p7M=_GFPDC< zt&;emjZ{E06evr+7|?#D&g&$h|74AQ7V%lbzQ3K$%msU)^Qq40xM!6NbyEj3uTI?< zx%}3t^?v1DYE&@gPB}m&< z;zA3uf=FH=Q<1DIshw=~BN??qW%mw$0MH7jm9c?}r3q{_V}tew1*I^l<*V*cTb&w( zbRo$o=w8&S2n~YN=v=3EjnxaziX=($E}Kb`0q>|}GPZT+Gg;#gB^|Inx+!e=s&tN) zd+4GJFm~rCO4HXO!_Aw?%nD;@h!Z#1Bq>hDqFca~k7GP!yIl;zgPMrIMJ_VK&c7i8 zhsJCzMDSlH7!p7X7TPb#ePkcUamYrNV!)#KcQ_ZP1&SkT8?OKqY5$ue;-GTb2aQF1 zBJs@0nFNREh>S``r=X&>Vg_MTSl%fuHTut(c{F5jz!DrRgTf%fI=~fG#TihBXe08!Y4C!0m8%}!d2uSKSYzCBYL!5BuPwga}|K5 zyd19_Bc9d!&_I*Z0qY5^4&1@3hKvy{>(yNUQJnLY?zt1>S}9<+G#|KG;gh~?8GeEr zMkSjxNGXi$q;!<`iVpl9@krNBBQutE21enX#-i+KKzp8U2I}t!Hnh#o#85O7b1*-$es79>?|N+aK;duK|AvG{o&n^+pnSDc8A-dcUNLy8E_Oiq`gJM|0h%!9_mq z&Gw5=`}No>7USlmu>1FynPuxaqf90BJ|PM*)##X zzNUPwMK|M`;)ArKr@dL!@i$#liz8)SI;z}xxGc5+N|ZHSE-%6cB8_y-bJ`NLj_0$V zvprs$tu$x<@)%~{amrPg)S~DqU~G6_k#Vgel6v#u3dd?ru~0&!Y`LbCz-zjEQT+D? z2i0>cw{gmf0%8!Mcif%Lp|6DAXZTihBaGjDu3Pi%QR?M)iVA;;69{{1GUA|D{`H;q zmE+a^l;4(oiyRl6ZQ*JCBQLIRJvkaBx|~d_7g{tnV|*7RLNB*x7|&svY+!qzxg~K5 zhyVt6y7vEr7+H7dL>qmcBfSbFEPkJ%>-<{Uiq zx~(Rh#lmE0^({5L?ChbJdywUMA^a?`fF$Xu4#vz>dj#D$N5)}_IWqrYsXjR?i2?Mj z|8<6thh=P5_2|DMUQWlEGuXK_tt=5E3t2f+aAAFxN3uf7>a8Fb!0TC*L{H0$19u^E zsJq=Ar+I<0Pk~r=hCHp}m`ukz*fxY2Z739Bb7X_l>ik4H-U^M=C+;=Upgm3RGJX5UEa zjWZbwWC@0pYDxN!jpQe7K#vwpekcDvK;q_BSg0Q*((gJ=O;qr&i!QBDPuRd!arsa z^YNXN&QEAuL!mZ+CeU2#s3y2hN^L;RLHh1n3k!t-m{=f)k=Z0Rxm?4g_q z?IQ6IU*NEGsJdGvgmu0)lW(uCai_=7$VA9h^nPcLkTSI+q2{;Xs|m?86Z_{6W&ILhWiZmBs{H8MFs?CzUU zBPDT>(u1s6p_p+N+6`8MJaivth)A)iZmu7yJUqZ7QlmWAHuNSFXuOi7sMB+2?2>wu zzJ#8kmv=S7!%oijmAo^VaU>U_4%+~T zc@ga(=9PkhShO{P)hupkCYuP6S1|01aBN;PP`Td#hOCxa{rBf$JsaYLhjKAXMrYwP zxX>ToQ*nj`Pby^)?f%UTG{)oy^uXky_s2(`ypux_bdoUqXv1)X02|5B$SkP?JDwU@ zqHx3m*XILA?BcHIR`ZTj(mrl_9`S&nGQhxdq65qnN=_vkf}vnM1bHF%7$H2Ah>&AB zVu$kqUz=<}W~3%fmWxEjV>H{%TA9i6o-QELY<*u=2=&X&6%pTZ%kE5@lPNmQ$go$^ z3v$PeBf8%%0c(=_?8oi@4g5sFt|Km~qUrZ(!GfqWK2gy}>AC09W%a(+fp&m6j2RFV zSeZqAHb-XiIALT@Xv(DEfS7^9;rAtjsFlc4fw$n7P*UX6RMHu)*>$p3Q;VIzZ-=0w z&;vsq=to}737R?w9&&tnB#))vhT@uHX9;LIH_?9VnCNDM!inw@?j9@7=vAv~4d16k zD5sDojD%xz0wS#hOnzu|tuYyHcQzlD+?Kq_<>{CyXaTD>SFMjiyOYh)jjd(S@YQEE z&&mumGD9%Mj7mHYi~1+n*GK%FFP#{dpUeuiF#UHfeq8NyKUaekv+`YB_QT1{@JD1n zE*|UqE%$_^;%*j7NHb%8YgMc*R75Sh2XJ4D5r|y;PHa0FU}Ew7ec-#KUW=kHHw{bw z1a5C%d(sl3An4t(txRpGX{c+oe!9$MFDvuaO+&cv{dG^=-(w}?PqPTe5-!(@3T|0 z{`ebc&*iQ1_u|Hn+y{Tf#5`d{vA4Po?hR(z)bKoZUr6d;AQ-4d(2w%sFU?B=#=7mZ z+rirhygr0cw_7>UL2-i{6}*gG`i!ps%5?mv?s}C)7Inf7Ql)AK518|DeJJ z-$b8(AtwU;5pygrG0gisW~%4NE7Rx<+Ok#9rqUthg5J%sI`@ilDXH>(ZcDAGzb{;m zmQKI!T0R<98zCsyCdHP=@slYwIWc{P6(OyW`B%gRo`fqZvJ@MHVI$HeD=&1Xo;YnJ z%i6O{elh;i%Q!@=F7-yDZhK(=TXi<{N*&wMWkr< z$r&i?*e%~Rn}*NnFGONPWgMD+fAK)BUwOpJ{nb=FprW=~qb7-9p#TGcfK0AV%pqdL zq&usN*TT>KV5t0zLBh)EwED{<#jK&DBTr~*n0wlJ{Hck8`;j)bo)j(xOY!mkJrAu{%FmP zutDyokKMO5!|YvO-mJ82efg{pzoPc*GL5MWp!R4&x{O31EQ77nXHo@;X+Yk{JG)jS ze$Z0MyK`EXl@l-pLnCfW9Yp76vRIPXaLF|}on}bE;KM&q&kxj2P!&Qh&yPH%$0}^m z+D!>s1E-7>7J&#T&!f(ZaOuM{+w2s$MdVx{{f+Gq z@#umP5|@7(}N&dEm*{f_;wT|KU3swbibFjb26TD;t*vxuldmwCg{@(Mycj9z^-w= z8f42N7b&1P-lC4n=^Ar=r9Z)}jwJsF0YjRJ4|4!>I8VI8f%@WaDvoY-_+NyBfMw2f zB4Yi*C=97V6pmngunHarjqlZ>-d}!ZXSIpdfIv%TxfNK3=aYR z{Tv~xhKVrymZ%bFn6Rv`Ige&)6%Lt;$(kq2PqmxwVgIKaCYA47#%ef5Y=U9;hTyum<93G@PL&?) zIp+WM`XmbWM=HIclkkw=$`=}L-ttx zo#4V(mv|FyoR#2C`B-`GZ}OwdPnXLtY9)zFb*OrF3|!kCJLtbLd7(LB^*TAMFrQm& zqAqNE#d&vlS<~(;*XOFSnozD!U#dFhU5TPC+4DwkvyV09tQh!&<)7>Alp1|$lJ*Q( z)Pm}8jodSf#34zGaS%*n`)??o+AvkH$8i>zH*K&YUd0q-dPxd#)R1B6&VyWz^K-K?i!` zwovT577rGIq)tsm>*Q#;Iq#)lRjO9jy|Dn%P!45Ff>vmN=j)a zDA;s&OKd5=c|O+sNlg6WjfqUQ*#?H1jDbFZEME4Cfy1FK2RWfd**0BUriU(&Tcu@M zA6%rx-EA8`@Sb*f_T{ATiC@D{Ti&)9B}gPu8Lq7lYDU!RT{Qju@6$0~$sl$Q%ib`X ze~+G=so-^w2exb`v=G;f3GQrm?`x3P8p-Ei(&Gf+`5_@Ww+B%{t2FdZ33nf|v7AFS zsEEYRbcxwEHl9y1t4L!ra=7T22@7CJp=eBJPaQ#1!N5PiCE_uJ0ou#Pi79b{9nEST zZ!2$6m`PRxDBMI9Kzz2FbB(voSBgFP>EM>yY#x!V?Z@IkHrVY~a~qUYW(rKp&wMzM z^*z=Ao-Fk)an8zof`C~*pl*f2wo~3c3DNr42 zu6%gs?R@@ld@IOyFbXrF7zO?JzQ%!hgsoJUQfLX6T-Ji=7FzJN_}&04jwgbRJTSOo zb3x$P^E$VD$_huQ?H!(X$BJq!Mg%i0??gp5_vYb}A3pr@0f_01oy_1Dd#+alP8(W; zqAHjEJRsX%U$P+Em6WX*3#9} z3>+*)rKOcC@xPzd(%0s%R+3!jB|*~r@&SSlr5XY} zR)hh~#I+LV6Qi+Vz5ge;SzjG6sz{fG3+Nf5L4{RBT;u|q8K>?MQWMoh0iC$;&feWY zD2jER8D;K>msQt=T=p{AFgAt304@XmQ;%7$lO8uPU?{Y^SqzI{qaWa)3s?XYE3iui zb!#(>F{J$x%L@J>UT~8tDLf>I6K02<66XW{Gremh`UY8NC-Eot0eW(1b^tsz<;-FS zLl0&$3z`jMIYmAiFz4f$IRlN%%x`6<=7VSWI$d4`C(^uroJk@3dO2NyYw6=W0aq3M zk`3>p-YmuUkAG^8ZzFnJzl?bJ&KftZ*rJJgk`kS^Fn%@n^C2kz;E;KG3@#_(*KFk_ zGg))hW>3W9co7*{*w^b(L06#4MLzmQEI$c5#n7=9Bk1{hx34Kr)i(@e;fzs132H%m z5!>yT!o)Qz#g+;>@;G~vrvC9eVIsHp3+BzHXUHv=Cy(&@J>TZqjrkF&dUEUgRx$IT zJEe}0{)w$Zjn!!+?;^YsMuWsQid>$>iha!2uyY)G;QxWfJCAU1NwL(Q0PChSNV*?y zBr3ig!S#L5P}3;&>UE{wnn*lP568*|nwqLzeOQjHQj+fXXRm->jB%(NwrFst-Favs zJ+5Hi5w(yOR)T+vufqGRO5AWCHT!q7ZhzUXzb<*{ddm}w>qWU@zL!5|z3Ef;$_#>w zYpUnUfdkB$a2(>9l z)o<3tvov0RKmczQ63$TJqRV*;+gEu1GYvPXS-P`|aZhoog4V799S?*jP4#-aHLgBB zm+_55!S2(qXjriX>jz*1x+Iad`_^v&TW-9s(wSuCh|CH}unT27tK%4HbC z2?I^pyD_^mPWhloF)?7i;`SdTdSAx**8e)S?OHFgxYGt1C~EALM}xSfTMAgp{YE?I z>5Nq?ooTjPYuBBz?oP7Buk4-duBw)nOV^r3*o-+kJ3h@WF3Y;2-gvI)Qkg$PD(jn| z4lkXZoI1J5a>s&vNYu{g*||e$#LK@yZ9eiQbY#74f)a)!hmGB`I`tumM`Tj_Z^_YQ zZPf7lTNlAy>g2+Wovykk12+#p@cw;rG%e-a6sLNJN>4|NvwZYXJ{Cnfi#k_ziQb=D z#>q2^y5^;Z6{mB8E-c3t%x75AC+UcxuZs(IxX!Zit*KN8*dkO_dNE(AL0K&qT;*^BpSw&YiUnp)svd}b=|6h zG|wg6I*h7AKp?y?WRPjMJy~D%1YY|4AEd>eI=!}Z^Crg)A2s1HG|mH-M$Z(M(_(n3 z+5giZurJVvlNVU{$PnJ&DZP48nLPK%%FI+O2HmJJ^z6^FwOlI+Nu#bBK*oS|obgg* z8J;qIe?npMiO3~QR%RK+s$_7Zwd0+R@S*u}#q8kQQo+2w7lxS!?aVE(LJlm!==qm; z(KE4rjfbUh(V4i(9G2)GhsdqF$LN{|vwH(#hMf{$5C6dDwigUEruUN~Sdnm|GKk;&I|jQ8^=|X%%AIH_ZwQ>1Hm-n`2m&TM(f};}T>1m~ zxKu6p0zKAH0z5%7jNq323Y%cxmi_OACG+?Ahuh;rGjfNR5-wL*FWfukAFC|`gsRGWLUsx(9w&cX`LzDE{m424p~RHJ}{8D7Z@WWNi>1vJ69 zaa>doM5OXOimD7|JuJvE-3w5mQhv5MQreU^;|`jYQLF<=;oQbkx51^Z1PxRgAYwp< za41=5tnO{n#CM|;$O45FZ6}x5&e7D!@qrT}L4(lmJwaW?1dKpDoH4Ea(((`i;Xx_l z6Qm2bT)|^M?18@kqmh}r7x|W+madU$1!VzR?O3zbcTtU$qwxW)KFr}CCq4|#bzRU( z-!jDxr-WMSY8O@JJe6^&Stb8|1I0$NekC+or8D(s!&c>gkTajISrV53XO`#X)OL2` z4DYPqT+PD)igT!wvp$60$ao2;)7`TK_n4GFDk>WimP}QX$<8>g0OwM$Xh@^ zx6y&-qi9Y16cK^9vgwj;!D{l`m8R0>P2b!y`kT_uJ#bQuT@(;MS-JV z#xw5IPX4xkE6=}8$9NBPqYK&^N(P=Z^60I<)#bXSqFqYF?2+G21Y4O8P`*wFSnIh3 zoPfl49XUJ!FKes&%7x>0w|ef~<4U-0&0-ZYn{nt6QqKRZtEq+Try~vl0D(saRMMTm zw;nd^8<({#C(1U)#I*LU=JXQ+KHH10#CkPKWJ?M(xsXq8@^iq2?lk_pU3NwIUWF6T z+WqwYbdAm4tBQ9u<_}!+r(Bk9I-dY-jY+jVJzV_LV&koQH;R*UQ9v+#Rg9ceuyKPl_=QdY^YQVT7OOs0=1nf@-$f@*6Rf zZ`lM+4)0SSvk!8FQD)Vm5YPqVSk4|TY>_w-CpSXSOhiy-^M?o=kqajS!k3IrblP!_ zJnLY*U!0nflV_oSfc7tF))G$?sk~9|s8#+MqZso2cIODy*Jb^%2sTn-7NBbuaCWq; zuk}>gPMQ2U>yTF1=<|yw%Fcr-UO1}e>uWZTu~D)0D5>f~1q*XNUsW_&mnoBGVE82~p4RKWNU|x?29hb>rJK}-2MEz%!RXo*te&xDhNGE^l53zvOZLi?T0!5-- zZQI|omf??VH)S*rbS$k?qh`)InnZKiE!5t*5$x&y2qFFHz1!93Nb`v!uX!6iTjgP; z^MUbjl3TEJddgyX z?db|w-kEuFI)lxOL{MtWZwrXw%**RzieLT|w0(-5vcz@NtMnQv*8l5BfqqoVNL$E; zEX*30D}ivXEakdf*u51t!P)G&9=_c$0#17#vi`aE7r^Kn$EF>nMIFJbJA2r z<@2ocja*N)I08|C)ks>3ubo?xSe0SSf(}Ow!-*xMS+4vjFT4=4kHgcsChwIIBj8nE z$Q(4>^6f}{07u6WP*G0z22`z_lr%5lQ+5&rb{pH(f_n8uaotV3_K0rij%I%|oW|-0 z9j^&Nq;?c+w+IdxE;i#ka+9N*OqkBaHu6pwU}>1{^LQ4E&>-KD%qy~irtBFbdCEW} zNN{Y+@8sF*Vx4KDzLrMDwxMxKRSeV-7Y1HKS5F1u&o-|14Wy}^xFf1hKUi@Nn zjr4kk4AnomU}OlBI99yr>;2`jT;@gTp>55T!Of-bFY|8>7_xR0lCQaqA`XVvU%$Nw zG3149l-V-h?jC1GRyS3@kE~m{@$q)nleB9LOinD2G>hT-ljD!P2RziG6s203L29tm z>vJJ*tN2>U14wX*(;GJiQFE~tl`xWj{ApQ7z~{wWNce2vQpU)gYAzaQGyA$ecKPKD zsVGYy1H=QHp7y7*dGRDvlrYf0v?zaGn9y<~l4B_m5k;x&z%p9@F~Z&;dzG*gt6 z{kE}rs=+q+EL`D5v_|OCdUyQha4uAt|1z@H_zd24 zwew)+mkI24LRpvq*^&H8qbyflrA*o27BOoWiuJ9ngoVvxmPr;7{JSWfIvguBfr4%iX7o zX)L*O`+6n&>vD0bY~PUaxYccTJNuU#(gtwz|I_~&s1Ww3f1;vsbpZc&d)jIDN%9TM zee(RLp&G+;5||;NCI0_@UT*3~`S3(hF<$>Cp{=kW{`*ox=N>}1aQlTa3T%z^{Gd0s6M2+j(e{KvZ#_3)7xU z*9V_})5tTa)b6bGxIYO23mz!z*^0F?wZjq~u8)`Vh%~__3(#g~oqY9Uw|fSW9r4=V zbqU^q#x63RRh8L@%rVuhheEWeuCissVwB-GCngzcMa5NNA8!5V@4TKu*J$y1JXPMe z)U`2o@3W}sCbGiL8D*uR-Vos@3cjl|n7uv2fjYfLjo*LJ2fLV%UB+!U0P9~uk`pI& zz(pz3gl&WRQ<8z)RA^pDl$%)6U^XYWHU5AfJjtE1o$GM)WU9d#%%1 z5r`w}U6)^e${P^wvYsd@VDFN7?zfHwtFddajbjIBj&1^qAf95o+CZzBoG&Z{=)Hip zWeuE|dF^Ej;=3b)mGGi79sr`VuZEOr#q;zSvDRRV(4@_}1Qep`a% zCP?**JoK2`hPZeHlMY8g8kaJ8fg3Xk_AmpYV%gd8@ZP5ggm2a{65wbjw~CN%Gd_I% zvyk>ST-zo&R~vwhAa)KnW{Qb-wdX@A^u7j;_T+v~pnR+b-w%=G2B%u85&vawrFamd zaCX_+Uktgfm~1J*C)NNBHVyW8n0Sr6J5`~a+chPMU+ zU5U~h8kVde_-=?y;YIo(wHnvfIV$Bzr(GCr+#~>v1@7y}*dAeRKbjV-5;;&o0+e2D zB|#{T3bimDPlXyH8f_U!CaX{>s|yts4HNxVQGS+-7F%d_cJ7jOGqqLRdXplod;fK! z_#WM_%E2?Z!v2o+q6&{6TWQ_gRL8S?u{r+Ti^=gNV=9mOn75?n;4Ra8224FUzSEI{ zjsTJzzR^N#yV62zKe3~!n$jjq8rxZ{dkA|PV?|Lj4!l`+a8!w!Ooh+pGI?n@c^CP& zgUno(2H@2*!G+ZuPjb_sa;A+#xAmpH)aY!f@QM8)+c|>u)-DF6Cdyo9pNz)yb@GeK z++DouxH6vSo;lYx!Ivv7!rCC~AX^&r^bc2^%y-GGbXFQ`z#;0(^Bq1JkYD-J^@K;B z{3g655c#sZ(Q{r|wx+QYU^3aux%F!OTgMf7U+CvX|6Z50{HWOpDV->*3o5-D0aEdq zCzPQJPs_yCvXXjA7`~sg+?q*Q8&wpptsA=mLRU#oT8jS%di>@;SV9c%Kl=Fl9<{&p z&qi+EAQ%bSiEF+iiq}5Cvr2^l#K#tBToFs$z`Hl1`*o`9m(q9z_xDsR!$-(EEAYl) zDMKtp9FL&2>}MT_F~0)zp>UsTPZehOR4^3wclq)xqmS_~N9m2f1a zm@MyW1oUze_v|x2i08kWf)@~W1{sJyT1!4HtJ~=a4Pwv}^~y;Jq&5g|FVavMe8c|= zJ6%nHa6)>{UaI)Y^vUmt`wk?b5*E!|tq$?>2#<*^O~lXfWuTNNJ4d5XL!B(flhlXP zx0A}Ii%EG^vaes?`Z(yl1FaTU^wdH2$GW&$iy5jtvsVDTG4F+8A_#;@kry-}_D}lw zYSSn8&ir=jcsn~@YI<1VHC!_OiV|1;A&A+P)uSJ`;vqY4^$!~5@bz%7_O6o)L=f)~ z8X(){{gkuHs?4-87L>?vH;wuFHvtI<14W%Thb>1b)s<=6Ol6_xvEClqpQ<#|6R4Gs zdsNM--+2glg12v3O}r4;WtN4mKNXA%-1gy3_7;2inDBvJsrN%2Wx{YlQ_jv+>x2Fy zqA+qMdDG^dONJ@rg)sSG1`YWLMdxw@(I?g#*CJUkIQbN~XDXW!`k7L)X!YSu3KHuG z3(Jp@F)HA-z*F4kc9{wt@-Z+)$gX*e{$1bFUByn#(qi94d4bbxfP|g&)$}o)f0`FF z?`&PxJ9=ivpEw|blN!X)!7#4BWMoe?QjVUU?(L-F6#pieBUYe|Vhk|OE}nH~nk<97 z!gxBbQF7=B>it$~N~C$P%){mw9+`^Va@qYe{9WtW1jcBc0TWAj7#0$RkJU8X+OoXm zMU`$y>i{kK-E7=Xi+d~6RzzH9^zmhK0<9)1v&UIO<%%|t?iuYM`H}0!c|kYtCzP}J zgBWsWj^x#5s%6sC*~hoC`(oMIwAPlaHnxLXzgJ}$YURAC;(gD~Y@t8z;Fg+JYc$q# zrR~D%I-NpQ7%W}Q-dd?h(ICic4xDqxK;=oD0jT$X?7NS&;7keiAXKIlQ&eP_e2KFd zR)sc{93c3|o)q%&9N+;?Gi{e^^4ImGZ-3ww0D>xpnE66+q!6*Ilc>xh(M)3UWUzBN z5kYUBsQDA=+MLof+N}`Y&XiZY7&J=eEPtf!tR=6DJOet-yP9(`)>MEc2Dty_t2HIG z0|5wMr?f(HGNBL{VT;AeY>j79J9np$y75_c?NGk^cdPD26kO0&L#&Zy);3f1M zPS%e*I(+U!GPdCh*mz6YTYQs1o!OYW#unVg?jG!nHP-2r{yaMrU@<7DRaYZ*~bpj zSla^UF<2u$&t%m7SKapoY9)?DAo>+kBm zbu2lsDxRSEEE1dZGHv?)^n^jw!ooaXEKh%N5|Q-C;O`VC-HcH@#$1$gz-PTNU3i+D z<*oq*HW37lWt%pWBrw&NypYLWec{#kt6uD+#I^7ercH?mV5Fc4taqa?CgzaP{`cBQ z^Evi+z*CQfFRij;BTV9TSuu2Gin8r;t>05k7`;fSOpMQNShAcqD{2dU)wXLNVNEyDb>MeUxhI!@Duc!B?V=CKpl|Ep$+2sXt zd!Po|4z!jlw}ldIB6_7CHO?E5Krvn>a_qF{I`YOz4+B_3eIJB=JyG(mkav&tAvX+P z{Z9@qRsZgLoIoz?e~q#Kmu-kU&W{`qW8B%f7Bro?FV}HYe|P1hzv5qpTi1eoSD}U8 z3UH;<+k%ev)q=sIwJ8>!-5XEoA5KyHs1`(6-ZpCY&l;j6hRVRy+TIk_^iP{X|wPx#IeJqK*@Q1Je2cn<6!$|Jq z6#v#jVI|j8(vF-Gp`R|sZ1b_jh~Guh7xP@zzj@+%yVUhyjpJTU>EjY-^9c2QfL6$k z`wY68Th1D!L{RRLh>EOaWsZ~#Qnb5@gl*oP3*CQHh&`jC%Pz`SVcGth`YIO@5C3Bv z-$=?NX)|*-e>hP;$s1O;=3x8#tv8ux0bCkB-MGsuD8Dy7P{TjS6iWSXlcz(K6+C79 z1NCz)XE`n#alO^rbrb9ag~Dk0+hKT)<+$T4uqGfEO78+x3h{r7h~oI!KnNMWH3Ahj zcTEW-?=+$qi+H$>jegeQ;;j& z?K+<*fg08$KTO(%$NZ;K;%5TPg5A!Hd~iu3NC(Y#p!f-Duc&Y9c>RbUPxjlXOX%=pGa$+lQy%7j78$9+3+9beKhWOSVXKI2F@?cz6rjBnLF2`dbol;3g7M5Pv&IiQBK+c?5FOqZCF$X#G z&Op8yYS@QFq3mem_($YIwN){vg*|9nK0{^T>jsYiP@^6yVCSJ?ygTQ_4xLVWxOeM( zLi2Kx4Cwr0t{1L>0tt)iD1a`A?@tKRW&hlO+o;v1o$jgSztHEXY3(>`I4R2RoS+Tc zg$v(jM~HPn0f{k4|JG4R%^lgbR!cEe1Mq))ga{AyZRLc}<{^-Xe-9c8-496ybTypd zcx4S>2Ar#HlyxVFj>%qS>ZJIt1!1=FnavWg+)pAlo+=Qx+@8pw zU}be$RFcaOOS#tAu>Lw-Z|MAG@br+^sIQ67t!cp0kMT#&qp>Fz@j~-Ll{;q^DN+J7 zofMH~Ef%kYm$WjzmWUUG_Lu41OC9YEBX-vUxVf=-VNQ?foIzs_8V1@$8uS#sd>Chn zq6ng*kMC2VHZC1JB4`+%){7)lzx*Baa2#QMHP8U?b6X``I%rNcV4L0IKj+oDeRCMX zL=w(0e~#v~+ru{*1dWG_v>iHH6&4RMNYd)AU2Qj2%@*9c>#P#YEaL`aynTy36soa4Hz&1$DcY=<#1B_ zS1=i{1@G17LeUfPBs9}ej~{ul0XI3Y*f-^k8EcSB@MuR5CTuY97ypr{73L}|<=2~> zHuXqgJRsO}20LRFmaX7^nRFvhUw`4YdLdYwq0itu&2QgS?^$}DD#;pu`69D`k0ZbD ziInN0!mQ@ONFhD8vCbOQDzd*%QR}GqtB6Wd!0KMjUZqP#`MpHn zTaW^E@OFEwuB=S|N|tNW!D=13m#Y*4YX1kiz;7EhAmPnYCpf@dM{^ttx}}OdA-}O+O|@D`zE8flccHi8;ot(1C_ zqdkXij-~}yiDY@$K_zq@^bdAV@hP4_to{t260wT@$-8n?qRIEkvJwQBT3ASVW(9>W zAUlOL>@jg!E7L$AmO@B+`fz4I@^A#LU?Xrai41;keQ;sMRS%UzuSFI8)9ruK!Q`t` zLQ;2y^DyG`C>Xbk<&KfTYU9xi#xzR=g0`Cfs&VREnX*7x-WE28W(}Cgl;5KDEr5Mg zM|fd(r^7%2xRW7H*?)#vaT+H@oFkWt{gFBI9@@%494HD}!MUTU)HC$BDf|}G_pAKm z-EJqo>+*2}F|BqUS>j_LB}_U>2Ep-V`Yt;Yl4inSaR_SJ0*>QtkaM?FkG9w>(l!*U zL>6c`o(APO&IX>qwp_!`gyMgpmL8XcEnOZc%o^mW(E_yTy?V4&XmmU@NpE9!l?&wq zj*AZBGXR2RlBU*f7oyvlz=Q)G0Je&wl%9n`&W)&|ERQW69X-%es{lE~huGst@}B-v zpl1P6?HN$M+5bDLWs~7`cwE4=XqSGAcsY!w1zLolnOD>XsM?5D@s(nNy;DyMGAFx) zlNB2$|KBXCpqTK6cgeU;vB}AfiBzT?-!5}jhOn1~@Ds%^qpR5?N_gvnH$OAmI|*nR zHRm9HfGm}&M(U7?0+-W$)%CCU>)w93UM0={Hc{c`vK*%&waYkkTOf=vZgRWFeh6VD>w<=t^dx=LTY0^C7<0IcnY9F7oB>1*1Tqv4nG4J^o%^sgjGqo*P1nP1pn* zRd)ZEi$+?}3}|>G(d(pw2iE5&EmZ09$tbucynn^NXRy_>p`-^s+~^{5!_KEcUu@dk z#Dz8Ao5@}HXL|ZBNb)9kL!Zgil;7H`m3^DH(Zbofi8d}Gi&4JyK|%@hh?}Jf*&-Y2 z+gn~v9d8&oyswY2E3b8pz+>o1H48m{D&eyZ^tvCc=UY%p@Vv%*O6bkEck3@{iTxzf z*bq#%5mRTVI|P^CjjsJwc{k@p_%k^k<--(SPpyhH2heKxxv2sUJ11T)RGRo8;}rCI zOmF3jpzgiG4?zK9&a^gCs|V}$pKprF3r}($iCObhQH2$z$M;t|3=Vwx%%$H<#%dgl zPzJ4nphYujzKoiqFKeyC#Dl_3@HrY#xp4VOW4>@@$avzYY`Ft^RN{$-l-7HZX+!;q z6+wPZ5AJEq`zk>}B8>xM4<)Sohn_REBWnxw`zdXy=N~_NoliOM@+2yAxs(F|)dLf( zhU={-HL{agPewa2MM`$Rca4s)BZ1bhCnM!)*0j`wBT$}!(cMnG*dIH}-61E)luZwv zkKwG!i=aj|Cy@ifz@CJ|Mx@0 z@owu0N0h{~d!ZWzp_>Tnt<8{>F(>nzku*N|*H`d!iXRI9rwiDn#(Dw>B_nCY*#Hb> zcxV!egRt!^X-B_4KeE8J1>11i%`6RUza4$U!<+H>T{HlbkO<7?cc-W{`k$ z_p;uhjGlo4|GJ~rS&%QUgLnB)ukUW7V9saKt()1&axJQYl-aW{CXZcP*j|5Atsl6# z*2BA6+h)3ury`#Z?aq`6%GT?*++0*f2nnGJ&R^z?vBmndyQOMoyu`h~`EzFl^TYDz zYR+l~Y-Jpvs}%e~Yr?Wn6P}FgTaPhRU?uXNfi0~Yn3&tr5R{nhMR<(E|32`#&$>Y_-Ha^7h-mKBtre`S{zt`+v79^-RXcncHa9eM6d<5pk=>sTqY%qE zHU$1oSnw^xLmwQ+B#RPr-+HEIM-b|`a90IPHUj%t;x)tuz#KD{Bga#d4vM&dZ(_}h0gHDeCR2GPjrA>0(5Ohn?H;}uvI{49 z-_glL@YmbTC-__A5dkAdIM0q-01hv*eo46t^cNvEBo|gdxH!i76vQ9J=*f+PRbMv_ z2baWcu?jSornwaO9T-*VAF#yury4QwP4SJeck^_Lj>!Jcm`XXpqF+Grz*yX?gmH&Z99tSmEw_DO$Ft?$*8 zPqfJkcGD`6EX~f1HHAr4Q$(Gaoz|-xlSzM$37_5W{43$A3&X7cfd+t!xZ`+KX}$W~ zMV2?LAU@rU;OuMjD^s^3o@A8yu7K7p9uEK@btUNB%)@JC0(OUjY(4ai-cdo-heW-5 zT7Z49ykgYn#=MS~(elb~6u zs^;9y&8(2(I+87{#YZvHW!3;kSf7>TqZZhb_Y8<*O{0U7E7Jo8p=v|O2=ZH5qiq@5 z^@G29VCyEcDTe1J)I7ita~0)F@Wop)gmxFQtxhT(p@bjBl|ITIQhdnb=%qgbm4rUm zBBk`&(UxHgo^eu?x+P*3AZSpE5bMszPA5waCBhqSkI(|yX%-)T4D1rqbLW^^CJV$O(3`QTkm)jwBrUzzNL zJ*G3ZD(>QSrX$pkV+@>%h>A(t<;4XkeK>*K5U26Bg7vt%a*ln&Rm=824&QrbDbZxF z5b%nJL>%H~=PSE6V?`L--NGa%-HVIlch|R6Wiz&_fwxZ5_4>_=j4Y!)QrG9bHZ7B< zs}pi2>3L+tws8+wx_ zMVPDFU^R0*pE8|I+Cq^C$!=|(nM8CFh46=(#=0t4hy)8Aqu z3~0$93F_#RsYx@bt@WB*^!r`Yo5N{m&eN+c-$hytMQx>M#wgDCWa^aXRI!CY6Ey=) zA}{<4QHD|ATO*dQGA!81J4k1|c62EIlu8?=RO!DS69fMM`4p8dJ_n??p9v7(y=0O( zC54&^?h?x1P@*CMO0nn^jLTVT3kvD;4caPUK2X$qiLbr>V*x)Lyk5KdA1K>9Pnltz z#pk%ml;9TlUg9?WcEwp5Ts|;ToK2jqhdWCB#B}o|v!KM|sHN$+-y7qRntI|v7Lw8javIHs;&zoXU1G<$ADEB(|-(eLV?fr4q3DgK22zmhn7!ET=;|cMpZ-_z}fjPe1ZS7#M>5p+*cu?SOm*_EUS+*!A1E)iF z5f7V~P6nhgfowjdbHse>ma3yh7ehcza2x~?KAg~(`G;EBQetKT+3zStWo1eo+>nIc2x}ue&q7sL`M&pL1>i z^>h0UP4=9cVA6RrD-%z+;>rBck(i^wql}Efp|4ZTXn@ZpkTBb>OrOuveJw$ zE2%pe{Ul=*bB)%GY&{~BhVQ7bJR+5RmO!R3xdbgPV+~dV1!gj9(UxoDFwg0tIBK&? zoV$<#!pO}>AzsBU1h84-wV;g)0z`G3CzU?@Liet)uZ8+|s~t>Q@?Vr#jz+z*rDeYI z%YxusDv7rkzW%Q2$)K~6RdeK7(>DeC>M-AUr3d__1~}b+-^zW(<5T3gH{#@->-|c! z7?HCX_~`t`w=1dQ?p^*KJ6%@y`JA3=s7VACmj>3$$(o1_BL~R~EQQ?@d^Db=XyqX)GuygHGn_5_RgGPvGaq+vQONmQjKfH%ti~W}y@p0PWVH6Af!S$c2$I`ncm-sqdNiRK;q}JI~v!VYwsuxUjKps zun4s8aC3vD=g;?5e+t$%7)W2&{f>LXk>YR$yV)u&$BSC~v6%_^Ne0GEkP2mxugj`j z{noC|5{1+nO_2Vq1m7^Xo@&<|a>u8S8KPaFxKgIdu_J-;viECd7aq-t{INg4N${X` zygQ|oM9+`~@}=JEMD|c{&M29dG}!>J37fQ*AAN81kt0dyjJ&{5b?Wy$gI_bELDR2S z{+MAx93mF?p0xT{R<4vY~S;)LIy#}Ui_2OyrzE>=~+I3D2G2hI&1T(!PsFNux= z`R>fbRh*CVvujKzbg|iCFcU!`uw|{4Bcj~&H&Es-K`Qw7@E^_v#Y~nUJ+JBH80879 zHk6&8iS9-h-T~C=*+>g~K+r;wfXn}Z3Z<_QAv?jhG(kqYTIwUgHVw&QwNfkT`{td+HD3htuEgXiMK2Q8>=JfibLP8Ho06oZzyKlVnq|TY_1Rjav$nq%ywUEeV*(1j$VmwxlG>P%-GC*+5S=}EGgrwgPCEOB`8>jn` zdbPQN6a@psS&1%T5En=Co4A^7RUi%0@?h*rabp~_dV)Ku3uBD^9m_el&{)75>f=nK zZAZGLJRD+zmW7T-Mg&5JK%4+b2Kw~|jul)*iR6ic~TYBZOE>K1T0fe@9?EDIanVHnn11PZm!o$}!w`*1xQDAJ; zWzApDw#2d{QkgSkTSf7}sD(cjZh(*1D`04y3Z`nyAC?XZi(zNPdcvQ}mqNYjmeROqsdT{1{U5 zk|+ViAMJ3)2k$jwgb&WyMs7M2JTrgA3&9elVxEC>5|xi~15;dnO$?zdOupI2RFTcu z@)s2oV~*QL*0g~Wp=-n#@eu?56~Eg@h2yZFrf%{nxp%ou?I&FBElMK7X8gE6UDni9 zcdc%lVf3aOV#Nu})>${{#hfDd0*Ztvuey}?7e2o<%9AJgnl3~U;|~w4>LU)Hi%UW7 zjeoI|?UAH>4$P^wn4nS5EW4%D#rtomhO~7$G8IqUUd7@b=7o?;21KkoaI(C!v@Dd-65YM6%(Jd= zoCMF%cv723{u5ltj=+V<7UGAJ*k~mA<jcCI>N1AQifmF2~sUPn20`Z zY`nQsSluM~=F?slhlOTvIUb~3!hk(@5YRWY{4vejcltiXxcc>GXbdi1_idhqf-?_% z$0X!9bZ@%Uso&sB&e#JG8K>*zK$r48u*pie<6yQLM=aOqiu0O0jMR2lCzbe#q9>Q(iarid9d{D>-q!EXK( z#xVdULlM|laaUzL_Ii=*D5!FvJ{B|hxyRD_atwfv_VHD4$(#)H zL*w}WKjmYr*6ef=0Ab{H%yISsaY8Vz$TxwN{44CmS0!PFGnk{CYiC(SOIr~Hc|jOL zVu%w6>H&?D*en(h4POOB=5&bppAjI|z=4~_gPr6R&XzPnyTfP!;_Zmrc(OO12Qrfh z#sk>fTl{V8fQ#3=i^yJIKNb7s-$XR%P>rJew>RmP6OqK^s8<}}NK)}vR)XfL@c_Dj zH^%qgny9$ml<>_~$(Vh5#v(-EDr-2x^mG|C$M*7>Q6xy%Zt3oRiZGYPzOoeTQ;NNT63DWJdcsmN~NlhVC2Kg@of(tIBZj~=o~y_sQMt@Gp7^1^sSKS>I?n16|!Nk%|3Roc9nVe>tF zITA)5ctw!!a{4f1e$tMnHAo+xqI|d0gQ~aPf0(T6RxEc&F9>~czWn= zh9rNDUxKIbh5_ZT9w)x(1W?(L`?n%Y{mM=7R@fqFOIxOk`4ry+Gl#$$dx!WIoju|Z zRN!5uofxs)Wt`6naun19a|9%SZMYSJ z6dJTQnt?UzQ~3JO_fK8mDChgXhJJx8!ObvifqmZ&YCe1Hm%8AtTUCglj`*Mn{tRiAwVvQ?(o{vBAC zw62wPJMvAId18u%3$Hbn?Mt=PUaP$K;%=&eh6d*kc0VSACt9X+U&C+aeKu|s*lr)W z3deU&AK%>02}%rqTL|~NE>!`MCLfP1=?tQrxSU`tDzsV0z~CF@3*^y087g<{a)-q) zxuy9)rejD&ofBmi11X*c-qd8Y!?W+BN!g2KZnzqPCiE%wpwOB0wy_);MPdG(a}>&! zIUjR5ru5dPS&3(@zz-<`I>U2bSSI*fIfwqT|2OVa%H(%ZVx{N@LwVzD=Yh#X8Mnwo@GF7#Rknu9P_qlg3(E?5O?x@I1BmneaT7E1J)8WKM9A=cDFyM<`qS zT2Tl!D*-s!nBeWF$?5Wl_m%)j7om@Q#~Zv2Qk_XSRB!{bYj8isw|r;1 zyjPrEZcrbVX@_kp%M%F#0v%ly@fOHvlp1YUL=HvVN-pc|=YW3I?xe z(+DbU>0-$DobfJ~lVxYEEK2?`(4F?381x~j!ik&*3m&yu6FO~2h2YRpY#|gOjN%szu=JFeE`|MxLl}T+8awb#v zDT$`*JQDPksLy194XE1PFP_>PG@LGjWF1rpNGt4bn}RY0RIN)gBP-R;PxS6PAo4L? zf(t`(IA62|)W;NlxieX*r*$t?96}UGVJ)&KYpDhakhxGQ;(03g(dl?onDUN{Bk!k$ z7fd(i#jfk((hsW@Ec9iqCkLo#t;%~8?75&m2H5OXk&qYiFXhlq3vZNMAwS?L-W+rj zZ_eC`b)ac44?D{n?%z{9HH^G4MM{nM`H`f2Tj9MlQ+NlL3}mRN@vU>8X(Nl_H1Qf< zzd13^d2@RuRp@uDjJy7LrbnciN0O+j#z~)#Gz#PY zX1ZXzi8A@Yn+uq!_+{rr-508&3&M5X*zo@Ks)|}!@5}fHZIpgq@6=wEg&@aAUwYZC zlULl|h}d?k(Uj604-N7$*>k=-xjOmj>9+Zbsb}Gv*DH>a%&$b5w=5+0*%=#eU8aN` z9l=vewoF@HCKtoQog$%WxrXM4#Jf5<`+Tvk4)Q$6&wCZ2h%&T2w_m!A- zW3<@l83Kw(A;rrPlZm`W<9MU4NBEqUQj;x<>Y^lGc10HdEgkl)ZU6G&%|wCK6{o8b zO4~&?icH}sW={oMnbJ4ei+QZ6)a&=5#P(&2s$~%X=|S%xz?0-jlSG93BIL9 zzd=lajib|)6bjas$fDKUGWildQfQu)gvo6-d2$*NG@(i0P5CKNib>KVl76bUv|XDs zY))^LJDm*?bqCo}`c%l$i2K(I)8Rk&`N-F}BW|$;iH!{DKdgS;taV&Ekn-H@u0<1d z?K6CUc1=a^lje9dix`_S6sz;m@7L-H*=#G1VFpv3xWtzBYEybDC zyJedGL9Ag;6E1=_X$Q+ewoDRU_e>MidY3|Wsh*4T^MFqA5UOt{4?i3thLrRsvJ6O4 zc>3&=0nYA)8DVR|%K1TPvMOi2TK}2MCxLpZ@nUga^oDav(%z>t04F2s_k7@9nxlly zs6aojN4>vd;Fsc<=o)bi9n?fXx1zQ+mCI@Qz@4PE(`y8iS8rb6D7YO)A9A*%JtydcN`r`8;=-J6togP?X4t^Ncik@7BI9089Z93i;MF z&~l?7kA=t{KzbqH0MLnU53wcPoRDTJcZ(T|4ngAxF}x0OisEMG6PLq!iVubwrjIwt z4Y_g*<5L;dKS&8?Lf_8$a~zX+lFKRCd>!=Nt+We;>6l-qlC3-yA8eI$(Dw^{t(jxN z)X=R-`o7If4)Ljc5%s(!Ec_R%I|KXM;|GO_@?=1&kv%7yvmu&h|D!8IXv?)=usyLi@bV&gTbD~0 zF>^PTl#*`hpl4{ultC|Wmx(u%p2Szoo{1SWF{K0on^*f|sfvUZx~--S$n6{Kj~LKB z)-_F3i3PKIxdF@;@2@;mt5`lD>lW={dF~BG<$rq{ z!9_H@^w?skVb1}R#OG0EVCfNyOVCHgb;(jD=qV&em?(O?9L=vs`qnw8zXTGySxx#y`o|{m4B!spaE_mp}aX6xi@~SsO@AMyxGpi zwrbb|pacOm6UsifJBgE~MQIh7fGBr6UGcZgj{`0SYK>wXa7b$RwVmFaG2 z>yo!EvlGsBhF;z%>G7rD0o7M9&S|jaHrkl;;G%0t@=T zA86}%6Fc26NzXfqieM`OvXafT-!E%^Y8vG*}qvdfH*YJ|+z?eO=P z1&hMpMBLd~S7`(ajgo^GU(!|8{fIu6`DqO}XL^Cp@@IZlHr)3<5@69tYKDOiPl^tv zoL4FghoLRRD?3ULLu<8wf{!*Ejc{Dec))VDE*~UkvJ+(Q>#U4lG=NbM%Q3YPykTR* zdJ1T3`%g@#xV%6>Q3*9VDQttVI>~ksQF~}uQiFL$NB!XyqC~-)#2b-Ae1S%}f!MGv zL6`L;=Bq1S96`r;|^*L}`|Rx>Z`;a3Llkeq{DEPDEEA7HMdoapa@Q~OR=+BXibdgGj1Y#5x=UdIWIVkG zM57#T=3NFU-PQujgo6XDE=$z~e3?i6&Gawjn|}}Hw&uQ{gg4ZF1F_i}kuNB(B8W*8 zHjsZc_#~4iN!Y0ot3<%23;^P2>xl*xmk_&u=lU7Hj0A33r0gY>wlJcV%QY;->OCty-!y zg%`2bvJR_s-={;!mI+Oqnr2QU`qp;&JfM|}38iHU^-%5XpldWO44zUYV6tP#QxwU| z?%V+z8#QWQu97E9Qt$sVs3)twT#A45Mnz%Abxz<9RpDKYkwK}hToI%dID%iU&Xs5;S1uxRzvm0xj5oOdl}lxqn%a zG4L?j7D%H`6ujyZ{Z;IO4ToSe-R!gP5xn$B4QP06{~Z%F`;A?ovMV%?NDe_@&xVT< z5#ARAvT(5xhL7rfXvhAx1T}+(hv9(hV*~Whgc1{wmB1YDW!Z(ckMSksJ((aaG|i6czRWuEnfAbOi)Dq+$*M754_^+-Z<(0fC35{eL%KEu=bYFfTEnQeif$G*vL z5>Lr!j}qQ)ONZ~?uM}Rj9fFhewv&{}NtB{K{0u;mDj3w{eWtv9F~OEaFEb<$B=|qI z*p8@U_F2ud3b;3jBbpl|o0ndyM;s8aQ)+|CkI-2M`xaoG{*v5`6w{`GyC#{m6$xR* z8w+`Q!<}~a47auP+&!jadw`2?>r1e!dx#Bv_ZL6o)Zv(S?ZgJ02--du-!la<+#LSk zE19{DT1xUbG=CvAdnGyTEoo#}Bc0l85ROz8lg_)@)kzt{!v$s29h}xIxLpdFKA*~$ zS+0NoZ5(E8xjeHKXP+XMbR}%wr=DkC38HwZZ&R=he7GOf|# zi8o9TZaUFmgX|mFpzkORrZ(T9<9C=7?QfkgGgJ4K#lG#8;RT`95{hU1xf3-ctgCO~ zH0LJ549~3GcP+U!AVR;nT@3Wmm^{PYi&Fo;W_Lp$cw?(M1uC#tDq&p25qdNgPFsG5 z<~FlW@86rt{(s1N>!_yxH~xDtV1P&o(j^Ftk{I0}Ej79n>4C)P5E!kKPU-HDPLYz9 z8l{vpA`Yaa`P}dCeV^YszjN+CcJ@CTd%v#N^>{v><99pvqSQIRKue(gL2eJCiwP|g zddDg=tASugroncesMbc2;GxPJ6P%I*aq}P+Xs@cxBHVK^pr9+EL10!o|dSBXIw7i}Uj=X54E zJae=iNfjl`kzz}#@y75+cwzlFvuFF5>rsIxdhOD5443A0ky9R!o93rBme~@|C@faY z58jkdrV}-Byb@fhlDe4>c%r4{?egAUt5OvklaLYYw`d+*`b!Z>k>W_)hyD-5v+-8V zo;f@4c)1#%l^ebsW%v^M8R^@9= za40Wrr+v=9YeOR9dP;6jWc0tSlL~r=cwY-AV?05COXoMf02(2oPVqG#$r}rL05PcJJJ2sRG@uQ@sRMqBo^hVgYVVw zO3jwQPsy_8XvDe$f0eJNmT<4xZkTn_;%O;+ z*dSi+=RIn>)mXebaciWi0uyv43}6u?nOnH=0Ommqp-y|GuF;?J0(_vug5`&~zWi7Y z4pSf&w+%_v%22{0 zaYgY``YHJf2^&Dz62#4$pOycD17{J)msw5^J=52UhXRlR+k+$Y3p?Z~+(YN6TPt1? zNaQJtQjw-QE~WMA%ysNWjFwC>bj{+Z2x9-twHKts&4E^CQsSG5A?C_7@m>BEJJt=7 zTjl5FdAf53ZtpGpWVYC^=G8oYd+{lLOvlj@tQddWr?`q$e46%kA#_-aX#DW+&U<;;G8x`XV&X2oNhp{ht@v z-?|TqmOnH-3GD3mex*(R2a58RA~&%40n`rz3buk;uT42{8~D~v#kbcb9dE~kt>Hc- z&9t$qs^KNd>#Y2ME$VuUc+Gg{&bg|PBd1<&ZvQQzf7Hzn(v>1ZXnZh_lDf3-W>I3} zyPUlTT!Hlk)QT6TNW&kg`aWcbG&@_a5)`>zVGmyPnJ;Ho%hO|*O_z_8XNNl zIP6_oxQhlv>p&C@>lo}3HKzHh%H1#aIEB1_FpF!WQkhCLVpD)=gHepA1doW)Zx` z;4~+yDWi>Ue#RL{LVTowUQtGFtg1SrLD#V!SYc#R&fQ$jruzg@yOg7}RWO7=`LINR z5>hWp1{?vULSwiSj>4X+fUuMvL>j3sgeIc7?3t>SaFp>WDIg&Y($njZSf71WSSriS z&Q1kH`)t2BLC{KpEJHa`^a|kewc^5yqLds14j(YET3ZLYjSFo4T@>%IY{R|cFAKcF zvI@iSknyRuwX`FUg_MdCHpO9Ob*LiivAP{jF)P9Z1Tmw1&W)Nw|1k82~=(+;bjmpcg{|_5qz$0;69$qu|rvtkK)lFZy&=SCP zRiG%F48IU569S+6K$SpHjS3XEm?a-`du10D60M zR)SSj1lloK00$w?0VXxiQ+H3Dl$_k@>AMoCXycV`6;4R0Gy)uTyDw*HK)&`fFk*D@ z869xVkyJs8ia2$IQA|K3CAna;vHw;TP-j%L{~Ik72f;}R-4kGPmW>J4Eh@^NLAi6( z5Hy~+{4;YT2eIVvDxe|=6B-WFm|8P8mn^VxJKNVnE6IO2FBu-s0lbGqvipR9`=)&m zWbd`y4JP29;PnAMv)x++(^vhm?N4K2U!3u1N0+3SL3Q%4l30v$>q!^JTAbv%J*fZI zS2ac%8<^6-VeytZ;FXd|3QS<9&|a226Q&4J*2Z9h~k}`F%TUb z9Qna9*&7QY9H4(+to}=G?Ar>$1b(>m#BRxVkK?@P7^7j8>M@nu6KB<0510`e9sDD4 zCoH_8gKN!nk{>f9d}DCpj1;R;Rn=u0G*v2kJY~G&+}6|T{LS|9;b7?e-BPO(?GF&e zDdn<8-MB*i4RiWr--|^)(=Q>eEt9|gJ^6R6^*Sa?Y5k(^JE+Q#CoGx9z1yCvVANAb zw=OhSg2mkFKalBKM>(#zV?j-?{{7;X4qmuOxZ)ISdIf$Rx-}Q=mDLj!xpC-yb@O}w7Uvh;-!;y3o`YCs6eUz z6g~`oyfJnt0}xF!p&^UhuA}(2i6W9*UPfI`+wq%R0gp)NkojHcZ|$vFOYkoiFb+`N z2lPTtorg_PYWFI7WWx>I^UW5R5Jkm=OMs1@6u~v7*^OPmQx)4mbyqpSqfBAiC zk@GZLTVh4CnjV}-<4$FTaL1*4&<>snsC6Yi)osh=NZ;kgh}tvTzMZ?X{c0>?q3hy8 zl_BSeJ++fF|8!GS*x@aTHlEx0{%`=imeVay>@YtCGRP<;S;%T&WkRe@!2HVNTQZj^ z6+&wt_R7tL=Sfd{*P>#PiZXEU{xv)&G)Irn0D}U?{_~mPwtY>)q8%L8JpW2IJwb)N zrOcmam9})qLEf-Hktn*G9~FCaFGb*LVYE}s^LTrBIY_O7^c^UO4^g_Ur|x^cj%gTY zxu`5bsXC_+l`NEsU)kB;)2s66n+o#%><_`JvD@WbFhSR&m1D+3rB>PdQZ8~MczWYO zvWlR&!rXlC*hydP$^g2-oglYEW#UifB%LwWzP=j0hUdmBX9C*QTPA@(HwZ$kTH zQHD_ZE{=Z{j71pJVuK4qjRfT_x!pj=X zjTF%)H{<9btO)$%HGuV zc)7hE@7XG>-)q9>(6b&A8v!qpKB4&Ni+8GDLCfAz{rkB`J*lDVP4g(b0+=z4CupIz zxnV_#(&RZ|h-Kww!;cGQ;pSi8qx)c}ET?G{E_Q^ZCKO%Ocs!-qY?k|hB{L@Q6BMt( zXo(vKjm=Y+k1{iRpfL6|oB#*BYhH$&Vn-+G&w zy!R(*y#OU|Li&4d)>=xaNF%5=V-Y*E4%~lGZzK`K{C5-1eTX~ti z>-%T%q)9_K&6Y;~na``hmG;)?la&D<%5l11Wcp`S{{oGobB46E^pb5EKBimC(ulqt z>n(f@i<7^R)>gOc%Y2^>ukCfatj<=KIMN{*d_Sai^SvBjR?R$mT>Z5k1Pn5v-eT~# zFg7zy?5CYP+5i;f3tgTPb)iGZp#^f*UOx|^yPZSs4^Vy`sfDNRi3EHqRzm!rqj1~d zpWpU~I>3?@rBWT@!m(FQ_tPJlW~6!lITWVWxM*xIv##`tzt}8Hfk&x3ZRw3q^0Ji& zFz&=gb;XM6BFdfpdKp~AzyCa0Flh0DpRc?fIg;U(wnPYvFm~z~y*nrF*|LzcK?%EL z&ba1lH6|0JYQUO^J`h}~hTa+ZYLwW1i*d&^nLBAXUs_o9Pg`+&d-ia9T>EeE;rjU>Z!Fp1bIl5Fgot5C$a<`&MM$r?3Rn+Q04c_rJ}zB zqKkc1QgPek($SlqQZ_K%pb-jU?$5}Qp4E?1-I%TACs0@QBQqxuIyw7S0!ox$DrF)n zz=u$+(_Gfip>n2431~2hmOe}bn^N#R3)sxaEjONo_ug@-tYisSy6fE5S{7}OxI7d% z@+55TEhGZ%C`FsfC_sE&db?jx?X7=l6Muu6pa(hT{=ljNc}y~SO<%H$N}*G4tV%TF z*5NdekBn=!+e~~Yv0*yxKeal+E&b({xq_-mep)cJ@WXJ6SgPX@93XOL?iUZ#)u&z} z)Me8Xzj8(F>;23z7aD#$SDUbT>t*z5#KK`@?@1Lm!s;UrA>Q`ixrJbqbq-mVdd){# z-W+1P*b-a~*B(F7oG_Bc7(bQ1vBUq_t^Dtu?N>zY7Z88PlGnuV-SHmxVd zAI??Y64t04(~gGDH#``NCC*`UDzz z{W&Cj`2n3J(z!-+f2IY@Tn0B!2asce>lI_sBb6l#I;$%Q=>@g`vp#+gJ8W5PWG7-yn>BNXKQ z&Pu>2+F{yKy5&nal*5}dBZueQ*$+qe)lf>o+3-EE1w;!eTT3O{oxM6x*Da-m%);t$ z;t>duVNL14Y4vsC;EGY1yyocmIW!IJX6$at&-2pBhl03Xi?vM1YduAS<}93}K^RER z;TjW!*{kLBFTqWQAkms|4N2HXxw4NDIj32AD-pM_m^`Qg$FchBcqu(8I3qYkV^TyL zv`!>J#jK`7=1jPCT!5wxPxxDq*M2Kmu%4G6V-7+bWW6l)QeVAK4UGend*E|#AK$_} zAF?u4CUf632mkC+6;X3m0AD%{NzcRwR}OrlLerD|J^WXEDNnYqsyfp(+l{wr0pBFHnd2fcjPx?vacr$#UxVJ;q;a00aGDH9s3HQw(`=2vk zJ`KdiiY7BqyP5lWimQl+Fq0L3Yvty9*s)yR~iXE#QTRiF)jrfP)EghN=B(H{rEp?XAwzjsduxN)8Lpu zADAc9|3Fby?hAO-9wqz)P`)cse~bn5wCOs}FV+|9TB|V!x&i!|e1GF4(Fko#dB?2Q z279Wja>TH6k=tQypQ(e7?qNL7ZM#rdyvBiPMh8ia!hTYcIh^rlr(sg&N>idoUsG(B ztq@+gBy)3JU-lKTgKCfoT%tspm8BCfQc~&~?;WTGlD(LD9S>n8PV_G0IS1HuiAqNm zVg2dZu-#$^<80qWP3AIzx>RVsv;JD5?NTaZtV0qe3Ic(3R|+C8bazyRAygk2g|gs4 zPoHX#9!M7dF?qpypy5n~q$t5g9*@&^oSfERr~2{U`dEq!sri6+Aavkpy>&d!Sp|oW z#MFdFVKw#l6CUX3$ug6Q`m!1w2xp-<=wm_B128Aq5xaZF-vc8iv-l^L_4Wktay(BS z^`Fj-8y23}-3SSv;N|#DvBVIpkb2*>mlY(YbolYoUa5JL^(@ZRx0XlCIyPDe>L z&nAU#ORK0HV#7%>5EgS?cuJFaYHr8B`_#Yr?D%x@n$b%}>Fk_q!iGjs+P_DCw_lrZ zq{YvjNipaOVOd@4w#JQCTg#hUpltSP3IksJR!wjB|7rK9x5Z*#ZHyWIkYIQ}p;Qu^ zYf|5>A$R6Yg$fTu{$)gZEnRJ_Dfuw z_yp%>eBazA%PdU;uI$!8*)U={ely!YF1Tde$u#=Ca=+r%-O}{@ zANvG-IP9bcNi$}lD(uV&}4_HTSEhC{?=QG1^jK0clc z7ed>iMRMRubZH(jT+;@b)A(c^ZNaOb;kZqJ_uP?Kn=ca_wW1;sj*QK+e(@A{b&Jh3 zoexOoe{WiF=TeEP{o$C~KMYwAziD_s>V)W1f0li{k2w&w)4l@cI|lfMj1^q=|& z^&UHIN1<~|Gl=Iuxce&07>q=UuS^{qhyUh7+q{WlGD@MAVv}yN7}HSIWawa@ zN+{i4UKqRk!Q=;$Qiy~@rfw-ycuwGD{L;EAM!jER1&iPFE@)w=nx;)j$J9gP(79;& z^KY}6iTwQN{_yvkHa@_@YFOXjO=RMb)oxj7E z7NGr&Nny1k)lYKY!q+1>`LSVQQ~krNewq%xz(_UKF7?>aaI*3svw|1yh z`hogOHTGmG>IpZCOPv?_t!pSr9JUwY3!S#@l}2L)l1l{@Wry5V`{)Y2Si;bCA?5ErC5}o-P%} z^LJO}JE1`kV{8ajagw@+oO2?*dVlPFb6I>b<7U#Ai-{L_TrlQTTz{a0<=3?VP5@_G zp#E(raIU3@8{eOWq5Nf_rQqEw6ni|rhI>fLiw6=uiCy2iX}%+1 zWRBS_OP2fRUrwocdVwg(tI@`#Uv8Mdk12hK3A;$xQny|K8=fnEunF9_h{rj2%!Dk!>e&d!BOe~?C5yaUyVLi&QWWjdXndU5 z&s)#`!AHws_t3`$>T~P1izAlv4xT3jfITeGDE9@yoHd@n4CNh96Nyy$xPkUf#VmP` z|7d}<9T(jQ9b3+zgT;tN(&s3UuvSSbV*t%c6_nE z<`oB&TOF@Eg;;V`U$gL%rtvc7+#60yJ2b&;w;)biSx&JH>!@JFZ;#J7FWC8?WO=}834aXZ&X?Q~mPgQmk2WHQT%Q$)dyPCa!h_NjDYb!c91Uu71FB&mysNKTU z*O^4ay}04pH%^_Xx#sP($>opoz^FXnx?|p1_zc0KoKLNlZW90P3n5pF0I3C9A(;DV zkauar`0Ewde`Q<1Qi*HpthE$P`PH%+T41G`*0RQ=6p9pCRDQk9}8$(6jcP3(yC5{nCT}6mM;V6Fy$a0;A=9|-ph0n%V zBYOTmTS)c#2?LSsYhf?p;G{uDAbX=AF(@5>$6YcAdL|#ov@bywVmc^9loNku%NsvO zp)@TBX2J){*d%^pk}QSc4}huk#AZ6fK;X&(V#xxa-U5UJDc@Js0U9v4adh$GQzH_g z2(r-fvjS^%`N3-pndQCVqhWLTn7gb;dq-WVvr@&cy=vkVpz zG1lP!F-GMTWsWyBOGnR`AT4dr}QIEIQ=X>AoV9(*>}(Xi`P?$q*B81FdzefwAzU zlL{C!;OC)kVJd%-Ygy0NW#H~0FN+)tnfIhKb>$xdsGsr2O>jxJ9Q5uXAOBpv-q-+Y ze8Ny1%9}hAo0tePGP+Vik0ov={o+Avo;-rGCw0a35?5*P#(%G+c#$O*_u9vf#NsgP zoq+l%C}~v2=)G0)40+WdvWw$(zN^sR_j*5lSK23a>Sxb$#`3h? z5_*|xs?KOIt`0V7(bu?nmhUJmr)KpgGKT9igiZL;T>Gp>{uX%c&i@YgIa^Y~^x{*G z&CQKW-|%7Hl`U$I6q|~}x~QZa3qI9(Rk?$!SE9~NS|41>WRC0;0G)4Z+rpY&XQHrV ze_BSUXklrE7NLfu<&Zp zmr%w&z44h)6!=KQ`0JK8M|_kEDYi|5;fubBy4QF6mYR#?X5-eAmC?8z8><`RLLRNC zlU)-ok}qacvvdbmF=1@Hq@{lChkUKSyzYam>%=h@1EOCs>TudDW1IxG0Qrw~AHHwz z$e_p#@l6uL!V4L8+$STp3%oNX;_bH(pws=A#T&oe3NREuN`kVZT{3k)2Jk27mRfYR zMBlT!SMYxx>#eX+^r8E+TCvNNz@08JokDW&44zN1XJut{8>yxBes|b1Q?@Mqb-6^D zuiRrS;yamhgdygW_lJCee~gfuWT>>=wL`UMv49du)fOLQZZk(Lsc#BXifLglv%K2H zJZSM*nx0_ZxIfw3w^FU%NUEw4zh+5e^ir*JJ#JxuR2^R}xN#|ceLB6PO7uGvM`uM= z`{`O*m8rl%*MoP4p%hkQ^2{pwYsf|UI8uTSk2941narLQKdI#QbFHeG_{F0dt^S=4 z#mhXD(L`1k@YwHDMRDNu+`|X&-u8a`DYhU=OV*r7cr?KnVLJ8XkDGmP!~3W1heI_( z zAl9a>Xq-G^$99-H&d^0=jmy?XWA=>(gO>|Apgjdu_KjBkgM?%|T;5ExEuT{h=c&Px z$UGHvyXh(}SC>DXmv3d^aRYjV^WDT?gx4hWo%9)9X$jX-JP6nd-y($ewXW`)Bazx+ z)bov2y)%M+uTR=8%sa$^&$+r90;f(jvCRvp$#q`zuo#rQQW_)v541H;X{F7^E6rF} zh?9ls#&)`zYe35@ue>1Opt9U8o3brvn#ucFE6NXxPwEzos9t$?~-n&wvvI$ouC-7xhiC8iswb?)Bg{{cc_3%Ei)KSQ*RC zS4Rk8FV*GKcHtAyJiz0{ZR0RG;pfZ`E~0g3w_0xcTj2y4@BV>1hu zUYKY`j-7Vkr!nTZUDN~%JzV`NXX^l4`G&l;2r)GzF9y> zXPsopna7wG<4_eE+ur@I_Ios>^c+AC92na0m-Bc^%Su{Dp1hrS#BI>=#lGs~x2GnP zxmw>%RZqWj7_W%OZ@ochC0u)1usBPuV!87({_A0OwNp7cL>BSpqyYBwQut#-HJk_RMy$?pbQ+1Ps<=(pwrREkNiSMb0U_p$4Z@0J>{Av7Je<_hL zv{WctxNz#?dM>6#^+CW`U%corLw}I=1#x4aR@CjEUCWb;<{rg zECPNklcivKe+fvU(=WQ7=$s$JTk28{A6cpX`d3Vik&R<=RHr=$A{6?38`rmJ%Nu%E zhO&s3Pwf%{^#pwnSDYRYi{+pLWDybN=KhjJTS_@LsTKR`9t4}R`wCllGagiXR3!jd zz=Q}T2Kfc*1oxOLqk0m~N{2|L^gv|3_ulO#!{0gzJh^cKZst4z6ZbT6#Q)Ud5+q`n zGxx&cxb|XDez!vJBMnU|3}s-bZx(2Zr55P6tAwm=VG>FBn;jz3UX^lBZY-9HB9qQa zaMO01&SRF{a9)~KD~9}?l&o0=Hu1#;4==Lnc;Q8MBx&pPE{vqz`+|g9R0Mkon1-NS zzVZ3ct<7iGyZ@U%z@@L|Ll*%HyyY-pyHxP5Yk$kVUU@9!RD^ECMROPYpBLz&E@I$T z>6_d|<|6aB<<*hJHQ8;DR(=-%1wO5NtJdqg-h+;Iesx0Cy5xI^<7eb!ZI{5olY`7l zb2PSYTZkoNN6O6mZh!T+hcFzjvS^L<|4s?>cw!us+Yvz)D$JKz=WK zwj<0}kQkis842fRBbF4E0&?7Q_^?E$UdVQLu=5YsEnkh% z-O44#mupaa>DIpC;rV958lw_U^WH96NHKD8oUXIb2KrJYmgnUc{v~Fsm_E;78xP<^W={J znciP|7cViLJ%sHq^{bE;`q2;VEOkF@1LV(u~BbK_ST9<&W0k9a9Cy2f<9+GoW zjGK5iwWXDURe*%{r)Q^hq6DR||1(eJw65HiCFbP)D8)NP^9e#cG28G*{d=VX8UPQq z+%X9y6^Q_-BA}iLiTOyBl#rDn2UPU}_EnUJSC(cX6Z*w&;?`1z%q(bCfolncTtlfs zQ8p;ATNs*~ZZqt`C=5K@!nL9KkS(4IAcg?X04)G87{mw7k~2octBA`0_n6E`jV?4n z6cD`ug5H4rip5zM$RhyL)HKcVNpTDGJ~iejM1BE9!?l#*w~(ErDFoOEprB!SKiEfk ztlOY~ZVQO(#xfY8akP~16#$)j1)+gn+9N<|WH+k~NkqIwmLkv{I2YQY8ZamXk~}X% z31PxwL$51?^l+I|8A(6GDI%t*^iX7HW%--8(C^y@L|dHU&q1L<=VjuGS^hTz2X~0b zs){qFr7xg(Ji~a%rIsLDQDmRH zr4qWdCPR)_&r7yo-4(P29xHmfz%mfWlN*R;Wz>w(^1W^YeGctCcx*$&)#7vj7q*n% z7O+6{)|hd5YDwL${+oZkAWgnjPccLU=5O~h{7cAM&q%Iq6|S6_T6g1bw zVYrb6gNm~wr|Yk!=d;O6;r z$D0x{NP|T5{Mg0(s7=7DGa7kz;phEtAJaO!iC;gJSvHy7akp|c8Ok%M(PV1IUYS^x z2zmn^9$(6&b<=EJ^B;U&9_y_k)Pc} zIQpTA_d&9k08Q$ZmbkhTHG3VV(R1;}YH*;9gZSrUH)zGlYo+wSa{21`%rPwk zvWR$6fBSsFlfkU0EBuwPShSDwTxej9TPDBdc8hdW$K%5qI?Pi_*ZT`|Ol*LZ^J6+8 zCFKyh8ctOKa;Dzv>&-SI(ux?orlDevK>7s>VuoDV8qNp)tdr*4^9+AQp8*-7w6+)9 z;fC8GW!X8{2?t01;n?l#*{0F6K~ev4+xWAiSEoy1#3BiS9tXgaQJY(miVDg|A3(QR zJgK&jLrSVv`xq>3)!WeQ+5_#h2lfNg3z80a)GsYCEw@TF-agO)H6#Ps&Bg(#DoJEm z-~OQe)5;bxylrZ5xv1)%b}}vfi6`Z14y%v1`yFnrG{IYnQOjUn3x&`3)9pU~My}XY z4})~Pd4o>Img%+)(dCUGk@=DUMxYeO|2{3qFkx!?oI69(#e_Gn+t_JLDd`)WEkglucVfpITPVY$Iq`eUk)%{Te3#=517beNm5 z@Fc1bYZ{46+BaYF*=ba*w;X1F{k@p`&lVMoJkxh`fvs4h!r5a)pfpj%xuJD+Ik5Go zW-s?R@yNH3*Q26A20bnZyGgmXEpLbN`@4U4$8~9OI3>~1)1Pw1Raw|;FEbdcIc`*Fm&H7a(&t}1GIizJz9&vF_`8-_aR?=E z>X@W7HQC|M^W(ReYvC7BU&;{vIB)b^PnC4%#c`PSY>T$Ev1fXQ!V3usOI(0IUOX^c zGU;SW+FSaP?NhRr?b4!fBhITflU{T;(_lpWc80e}-jd()m}&a+@xwFpa`DdwGTk&4 zgLGr-0--0OyrZ?9MEvUN_O4$^18-*YHr9YNE&WXR0&gv^VRp^Ju^JCcH864H+P^mX z@`i+7W5vtZ?%yy8S&Msbh!L1>3~Bl2t#HLz9eO0$@IM|Eh%n!b~)V(EyuGCYmTM9zi4@;uLyyCoHWsIbkT}d zFiS+~H%%^u6Rj;7ravBdCc!l2yx+p0@8g0pnTU-xcFPX!viw54{`ws&xp`A^!z_`N zGiOiHfDi8PP8-T@$2gO}42Fvw8uoOo+ddP4qzV2u?Sfr`suFNA>6pI@y6>AQ+$MsZ zl3{$`(;$;ZJ>BNB)xmUen!fXloyi(UCbd3VA0B1<>iw`W%kW)ukyBaPrX&rxo|zAz z+XZ~75~u7V=4wxKvyry9+Bz$^+=fQP{%#X`px~zXG}h&09fq}!(do2jTeaR_NZKC; zA?+Fom#mtUhPhmL|9%dPxHiURic4a&z1uF!6i*{1$KDh>%v{my>JR?Ne)+65e(_bi zkl+&)GbW=peD}?%t0U8Qif|!JBDbEp9uDmr61@_Fo1R=8ejia-n|)i}Q@m)lhFhaj zd;S_@;~r;**0@s5xLPygT1K`Vh;vd)&suFa?TT<|ZEDTzyMac?la6g~Hr57E3GALld(yG=|_|e{<%Y^Vl!_MjWL7H{=LfHjO?Zlh#!# zBAF?nNZ|KO)9f?1Y0a_L`hUVF6Tk&!ZMDS%En|K>md{*A9V_#8d6FCvb9rZ$(Kpms zSKH=yCHC*8p7x+?yd^G*4=!h3D0nTGa+1m&$!orxi*Qr6GZG>UBz}?CUdkj{GR5R% zF9;&RFh-Yh{40@0PH8IP5}!zvk%bPW{#`krV3R?c;E?Sr>mi74_ur{bs))Bhm!$Ok zH^ZZIHnUcttCi)vYvIo&AUoK74NU+Jh+>0*=wFYMrB(h1!iF@@E=9AE24Za4kAjy- z#qx5w*IWHayAiQ&st7Xk5KpzgvkJgh**T1WR$Mt}?m1ZaVwvTB3Qj_R)sMJO?2sQg zHNbs=Z2MajFLqCrFL1c(te||d<-@6sciW|g2{+8`N0HkuWn4yaA|!^LfexcVfz9f? z)Q|E(5a#BB^8%a51C$s!?m9Ev#I1PV(3g7^Q&!6++iQTUN4^ z@%%uWL}IvwMFe^PpdcDyCudg(&=ywpFxwLf+RTxf7Ahf@_MD^86!#d^?FP6aD6O4q zDI^xdj94KMUtMiY&8?nt7L+@J{lB_hP&?jMi`~JCUImMqxXzYnPuWnwv`qSfn4zlc z?L6{(#amS`N}xyX0m~-WX;~uG8OWjdS-8kTL(7lmAIe6OdC&a+H!VH)uI|iy2($3N z`wsk2sp}a&+t4I16h6D24Wz}78F!#z@ia3ztLE57Jv45zYFw$bCvFUg zjGq@CVM0eOw^dYREo{9zo)ngxfWt{Eghh7yOg`W$$Onn4$G$S}kv44%{Rxo7i{&q* z(ocv+_SKaM^rZAW2sEe)HoBeZ8+sH8^=is_g6^Pb&PUL(iuU%%V&HJ1M?m3;6>;kQ?EBq`8= zBe1`BsKp-IYsI5Mou-lG7dU@cWH$XngX6=S!@*3fVVnF{=Wh-CUtLLJaNe;s^|$C@ zRv5JOV}xUs%X#M)c_`(h7GxpME6qgw;cRS z>X-S_c+Q$XUuDp*%7n1$g2-tMz}{`#ag*EG0!{=jDvHs~upwC|@;~}{ey&GZ+CAQ( zff>3B1_N#95-%w5tg}$0xF9>V*y^#9I{&6&C-ux zebn;on_}tkH*o`9#VouCnPWvsi9;u>x)<8E9=E)ZD)&@Jat}f^ngE~P}LaOjb*OBH298R!bHF=D_MNmefmOK6;ulR z=%mgHExRq@L5Ji&9GA!*U+P~1NvuEuP95PMeMJst>PlT_7g8xW4&lwuC}2@^IuD8VEk~;`I`$G#+#?NLwV5sTY`Z`wN`8V7|JW=J2q7 zY_iaWcs=}2107wU0I!RlzQ}RZw?^@A!PT4!%7W}1zE$sEbQe6wtTnpfYS@JGbz#jT z3>4a83Gw3lIw~&ctkImYBh-wy`9V&VEm}U|SH*bTCq*R1v^Qyfb04Tw#T~n4$Z3+* z=4Oc#f!|EReZy$UG|92qqMY6zhWc5tlo~|}T4GXZhpp8Y9WS3*oyW=rmRZxV|T7 zKOwYD?>n!ZBI>HEmf<=af7C#`=XoMuODaX-RSQlQ($Vvc^{(jKtJuvW-4r`D6+#nu z=|Vipa1se5N*Re2V$x~lMY*|Tp(VEf;o2wbrRBlWL9-ECiBXH^zcn$5+HXNR(`=_fe?J!8c ztIi$}6BiTPO{;aq;4TtQs#%6UMBqWCDJ;zV{eKMeuN8XQJM=|!kPIAGh_V-l(IY%o zp$3^8xiJ&>lS}0iIK9um3!UtBi;NHBqt5CgV=db2mHEH*KX6(L(8Xc5Ot~a(^0G^x z77^Xn_4w2_8u@tnsI%E-ap@uTn>V#KZH^ztvTOnp?|8`z^fXCq!KH8te@pYacl^oZ zZaXR7jnp^QU10ZZo(B&OYNhtwTscm*!Hfy1pKdJY0UIzVEKjn8V9QkOQ`w5MF`ClJ zZrKYY&x;)3e_b(3OE*>Vuhf1?m%n9-Rh(Y~1)>ERP;fLhhYLCcJcccW^+bhs4N|C6 zUr?mzC#y4B17=|%bwB%4zbA^GNnc1R*pc^>&e4!k=%m=cNvA?E7?U-;V~g^at(^^n&b$j=vEAvBE5MBgyY25SZ$0cqL$t3WKe0v_h z{WvkcCrxPHw9d%u7XecDdzT^)8K#IU8Ij^?ss^&d`A*7X5x^h0Q)iQGnw{LxIu;2f zG<@6PtdUfdmK0AH3=J!G33^x>T?taN^x>6<0?5`jeirZ52$7({T zEp#MjUF-dEGV(8eFOZ6DWsSy?s*e_I{RA4OilsY4<4Eu&2BBjSor#aW&xFO}gP9?m zDXsq37)sfP0+I#bo~!e6I0(?D%8;BFDE-BUBmmCT-EjW`0?Gac2%fj-hdOgwM;fg# zs>tf?yM@{TpntdK1K&%-$W&|L0$^_wH>2RKD0$L+>2 zsRqMOz<44Qb0uNKQE; z4OJN4)BP415204jCU*$iVuW60h<2>+J=io&1r=`i^fI4MmBePMFFMsGkWSKky+-OM zeXf&VBWTQmz5m6YL}tzDG?kSbJCqAVpPd5%(H$O*z2aXpPoPi9WoJIFS)u&+SuL3V*a<@lB3 z{A%u115inj?$}&Ra^OrXQhS{rHiYL3%iUi^l(*o$LlADm#Wm%L30NhWyc8iIw>u{o zIEUWpg*#v|cLM=Y!jlaIXkjXlu0y&f7b=6jLGNoXmO^dDts>|N3TjWmT}+%n!*l>~l(R#Eri-EVhd4;m^Ik+HezK9Exs zaZFLPDmhjl8f4PFs2Jj2RRBFm=+Y#$K)MBD__?J`>ZJ9+87QGsIQS%ZZH}TdCukQ% zaOD?DW^RdEIV+K2MtDG0_Z7(4PfHp1sQLhXwGQ}7PblOcwl>S4m#Y-Ek-dkzhdRK8U*gg+nAA z%*$f-W~E@Mo!0_%X8jYmqb^|>C1OAsV$Gi;xtaQ6z9C{u;zfW1Ak%M7A7Ua#W5nZg zdnOGfE&BL8GvIW*Ryp6Ts5#1vJXK}*55(+TX+`mUH+=(uo+$tCL;zEq+b>(ONwV8B z`B4|Vv)TzfR7&U<`NSHRTZjYXawNlicTy?v(H&2Ty;alDJiOYZB`iC@kd)!FssxXU zgSli;mId`|Fq9%$U5e~qn;{A%ay`dI@<(E&9r`u`*b_gU7b z=5UlWm;AQGL&pimDYDfp+iuNK&-wk%`Q6xk&e^!G_xtsFJ|B<9l<2sqRMJQ-&Zr}+ z!)hDjGL>{vA37>va^lni0?FcdQyvvh^kaJa@~}Pwl85iHiW&|s3lTP4*`?K2=2bu= zz3f#aB>GgDFV@c6NNmc5g@Rfce;#VoC%na25NztQ*m z{Z~Oio!ubUt1(HJpEIF!dJ2_nByS!Uh4;im`wa&fCVq*M=+h4NF7sWg~uPgX0lpk{} z-|`b2ZdTyqpkQaaGrz z)=EOtfripTKE4t%?KKp0N2g2b(R$@N zUqCgicBcV=Kzd@f5_6(W&po*RZsNCTjLoL^r2kdz!M^gnBv@^Tto{R0-|T^|;#hb8O;Jx>WbJFSg2(oB6$nNB z3WXwAvfP0RX5SthQRE@fn1sCt@>NRUC;Au;EdY^%{DTT|{0n#Q{$ZC-_3^fl%)la@ z`(V9B!2hO{3d_mBB)QFlOdGGd^JB6_ZRBDjcx5;f5z-RqCjSTHw8OA@4 znsrwn%ko?6L>GP;X~mLPKXMIgNo4yEl;Q2MJ&+6vWQ}hs%kU}v!`vlZ>$UrKnRX_! zEZjIV*=Ot<@usP~o-;Z6eBFfXl$+I07Tz^suU6(#U_K73pCHN4|;+qz>```@Rn zK`qS>k%@60f|&R5>ZVmoiiShzgu2sQ5}?y>Tvk#>QNi4Bgv{_`oTH_#40g(xe^Xp6 zIUlECQTcb0tb~hy_-9G0yBpb}KLM!kdNH*uq(-dNdUz>LsJ{KLQR@R7#A5d8b^#ah zu~YW!R>+q8zv4=itMr^;ZPhNSWDnj*ttjTjpcL$lw)(Armd$&Nz~3I5HjRrl{twix z;-uU+z_lP3`ujgng6oS%_78B;wgR;4`F=qXTZNE0)%R_+GvaND*|p9e0mV&bPw zlr9M;4DFVxu?n~>*+N1*%vaVaSl^3`N9Cf%x4%gV>pC1Q%O9stUa3)>dh{aoA8Ig$ zGgM1XOh)u`z)e^Z!GOtZiaIYtSiTrs6?!0gu4JT42r*D56f6ladD*7NRJetlPL_@L z3yslr0VN?4=3_TNi`pJ$!~`^Z&yw-KRuXUPCo^`MUX_7`<*?UM|-s^w4%*Uun_@F!kIlFyii-`DN3 zSbSNs3WxGFxP~KSWuZ5&Fm7>pF)P1~=d_?#>$sN%voG0$K@E5xlN}RI`%@f!Nh|i} zac}&(cTc9N<4*kxC4ROZaL#7QzL~AyY}J$S`%ew?O(;CY_m1ib-lsL|`Bet58U>p- zW2hg&?ZM7AZ8isGMPH>p6hOuFI6xYMi(zZ@g+8eQ!qFGx7bC>^BO)$+kRG<5BcKy6 zbPO%)5Dai4H#PrS=aeFEc<0bkUEeN>QXc5YT;X#mD z4k5#+WXjd`e5cTA7ruHr{+Eu|p0gjuiK+;AKI%yx1y0(Syx6-EW2)MLfmiKmMU zViG~ckduxT3))&q!^u8IO{R_9f>cCnO~E&1*?&_Tot!x}Kj5+$O8-a_f_U43D<7k3 zae7DA1B_vH-Uk@|CE{(IJvj4)pmns6lB>SVn<&@Z^i|0c$K?osW#4Z{6i9 zq8sqt_e6mBNazBuI3dyNd#IEzBZG#^b06PH-nZNS>j-Jdc!3zch^fhX-+5DEXPvZw z!A65jU|~1nBnaxQh~RY+FfQ@+^E17`KJYbE&@h?jDS>wJoJcMKRDl^C!JA)b@0XI# zAYXaPO8+`adHQZtRfpiGdbOTmjxG()73)6z^T%|uFy6Q*`La*5dT*GO7jKSsNZMYN@w3PRBK;xoHa1z-*q+&Y9>+a-OGVNp?#&`R`D zju~q%WJlGQoOB*5MRDAdln~Vaebp`I>)ZPduIbEvtU|E5a9b1s+gLmq`)0mqDrG8R!Teq_m9T3s^qV zP*$CX^v1{vUzGH50890V0k#Q<4AAvu1Y~;fK6vh(xiuFzs1h~L~%|74I=z@Y` z2apqB`Yk|gVHFIBG?^tL8Y?*Y8U&VMg@h~t!TO^4sd^PmYyuJ|TW9<5HEA=N-bpC0 zAZnxe!*-Cfv+b!I#Y{z|*4z8s;xCUJOa(vKODW2XPMYaWt4HsYsSMcNfkz? zr6-N_3^l?$5=Mr#s#G_}#Q!_r|Sf*vNS}E~aKZ4=no}eDpSKo){?asT+X* z&yjKP>`HVeZ{AVZF?}p@wl~__I^+T{*Cd44jJDC$JGi+1eDeW_K<5TpjMhV=Gxuie zr9kk8fXDcXOS4kh+z|ZOjpmwD;B~B^D&=3d1NPnLnl3N6ncQZOUvviT9 z&ann)M-1v%gT;TVyWtmb9}n92Y}MyK5xep70|M;8nrGp-@VY+5E2WW44>%^=B6vZE z>>HmwOnM^PfSyz1N|Kw@v+=_|_*Z*ev?2~D$8nT&%6ob}y^v1o*7~%DKj!+jris9& z%m=>s7LYy3vfdQt>(D$3e<>q7y35YtMjnHFx(pi3h_zc^*Td2A7N4mz_+$3Kk5LetOTWy>xAXe1 zTV4iVT7 zxo+u!?VvbAQu_hCt#ai9B%9+CKiMRvKNKjUg&IdOGUiijsEd&$cB7*9)Iqs+fNpz>{!fovRb%>dIe}_uOf($p3?IAQ>#Pp_MJzbYhwvu~&vWu6K zyJ%IA29i`_&JeNu+4gbtxZW#hiGAg)?N!L zo~6>eE*j*mSO;uXbQnkZ`7-mVJ613Y5-5F9*uX}jm~x*p>jjoC3Z^%5D)LL8l28&B zQ5E2vqPe`~54fI}B_qspb0%!#1A(_lH=#(d{~30ZeYz8IJx#ZCR^+vi9q2xE5yQy< ziBsqxwKBxd(dVMVi-bXeN|7Cq^MP(efEC8}wUuy}M(^$pxLznaaR$dz_tKo?Vc9IA z#tmt-RcU&c^pR6uUBKV2u=iFx1R>6kSw6}8=m(;hf*k#A{x|9S`g9*=wtc0}3E{}v z8Ic3}b9yh)N$b0l;S7h{?fiV(=QyqdAP_DFT&u+dC3O85$IM$rkryZWofr3 z#C>q|Z$3v!nFV6sM(`T;>Vay+(ISz*Go@$;Q!+_-ub$6^EUf++e&9GQB6Ag?mz*@- z5cGPAez<4e)0iet&AKSAS5nT*AWw9Ni(>_Rd@JbaM)d(5C8xKk!*ZB;(tU`xT$$d$t*UsQPx+D_aO+p~yXp zcq@m9UJHe=>q*X8xvx_cy?nev@%rj!&+5F~*2F}2yU*jiU6yEaS2$r@9NmpNc*oTI z$|=8zPW~CMN5#c+|9S_}WgcnOaPhWl(;ZktGXGWYay^*}{YcA)dks0{n4t@EWIe)5 zg3rJ)h?LW=M@Sk-zCAD^?FtANMcOsk)!`NwtcDv>hX-G1D)AfN?VD!Sx)m+BI9T#p z_8bdALndR`O4EL74NwCOq@7$X&PdsR#?IcAQ+@P8ArmLZ=sK-?yyyFt(#KaTkXCnW z+xwV|&{kuaz4%^vS_Qcu>V@*6fgV3canbA9d|`+Dg*-Vwl}K}?gy>{VA3Zlr{troW5k=ty!FO*>mSbPTlb2qlw~-FwJIeSM!)*K;ygR-tt7`Ek z%I##64o^x*+;{Rg2Mj1_SLhVZD>7%$_!LPm4{I1Qd4T5~B)O;f(ADMP!wvqKbY_`5sHsOj}wErKXF>67nL;&V-h0nD-=e|Nzn7@d2STFokxd zYbR0ypbB)5g7Z~?HW%xpQyM4hSs`9xUW_oG6|;WuI7nR%vT{bQkDs)BBcQqRy0~!i zPyrbErgZ)@s?vLbMI>}LPUa|gZF~y%_Zd;~!&_REr-aZFP2|cL-)c(cq@d2vMjjL} z%a`d_2a^@Xq-T)RTPn_&+ejmSe7;Q6jXzmhs==>|yi(|Bw~|`PQz*mdqRatv=Tf*c zSq&Pra%z#Lpzk?zo(O!@7}p?CxHigne6B`sSQ_B&I-a7T%$}DGjNUfoeT&3+;})LL z%mhz6DhopU_p~YBcP~6eewvP5Pnvh1vCg`l=Xl@}I7>2)Fj&;Ee@E-6-%h0bQ{WrE zxAP1&rM7`6$6+2PY|Glw0`f7?lw~nmsvShFCJcxwMN$(-Ji!7Sqg#$Y~>Pj zCiR3B{lAQ7QLx`{ShsH!xVNN-8uc|j`jp?3`T+#zWJ}KS-MeFX4k&BkF^Rh33 zDxh7C9=CfQhHN=gp5P*O|D9xC47e!?u1#(i9vr3H#m9Ph0SQNJrR_gUOT5I~xD7075oB ze$>Aydyv=Nxsu}aL>GsJSnqNjXfxicFsg5OnmzqcY`Y`?Nq1$Wys+5L&!Qvr*6QX~ z(ZZ7$3!s5<#DvX#6`;qiUVQRXM4@|Fg(v#p&MOz7kgJ$Zo_p`F?qY+|k9MVNz9 zyw2hOB4kj&q2GLMy_7W0-+d=#&erEgk^I zB%K+L-E*?q6-#OSkzQV4(ZWZL^XYu^AE@=j)FhP1cRegVA$TMob<(PNS{}^Rviy=s zLBcY?UZfy@f%t|@Dy2yATHQ&$O#CkV#{-7L+VP&U0r02lI6;K=8r_NC-GTHr@y93w z@h!2dvZvky_Z6q3K|~V=+PP0%W*So`lCq?%(;c6QnmQHIb3K1gbY7-K!(%8b!_SqH zB`?Y$rJ%d^T+7k$2`NsNQVW#lWmHBd82MXejIabsEas-yjeBGhOS)b<2fFF>FW#_@ z_`x{PE1?H6l|X)?osNUQT- zd|7Ju)5ipFah5_TVP0}(g0YbdwR5a#a%6skr=XD8%Nq601*34p8E5X?74lPoyKsZa zmAbE&hsgp^OWxYX2Y1?TXV}(-HCn&YCLbnVA}ueNLjO$cQ+NuKz4H07@@dp(RkjdM z1(I)<#sv~&3`-zzKt(FcI@)XKB2RCBQR%@mE9K_;(D=?zdU4ux;FGA6q`$5h28z$a z-q`X7Z#LUJ2w#uU>d^IUZrk_&{!-IvEbQz_#&0SsbkQDIZqKK4#hxLnNkjSE!z~p{ zzv+G4k4;tS{iPrB#8l+NUts%s5MR3>SW7H!YpZlbx_}SX14vAUL_%0>3)EGmYd(qX zt_~B->>_(G!q4eVf^p!-XP?ds3h`0FmpwaD=VU+y8wOmAu<5NUZwY{au)4~?kq!aP z^tcA>YegKy>xwO6VSRM* z_b_8)M-5q*Ko8^|ry;f2$wbONO!t{SUZnC%jlx7v0cBYNch*Tfc!^M>9|&}OYLp-e z9y=?dx!GGH%KZdP!{Pobh&pG;IH>DvPt#yL)VLiX>IEZ|YdJl~>_Qx9b%1meFJ;gO zgc50oT61nh+VHuGN{lKoD)C61sc{rf36HeDFFetkRNE!lMsm2W%&&jPo_jr?f zYhF8_IvHDc3X#m{v3$Iq@&D@=xvZ-aL}Ic4eONY=~EOzvyy@iOis zjbRj8sm|tsp~JXsoiG9;=h)OGito3-99Lr>bFn0#WT^8#jy9%eEMCrJe`kVlURBSR zxlVk7KmrW)OgzG#=uqx*5w@AG{YLfvo)?5kRXBQ)>$kMUuxn`8?B6JLSu)UICv_fl zzhe|RRDrtUGWnBJAVSPrwx+3ChlWllhG+aeGVyvB2BS)F_nykXKJTpi%|E>Lhu*m5 zeA2S}{>a$TTf*YL3FR^e1p-#K<@wgJ?~0MlSjyq8FkoQ`Xd z&##XQfd_3k^2H4QTH^)X4@Ek~jOUgE!k@)F-ldT>Whp&YQy*|5!&6}dfl<3ybM&tb zOP73KFb|8FJ7Q%olg6sW;@8Otv#lDz7~__MiA;mKovBlX-mw%bPL)!(e~gI_Ur8C^ z-^A2~b4kT{rPci%0nsg;9vK}_;vz$a*HF56X=hfG(Qh1xZiJquBGYs_&y_y0kAE$` zN+N`gxnknfUK53fX_)gPvhj^z%ScG2!b>=JbDfZueMI@W=w5uCe z`zijJNVm5NG>*_v8MCM(f`5ArrbX2y-rkU5ED_~D#GCV+v_B?_%XTu2iuFqLALY8e zZA~3;vL~g@UrW?j5zJ}K^7!b~){+sz>@W0h=0!G$9GsY5uF-ot)23b4e#}Hz6+CM^ zKuv%h9O|>qz!t$oBsZytB%jrLJ(uVl@;)xz^5{Oj(od#XMn!sxtyHL%_sEzWEg2j1 zK<@K`!ro;8;@wo;nEBe~BtAZLaFTu5pBtLH<0M*u(=SBXq2Mwk-U|X-{@J&3Pb~9u ze0Uxv&S&-H_pkcq*PgYD9}F^e+C=;4qi?5uReW51pLpT2`D$xT(mG390&!J+cCO>{ z)9TAKQqDG=`QASNCZ?D$SFr2vr=`3v+d3@7nhegrgj0J;z;(E9CzSVa5Ankx9*0!> zTD>8A>Z0W2c2NUkNPrUtV#%;kw2Jo+;zdr~+r&OrQSbB*iwRBlIMOr#vW_Q{U{P#3 zy{T2W*$<*-%j=ibdRva>cuY)*WWs(5o}jHi#O-$bjkA3Njpi#_1`))>u3xWkQr@Z1 z3SBXZdBG+^gBn-N8&;&L9-4bL)wQ{8p^B%8M6oq@T~$Bhd9|F&q9Bk`O$t^LJy7OWX5o`@~m!V3<@0jIVia_4%|>OgB|M#vMVbcrkK; z0Ih+P;3~i8v5Z~$grM_$f1*TuZ=_#7I6eS$q{%q}_@e7Vjl&V0JVkJAPaq9V^H6o)z*cMTv>7_HOaw3rJR*ZC9HeR>#QhM zLr+z)u3KCzQ}zM?5aWDejGot;e{q>6N9FjIXx=Fp5OwwM>srxGVVzu22|n+el=f4B z?!4Y}d#vkz6oV(#KRcx}nexw*tpNExwx|~ekne}P|Bo^%e!dcXYNC@OHE@XP7Oz(6 z-%J^Xl@MS>j@?DpXS|Hw`yNKmg2D{A=YF$$%wb@@01!u>_6C~1-nJC+*~;YTW#LG$ z-)p*NC!(Bn@B35vISA|W_jN*w@aSdoHe0*pNg7PEZihU)k7#YEWh}|3m@QCOW z2&*V{Y!PNP<}{9Pp64$&$STD^ubb%G)bNZW8Cj{D37CJKYJT8vY88WBwIAQQ5Cl); zQ1lg9=v}mi7zNU=r(f1s-4Eg|H1_jOS7NUV{^Z+5^u5ePq0S*u z3c-_GkwjD4+EnHO~9GmmWQ}V&q9qCKgTX32*bIx7O;ULH+-d%V^rPM zw~Qga0m|8K=cO>}qMXT1$hbe+>e`TzrjN}TW!dYMD~W$&+(`v3V8Z8) z8Yk60{x==&2Z_T9uyTCP&wVnbO6~(ZcfdJ#McWuo@FZG;%$_|xoJf>k0eX%lcr!f< zwc3>gO-0IxNKffmFW(}5%U%?UF_!VFs!l175(@Ongi%#UCWgnuRPT?G2c3<8V^_1# z+SOM+S_9{WAQLms&YKeCL{!2eP|ZMVh4- zV$Wx1Cs#%r{{B*{x#?=sX^~M$WMTHxrduGE&kauh$@r$VIE_xI7w=oJDavpiU+lX6BfgMs>E|4x zU&X^=k7jdTSi#9LB_6{G#vd5?Y~Ma0KFrvub~fa_YLca|XX%}d=_e3J;h)Stx*YWk z_Ag)ANfGC@vb|hP+A~{Y$=4NaetkLy>AgYeojCktp1gGAqFc^=?=LO<23^}+wRzi-#7{hF|!7}fX^E97c1-dea+e#%RmK}!k4`xxM{ zFIPsi;FUv}5o?tUS`sDcJ}W^ZJb1N4*tTp!O>u66CIfsmE}fiPG8_UWl8N$@8f%pp znz_yRRI*MJ`|Qe{ZF7^in>0{<43Yc1l7CtLTfe;*6#l;#niEBT^@GO#6rFLGP#B)8 z499C02Ko2r^Il-%+3TrAkMd3U)nvA9|H_EgbQ3=e&4nnQpMqOcisSE0vM1)m= zheNR1!HMhz4VUoi@&GXWRNeDgxe$|ljINKG8Nq@AnM&Jx{V6o8@pa5#KjzJl1#il1 z+rr?#eXVwe`$muQO9+)mw|`gQ{E-?R_NBdM+>-}L9FM!v-JuWz*(;*}sovmo3?H#9 z#%2&_POZ{K;49g@QDj4IW25gW?!ubbTu={8O5tj#o4Ne6D`c=f_(E?4PD#0712u}m z$q6fyQb|&I02~fq=pH~H`7YRa2L4WNnSTZH89IRbTYMGomXqj&31KHMw&JQw_U`gkj_?F9qd#b4I&2QP?N9pEZ~O zTm%M9Q-edb%T-v}V!x_+D7&}{- z6%7D_x>duapIK^`hq3-}dcrOg^QRVatb;~n2yK7*e(A4tNqPtyP#k&w%qu?FU}|5( zr35sBhnfs~qRg0YQ_qAE9@J2k<*_UK;;K+`O8Juh!lwE{bvhAT%rVej9;KXoknmK@NG!837Bkv$IW9u3~ zmYOW-BbF6-l{}GgeCC`m9k-7rV*Fc}7H>$5G{sW3q z+5~o>0UY$EBe?$ICQQQzfLMmg=>tJXd9){YI5kb{E!vYJ<%i_T>f?1?pdrRsD9V>O zeS~EE6%AR$g|Zk6fAtK*8({7_&d7komN}H2BQcV z({|IpiL`yKd@2hBORQ3CjBI{hmQsb-TdxQl=N_;ixm~dJ(;p7vq~wQ@G7sNb2{6hx zFEQMrdvvZFzFOIDmwa_b>4HTeka(o#53?Ex@y}{BkwxY9T-h}hmh-YkX$}oT$Z7twc9vrn+3j+ty8YerbjL_i3trjdtFd;GV5J z7rk4i`sBkn##FjL3Sx8p9Z&9jsd80oJjPq~BDlhh?n8XOD5>1W7eOmRE-mg1^HfMe zJ*S;3s+W+50MH4kFdxu9HK*gitKc#^iEKVEJ{*5XP}Xm$FE!w z*?}yJaq5JU#aC%;GulW`I=zxUWb7mQ@;1uHAIQqTleIu=7^FU_9x*j&I1WBc+W8L@ zZuFEclYrbCx@T4=?Ns-PQApg%!#=6?TQMz+rFqY^?u*)RL0MnITt$gEU-dYCxE_|D z^?)OTJEz#=+Jy-}R&nOlF2t8Gj8tvhut7%b&Ntc^6vq;aoRoRlot|TeSFm@UZ<|Bi zxm7Z%uHO<-5LVZ90+N9>FSp*7w#nF~CFJLQWIdoyU-z+)vX-@G(qlCfP3VHRtT&u- zzZYtj#645c(3wS%c6r^7{WUi_TyxVDj~S+#&RcgSRsBM_Tj0ohqEm^%}k zN^tS{?&FwcU-PMS5XPCPQW({%?qFfvkbeApWoYMl7DKwl6XS7lS7t*4auF|1(*(inM)uJ6ds6^x$Gdl zxB1A0dhL1j9mJ!5uTcpr8Y1y5*9E+E`%8v8I4rOCW4wM4q29hSj<|YH!#JW9GVVsV%0fF#uM_mSRe2Vk=hP3R`Q5PK&%3Jt46p1R>QB5x6xze*ZUj0mMnxFI;|CY#g~*s<=2B~>KvN`3l{m^^CG(5Up8wfe@M7jZ{Vn)_&lJxgM6%lN{(|y z+cq4-0`Va`dr9ke>9g{uv$0%p2xwu-C={|0Y@}(unm`Z-y4DYM%=a64=o-t&G)l+^ z4)zrAg0TqCVpOkBm7#k&{j3}5>>I#d`SqW_{lo0Wf6=GRB?Icl@0Ka4YO({oTX_~m!r*uOATd@d1Cs)jo}ZBP>_eSWlh6Y#eqQM( z8y`Kcom#k>uGLPTgAMg{W;*TiBkHz(XxcuAHl==sd?#5GUdmX_WmfbOz6tw!} zKhKmxph3#4(j!+DBnO2pwb?jN6K?nN$|dBfh2*>DfS%}kkdlLxsKk&Fuhiku=NY3i z_|}5+R!b@b?7rSiJkQf<5{k{puBhFFfINV#e6wny*oCFPkkEV<8_M+6O#$@4sLRbu z-m$_iNy#r)uf_F#64Z{N=+Df7p#Bfq?)4g;B}~%B=XCQa$-h+rDOjxsX-Q%Xwj361 z0Wu@4Un?X<k|a`|x>d&jI* z!{qhD5ALlm%13ci{1lC}G8K|h>MHL$kz94U56P1|N?e`pWK3qKHUb=~Tj z`4IG4s(RiNOnle`h`A*f7)E$_<3H&Un812}AFf@`)HCw9J4;M_ha1i$?y{92sNhCZ z$0c$E2Wp0ib$%s}#6}(im9TU$>n=?mvY1No+;3d8&t6}Ps0)a^KdwOB54tSYYW+fq z0r4mDr9>8ksy3k|`E`gKeqwUU@iI%WyDyfLKXWVRU>QZ)nj0WwxA)gzk-w>lHj;9! zG*5zbI&;dZWAb@^iaNTMs3CDZW7@d@Pa)W;_TWLPfa#%$mYT-k$2gO_TVM430;(*6 z?KgGF?d^m1+e^`G^FVE3R;TqNZ@R9a8+Yw}D(+^Fr%jNb`cbuDlBb!V61hO<&A7#QQ9&oxDqBAJf-ry8pSI}x9yqIFPHT+Vmd9f4i zYJiG&KHtxJ`u3?_s?wSe4pHS{-WWGH8bsfIzEDAW%Vfz#gKyE(Ei;_QKH z5?v}!?Tq(#7W-zWtE`qX(tRc-76S4uAfhj|Wpk(>Q$xaK{=;ou!EJ20=tX~_Rhm0b zUi;k$ZIYqA2x_l3ZC|sVz+t`Bk3BtZhcLvAJ1T&!SP2;`Yr6XtuCcEZ9=+SnFX^yZ z7V7&+T_}A0ZieZoA(@p~Mjt#)lb4x8sXVZ6&>)@j&nTRUy*Z!Q`C%rSWbmfxEZ-fF zADR=|Jb!>s_<`jp#4YljR~=tWt&HF(8J`^HNMSn&X%W0G-IsisLbKD&y2eHm`5?KRyl(W2 zhfqP2`@?RiG4CrgC^-0sSlQdpEolDfqO4j#+G{;jyJK+OlO6u&4~F!$K_haRkBerliwd@-iE;L{19kqAC`zru%?vm9Hd#*5^O0P zU)^6@kizlq_nfz>GMLE+Y@k z&n&2;c_=y|Q+*K3mZ4KNQE2+4XUJa9!M-+eLi;U0SUe=m!cCN=xri=R(G{^YC;@P& z=}JbG)}R;yFPsQ~R4uCdi{T<(-VD&&gRKUyB=n49c3npK>4*p;j?k`A5q(2@@J@Gm zQix|0hp;)tmEK^V*OBt8)0He%Kly*2km?7nO@hsC?$YUZA<;rIaKo^LTLB8HjdVY!LdqC3&!XK=L+8M+PcrJV zgh-Q2mq#IKSRmXvt?|ex3uRx3AYOTWx)QD|3BusX8Kz3)@`Ivs&zuuGkP(SECN6~7 zf#zfcSx%#*^EPI0|87JU>A?yR%K2KUGLyl%>2w;#gsv`x#KhYLN+Q2V#wHN z3X$F*kZb_r!RLj?dFY6@BclRol{S6~Fk*Bt7_A*@7n9H0lPuLNChA@c(x-sGg-47c zO=BygEr~%J5=%4m;Pgn%&8H2`ZPYf&BXzqKoQCBZVHW8iU8rP%ypOrGyKQu;p1eLL z(juLoFk7DvS~#R3(k2$*p|tlF*kR|^#KEV35Q(gDob~@N8Dx+B-<@FxxHHrls6YR| z?hFAB>tCsbId_}oH_H;=_LLWNN;P7Nr5%!&;LA$O@ZQ=w-8SZSV>h^xPhOjhj8cLl zB4?g|f9TD(`f`;Mx!d)defEjL`7eKMR{t?p3Yu-ZoOy+iY5T1Ha{bIR{AkE9Zb*Rj z%?wL8OES{*?RJZe!7~SrY-SgH`L7;37-Ks|!W)4%4WP7}m&>IOl10_Md)};t{K_fj zA#Y7blZIDtncBzu*z+dl)*WiS=qC}em~Va_>fl5l%qM?ry!}?2^k#6ek%!~RIP+*n zqbqjaq@g8oTF=<(o)$~`@l)HkhJgP^zGSRILB$k$@SM5Y90;rAAyw!5G0qP@XzgB> z5RcW3EAN0KwlZI$%XD`Ss6~H|vBAD`I`|iFLk)*6Qq@z!j#`>NNNO9Wa|Z00N?zP6 z?nZ@bkqIl;P-GK_Be>IsT4MeKwaj=T(}WWXi5^1i4|HEZLIhb%aV-&Z)4LT$OS^U_ z#8|F;Kj>NhCLiP-9WN!(YByR>Nf?^+@wo7RBor0X`^l&A02)QF1k$MwDKS-d@Tt%E zwzpIJ05#ta>Wt`Hu_BkbHYp@o0;c5WhENJ74HN$TQxB;G*wWAMKYX!UhQs2$<0Fjd z1+`REAke6;Oda~1@qGU9tU>8f*>{bwg`)n#QTIe2e3|~=$go;d+niqMCfcWck1&UO zM!E$S5|#B24CVhk#$%#2cJzIXmW6}>fN`C^p(NL#6A?*G#G~XF2$6ZQ*roBt>xW+# zm(&7W8}Cm(N(p%7S#dW}8Mn-CX^KqS+O2=U$(akrf)4gCHM17rY} z$CKwP7LQU4AXh`yXFn#niuxQW$yAnH>qR~xZ@`F%uB#%D9fIaWodDV) zf)E5TTwI1VG`)cHSeYoW&lS9zSQkYczFHyh7ii5>tt>CjM#`RXrwK9V1@CuM0nf_$y{(-ht*NJ+6Foh_XBa&kN-!`&>OVBu1Dh z_VzV}?~wXJl!pRE`8P@#0`3J$34Cng{A9$AH;5uEAl#K4_u7Mj*3haWz&K%B^M(km z$04O3EenY&5aOsH0MfIWl2!z=50jHJqedl0L~p0g@>47iPgXy1DU89v3nm#=3J5Wj z$Mswx_(m!23@dyxIqAHTd@m=AYG1A9(W{f{r(_AkPmCN=xD&QN^gp$tWjP9~wK|v? zUTEtw&^G;CQ>r|~Olt7@DTBp(R|c(ZuJ{=iu}WE`1CzIpLKlPR28TJ{i>#E-Xxb!R z6;L#*zut>x(O(Vl{fL}G{zeQ9G|MMs5k{g?byq_6hQdDu6%X_iFXXQJlEPx8lE%8a zN-I}PzQ+>Ps=*EsblHRC^Yl6+K>cPRFp6s@`X>??yicJT*_AVd7$-!_Kd^bxf&Ba} zwzxk-^)vf4BFI|D+`&EK58{H3_8B-_@kD~f8a4#3@aGmsVeIMDVkkog z=L!)80jZK~x-<=ypZvUOX=ntYE)%>SA8+}`)kH4z95V_$!~r1Ifii9k5^aDYcQ0W2 zr36nQ1|-moOnaw>?9)A*th+*1D@`QR9BHSZnTg~woDcdZ?ocg^*tO|U(usa)J*-X8 zTY|gs0uj9t7-6!nXL~}_cWhGqxzV09{PtJ1%W-?NR+@M0(zh9lKL>B#tctigqIhk6 z#y1ipAI)3!wBSC&OsEI8TM{e2)qQ0aFGBE!QMy4mHEC%E8-7hR`6ZZO1oIyoOkyS< z2w-gb5c<#C<)$ZIYJC18Qo*oHx*zQtsf>;2C59K9JI2R)$l@d)CNRCqC(NB$Q0T)G z20DG6t^~X}j){tYH+376%e7O9#{B7J1-B!hd|&fRQl?bjB=+z!t9p$gp97HXhoWB3 zb5jGr&nC0>b$-^}f0C9nIqAC(BVkSN4RERLS*PWSyWYD7|vYU1ReWlE%btX>M z5it9dpRS3YT~e*BV#(QM*^CSDLg6E=iMZCfQ|?spQns0lXDIh#VfWd25>q~Y`ljN# zpKT@E05xCZg>lDnS(YBF=^`o~Gthu_Ar$hX5aYtj;1K&g^JUSlA*AS$3iR%RUQN&R z(Lt-=q~gLvGJ|2bGiUr@!4rhKq@_Up{4-C?*ZpUaCe^tv#KRd$cBZ)uf*7iHs~RcE z-^n_!B{jECrwc<%34nxK2wr+I5%wV5PM;@>)E29Y}co7=X&)0 zhL6H}^nFi@;taBO>Y`wJ^^2dbz6Ns(5bi~eyd8vwiQZptVPLs@MK}3tGII2Gt z&i8;_CGwz5KfJSKDcDO@Jf+&X*hM;?CqzVNSR#!I4NysSq`&=0xs9J3u%kM;`%?)4 zlC}7<&-)1y`f|c3tS8X+A+NLqb^r3*{(p46Wl&pvxWyaXr4T4Ch2pdXr#QT5an}}y z1Pxv&5TMYK;_gyhi@Ozf4V2=p1&TwF-hIxUGjqS(4}0=4GnwqY|If45`mId;HU&KH zj9CYt=ft(GCWA+0=xEoh0jC4iS3ehce}{AztzqK+ zNL}v?@F|bl<8+zm7~Fh~t{U5Wm8$S!s09yS{$yz&Le)q@(GZEgSCPla~^6&R-{qNYBQ zL8Ozg#oX_vbeYJo$mXGTIxoQ>{Jr_G9|wQ6KH==%FU4#r`mP}5JQN_o_urEI zW;LLS-j63Jbjrj4K&iNTaF`S=ea6J2VJL{m#FuTl{k*3E3PyrN2#?vX@*pu8^mR&B zWk4eckB3U$7lD2WGL2Q}^QA(9gj2n4E!n4Mnv*6LJcd%JEmQ!MkXU+xQ=Ph>O+~8n z5+T|x*q*$+5}=MzEGc>5ag~d?1#T8A*a8>FY!-p|4P!P7xgbib^!q@xA@-95-I+Wg zTos~DA+ET`zN3NuYl3Y$3!33N3v#IK z-CJJHkL>335vtpSWI;60sG4pHK1LrQLDc|m%IL2~-((eg(JQZV$#AIv>jXtvP2SEH zp=8v5*BlRuNXb(C!I$6R9@s&9A^&S2@@m@j_i5?~rYgt4K5Lr&m=s|?b*sHIH}CR8 z0c;R%`TvR7qBA5l6>#|5MIKYTyZ06oj9X=I)?cPUcA3pW1S0(m^bK3R*VFa2XCI^g z`y^1$1FqpIo~coTI`yz|8M{?1RDwZE3H2^3H*lkPGGNPho-9f+Ec;IFaKN1REeX%t z3#^wZKO5vK7|fjS*Lt-P=$9J~Q8h0ZU6Q8OW29c|DhezxT+w2)xWe>4x>bBAv?$`M z5Op=_&$lA&c2nGWI+h^Co})W1$$44VmfgV56&idz77)6Z(C9fs>Vg}>Pwghb~yD+P2cG@(!3U!S~@|_#>tc1mdB9!BO4?<=m z!^5Wtaj58B4IZ}UeJ@;-?8J|#9Oo&)oxmH`Rw2M$br^DPYkK`aoF;}J))*OwoRNM; zvhl`|8Y5z=QKGgo=4PgfJhn3_rJ&l@(0s}6>+WD7lrHYVI`gWM)ngRCz3nMTw|6&1 ztO@=^EGhlyMHsvI>+Z8AOim0q1|x_?!I{MMKO%x7E$qPs@x+q*7*y-W*99(_QxJco z4@;c-z5^y&+)OHFTt%oQR>~AZL&}TCYz3qNEp?}o^?ZZxq5^AN#TRQ^!nAG3k&y%3PMfq*RTa`cY<@W> zbE!5E$nZ$m)?>O>sWbKTyGXl^0?cYuK8pTZ$|J)qq2Md;cmVm(suylCIszm$f-GH2 z1{*y&`F38uPfF^d2_d-usuI6uY=$FFc@=oXP~IHqHA`9WVcckjC!iE>WHzKVj1Wfx zohnin&&fXBfOJzzcQEKc7588@9kQ6>Z3sr_z^`r!n7yz2nM4^-e?dAQ@&(s62K)mS zwNW!5>^MzE|Gzpj|BE?|)E#*|M8n)dI*1mI+Eec$81Qh!`q4U1E1BrN&&SdQ%Med8 zavq#&(8_ET@{xzJ-$Lar{9-DFG4620M89PW=sk3qXvvCh7Q->fgwJjqFz8-ysIzdl zF&2W>wYRlWkC5+(Uc+3Vh(o?Nn+X!rar+!-O3P**Oj?8}6B zaUC*#T$1yz!8mi+%4oL^= z!PNrz@YZ}93pTOGYU~M1hh$w&az0CNvkn@GiRE32>zQsuQNocPll2ATDWi$Yb8kpL zrxlI~1o+B#i0T&hYPJm42r#eU1R1L+JELFRHd1s^C6iUV1hYxBf^hu%JGA;AmehA` zCAw+_Rjdh`mCNyODii(TyDyrctj96nYQ4uJ|fsYytWUJKsPRx`GG;(?==+Cf5 zGZ_e;Z|SoaH@r$8aek?E<3CV`p59KcxSKD`)qP{x=qJe_28G`X{a`h0Y0tRyJUZl#xgX!S z!;2Ii@T(7Z=?!0*Q}Xf8xoZf2=*vprca}`#+K@M8L+7h=#j}RY0DZCv{AHqu3@tKS z^>Vo--}0rmo%!O(-Y2^~AAH)odF$>2VPX-AyI?Ww)={N&+-uXGlxLxHRLqQ8jx2g) z%Wqk02jWBx%rFwd_NY(OC$3S2Eg6oL?|%Ik$JCfa&Xu<{Y!+0HOA%w8P+qz%o!Ctw z#!gjEp3iB^BM|8h>qu5CAU;iTxC`Pc8OqmU5PnLWy$Qm{K*ymkVNYk+#$uw{=U}Hx zCy|$B^1D#E3FjCF12hd;;JqG#BOl}E#U%E`J1Wyl{lwUz2*l7yq!Je~G1qN@w`jxF zKaj@K(**Z7_Q&+StDS$Kw^%`~4e({c@PI1(OOvdSV=X^~f_|*!7kW3ifeUTE^WBGX zYk8OGgSE%_20@K?ym!texPsvVtiKoT_ye!r&pK}cH083|fObM-3SL4b^owTLyu;R%MPylZN~%wgUu)w(QU z12ZHmWi7(oi(H~u6C^h##ck$8@f`Y|F2au+dcQYYo3oNkjJGl1T5UrQhv%AL=ZH=( zt$xI|wO|31tnE03j7^VXVhsil7yZ2meW`DIUqgOV)=;waOy-xC43*?TkNdM>F_70d zH)Z+ovxup6OBApe;_7dujkcze?lC$pc+R6VGSLR0=;y|QXRQ&!e*vx*!CzE`>JJn; zb8HQDu@c?+n+os#wA8W^m~Hzij7$bcT9|9<_45RA{u<+HZ^n*Z8Zni>W1r?c@9H<1 zn>ly+xqs_kuuJzFAt+fu*>4QhH|wJ89=~*_E3j@QX(dez>}X&(^BR(87i4A^el_(@ zGG#5%O^Gy`L&=%`AJO^eo}mE!a~E0CRTs@1vUO9W5kZQ4^m?SXy8WlKa?4I0zVp`Mlr|b5v>M#COOTVd#(W$+DRC~>c!YArWeWCu_ z10zS_m`I++!@ihJTc4*-h8BAs0u06Rj&WzhFMwNv_KyMK)_s@s-9y<%OJ*mzc+ct1 zZH)SYdnI@A<8{uX-zD+3H^tsNI{DWTg4Kv^wdjDPpugQezwK3$gT2w+-5n+YlMh9j zjLf$L>SLK9N#6pHrXcw^#`i6Cmf(Iq(nrp%;*}x>(6L-L2mLTVltgfOW{=*NIu9}0 zoG%G&tTx#h2+7pK&J>m;dtz5hV;Rp`sSJ$!~182ojwo6FT01|o(h zHU`v9n(PNx*>hBjctc4|OvBml#|?QaHiR@|rzl`LWhqmut9#k4g*be59C3TwWG8l`AHT^nkIW6 zWm`ACG=*=ve-E)T5M?5~+-z0QVMr1==- zS;6+Z$`uR^?Z>>=McYgi83k610F-`P#W-dhaGa?VT?A~rjlO+=MGztdg2$=- znOA{{Hd|m|o)Hfek_T&NbMkXcn#fwJ6yyRiT266o3ykgq*&}5o!7xM-I(gXmD~@r# zYz%ymj`D%JBo?Q{EZ&cmXa~~b$L|CAF9S+dwicrX?*}gmEoc8TAtofHZdG33YL1vcfFsEYOwC zbaGmQI@Fxvr4o1dp@iPpemdxyt9CFkg4-E7|EEM;9r({mW)>gz%qdM#dQNaPOGyy| z9Ea2ru5t_DEb~Q2@Nx1n;DB?1g}Q}gzo<2x*Rc%od!Y6H(9(kQ*Cyh*TQ0ul#yx81 zP7_=OQOSL#5|!^-DDf=29z^~V2^VFLnaTKh8)Ty0L|?jWU8nM6?Z;)^VC7 z=g4w%nwg}m2n)BPA5Qv1iLX{x6to)IbFMoa<@l+w-xzW)A9W0>GpJJay4<%2@i=%# z{sZ|S?KW${7E6sMyt>Rx>t}LYf9X=9Ku^b4m7zupF( ztL|a>k=|-=>)iqZ358AA{~*!+?=qRqupOauGeVZ@^z;kosOWc1?&!YsvNqx0Nw+sg zV^Co{{(eyb{MuTk?%R;P#U^GP>#b9w%D?lhgE!wV7!!#bdOyFrkW};O{=z4mjm07H z$`q-Q7lk3Vb!uqSC{c1^92J44T+XE;iji=jPvMR?*r5C#Utm^jfE(M($TPa5R*~~1 zGXf_QWpw@%WKHkzI^n`Yg$ZCw@@=u~{?$)SGiM$kHgxFMVG5q`FmPTPL$vJELIqVE zUKMzUjy@;-Zj@80L1iD^+3?OxzO-QQWUNi|eoji6n#-NbrZuD2@|?n!YEp=rhh#;N zo6PsHfl=e{?B42Y&Z8HRU!3k5ndmQ7$I9cFvBA)-lgvh{b&I`1hcxW)#BJQ9aJ1EyL6b$6gaJIEi3L#uZ}uHSoxwS{ z`7?B3?q+m=blR4AZi1xNROQ2?FD=jf*jyaibn--jNhneBKRs1hDupbF<^y$xkg(?N zXj8Yn4qj$Zz@hxW@rwTx`cBHJZaA^h`+*Eqb@4C$?ur4>;%wj)4p&)>eIb^w^6Xn2 z0k`*68LMR5oj`azzi*s>B@`skuf(Oqs!8{yqR=D8WT4=6*_#q8K!>QobeABh4&$6H z5~C1j)#*NaLmBaN*FbcrVmGSNJl{gq;y7WxVo*R4q%#)Q%5mSom!jx7|E;Xb7o24` zr8i0*P_9XI(YHX>=cu#l=${&yJUhrEvtE5adJDvDv_=&1&sAR3oj4UWrn!0!^c_N2 zaZZN1PJXKT7}%%J)eCmkM|xzfz#6hHMe^d%RPyith>oJ28VF=}NJ1BT=#=-Gwp0ft zg5J0&?{#3Ve=JHslU-?>nmGa5!M6a$?aPjTAOIM{1Sa3-L<5Ypth?!c9K{y&OMi;V z&*Rh?eJ*mfAa_qZ9spc(6zSr>8KSf@^j8ZrEF@}d3BDSP5O~l-TroZAxf3yy01U7$ zy6HCQy?>zZ>V!aLi&@-(8g>o7h@Y14IB1*y`T!}LwR)s%l`wdb&&dA>#USPculs9Z z)WS7}u8QnZ#3sdZL2*C99a8mlkHA_<247Ru#4I~6=I(*BqhzoF-RfqkEpj>`IwV2j zcydFf+3Uwc32E_n-t)`d1PPZ1D4*W_jD;uAY!P``GWmWaQ?)iBa#s2NS1vZB8*pC9 zfUggxq#w;of#^_3<%VWL8l2HD#igQTR zGamuI`-WgI_^T%O#(6|#h0+K1Qqg-aeya72pxd%JIQSVZZ{i>s zdO_wnr@qb%YOzN~Miet)wLC78)nA@+iz3P-`9^!+lEXs^>com5TP|Zl%gQ(@8E1>a zIoa-ne@?`TFnXMOx_bFr+M!JyB7-jc+SAYazTCt~b_f(4PoZhTDcetu{629^A4l|O zrFfZx(bt+`?!DTO$_-=d2$0h7t2B$c)@6A;V(6taD;&RVX*7^C(x^lu_y(|D)A`Q^ z4;Nyh6WBwAn2>%UDPMYO1#LU+Y|Ezq>;G7NzvQ|~Ay{R6vz19ye#;MSQ_W~cwqZ{LTZEGzl>ymIJrX{|1Q5N1m(;<6fCXUb}Ih2h>m2CrU_ zI^1ojuq1F|O%&ERz)8uBeB_pzR$64B{y1d!u10hRfTf(8_z;nCkl_wT3o)CE5R3i; z{VHAEFQ_o73sY05+)L#q3$ze>=+|kfA%4jViA#-D27v(I5q*t`aEM5-cbVdwT^tL*+vpGODwQb7b<(POb<46nOzP?D2_$v#dw5tDo|K@6}2={$Q} z2Tbc2gl8I7c>U~D*9FHi1XDuP!-pLGuT1F}?{~kFiO>;?R;WAUxhoGW=QQ-rC2w)Cj95sF$b36CorN7{HcZebMG@ZCKZUykc0;l&H9;PuamAQQiKD zhkHTs6O+CGG#F+jS~+?^c0wWUUR5S{Pp-{78eNiKe3+8Vrt2u3Z1<}jU^N!|eHZ-7 zGj{QDCaxKB$VoQ835_)PGwgOKb;x1W@Oq)hm{R-;dvM0dsflwgD!7={Rx=r2irT84E~k-6nRQo09()VsY2?t(KlYmicdDs z@iHeGuv~X#d{b8nH+i@KISnO`&&T`@er{^zS3pP=o1{VK8J&Xc%b1kVC{!tb9jQEF zz;)SwwqKEbm()ojcv z{vKm@X}+aUq0vjOwy{vs>hk@eu3BMxfoP=9Vgu?{YV`M_UP@J-ZAZe+$Tsdj(1c^c zjORrujPF-uSwg2F4wk;sIPx+XAH4!5_aYXl5vYG`PCTv3v74}$)E`B_{~|Qr4X5S1 z#2N4An&S=s0E8~6S-s=>r{N~A8B|#O1?%bAbIdO=1xtM;EbE;e8>kN!3UE0fB{b1jNDA`yIdIu;ebR`wS0(MifT3^ zccVZF5_@2a;Da2PoxrasDyn@>#QCq4^Q+|`lPyXiV|tJl2A|U-cU|P>e=NC{4@Z$) ziJO5EuOI|COD--`LDk9Y}sNwB#PiFh?;H zt|N_an}ME7qQeE1;TojgYA`>EFcFA5!+rVeA81iW>47-Q!8v)Js&WH&sLi-;6shic zLOM_=FYqnqrU_*rf>2BjV~!#j3w!QJ`PV?-ApA_>cZ`X*GWZh$GA`gF&Fe9nq0z5y zP8Q;4mmqoncS;NcDWk~GUDEBwG#wXRkJu{YWSWB94!S_4*Y&0hi&gQ4j~YW1#A|M< zp&G;ioGn|@g_wmud#Ml$KCtX$Gyy@B(I(~qC=Bj6g&g?a^H>ow4FwGY zya-kuP;q2b8;nm8y6&OI!yz7c3iI~<2f{6?d~Jd)?gH($`H1TNFqEeOX<}GLMY?Au z726{%7*|Z(#P;if7Lohe&#Lw}-ZRl8U?bAvBHFWJI%lWLqPUT02T|J6u)&*rKu0KG zi-u>_6TX8#1#n18PZl!McD}1`p&AFKCHnf%xO7NAn?Di+8WbdN2uv)9`Um>GcQT8| zWchhV9Te(jzI>*NO~A`0*;0Umsnw0GdUG(YH^;&Y8&g@Kbty-{CxzbKZce!Q)gB8f z!GGHuXYQaa^*fn%n%T3k-#VgWGxr21v=us;DCfo&XLTlpDcE`U>X~U#|8VVSN-mV2 zkX?k|l#*`fStSOXaGLCwXEsH3ZL{02JyHZ++9Zu5_uHZWK+FWve=pxZQor4{|lM?&nMvM8Kst|?$=R zPavr+y=pXHyWO#d!B|jscL?6Pe;}DEE`pmVhDJ!2O&S<8-uTJ7E#YnS)=YY&@P#JG zr>aG9Ff{_aW5^iBV#Dpcfq2^C6B+r@I-B&Te9hTndM0bIRt&eQEodFQOP7!tD99bc zr$H-~xW4etl;R~(&mNXPD%mD=+x*wkjXGbvhU7ux?=ILVNxH(Frr#TaQkZY#pVTJj zm2PXbaBT?&%R6IJ;{00=T~dhttFGy)_S1}!jMKfc2GyVPws{t8at}*-`ns-6&D4pw zL7#Zv>9+DI5oPMxGdI2V%UDoztpCh1WEIq2l~_V70$xPrMM!U{DjMdks3i}y5Yij{ zF@zSGw)nHpa1p1SaL1IWKHVPG zZOWygD&$xwuJ*h@W0NV>SSDG}tNMcN>fg}ki;2!d`hsz(pCavVOC@EBqema~2KH(1 z%a!HMMV#+^{B(goHL*0lZa0hIN?G^iU<0cl^^d{TV)FTPnY9b6Oc9?WH8nTuHt(GW zhvS(z2PRSNot5W2T6ZLn@8XRn;&uiALvDn%$dj12|qL$QUi!)8$$;_wxfYcYw1>GnZ zM{8}lxDRCb+q(uajAkQF4Bxj`n&TTv9Q^42l`IhN5gWkiak7?WTljmPU&*^SgVP_&;;DJ@hSR>6IR%oS9bVV>`Qlxs~S+#r*6qp!Lsdw5NeaRrJ-uK~F#*jM^9 zh0&(_mGGtrXI7vjrY%-e7 z25*UXP0oJ>rQZ3{c|LNm{-u$@enXt-QtbA82UxAVMX#TNKN#hUT^E3sj69Sz#cSRs z%*RH{*xj}2lFlzhy7ViqyzwrMS4BpBDPSh{So3-j8P~)@&>Sn4i#|q581Du;ailfw zydYWNseXbg_z?Z<@~dXPW2WqDuG#r<#&cR!h{FrJeRaG zg0oPc1KNXH>%(pujXRx}4TS7%yf#YS#0(K|iw^6Up3ICgRo5i%m#!Mx*f(zIn)Vq7 z+i@9%NEIXV(P%oqy^6+4YCDdgt%y`QnE#e2v}>=yR{JR+lYqvyw6Wf;0-TbS8a-Fku$*5fk-}mh_fZZWIe*V4iulII8 zlBs^nu-f=Dr~oN3iBf))LCL;Pn*dql@MZXO(1vYHDR*1|BJSJEL# zBrgAI6!=v_b!cDVYt0>l&QYjt@HXOXBq-;^NSfN>d((+ z?dxy6#9-CmuUtG_b+a)-y@(p0DK}@cwHm!CTeeI~QnsS1!mDg0a&grZ=&ZCady%3) z9FXa3bWmjgqd4=G(XOPnf_Sx z%=36fpMZ(66;q-3uPy^+D)a+UrF~8OtirA4!ye~lD_q$@Ve*7=rZh=&%YII^YzZYM zZ|hD6-+*J5L3_Xe>)oDq9gjwUfOL4=icmnA-kYnAs$QIfXGl?Ch*6(2|u&j}>SUHm8Ndq&x$KQlVF@&Hx9%H+?>l6bB+ zZIlhBB@&V@Jc50Z8qaKe;xxeaF}DUMKQd500V-Nj&6Z~pqZQZpZ!*-XIMm~O z(wioF?zCxXj~@1e8yUULWpRO=#%=r~o|BX>R|fRy0;|&Vt=t2h?ED?3@J;0iyKRzI z!&`Nu#ul%LFKiM~y%g%f+JALzSea}=P45(7EPjiJ6rHANdK5h=2JE|+#W1o(rBZXr z&S7S6gUBR_k4bUXx5Ay?&RRdd6CVpZ7^t$MjH zR{H8hz3*hBvFC&SbtNzUguw3Fs&ZT}9tWCh``~vWXZLSbEm?81x9>IHcxNyDe0;Ti zl0a~Q15c4?8?6?0FAmCox4*l^+|=+A8SkYrl_aYyR2H zo4IVc@((3y?t^Kj2`^VTPH;~h^YZ@YC7b`{JxC=D!K`tb(=aelgbGUuD(5S2XucAZ zLw0^W&~VCpgo3Vf0dhk`8M^F>EORO7uMR`vC+gu`K7d&s4aK7;;zJLB7G%{!Eazhh z8HkwCL#-o+6bhv7~i*48L7 zPgDE+{Li$Crlwu)OE`5fqx1;s2X<_~mpC2PWcDZPsSs}aK5Ck=jOajpuAsJ1BNMxw z&QNbt=N_QZB!FhWUAY+*yLb8@wlujy&tlq?O&p-ie_Xme(2MFuUn|r`#Hw6BB?W3{ zaQ>`O0*8-}^WOZv`beYBOehmb5kWal{|i_dWp>5O!4&TYoU*7yz}B=&eJ6u zL91npL(L+S*Nr61v;Z+T^g$>yrPcBIsd2i&`Qx_*Wf{!OPNg&5HvGQo%%$bXY9sU7 zBjhqbCMlIbZaF4p2<5gg`dk*HdorUtYntv70fEe=cvXv_811tVX#=nM21W3J72+h={^op^2J!BoQ&=yRcD@ zI7cl;H#>CK>QjV{OE*PHxRXlUnfNJg5kEzk`S0~+?wx{qW95j#PP+N#Rzk_u>W+>y&ePR&(m69;<8 z+W`PFD&D}sMQplTl+$sVZUPF@&S`rZ2f0ZlPG2x~WYt?RZc@mIgYexX?~!tCZQ9D# z-Piv>qJ`@yUs^x!r^Iukgr{*TQDp#+0(NjJzE=`Abme_8PSISXx@-)!x#9d(E) zOQ^>HbXL*IE2H=zfe8nR3m}U%d8VZzDR8TW zmPwpAW7t5CX2DsZ7--#(YxyAU9gUg^d>2HcFP^2ZVn>e{7e;9LA6GoOYg493DUHeM zZ!K0ye92)^p>hhCQHG7o4>f-&!5^ab=ojTxL^>Q!Chg-@a?ANVi*&9?#T&xOBzDvg zW{S*7uPv$an)OkvSHsnA#?Zm0>Isff+bx&r zM|M3OAv|!STgj+Nx-9mLWXa2=)%JKUzdD<-YUzROZrSz(h6QN&f@$>Ub=!Cvl=M2q(d#ms&KK(S>|GT#6BZi5LzSuB=xT6k z`h^|lji^~SjD3OLHiR*}rDeDn0tysL9-DL0txZ%^6Oj5T+du^rK8Ea1?jU?TEz`fh ziICA3vk;-w)%_tb^qrP)?DMYKA0oX5)O*~WBjA7({4@#f_p+cT;JRK>dxfSwsG1no z0vTeVzz}w^!l;NlcD*j^t&3vIc)2f264Ug8@@+z!w8))cn8*3%SCGq|*wbqhS3ht6Sv>|R*9<`##pyGv^eV)m#)8cRue?lvc=9mC?#E$mivHXa6Fy z7HfiQQP~GHU=6pBpIv4VMXuV*lfs)tiXECgAdp>NgJlqah&4n zb%I&>V`~-rBImWjj}$fEplB<_Z#P}jzDfU1Z=3O@rAc#9CWXeP^X34Q!aB zz82-yP81|t-4!2&!=0IvU+o0Tbww#dBCjisDkbBC8V_U?JTt*8-29J0Tq&Ae(U0jY z)Zu4h4oKS}poEgqWLD85`Rws@Nx4}zq%IU zEDz~;cN(YjX<5amI_n&bw+Z{41?!+? z?aan4Kpb0ss-N+j!o_JkRJzk-cL8!mV=`7g((md&UFpu1HZRRRk2yh_#fm@aO%eR~ zElndj*da*2+QIpY^%9_mN0o7G(cwEtxa3n8V4S1f`GOM>+xIh1;BEn6+6(GXbw^_Z zN}Z#a2&?HeptATrgz#~}$F-gmqMW1;xu8fw;?P3on}gL9X;nExMiEsD#okDU=Asrc zOAYp2v<%iWW53R_MqJA0{YxIrksrJaNLSwLQU+HZrwX3C^=8&uLjwu|J;-ZD3v z3onDyy~d(ut>zZKz4g_h(yDOKz>yF#n5}pkCiqb7g?bp-JB1sxdYBtXG@hJbBF(hd zz^{3_!q6%Cee$&0N#Vwn|3EEs-?Xq9esh!DV!`%ym;Fx0ZI@lt)siMhxkR3%<>=H| zrI{s_`?Wk;BJP?g+&6w%xz~RUEpwVp)cPlV2)0EasZpS$#g?>_UfUO`!WSJ`RBO6N9d;nOw)-uI)ncnA?6@DeTghx-+dI_{Cx( zw_KDYVVBZ+{80nK=HJW|(`r>N&2tNscutnF?)tB?% zd|;0~`9MJ58_SKpp7ip^eX-Ahxx`|?DzUT8@S$6=bXic-ziH`@ZmK0@EXj2VbHpOR;0u6?Poaxw_9Tc&=tSB-rsDul82*;~ zWu2|3JAmDPtjK|;xG6s6rdddRio^lRM5O9*<=b4ORVU{n&U2X?kKL zJ==G|p;jd&sVOCS%o1F`7ifw<;dm`#8&&GIwGgHL=wb0>Kh@9h0lgltFUy9_OuctF zeGrKF$XWKvqh$y4QOhvX48;0Frvm;E=7;ksi#V!s0GFe}G$9iMIPc(JEDaC|RGX2F zb>$XP*nJI9?t>|<^h;Z1=T{mUa8KdakcZ>rz)<7l-QWQgQL16KHdfg}UncUt#n2C* z>0&bffzHrdjxjXe6cuCTzF!XKeKi~T;!k&g3PsHpZK*wqB|?!mUrrZehxMn#J-r^w zxS&UchO+h4th+om4x#w;fQF<)sbpfk;AK7Z(tij*byde{cZHdh5%Vd*`yFoI2{~(Q zurA6kCRsim6$K^P7OA2evI=m&Ugyeh*`7CWCJWbHL;A(zvWQLimISk8&Yqob(RXmA z^X+n(h3gPnxQPyzZ8uM5&^oj3WE_}?e~}>L>iA{Fq8;C9S%e+d|HDg6=36ZIbkS zo{K=rqW%!GDGoRGP|w!qr)Xds#DQ>L{6NhUxjmz^PQ*>w4G8#~<8k6qi)QcoF)rB^4N+NDcOShmprZ zCdqs&J#Ej$yE3!)L%hx!8URJe=vI0K5VK;w869NUMMETi==>K?N5S~Jq!LP>H7Z7^ z$(oQkPgWZ63`SBi>YHERL~8n?AO9SUF6X9nj|qMQ7*c%x6tLAPMBM|mMsxww8cgXf zAMSh$&~5f4_gSK`FgMde7d(#DWO@@?0a*j@vIvr2LLwoua;hCq6`h!yBYUT-a+NEi zDF&VzAt#uL%ZTQrNRjrx_19@0R>5FrEW{*L0{=LO8Hq`aNexU2z~o>-nC_ODv~znD z4%1TTYqyKt_3Tz9voM5a>KdVug9H)@(v|Img4s;HEkj<)_0EO@JNxLRW}qogEvNhE zYX@`=o{Z`}pRRFpkuRAoi0C1Jy3E`2sMegqLuAfFxoD*{UQ=hhzfRs(_;$C(K)1Vl zMNY28zn7nCw^98Uma*v}#6Sp&@KyxHwUrK>aEmLhvNgEn;@(-1G`#xG{5(39Ss9a0 z+JCRy{4+J%$y+F06QI{o%{4->BCzzbxf)RK{3wW823Opcst0n4W$88*l8=6mxG8D2 z2YpT_AnW5CTFLa&Gb%r{+;b%SSb!FMY)a!fV1%iraog1{N}$((+vw7afwv}Pz^O*e z8cA3pDtc;m5tTMguRWE?pupTMS;~_1GRh|Ei;n2zAEXXM7tg&q@k4BGj%IS!Ey`kh z3to)PkTmO`IsY8! zEg;rZ!1o(^h@qtA6DSy#5mm5vB!lrHE(YAk+>&QigewSP#}QLmeARY!fg@3EVLpFaQyg@=7a_|{6M>i z|MAW2S)4NHA7~3jo>RyyRZl)R7Gy$&`vEwBq|3)R0jeM4NIDwsR*b3-?YN+KAx;$P z2f|=V1Tqdu?B}5|$$ddzKY7!^DN9>|)<@`p421E07##lx`Z)XfMd}HM zgidshudWKFS23BpkNqlw;jN1(V4=_oJl%NYEQ6@>V<{7}ChtV#(jhg9!D&SUpD{w; zCQEY;7o8NYzuF|0N;I-gBx}Yw&m}e1^w1iIV>L4DZgLFXe06c1D53Wo<1>ZB-9{gt zDe`kP^ub*5u{UwH6h-Jh7W@O%3mD7&1L?N_F}i$&2zAomIhFj@bT#wC$e{M>fJGR0 z32lN|zf)LIvS`hrGGmtA_;+JwTAOt5!%j16A&RP$V(!oX@xRH*7?X$@srdSZcNX#q z_{C~v^3y!2&DIVDYVL(XWC|Yd=sq^kCDVL5q`A?yQP@X6(@`mT6K`#Wd!i|%qjW)+ zVl^hdm2PNz9)n!cYzTr-Lf7ijI8$^gJ~{W4{R0u`5HfZsyF&&fOVopDgiYt`Ux;bp zV9xu>RTNj6H^9%MJ&tu*{M4o+QWdE@uS;L#z!&7!15UU&6!m54DZ|w3C|y<@$@2=W z$@_B&MrATd>Hrz1s&<~p<@S3ttBfdm>4mm!@w+h5JBnRmKu41Mk z*FxbO(&4?6Da3)Nb>j?C@n^#P3%}Cx&`(yPTEvGrG9P)QLKK&lI@pRJR)@J^L$Hgj zLdWbKO@ESe2nhf?6J-k-1Z)XgI}hAH9p$?v$p2_osSD z`15y=f7D%4!fKNby_X404RD6QbD-x5=o#4SqC~o0M9(7QLA?Z3U{7wnR}Ot~@z6hxv4S z*#ergD{(8~vM)`g!yGB?1wGfZI}SXicm+kyE{1tkv8S7=%j`v;9WTaSx~8Wf0MNK* zb17OH#SbdkYqGK!m;1r>$nHeXrSOT zsklm`gM~s#teB$9#U=Cy;}`t9!G|8Y9K|i#3DG45*6G;Yx`IwC-XHr=$dO)8d!{SV za-8V$Q2l}?{N1;1EOz_S;VnCON_u|a8c6zfiIFiyG%e_=OY~e z#$$NlMCuum%KPIaxam*F5Pq(6&VkhB$1kCBq_HwvcpUuAM$Q` zC@u>?RV%*`;G5va(3-Pt&0IL(7#kB#mj3uep@L>@FxNTKL#w%J#{XN)%-QuC)|peR zWYKeYhMA%iN4@2`qhqpIlswKx>A$z$r4SiZ2b5MCucU3eCLq#PBw*bVs+(WQNKd%pj?V=oPTDl>KG^hK5i~IZ+dt3hK*G z#@ihyrXkRL;J20}M$-aIVpBAEY}y3u>j zYZ`d|{`%&ll+zKSFL|-y`!@|;L#J0mV=iO5CHgGX6}QyK`rao>8X|sHRZvb}oA}KM z%6L8J0zwY!r)l;|M@&mL7b9rTwS())cCz97Y(cvXfqiZ(cWd?0;H#>D*H@;p_v4~K zJGcWT`ERtzBLnhxNt&m>cUY*go^_R!Hzq&VX4K1&<|)H=!=4j+gr&}%u*%gc&<_pl zthRaFM#juk0f|}Y`F2O<=s8^i<7o7jBzNNbXJ|Bct#3;f`8G0kMR)U7yo921H|dEQkSYd<{4hsDs=Vm5X{(r7Gz{+0sRMIFvnuU<5rUnNNhVP&fP# zS4wM;DTsEi0kwheV;>_&dq*>K_*R##vS!d+zF0=iD8j(J*Kd?2B>xOO7iV{W&iY+* zxVa1GCKYjH!7-Nxj@c81QPS}cMS5o=IT+X#WB?gbFDgNg8wXN*B+h+T61(UC6qh|z z4QorRaGcG5Gl6c3S?Qev;L1Bt@)H;Y6Kdo}KXQ|sw7!%>KyEY~;qErwdsXnODvJ?9 zNBV)8k=*15&H^l>DX~(Ier0VVTG(r!cftFH_5*o59|0VwcY9I^ag!k zwzTC=rXMsRe+xgb=DF%Oo~>l>XjA6ZwvCGbk>SXin)rPB{;I&B<(KPo9$BXZbNz;a zw2k_6=iux=>=R{T1O9*UbxK+>Ew(S&LuMEW90r8?n(F?j91a#go^wZbrK=P{Srd3b zW|3EZX!8{;M4B9;8S>UAdt?=&x?u3(gJ;R?Y{{W=?t2GEnMx zrJ30~c~|C)8AwE0#{;EkY1Ao?+1wtz<+ZcASsHi*WdA^GB)~JJ;_DE8IQbYepm>K(0*QJJ4vD*1JJc^|Ifv%}O79 zcHvW2O&G6UK-7~TzmX&t9R63YUkxcMM!lC__NUz@T!#q1uT~;iB707#b<=XKL4k2~ z(0a8>iClSHlA^8xn$yRyBZ6@$xW*tR#S-TcQl_*nBREduQ{5GE?9KO; z_p_)L?x0D2*{D>0>A2SmkexLmG}kiNxX58H@*6Idgg=en$Ot4`Dv33YpJ=SjLn|70 z@}g4hH)g!gv!Ux^9;XRy>|Hv1t=w3U9q*~(@fPJZAor^t>kO;35iu_Yd=tD&(nACu z8Jb(S@H*#5jYQ!-a(@IvbkFta6J&_kP2u+Q^#Lxz4O#&gIXMyEnh#Lo! zr{z@;z-3vuq+#P~jf#47bPKy-??i5pdSzymn)ae^W)l;z1Mtw^0<-MmzQg&O2JAx<41y z{}R`UJG#qjCBzzl&&_J+^uGviVzhg%)O}a&TQA2NOcUyPJf4TO`(#Jj;bl{?0jPl zOZ(z+>27h4_KB@DnV)=@4z-4vsHC&B{=*`Kz$hOR0g8Hpji=022m(B>s(x#RdE(b& zFsK__cv_^ykx0<|${FgI5W?m_z{kxO4Z1qVExV*r|9Xym2-D=94h((L;5>lZ+_3hnaP(sN} z?DZWScM#SOrRrn0%`ZYLfspCv#XO&!fOqY_s9}QvFHR1g1_un3lItYETXElwlNqG& z`!ZNefqC*AJ-9_28lyamG?E;?$;W=drj9msACnzw>ko*Zlz6;10FsPIPL66QN){&< z1fbpX4wL|NkRUKI?2`UJK;t;WA&J(v^C@(D6N8d4q+azbP(ly%X;HLcI#kXK8dR>z zxzBh78i0R2GpJ8MmSS-vJT;=t$G*&%ZKZ(R43Oxu9VFeSuF`gXDNH3aotdGPDF+~6 zZ5Yz%()%HSt^2h`mt^r{(*+dkNA6J|bbfCn(Y33ObdvMwlE1(5 z;AAWMA^Piq5Hu`ao%VX1Lo_PimsmP36CX*rEb z&BeWfs$ogQ$DF#tNGogv-q4Ho*-h&`!p#qJrKKdg3n}#U*?-iJ;W+m2SGy)w37Jma z|FiF%7;Z_|=#Hlt;jDvJYLcbD`Pkf+WVOHfcY_Z5))_IlzRP-&bA2DYjc&jWn>4QL z{!&92Z=*pQu+0De5E}3dS}2d$!;&^rXdR@YlEee$4|wTt5%JWAD82*_(+6J^{ZLrA z7$9+h1>ru#|48<$;sBzAYQRGVcZ+!vPR(-R$$N!Kqv5!WAE9VXMJp8c;WYoLv5Lh7B1 zuzFR(Hy6Z%$g${g@N?v)+-5lZh07H9)v*=FV-?Etk@cC-Zp~<{eGv{vleR*&KBCzb zcK`EqHm(bXuf7_eQBXWkoFvsk)5{3&?)0k^Ch5>~jvOU7z9=p_Qe6g6JdHC>>`Ik> z*K11@xp@zBOht`TW6OVv`TPwQUb`l=ktx;{!Wq#pu;w{~{Bq=QLKd(-RiJW->k_6i z)Tb3Q==oM5WYa#MqIRVA%`ItBQUn%F*Baal;dPu;Yw)s+e(!5DxCQ^&8Bs%66yCO5 z08Qyq>Razco=3;1&57c*yR<)O)>D-hi6jl0<9|cX)V7aoaN6ubI58lbGS0w#M+|c*0NFt>cE;gw@EWU(oMmyNF5yOyV z__s}3-Z7d>`^FRQ=t}KoEgKp%_S>4~!@qXNW%x5wG?i-eipRsw_;v;jFXf#2;smZU zm4XTbhFmNAuv97z(O4(1uTB!y8P|{@{e+UAr9Ko=hc*tnQ?qDys z%Wfcnahm%vSt5tWA0w`{@HB}^;7Hwvir?t}=Iv;LQd2!Y_Y5P(E8??tW3z*?Rc-aF z(NA@)>Nd?p7c5B`lPy(4{H|`oP4%e0ycV2s{X4(rmMCc53oA;Y;n&U?b}K!Ogtgp> zEFDX`pi8S{4yhvy*|oH zzU9dPe=((YU~9TP{9Qj?{iyHRMqNmAm4cjW&I<6cE6&JvUi3b+-3_7sCRIaxW{1ot zn^=Y4dt3qzNNoK_&S``hnBbHJctArMZ{9=6)loweTsSj{0Lx#k`Aw?+p4TW4U21#; zIwa~pj>Ke#4}O$ECke(4nE&?$y*gx_3-wcyC=OBJ?dSdhNqbi(j$%b4RU>>-4gL>9_aF z7jOQq1b^7$Rg2#;=h2r{hyJSRfF&yAs+H!3ce)~^>&K&X zQLFx!l)C39K~*H;TW{)?f_{D9d4KX|d#`FWx-j8w46nY>aB5!WBewyW1G&zgnmkv} zi9T94RYpcw4zY&~Zmeb-k(X~oUvd5ViZ!kmj++z=ne&ijiRZr3qq2fv^_z@GjdJ zM@dmTn+)Q@aNMo1n;#Z)p$6IlPJjtg(oe~B-C;q1E1Uk@k@D1s|1N(lY432S)N zJ2Ye3$>p9E>0;a^W3hN8MV0@tVzw%q4K)IG8VRo zw`$wkrhKOq1Ri7=L7UFPmfU~EN6m*yBm75{!-F%&jm%A15_iTv-7ga$n^_&~$6Jrt zlO>gOs__NyKA&mD5b2o@Mn)%A3;`qG@}}#njwI8QUAie=>btWFcT=7azJAX^h~h%q z5S+}kP)Jc!(;UNa+AuqoXG^5}zPdGbaY13!#)h;{QVkQKVZEDMo>}oR6P;$kB!0c{ zEQS7irKwd~on2F0KjPjP{aCkW4(bf3NZpl!diS?l2@4fYet~v=yB|qE<7lHmCdo%P zF85}?<{0~8Dp->tD2DFN?+V2;3Ncc#Ul`V~1R)5Gguk9f>NFg(#60o_P}iNi3{aY$ z93p?bb(Q1H;cm{v1-^sU|8@`!KfpyEWIMQ$IcZpfj-lj=UuB>a{gD16Zv~cWN7mdc z`t65*P@p1;dAHP=@qw(I8@34iH;Ok}jV5)htF1n`kpJHDA9NuB=r8u;I zD?WRyu_Vn^GgVo9(aZGmK;`w+FW$|K1Rd6wlWHv_82b=BB_QN>jM8!{v%Y*|w`@vE z95c<%8Mjzs01xlw0wgiR3H(dpvJ;U?ya#7_FuQrs!Nx6Hk;%O;s-ykx!(abAXSL+rpmAd^e zwq(O@^wrm~r`Fwk7T-TQL{^=VEi2o;tLd6)GHieLA^U`7&;5R@W`{)*C+3+!@u!~X z;eE8*Sk@6dC?AJOjRm~lHOj1zs^VX_J-^a0Ch@vo3PelbmW-$i4KU-{6$r+Cas8H7 zxS2BfzHfG(Q2l%o8=7E?T4(WS@5cR!5WSYkykE5c;6%7I=;BjB*E)Gsny=5=#gvLh zzxKD;(q)}jO%HQ;kz_Di_?4noEI_^T1jZ{HLV4*phlcwq=95Xm(677KD6+LE_=+(N zw#?hWs|t_xL1wuRPMY*v^`8_IG~R7R_+pN~t($c-mC3jD-gs6vtDNG0DnRiS$Jw!m-mc@<-Q znJOhgqm_IVgn}wqp32DyD7Y;Dp&{fkN2kK`yUagY_g~||wyh1rsUZ#94^9vnwzBrp zG`5eqxB?A}s%=dupKr}1wS?m9dG_*?LDuWefv9cr*ECZ>yHWD|@d2{YCUA+;`oktO zn@?@h!;*S5p(?hMJlb5|T`Zv;-U?lb&C-(_Ufsxy0I;m*Mwz%{DJK%?69AK3Pm@{H zp|f*T=D|gAJg)5f1SlODky(EZ$=Yb6wyfO{IIl>r)>58-x!LI0kg19YqNC!dmdF3B zJDz(?1Tk?qGeBJlm3C~(I?@a_3bw_%S>H`n)9`@IGEJbm1`sdo8KGM!XlNXepdtB@ zOVYip_^mn4b$-*v)yMO~k1vQ74x3|a1Ks+inXSTNtmzc>Z)bsc+kRY?9^j(k;#!PQ zx)&oUi!lm92$XH)J=)T(qqY!6!Xa-)dx!ovO7>K6@uA6AZuUeM9f~HrbZG$&e~M$N znch=|CZ$Zp2dDOX%k>;qC);uNm}FE~?ce?|I}l?_;Yk}_@yi>iE5wjsO;c? zP18Qpghu?oFR5@p`Hx?hM)`r_A>%xj?UB%Bf{PQ`a()wAs^qB^t#rC9KTbkQjAu0a ze@cgO*lIOsK-n?;iaGD`!aaca$xY85(~9cas4uZO@Q-2lu;DG!&3D7hb(=vv%oY7C zWqOr#*+yP*6VVz+gL)7f{Bt~(>*AUWLB(?t#jb^uT^mhJv8d;X%hnP7s z$2V*V!%>^mtb|u<^U8$NxsQ)dTpXVz>|ye!5Ay_XRIzQ<^PWIWh|nf=7GE?Ft#Hv> z(6t7oeETY)qn!3_D}TAWc&WVbK&nZF2&@iuN+`d9T`?TwKz(wf_vz^%a6qs!^sc>V z{Xc*#YoL#FO(>PkUwWA3%TyxP`Im^ELHanRo5A%W=S+6G7inVlOaW2OqC)H0JO6UE z375D*;<9+9ds-hN7n&y}%u?eneH81Wf6ZFcLcTBR&#!uxzjIUU`e$VjUi-w?;Eg{m z(D<)ZpVH~8EPggDfWJ5q3r-XEz=4dj+4mGZ$=G~?Nf7i|(QjhVJr-z2$>L~u#rGi0 zf51&XtYf><4yb_niQmtC6r5yF$MO3G%gvevr2beOE&l{f&NJ zpP)15!zS0?wghhfHKWN7=%0)NSvzA(`AEi~H*x=)1+=5oR{{Lr$L;{h3^LGgp;ld{ z5Ns1*Q3KSwyo0{&^)^spr6raUZgd(^PfEyNH#JiteM^X&6g5*)<)q;awti6he)J!p zPxe8)VMcPbi{*QcB0ZyIsp6pSOtn+Rm%YjLkc@eOEU}|0#AX5k8KYSo{<;oap?lCt zQE@=XOe8y1t2<2AX+}rrvPzFWJgDqMZY|O+B&xN9Nc-!{yVh7>vNkOFI@+oPhko9+ zO*xH;j~40?O~+oO;FC4`DVcd^9^GS%)(z zf!n9qX!uc!7lGlxvMD&u5KWTGMNHk9zJc4ca(8OLl}OmoTEvznPBmVttZ$-u%QL_> zaZ|h}vJ3sOPa`7*=5!Fc_SrOb%192{tFlmhjbX+`*)m49i|J;Jkk9J(4R=XW=;%u_ z9{nS?)oyAmV}_U-Ah(bBZX8la(eNkbZqBPZD*O0IG+kJAHB)~6R9*~D{E5J%jkP@! zTb0(*Z>#C^T2aF51|++37|RbXVcg9>*ZJq#wBS`_7_L9IYr}N>QVCgZXWR?P-%wB> z;ZCqpYN*`nEAN}ue^cu6d}tUeTS67T&U>g`o`!ym6+5=<0S%@&Cr38EyBjCzc2dK0 z_{0j{3Nbbpt{a+2)!n+C;6$@YPtpb#YOg`b_Zxw_UbI|4HS~4?^3uW;55OpUW+D3( zV6PYt?m#<|a^AsJV*@>RQHAlUAcbM2Oq*??#AlqLYHcm?GyQu#KGUE4?ZI86yDMEH zk&*){?wp2^Hjx-gI3qD$SZ33>WB0_UY22dLFFMTz4JdbXXfw>P=^revKAr6QB*0wZ`q-1BVwO{o{-dmD2CG8+yQQ7)5n@6tgbHx-l3`G z`pxsa)wp<41G?uUO7mSuBYna(Apem$ijhI@-#W5FPk}HKw+{43Qqs+*!dgG6LWX&I z5HQ`@h1SEkT(2dUBm2kvjz}PCAp@C=Ne*-=FTYRD-o&*P%*9B=GrAXGwq1{p-ied( zDz*7nT z$&IsE1eGai2K3)EA&jyKMl_T_h*O>UqO4ut>H(WJ*UpNgH8ud=NbANdf7u;|?QwTS5 zRfUV;soe}2>d&5TecK5wuZVmNQyh1v;mj7}(J0>g@Z807$i6LceT`URNU&Ufy(039 zpgn7%m%1c-Y$#eC0j5#~{>1r%I?KHR4Q@Qb6)Be@8UHuW@CXOWeV-lPd~|G83N>Uh zQ!soVgSYKU+g%2f{2z!6g${IH6#c#~nR?}Ruh)7&tZlC)L_nMk{0Cbt!9p{4ktHvz z$s{E!^ZI-g9mVJHQ1~9INAr4^PH6sgao$xiAZOK|&oL?Np~5hBZ|qUeW=H%ieblVI zP@C6SqegwV9y>bL!3!<1cjEcnCBr|{a8E5%otV!>aEbo%MX-8r zDNEihks@&-Ii^L~YD8ki@I(2klVBv@chc{PC`NfH=8iANf5;&tpxG5fV&xEVhM;0E zXwC}w4?p2vKsX!gzGYxLmhtOVMfeH*c^B|d0VyORe$0?h`W~2)x9|~hMQmgk#92Er zl#yE$<@wLhL3N{3xSVWgHDYp$$3iP_qYP*;^s*vJ*iYuZ4{2*|szsU80;5ZpMGr#R z_(ec<>;dvM(}KWm^OJG}&FA5|mz9WF$L7WX#_a1eRh%l(Cb&>PY={A= zDnk#YSUjDn9Rin;qAncemQV~_YS+b~9*62vz9FF#fZIO2-< zCfP4TeO(#9l&sc$_yAjd$0%+o=Ro_S*!rR3v*IvDdnYdVxrGz%-TDyIIeY#jX~#IB zJJpYqK+o7?L!I1qlIu#G`@!F4KbR9Wt2Q7)y;zStY(qrQobf{*#TVb1z6YO3i3Qk0 zLPzUEE6&=ojIY3B$n{FA$AL?cr?W}zn2H8BUt<()bIto zKtJY*ZX;;yUW+7m{iRgfk{RZCnG+*2)~|C?VTOT6tUx>Hl%NWrOJ05=YD8gJVec3q zG-=<9jzq1`vbg8Krkj zLa5WLLo;z_B2#AC?FAHla^F*G_uO1WmHqNMCV<{9M9Mp)A~+=UKL9t`NOpzq6DfQ| z*t@;cENxsT=44t%j6MMKd%3*XKFtM=#^M|Yp93a~n;x}2Iu{_8xHQy{n=#O5N3l4Q z8JkUvdLFRzp|c1d&-dwc+t5KaZk$_Yjh>LoAn9q`hrEK8Kkv2)&Fheh`szE)^Hk0^ z-=N?yG{|LP^7;J$ndK|=cMkudJ=o0uMcezQhM}d56#qBv5XGKjCWH-YW(pd&^p}SI zxzh<<=+iY;7A?`m3@;pUC%Wz6hL$a(a~-0kU(cpnPvEYqO}-;l({0>9G&Be z-0}lRwb7fhd@IQ0dU3KYMrv;0EFNK?r^-huRtM%#rAO{L@y%p)WA2uIHL4mPqL<<3 zXGT>h$V;wfr^IKJb8gWc>#;nge>If(Njw^jgkcZ|hr1U0Ds3epGC-i~=7KFJ4rup8 zn3czmi9(^0(GE0gdwHTTJTw*7$-94e&_Bl8pOqg~w_$c&n}IX6>kM2;;jb zZv@pWt@4I!lznjpB&xO2l;a;Ovem9)&Pz6O0l5gfnA+@=5D+K&6}mr}xQ}aYYBlmR zxnqA~rBVk=`@LLQXXuATkH+r1!e&=m zzYumx*t^42dCnf`g6^i0v};u}P2XJk`9&es94(iEih3~d!dwx(9h=RqYhk}+2!n!* zVO6)ZZeR@d&x?rcSadqQg+8e%zxb7|{75$5n~Ge|`qsHTVbN7qfb<*(4a3nC4l79;k+M{z3=Ep5`c_o!RzDdo zsMs$dHf>9;^?!iJ=~t-Xes)C{+r2V^C_`VX;&AU9&o-oa>^@T*7hAkH65tmS9ptSI zcn@{6Y(QmiB5g<|?)o{j?6b0cw=YU;IU={Rw6NoG0Z_Z`4w;Iet&F?($xe7~R-xF) zcUzO%<1uhyb@frEjx+UaeiglR^H~;Y?XmcfrC4FKHn?)-sI584LFVU)B!0u4!V(82 zhUaw=3{Hm|KR89WK(^rfas;|UlS-c#SjCG(jN~cd3={GZc3+IeDq%SB!J>iLzr(PSr6dcnafXOu%D! zq#1VcX}1xlQmC@^O(PWd%dGnr{HWYRD9K==jk@eclnL5w^iqU{{$Vw_AVuG+qK*xR zfwtcWMuQ`x2V^M{aHKD-SriuBvzI(5&*Fa3a60kEe`9SfQWp&6#2>$y9;1eMBy!%p z)X&p+zGW~x@~AEPLgtimnsyNT%bF}lty*FtK$7D$+j;xi zy}%)YTd3F=Wa*MpqV;PkKZGKFu2tG|wMxlNeNQwgQsR+qa&))g>73Flx<+9FTU)Hi zWRX`#>QX-o&I(W$kti&;N12ha+$;MEt=U>~R|Gg+xK6H{5m;n`RbJtoNo-UA z!WLPM;B>4W!tgaann7EIEgV%*8~R9zS;YATYe>s+^=(CyOB-|Hb)9F;Nii%YWOtqd|~0~cC* zR#BYS6K~c@_rHAX7-wM&;QxCl&ouGwA^F&pMr|G4FcZ!+84nJ z-DNdXnv*|2I+@J4TesO#wY0{ybgh;6Ys{x6NQpeKhWr#mIF+`2KT1~Prn;YgTr1&#SS8k|fW^nku{UwjMSJ4mdZH z2zXoy#mt*i5=;4)5U2Kr3a`t;AHmfP9<@T_>_A$Zv5=3**K?q7xR{3)G!_^@h6q`u zEc%R(w<34OjyxVy;O)CW%@4VB$JWZ9lbOg8>09diTSIVW#e`S4Irg@`@oE5JtO-?; z1~_h%Dg8FfDzK*2l=dH7Cv;Xdt4}8yGllGXzM!=^8=Hv_C>#0j14Tz>i5FGzUaC$Q zzq(A$cdi(mOj$79k*{TOOYJgIJe1Z-5*tkYN=o}YKWNXhK{t`=?jma8ALG97JjaFD zT4mxK>X)+aA|f5tc_TGx@ymK5T}#9$S#fdi42fF~)uWPX1Ysc>tN^MP0k8LvQv}oo zS(1GtAewfyoDq*61aUvEHvne{+H;{gRYDIntXS%^e5~ z|2|jw4{+iP7-_uX#F`+h2ssf$08j;q28ua^J{tRc}|9-EGJfU zRgRVxU(DgG9E3PDl_%uO37Mr3;fs3FfbHFGyhqXGo=hB96Tql&sS$P7cx3kT}jmLkz1MrXo%@ z$ct!}L^aAO9M2ewxrS#vmhh(ZSJI!EQw7Ir{iyU-oFFu6Y#kTzt#@V(b>0t>CFDBC zO+g}RT$Rom(jsgu^Fu3Xf&(Of>a9a^IR08hyw_%?5OL#kS%y)SE3C&78r0z)q6^We z*#r1>ri7n8+eCpAP9CsTapL+7vg8Y_A=6ZAfLsdIarBEdT#@--j5?I78LuEp>*8no zs3F*5-DYOGAdZ)Ulb7%9>rKSV(3gPHSAe{>h~4ry)C&0|fiA(nfuCHZtD5bEn9qJC z{`nlKTzrpIBU5?MXR`ri%;l};jBxw;0ZGfc061FO$o0GZ3D_k4R z_u%zrUScZDOSgksPk2r=9l6PQjK#SYW^rm6R>!JzP#3&_4+$EVWNSmd33d; zqLsQ2jaKu1Y!J$5+bF^Jg{1NtEz>bVX~McTu@sggyT_uDDsCySB@T6*3GVBg_2+2@ zJflzOc#M}bC-!aBPj$2bwna{eCdm>bgTT6~;w)Qx!)~|#MRf8+fX2F#tn~jtDe5WB z1t^;G+T6`|q8T*k5S51+{B@Sf3nDkES-fjeRKhQmDDInm1r}Ncu8*EGc@vt9KN^?; z;1Xgr4aeU)43foqty^&=#VVX@CDOXP5U;Q9(xm|Uyebe_@&MPxz&kgGE1l4Yymdln zy&*TkEESa~O%2Eu87ihY5GDzXvoT~XkK6<{*pxIYvUdGRlpsk*j*cBJlP-lLV^}`4 zM+n?E*52CGxsxQ7Nhh}ZSGegf207Ibu<#2ivRqf`Pb@?K3VpO{A($zM3$LE>i|Bu2 zgM&qx@V6Yh(V`X$k=00tVVmp=`ITgEd2*9-n^tu1>84pGSLrN%!5;n0)EMVmhqAjJ zEC0>geK7OOrZswlwP~G!@6BlyPCE@Q=8ioA<1_7G>u^X0FT3NA%7+GRES zp$t^vN;KGX>TGtj;SkT|T1>9m3;eV(e2SwCvym+t{bGv_Hb@#Q0v3o-Pevs^haRf< zr7Hng1~N}R#aq8{CT2ISYA;sm+^Q;H+ozfO(%5;{HXX0@)VrIrK$?R_i~VerEJ@cT zgi3dQWB~66t>@KQ#9~cQQQ%^vl~h1pAWF9}K+YrtT|4(hX88$ZK4brpIk-HQm9*-K zY3ot?dAM{t_J!?5%83qpvQTyk2B*ZsW{T2m0aFafH zs9jWf0eeF6#_cQ|#?ZqlPBD%fkk}B7%#eWs5Mgj5w?BH2v#~+~C1V&-P};Rm#k>MS%p*9)}QHSn&}smdvsk8eX@A7 zCNz?sC^33f&XIIo=D=(DCAOYCMC0?1n{5M%cd8@3V4PeYWytq0Iyu!vG4RA{j6R{L z%Krc*7K_RS{NutGTA^&dv4Y@9%GKH&e@E)m3BIi%t8wZFiF0%lQcqsugB#V%&sOB# z7I-9yBGty+eH^(bhH2*`j766bv@lpiDl>eI)vYDh?36FiKgX)*3!zGm8)OqjxDc0z&sU(v>~0_ z`r*QoWfVn@q-zMs@X!{D`7&}<|1XQ^1AR7eP=&a^g6HtKMs^EM`}0^^FCQgI!~0Ji6FWATy||finy&E zcfg0bVq*3^x-*K^c9J%%2)W|xy>lZRru4>-Tv+(J1 z{{tYH`NFhqe=8303~C%nMo5PiClBU6UCnq%dB%x|AfZ~ssUjk_?<4o;_;0+cK0VKZo5FglZwB66=eOd4~C_Mo4x^j)IbG$ zwfkXx>{fBRk+im!vVHat{CG`5o4WWsmI8kS3$Jj}wx5$9eY4c$=0Lb)xqH3C?eGJWQeUq{2rmaPc*{%jNaVS&{so6Xr?UF8sz4>PT1j zB8#<+u)RpW#a%^9SpN?7ktTTPi8MfL?C5#V8i@RHO0oNB-ZQe9YJI}(^rW)t`P*0g z`BcR1bI(Vg)|ygN{0o*xdT*;n`$o;0>t6PvX2|J41W_yCjSHQiP2HN(PMkF4=v6j>h4dgb?_K06rstO_nT=roczb%Oul)} zZ{YgsiDs^85A1rHNVtb540v#?ds{wl+gfW~;*^#ied4CYJ5mh!$vGBB zN@rTYPSS6M;Z2O&E85D0hTm=h_Y5uWXZ96CVzd)%^J-d6bK~&0b6E@kBZG#p+hiy4 zmRL88cWd9yKT8-9!2M?ECp|qSPdYB4ibPd4e1zOg_hU$({nl_b0hFqjwG*WJ<+jombx(M4d(*Lys;z&;ypazp zr?6wg1vp%n2v_UMyr27ia;Dylh9p~i*P;P%-q%HRUc_tLd1fBNX839JPYou zx#N>HvEkhJpfCji2zdht{&I``FKU^Pz{J&&?pGn_tfbr^ zE+GVdms@cZDE>J*3y6guI74OYuCfOE0A{moQoMtXf@c$+IP2Ylw&BFF1bLlfXj8G@?@cuu%T0?|;_sYk%0@yN+$9e-!iF z2k`^K{{M>L!Gx%)Ts2CmQ`{6uk0`#tenH`|sYyyG|b#gdr@ zz}_+2P4&8}kB66YM8U|ir((UYekG#_sPHB+#IGqf+q9RHqxSREOssvHf{~gri-&8~ zILrG*8-F$ML3Ww(z^T;yv}`ZNuzj+C-?|}M_6$Gj*8#d$b92z8Q@;st2hyDsem0+T zD;>(rB9su&u7Jh$_U8<3GkD&>M@xlhAbp>Xcyh-U4w}MuNYcQz@>kP0(6NhrYq4&F zMMtx5^rsMkk4)=^#dIIz>M8A#CicKZ))ctvguTg~;)l;OE^wC-i4e&#U8a5fwy8g-cPD0Rkq+FVN||!Lt0MX&w3RTvg1&hQDFfNf+eBvp=E>~>JOzg)GV=(dj&tHzMt!5;iJGYh`p+N3wTv4-f`Mc z_2YJ;5R@PzY-o}JT<=7KFm|MaMg8Th7B>_8<;c&>s6f~^*zZ(pRLKaLvi#f(s7txJDJ&M_py?{ zBUE#O8?=XO25wbyLOp1N7{lZ8n*dB&hDY>0Dn2aubR0i6oz#$A#?FB4V)_();T^l3 zAb2rWm*n;uthnEY(_Cr8Y4CaT8-xYNT>``+S4cMSOYhJ^KE-ajmu1GAK7Sd8(0Dk_Chij!oE>$$kVy_rmsuZBw zGU&A(1m!p4W{RF8GVO_2Yf0NX1E_2p>SD>)LfT>btsdeOEleGTmHjsJSK}2&dgfnK zn~6PUKA`w~FvRd>@@0xJxhqn_ERqFAlsQ@4Uxr7M;68htA+ON>yxY2vv93-WOVaWZ zZRgZ+Mwp(GDGmC1l?Sm=xi}%i?SiWEZr1$DC*O>aVIUr0a}zE6GusHZ@Xbi_5B4(M-*H zCMcrbEUSA6GuErK!Qbe@eR}r7Y2fxVce;48;O||XsNyj!*08XL*QqGGtD=jwzf2KT z5_VsPKS#+@HsT3=GSk{hO~e`VdxW8xp=dOVBWwo1w@?DtS~rNC$Dn0cDyQxNy4h zJK=O*#eg@=(2aMHDqks_5(}SrMNc)w-miiVuP>%kCfc-fL(xpA#z&2Th6lf_tUR^Z zbv%5m3Ti6%8~oX7>=~aKU#zKZKFY%Ht0)Cp67UiB1D4FT<^l2-Z932ZvtT9AKd!v5 zYi1ylo5grV+s&&sepMcWQ!on`k40)3ds&;yxsCZvDxVp^YlP}~sl1X!Fgm*T@1D2H z*e`0uFaueDwQDzzUhscj!mGjvZUq*i#j=4ALZdjcxo?d5WsW_HQ7{%9G<;Uxz?LiB znTim=iVmz(wSK5()FJMw4ESe+)l<$xHYI>*#D_ZeQLGxfN7Kb9uy{RNP5zi+hGIJl zYoU&|)8cAx7ecM>tbSiojEkqd8jhDYvp(WdANq?DrHy=1#FEr6q@w^v3F)G@4N5Ep z#Q@;MWfbrLYIE}a`X#0CMl^U~2rN%W0%d8??*)W?`_|P+ z+!0D(*MX2Ff4=JWb-(uviSTwOpH9}SL0lCUAq;R+y5mJ`&J?Eu0ZEp|W6QyqGziSe zsAc@c=u1dTkH?|vIg#-zQMSSp11;hA(h3*mQmO!r(H zmi_KRTX^4vzY?9O0HDY-yL87tVzOGuM}}N`CDGLr2O7WMBFL&Ba6~oQkeN{Hbp`}f zIQ8haiw)rKw@_*D;JyB*G$W9#ssuFRb0a@mX8)KR3otm*l>W~Bnpx8}oEz4RT~)v^ zk-xy(3#f}%KQv^5rP;u!LS=ZeL^Ty zF13hD%!f?f&9m~=bX(01L#LSCy29UC%C{~gnHqU%?a>V?m)~1WIAzE?)Mm<$R#+GG zpRJ`R^f7~WS!87^c!qwL7$cUpAVV&Z)=wud<4~mIq^J7JAsJOsHBJ2LsyL5FKGbQ` zLNKM1coX#8k(|9x+Z4x49yFOeT_R;DIb3|CKPqISI>Karbma@!E1#cLa#ZjN^mCyu zZp6H66-1lqm$vqOLH1Vj<1*_cz4ec`2E7JxXWsGJ5?;sk+}Y18;&+nt8m|OH9eiIs zk_~y_7wPyxj*dm-`lU{;k)O1}U&_bp=DCWFR*scd$&h_}6!{`% zWckVsle_w-zMgoox_k%6;|zBt)?VWryOsUC8}5GqE2&un-5B?mL}es*}1&|%?hw#2r<+7MZN*B5?P!xibE_XvwfbReHM0T2%R|sFYkYH zs_hpP;rgYfv(<{K_TlhxlKI2{`3Ez#PYUH@A$y!1X905yi_dVg#)BB?&h#3Vw8=zE z^MpLm=U@*HAoy^&N~}53iwc+N#Gpr&7zUUW&F=T63#=<+_5w>%9)oTa%%+hH%R;;I z9T$&Bv1T>*6CzLJW^O76q?+0 znRwnCJdNQH-mcENngXOw4SItOskmETH{kCm(F`(+gmmcOKC3MjvASY1gL}N|m(w?; zz%caC22PGIRAhQcAsups78>+;lmhrQa;e}`Ypf`$&HF}sUG`rWxd?hU!?&7%ueb1) zByZP5aiGCf`3W5;*6z8cbDu8(^YHK1&X_7;9-_+c6hklT$<%hctndteVt^FH-Y5a^`**IttcS%a&q*yzo}(q3Q{zGqn7)!6q~EH@Q`$fE6l**K;!( zkF)<~Tc~1<$wMkL(;qVq%sC@O#P4X^hq}j2h=aU!FdON+UIL#-T5vKTASKBP-L|(# z<%ty_4eA9PZE|iA&GK-h`LueDnr!Wt{*y0I`*0ZTNIL*ui&%)1R*?5g{1cP=mDCD| zo|Bbep+|b?;oiZC{hDUA0BCJIxmQ3DX2dXRlckC0%cOpj7cu5koSn@!|M&{oN zG%H>I0o1=dwI)2`{gyF`LhC@8ghCdn&}~s<{qJIF+97l+v`{IAGan=7isaVF70nj) z{SVNEz6Qngd{{W#S z{{g<_^9I}pjJe6M{B$E0$<{MOWeM;Fg*s2;MA%>a z4RKTodYV}N4=|0OxTW3M{JHWUU=xkg+D?U*aGpAR`G#Kwu8){?+m8DPZQ=gu`{{h4 zaFXy#BfIMQ!Td~fsKn#%RrGqep(9s=+@SNH@|P6R#J$HQ2@jvmM`TvBv-kPX7`CLx zA`0)4pH?JejcK@(I3nH!qLQZ~%H}94(q?v$j}A#>M<|EddH& ztzh|woPT3S2giEy?)~H+ywJtRNLMcA9FOe4)sVkFz&xNRfnF(&~d-;e&lC6psAW z5&CtBx7?f8^Doe!+~|MXS|zl>LG*}lzxkN_M98I@0kq=qz20h1xcz_H`wpn4wr%Yo zRpfvmC{2h0hbATTAS6l^kRnx@0wEws4Io7&bVN!30R?Fah=5=Nr3#4Bq)8Q!-a!;; zQj+jiK+pBud+vYV`_CQk{qG+qW5C$id#$n#L|6)1lFRnFaNlx#f-x|ZL{7K7Gkiuhp5CDAj>Q)@#0AQ!S_M(UQ0rLd59 za@J>h71mR|F|}Xop~V<`y*C?^>hYNSDJQ-piYq)A>^G~pp+M#SbF+&*@RYt)1wwartKj`nRqW1an3Y<^b)4fIRiIF!sABjA~ff6TzM*FTtw5 ziG(txnSJ)jEKzv^uAdV#M>Hdeg+1y7$s)Xu=%ncT{MXdE{pP?i^s%p5+~ghI7`8ou zJasxhY1CjHDJeDdkrl;;83Po-%~J&x2-?)OZs+PHMlb|b{s7a4cUSE>u)ZgJ2^YdS zRu7~a3NtYMdhZK68j2+ZyJlPU*?(^aOh14`Sr9pPp$RYv za-}6UlIEq@IUTet7Gd`g$=qYQRB}Dn%CbWqf91tlV)4TL$XOBYJqE#cb)mle1j_qh zbVy=bqk6fPtFG=jgzOK5> zy?hu4esqi6mX|&pE?WNTJ_oeFiMV`7eZ8u2fW2*44LO9ZvQ!7R^vGDe^n3?$A%l>{ zz4RCj{Ji+$1~s75^<)+Pw7^oLUKRJv(%Xw{E7`VSh0LHBN#q&r5mKIE+{YM_`Sf1yy*=T;~36uLT zbSH(guw;$%Cfk}r9^Hk>fK4?6+a-$ldM0g6Dm{e?| z&g970$G9lvf*ax62Z3J^=_HWjc#^0}xTPpT3r{vZ~Bf$&RcQPK=qhU0!+PZcytYl=_>KR;Qq^;Woc%myC4e4C z^=N?YuQG-M^Tlq<=TO~9DDv=*j_jo_j!9&%6xEUTgSju=wCke?xptvoF+>t0#>*L==@s zmr_v-#m{l7va1s3tTx}8;p$8T=0^rrt}nK*n0ou!PcIt2b#}QJ_TEl{jfThj^g!8= zW2b-%uhBwHn=j<%0%d`^olVe1QOi;$#)?!gXgXHDzPzJEt8#PT%`fR0vzExOTlIRb zh7N3eWp6CR^mUJ?8nMQjgGn<^e z(DUL__(u?nH5u@fSRx!iGEHb7fnpIL9w|@&193~$GoO;~$e_05-i!cg*eJ=-kz@2= zW4KHZv*~sqcub5MwS4Z3*8<)M%2KIt6vG;qH#oTi>B<64eU?JOLYF(K$la8Zla-ZC zE*rumoCzRDZGsr22PlHV==dCVjH$E@Tl|~hH`j7{*7!b>#j@B8S?NsVvdk8aCR^6M z$l+4Yd4XK_%N46Dv$fHAlBF1$$Ft_A7ksu~M_`nizeE!^ASQA> zxE8Q#!Pt%!Ur>^<&xZM0{$XkG+OLb`?_52Ya}8onbGQsRH?~hyOJ@=}O0T~esY_aj z1g`(K({r-TvGk5ED!$UG$Y+$cQAq1>1J~<{TN+I{)tbN0{6Wd{n9fbiM%~#zal*>)?Qn6iZ z&P;sv5WZ<#k+EUi<~Kj@|AI8?93(x*)D9%#nR^$36fpIpBfJdcpgN9dYVI^|^09X@ zDfzpkCKA4En7AOPg?4k}a!zxp&`Tn10^}JLx-%~D9mw$tu?>@FxXnm)phCc<7+!b| zOA4?1uRG@QLJeiWqGN86mxbH7We!tVG~&RHV)2$2qrF+2Fw7n% zh1Xz;C54qpmx#)^V%h#i-mCaEYfp|)_z^d-?OQNVS|9V$8fQ@yp_1<83&vB?c)pZ} z#UZOK??-&>rsq55j(0Qt5`L1{p0ss+%rv;><>;hOXak{q2eR%}r66B2RhGK&_?g{p z8{hU(ffMsoleGScK6qr6Yt=YBM$rm@q8ftJ!nAt!9?T|Ymv zc0iVxCOAF4Go|#|zNmqC(6oA%#~G;C9wcZ6$T6~nxHL@wMT5zt%=eRUx?i(I4WtaN zaAnT&Tj-bDX74X_TK&@cEC?e`3g-@!SDGz$8SIu&A3U1^qSaOE>y^YG#$<2-P zrtR7X$Ii_%Lhul`=#~;6~xW=kWC}+ zMTP*(x4U-wr>7<%r)1k-m32794mpX`=De2kx_I?Agk$aWt=TOPLm%orAr@^Ou#fH{HX|(6#YESsB=GQl?T6sHjJhwdS&se4Y zQTo!Wpq>CwWk|?=&1(qa*Lu2BBL;F zi>3}3Jqaxz-mUF(@*w0vcsfb*N@PRk8X^W=@@>$~#DHHoF5EV<@MEbc6X-R{@B;p_L4n2IRmK zTn-4T6A3+t@oDvwhclx^8&0Yl6$H~ohVjyZoGKJ63uY>N(~q9gYe#*VM(5w3K@Jov z`0LZUFl3g+wM($RLJv@Xr3G(P&Zz4xw;nqg;M0AKdwm{YMI`ZHe;v$Hjiue1RP%_@ zpnTuj#I;0=&n^;{S97nx1jePBxB^99`zbNJ=}OTmL3v$iBxam6bPJmf51tzifyk>> z;!QZP%l8$YvDG^6ud+DYmM1_U=*Cr{)gDsrtPHH6XI>ZfR`Ro=e=%qJ`9Pf6qIz9* zviCfrJZ@}Tl59%@Y+K*Tb**9$-JS!mWPH|}rR}J7T+Kz1MumeqmyNr1@>NDraI<+N z5Z7WJm_YBAE~rCX8nksrK+41c0Lf6UDY3;mQD1J+Xet;Qmomo?;<8bn;{ux_&3e+W z@qr+9Cj_|xV6wl{&AJ6cAC*g2T`0*0N39iARUUO4k`@T>Bn5ge#wDXBII%k%OrlBC z5FUC|BJFupx2g^ zO@{$b0dg31{4rp(hr$7~fc=yIO#5lU@f`K+YATxO>a*jouCHG5}G2*P?bM{(Ff`!@b-%9_9wg z6nc(;l32!O1j)AxNi_|`figueIbdYDyErd;*Sf_66{yYa4d}XVC>3FUD{7HMA_08A z<$F0zxBp2w9J^j^CNml9|81!cz!(i0r1Zau8~geQDEFQ|gWVMnLXERQRBqO1>wP-x z)@GmHH5M?r{~-?K7;PEI3bH}&PBLBI;5$?AP^rY?n`L9_bC#!A2|KQlW$Dxeo$7D+69ObqMExDf5J^jRxe1y=w)rZj3UBaV2+9!_Mr zi|w%7o3nbAe+cs>u+09x#GLhW6Hl6zE#VI2nCVLbW#4a;8)2C*1)$^%k|Iw^oC?_5 z|M;ukSM9#+?_7_T`b@-m^E^c*)s808mMXs7?yWMYcpCK0KJ{^#WXVKamKDRfvNLjW zY)9p|f&%YcIa3}y*KtvxJkU7@%@jSZUzA^Tx^0{pclQ+@=X{j2UAj_&BdFs|mvR_K zRG{rZ%=wkHeE*8)bH=${i@9N}QO@kj#79btjHjclSfGJ1u+D7rGfZbL$QiNIw44ha z6=JFuAdk9Mu&GCRfR)ZH<{tYy9!=DZWLxJJ9oBtnZg7fG2+~5oE8hINQauk^q@*c2 zv?cU?(x^~?MeN%m0uyt`MYg-stRfe$Z z_G&R#u&~^C%8Dk2ctbV{3(DMUjNe)_=(!To*C_V z!B1WOi!-A?lE6>Y{xt)C7Kr}H2L3M?_^At!z{G!McBFxGWN(7^Xcu%MAoA4cNb4@>YsLSb)tD0B=Ee?CNQJ>XZ&PXg(pn|5~lyiC}As%Gx#&T?*o|($KE^_>wQvuw;hC<8{k$o zld}A=9!+bRv?)&dkNOV2g~bf?e#$SZQC34yTPX%re2uw#rN`GfzVD6kEs<>F1*sT? z4UXyLD5p1?;&P+0{w}BH%p$Fw?hhF&9Pnj7PqcCS#Clj^S!a47y=>uZ_}P-MNeha& zX^TY%w6BbPQOBE5JnR%3OhckY8Xj_l#`Tv{eU5AJgx75QdFg8djM_BXSrtX}v}N9l zAv)unZ@GJfSykXDU(C3S)61d|YyPoxye_m?gRt#0MlMB*PW_ZE5r>z~oRA~)i+8VK z<4mQCn-^-@fml?3&X^YFHsSNSYIjsMbqBH~L2Kpgbn!E;IXaT?e$zzJ!JF?nMd)*` zQ92#g7&V9io?mVvv}TlU`o$vnnZb}9c)HJP-A6~mdr;kmCUbwnq(84gUL2u|xPq0` z&7`{a#+Gr@E()1Xyh!kC=<$MovWaXolzSOJ^)kr&gf%9Z!YXaZw;nNXGLA z??1jRove`Qb9#96bbkOWX(+B{lKf&U9NMA58w$0WSbg;F1=BM{6)HHQHtrY81>`xZU-b> zCWRNzZ5gLW9@}62ZB+)zx)O;ZmiVw*zUvXF4qXI*0fc;r_AhSl{ zhs#dRz1N&$*LI&`jbSa~6%bdyVz~qHElk+HWW#zj4au7aGyRy7jb90!7cRBl9%%e}t3~zeWyT>eU zB$?h|qdd6C)8BSvEqlN`qDiFxo|-VNvz?BL7V{}WFRBvvkd=F5?R-h}m&Fu~&qbO| zaZ~pgDWPkW2uQ?2YS<*HVJHq$9rEnj^r|y=gbbwmpL67nJJCV1yE-) zw}a<=Gs72Ku^ah^P51LOCSGr{@DB?(O8pV}oW2L}k{b!U@g8e4M|0sAY9cuu8?D^bxoN!<$*Iv2WAHgkwJ$C9GtWD?b&EV)CeM zbFDmEcR;uv*hzVswzrJLW4}s~DUE2GbHC7@E>5?#J_2vP{~5}pbADK?^ivp@~-aeGQ)Zh*xgL9EwudPu{Bm=G1c;9%J5*@3*s*gE*Av6yE3*};hCQg%ooHH#3MW}{PWZdXJcDjZ6e|#;Vscw`zOgb>dAb=&yw{RKFV>SP*n*T(+X;)e;)-t>jg#} z_grEcb=`3bDUf=cR@vbzPc&aVI(F7s#RxL_wfUgB&Z!F~ax?pe@7nWa!O_vmWU+UB z>yhP=4HwE51`0Qsu42&m(e~aTzq@nhXApGE$q(FWs@HZfycFtJ0bg^% zYR3N+dj7jZPwSPW^=WfY5sHIPOnFU?eN3b?q;ty_-wbT0pmV#d`LO-cYrE3o>$l<$ z6u_1zYwB4&f^p;I3SxTVrv&=vqnw<~Ov%sKymW~9_<6#K{t9MARxGQP6 zvyEvgWr)!!_pW_g^>z=lpsq!akkjl9}n$ znXC&%yHU-)dz>Q#rhAg|qe5w0FIU?K-QI_MX?Txhle1k(N;1VkUnAo_4;$;w=(CpS zW1L0ygI^eczq|^0DH=RXoIf>e;ii<0HvQ1p|Cv^ldU85nTe>AAfJu~3+6ZB`w9QX*)Gxs7ss&i_+fy|l8HvAG0pyCl5>+31lUJ`mxORZ$tkioPiu zVJvtyAWT4`$*6Xd8g(IJfqSQ)7VTo|;fX<8JClxFZ5(M~FsL|`bfBOhX6WmN7Sl$1 zTH9KCTGNUdc-eT8&YagiD|Qy`V()ng3X_x-M)S)(qaJ)t&edj}Uq{x22P z{7?s5MSc@$ZEU7z`6DlDJ7lnzyBu_x?FxJj!Z&%D^C`?p_ACSb@+R5vysC_30zA5rw^7M3*7ZdaL z_7?S)6m`Yei^1S*8tcBjV!01MauWh{O5cy196W?(!sxa&;DS zI4=eh6&L$)BNZ?ljDwq}gR2XabYp89S1(URelITvTX_^(0%a!wmlTnfvPOx(U}zZ; zaqtnbvxB3>VKBIz1X}9H?c9E1^LO_H7r+fAfgHe*ydK8Y)(eHkDDrDNXc?lrX9z>gtLy1eSsLXHpTDh6=cO zNPy{|Ct7figHRlf5njg z-AcDb{l>7H7shGVYiv4Zk?`s8UR&%FaD2a=D;J6XHfEAsn@*rM&My_`Jx5k@Y%t!?+T;pBkWJJ{_f z_BUF8psU?ez~_P5#C}5*1TFO6^!fJ@`WuV_NLJ+cCV}KXz_i5QQ2K|z3;Z*~2JS9M zE4FLPK<*^}5m1pQIiI+!gfvV72H*8NesOVr&=13NTf(XR- z(BgwZ+tG?cVG^_?h}-)>Wu&DgrJ;7v@8@6=;*!waOHh}+b1*p>DM0df=fnXtN=g0w zIdQn$-}NPRg8f5Zak$Js^o2>t$o)M%@CK7VI42JO$99r`*A6Bp1(*KmoF~TG!3m84 zF%>Fi;NXV_GJuNdySjQpNzqmxDyHFL=L#k1RG(H%Lj`KCAPtAhfBFf8D~87J;Dk@U+Hw?g}2r5s;$g<5SgDqx}!MTC|b? literal 0 HcmV?d00001 diff --git a/paper/figures/CollDetStick/GOPR2201_ImpCtrlv5_E055_part4_t036_manual.txt b/paper/figures/CollDetStick/GOPR2201_ImpCtrlv5_E055_part4_t036_manual.txt new file mode 100644 index 0000000..7eac612 --- /dev/null +++ b/paper/figures/CollDetStick/GOPR2201_ImpCtrlv5_E055_part4_t036_manual.txt @@ -0,0 +1,12 @@ +# Bild erstellen und bearbeiten + +neues Inkscape-Dokument öffnen +jpg-Bild importieren (nur verknüpfen, nicht einbetten) +Pfeile etc. einzeichnen + +# Bild speichern +Source: https://pandemoniumillusion.wordpress.com/2008/05/07/compress-a-pdf-with-pdftk/ + cd ~/IRT_DRC/drc_paper/Atlas_IROS_16/figures/CollDetStick + pdf2ps GOPR2201_ImpCtrlv5_E055_part4_t036_bearb.pdf GOPR2201_ImpCtrlv5_E055_part4_t036_bearb_large.ps + ps2pdf GOPR2201_ImpCtrlv5_E055_part4_t036_bearb_large.ps GOPR2201_ImpCtrlv5_E055_part4_t036_bearb_small.pdf + diff --git a/paper/figures/DisturbanceTorque/DistTorqueComp.pdf b/paper/figures/DisturbanceTorque/DistTorqueComp.pdf new file mode 100644 index 0000000000000000000000000000000000000000..07147fd6ece15c329d8c0f06ee972d16dde9bcf7 GIT binary patch literal 81631 zcmV)9K*hf$P((&8F)lO;CCBWKq6#%2Fd%PYY6?6&FHB`_XLM*FHXtw{QZGhnY;Nxra;fcWrG%#3M zGht6`Ss*G0vJCRicYMu?b2784u#uo{es7<>qgnl05$j(b>6sr1|L6bx@1MW^{ol{W zKmF^k{P?F|8Bl2>J#z2;@xT7@*Z=&pSXl?^^VuIISNu;-!~dy2Q!4%OZ@y6|fBQy0pI;Z56Tj)4C76fY(FcxZ#~W-X8kO z5AO`}dgvQRytByLLti%NZNpxV{3WW(ndSB;~!!qn}mA9)Q08o9VmV=l_tNt<+Ua z;lKR{J+U6$4;)V4v&{3-XAuwlyEB6PtY=q#`W5nBXylvgLm6Yn)DZT8x z;QN3o81C%Am*Kp<|L1uA@%KNJeTZbW-~P`T+IXgt%VA{=?KP9bxh1a{+TZ+mbN=$> z{AWbL8l&aM{jh~W`Rzaden{gCs{Z!*duh*|YJL|BUu40H_5a`G@0+;&`~{M$vws!9 zZ}Rr_#1{$tCU9R*d=bHK68H7Q7a9B}a^IeK6T&|=Mco4o^4GP6ANuPW!w>y+t>K6M zy5@+7-Uj~v!Mu4t^O@p!*48IEDuGP?KoTnH$e=w$J;c)&to#|Q{u!(hBjsT5|91ZK z-yKuqpFN7dKgwn9=Un@71jI9SuFydi)*8s6;Xh%+o=|H*Mq5To!hRe*l{S(5obx3w zyODmBPd(rCf?-+CHsV(;3CU+(2Uv$>rh&qBpGU3nQ=U#;$%?L=>7+9Gnx$zSq?Ae| zcP_?01Dj{a*vHz8?6JQf{XBgJNENz`^kZb!c^1XU&?N9|o2np?wJ&v6EZ{X2|dWO4t-9r9W4qTPZJ{L_&EXO|8c;l-^CBX}csbOuGT3^FK3yjCJ-?7MQvA}1i&TKsBG0-(4-+KJJOXKA7oQ4^4c zPmw-4k@+lnb8Bj8Mnp{^YHB)TU;0!gBYph9K8f_h1Ni>Vded3oq7Brl)|~h+Y+%;J zj;I3lVMHF|LDra})Xp*HLt-G7gB0>WJ+{M9F{Ir(suAwRDrZ%jkyRQAlT=u9)5PXk zphci_m-w4mjm%L<-Zkk*gYzRFC%t!))bQ=Cbv{U?=$V!WK)OXwuR_k|LehYQJ)8}4 z#EXwPW1x{~w^_X&p~xwm1@w%G5L14#J84~$wo&2F*+&Lt66;rgl9uNoy~m z)@ZX*5<*M?S)_OD#1?_IW0UMoQV|&(;83<`SxefJWp20Pug71?MGKL%5nUugWk(HJ zd*y$_Mwp8aQXn4=;tf5{1yttQg)xhPWt(qlQoWlcMsWH;@N-Ih&7ltpPYRwqjLiAA zQ60vHzLfpmDZO!ilOzQD;;*s9!_O=mFK4=I8G+e=#c7$yNH$D1=|_kRlT9HHB-=2_ zHahBYOJ$h6eswr2X&+2Voy`I>ERg_f4QH?XrLToO$}jwM;$vo|BMLS7T!RwQTS zl7h#SmKoCH<1ntP)K8PzSjA>YwX!|{l{E}>zW4kW8XV_8nDt=Xc8%uv`9^4PoTVuG zP}iIwTqT#zzhGKbTI>YI5liBtEpz7}Ye|l4$t?*nmbHW&Yo+MZqXt4%eMnvQHHpf0 zlr4wz-@4ghY3pFI4{c`Aq90_N@0S)GJJh+tTf!D=T|_rtVMIxigstpiDt{VdJ#>+* zU#PU*r-3%Q5H1Z2zS?A>7#UREONcz^;1(?jU@Jq7xL#@9VqBauozcGgwB`v=v z=qB_selG*0S>}BFz&?pU+hJsb0)(Tbt21Z~04db$^gmWJ0<8(EDoekr*Ef`u20}9h z8otIe@;X5?2DDpe$>>928EWruJ{=I*Et%$>5E?Gn^*xOQtL>#XPuaZK(pro(>rV+> zATni=1ui6HOtgA2wkO)CEQCOm({`@$tL4oA86D)vUKuylv zs2Cv9^<;R>>maqzT0M?6fg=^BeX-t*$Qi3#I3QgfC#%p{W;HK4igFjmWwwX53c7=Uw(3K7L?_1&<*fHb0d*fR!>ui{w$OinGA;rWp=E z=FGI5YsWC()T%J7^-M%whW!K}(6cljDAta^qP0M+x&op9hyXy=dpgOFc3cXC5`Bls z-;VKKisbI3dTte-ahD$@PCiHzr7FwbA*qBu*w* z96P;cOH9$zvC}oJZkHPfBQH=V8el7u=;0K!=D-U`g{lk)OdTL|>PLu*bz04X+;Y7ks6Hj@hV zDUe1f0I?@62}HW=3c~K#3@ivqxnuFm51k=Zx`Q*2o6%!m?JoIHdK+}Z_r`B zz8DeWyu?~PLNitV5P-R)BBvB$-`rUYIn!-vBXM=|L-WblE&L@P7ju!i?^nG_<2Yg$SYwEut;yoItH>ugcb%9UTc3>h%ou5ye7$lWAfAH!8Em5$G}gPG7`$i zoL97R1@j@WniL0BFaikd8ORg`d>f)?Jxh}?@Cal!Ssf$mne0e%IHC{v?z0_e4q z0y^byhljt#iQ=G+xZRSTnKS`_fCKR!k-(A0G#F^Pw?MS!k;&-EaT+*x!vNeB3hku< zJ18@~dYw@yZMS}MR=O!Zt62WADrLm1P^Lg=#DFZxWF2Pv7P}N~chAXT@kmSop$1uS zIjRx4rOgSPevEWUsp>4jVOg3i_&CJ^00wD5BPkFXG0-TQWsb1Tvh~<=gl&d{%s^zs zbSpg|^ixAQbcD_wGfin3sk94+Bb5Ev->F;UmSKe4fjLZhec!RqgKU~8^!{ic^}@&v zNk^|P*#=2wP(_FglBAeIFNL-MC62~i9Fu_=NZSkuV=`+wgwTt87rIL#TZGCPc|Baa zmyxD5r8L3cqlj7k=|SU{Jm3a389&@6oC~INp<;c z{TSoWK^#t-MifolPfv3>M$>~qdqiXudJrNLq1!_4BgvCHidz1lom10%Clj-T$-pI33ZjV5!11FZ`!vuA-dt*wm4`q@WHP-eWgse0p&UN&HQcEnL zs74m8z~oR$AI=5Z@&vNvgpJ5H0g+u(oFfK8JAXF&to=OQEnYp->5$CIZ^%q8I-q;k zk2$VT)1<)wBxq&bUlk=fu2@D)K6_EM6=xW-Y_8QZmHeSbpe@_yupM*d=^PXd)GR~q zS=RA2mS-;4Qk3AEW88_nlXEj4Kd?_C;`ciZRJzps7LEoY39ucN?c6Apy2#4`0!!i* zv+B!@J*X}HZs$iKW8ErI&CwE6FIv|5WqXyMsIg5hqmb~~^ z)?Ucp1QNE2N=v#^5tPom8Byjq(qbJ!!l_@GdRNfTaE_@%$5s`sXgH4TQH*F3NR=cp zrCgW}HxstOY@x{@xS`u-1hIh7t2t9w^0dQ6%Mw0{g#lTPRV2NpJ0>&l_`1XFIRrR- z_b&Bj1J-Fa@|&a@s#vyjIucNb(K)NHfagGnsj3KKlAM8{$OJho8QlXZv!pjmYK-K- z2y#RWYXRw&5lug;3K_#$9eQz-sJV(0$W?(okeRi8^1BACMLRmpZ&n5xLT z2Q`wTAjlG>ZKNa#4K2n%ISQzI4y9B_PD)G6;UE?e>hXgpZ1nL1`#eb2plLDdcXGQa zBz&Jc{=;8d5;KWVu_FM>raY5*67dACMWM z#WQpCw)u9TYGqf4PqL9=Q(SS#aZGWDQFvX%)ukg~;|8j%*E-txTsbDCB`Kj665(3n0y@lxd}N?CzWDmu??r zC>W80Sc)V}Bqo7Oi{0#K(yCnO{KxBNVL_!Edcyqg) zX`t3+i=1Sd0g>@hE%^?S+xW;XEgPtHsS3uaHV=qu^OEb@M%@%y5OlI#fk1)Z)c(hJ z=rACR^sTrR!#4mFHI72t(eh0Ysfu8r(xphbbtBaQi4vrO!j`ElmjW9D(eYt{t|7O` zAV;PEh-{Bgw&R%Fa>62+Ioh=QzN|ce$YGg`T?+{bA?s)$8eSD~HQyZ5TJhiWb)a~LAm*E0w4D)2l2_VBUh;_d-od1_s48%!fI5nvmk%u4UB|w~y8AZd{F2svs zrh#gg?eL|9?ojOxL)H?62y}Nvv*dV;V_GXWUYX1lqH33Z-(2in4u?tys$HhM9$Aw> zx*Zs+j?rA47j0)W1W6@SWTyd8+9b+^ z$8@x1b!Tya$fBuEq>Qs9D4=9z3|*zMvddR%Fu;l`>PXWM+l#Lf&4JW=l}fU3g0)lM z?7e}g<2J8}^OuXLZ+LfLs6*000fd2n(ODTGa*?>oishLK952M1l}sNif+@q96(9;k z42OCK*rjTDOcgfkn8wud?5LTJAQF(3lri$Rkmqm^-SQnz(=w?}hmP%n=y`20r}=>> z0XY!fxAS7P1>NmJ0^3)J5>(}e%}9IRnhwQ72QrU4+ZE8SHk~LcJG^)zVd50LUNe(3 zxL7z25D1J6X8rXe$khi@dLqG@Q&+e1kp-Ks@h~9mxT*YI)3EZ4gda-e)Nh zD@q!S!W#=Kx&nbFSXiU3;VGmxkVR;EG4gAVS++e!0B|EFYA~4v0|F&Dkrk!7o+vmu zFN89a-3O>C5f;d#Y2jn~g;!sp@7L_BPzwVC;8Gn{$(T;yXn@tF7ibWvM@N*`snu&^!v-t~T z*M|}4^M#US8e6j{^LeIb3l<1O(}Gdjg~(!Abcr}o)N&k76T)wybmI{Df?rOn1PC}| z9nzM>omIIgP?IvTK&Ai>5OLtN_!`9xXYJI)c#SHqfMCjtE|L)Veg`P__a|yF4lyns zJIO}Catp3^)f}Ws*NPK6vnnRAklyo%k&HUPwl%TMEwB8H526-|Ez2n0ui-n<%{O%H_~17LuXHvio1kO2?Uh3%Z~9O&U&b5=Lj(Y!Tff) z)YMh8xeraN#t32oZqH74o?W%n+vi7sbP~pf$1L&Cbs`DRtTBxsQodOOw~XLlKookN z2*w^)knhp778Mg7k%t8T=r8>B@KDLqw<3vs3p)PxmAE)Vkz2qeHpkV_PK zq?QKQWxUR%%3T1~)JsXB!;p4!=F-_OETPf^b15l=XNG^(ScJKKfC=b+%~kpq#Bx+@v_i99K~KR<$I?XCc0I#0$?TY%`gg%$$|-=5r%ypamA=@yK8$ zdx-oPFFB*DIW~8TNOp_-*@T)nYqELHWf?i6Lr}p}S`tyH%HzUp9V$4C=cF(Ygtj&l zT?bgGb^z&(ZRS`!M7)V8tO^7s%|>{ZqIe}4%6mj9%|fIVvSe&msR2O%Y9oZpznl0Q zVGQarAjo3xr5Yt5%Jl9PCu=@_V4nw38gxSXBa%n4kj_iQrAd4|_B2tjO!&oFbg$m;wR zbPAD7nRIxe#51r#0Jvgh6&c3I!EnG02+Y-d-t`m>BFdUEEta+Ah z6ax_O1eowzh^bc0p>#0BJd z-M9}mzs9Fo;R`7n;jd7=(6E3NwzrYO<$@s^&p;_~EhyAiRZt=0o{XYz$+v; zfleD43x7g&;m@aNy~-)%N=V~6g=Z6K=g*% z1l<0Sj`OGYPO7!@mSoCq^5+gxRs9A8R>VOL4;CYEaXFf%_vpkZ37O6*5Uu-}jNaVk zFY!H1h;n5lCJ{>45jW0?miR){vwP+u_O2?|Gl^s(fGdkfIwCLxx+j5fUNh3k_@l@? z0W!(>$kP)TloAJ+Dpg#^s)coZUW_P|5onl$%y`YB$#9S%E<%aH(uGYIXiHYoeBbtEp3JKn9iQ`BAVG zPxE28Ja$K9(S<$;ZVoUq$j}T98Chg#o@4}alqP)OoMDg-BM|Thfaoy-^?#81bY16n z?C>5GDOMDS1j^L8=<_wW-bVO$vpAV5LnM;A5lO%}vb<(Pl@M10h< z;>>xPuVF03D~RF(NCqMXVD%lq2EarzMh{5PP8H7+kz_*^0fhh$KLS}Yp0Xy|2zgOjiTujDxme1*(jjFmpXgR2Vp4sArr881| zuYegV7*gUpP)xsYXXh=NiLW;2z^Z4&{YJb(nrGGib+TZ3-`D}9+s#Irl!yUB=c*=q@jxJ&@GGUUH&2+!Aq5b6 z6DT|sU00qj=hGDx>6v(KM$^dTf0Jxu{}x(^=Qet6m5w z2aUkVw#NI8eG;K7om&v#83uz-dHQV6M&`RKY^3lQ5U>b{Oy{mJ9TI7YvMAuQ|(uuZkJ8$gBYX8MSbhgzhR3Y&KLEgF<_#M4YO%=ts&MQYUIdhmNr_rk3=K zPOUP6D*-o#g6rEpIAR`1@_`DJ;M~J;7o>GcGlD%LBKEkD01Amf^~!!h1tCekkEdaAi&!Q`427WKOr1~#AD9TH>LWqp(jrsEkf2sw$@Ufb zZ4Myy7#T6*}|s^%g)BOd398uw4VS zR}UI>a(b`0WD5})7={RZSa=~h4M~7R4NDz>F#d&l4N>jVNmC+HxX#CKWQjDw#dD?m z7Cvqlr~ol3t?;Fxz^f5C84|5ac`_O(9?P<6i*y_3y%|P1z?Sj8_jR0MHxW_3k&zKG z&{okS9cKypt)fT9LG(!VP!Qwbthb6D>AQ-ximHAX(a<2;&!so)jVQiv6A$$lCJS zDK#1MN=qJZ^D|ZR!qI{e$msf3zX*Mdo)wEbNYmc%QXC-+4{=_#1~R>G4*9wI0^BLl5fhdU4wa~nCksd2D7b}of zY=4hH7M6A3T&WOLJ?a@M8Y1$SvrZ5k1a3DFR4xgDy)Ab>p5d8MzIpiT$T0v}ijOdA zw5H~jG}FwD;%bxt6k4eFQy@FMCOuaGBur|=K)5$sVFE_INCaLz<|OortdTGaq178Z zkZGi8txDEimfeC>+#EzO0vSv39nT0Sx|Ya7+fqz{%~3z{H|N;waT93{?`%Dm@h zpofeSNKM;xi;VmBBx)etWU{rHCCIG=uN8Ubq*ARG0&Go+pcPf0k5?>C;w9@f+0PV38+gcGNHt^CSTLmWrxwinhZv~IBx|BLuVt!8 zEs$wsWpm$G4BU6DUGv{hxc?VxVf}8(fIL<4NjQ{?!hB(J%@?Sl&058dsFd%gH-M+4XHRBqFxih-Qh?VE&TX24x6cuUS2iWtK2NolA1J`LINB z>)ISB(arizx(Ih+?hrh9p97$l@T-_Xal9&!ZaOu&XHK zL#CcKY8Qw!zh)O%QOMZ@K-!!42*Y;_jK_?%6rG7}hizO!P9m&0B$KVwd4H^Aa&Lhs z6pZR!A;W661%K@6{LeKPkdn}k;^Rvbojv$N5<&cz1EFMq`#1toxVTwmAq7E0X*k?S zq*;r!0H`70-e(~}T*Xwu>_L^D8-8(>orLRJ1T;xJxVK$MmtYuG5qKiS*8T7^0~R|! zmHf< zeK{{#L}T8MFKXctav&p)*R?aP2eQ8SFq!2G`jwYd;b^^BdxffJk(=yt0J4yLw+j)< zh7qatZ_p=zBHIGWPYYP81m0K{wm_zblUg9OKSopF>mW^B}LN2p&fm?20&uN1pK2Z z<5nSKB1^6ivfnw7@M}E-6iT=@z#G+)_yZx10LWB~X$#3R2XNXEVCwRA_DPyw08ctof|8h+_ofs9S%MKp^FVyNl5q3 z*Bu+wC3~=AJAkQyt^33_Dac^UtaEtKcbYAbzXc*Ws5M~agM_K6kChKX%uG1PqdNTzr2}#-%83%8 z=P^%&BUin@7l^L;h+grT!iJ6ylm|UFO7|OUQSP;nD#jC`}%5`y&w)MvvtV zA4E`JJ>#x~gOHLoL&g`WVQhm7 z>`g$~$L45sG2B6DJM11AcOp1_FyfNegG??dZZq|ARR%NojMli){zAHbSc34%VD5}A z3L&x!cSgzSPBxmcOn*Z~|pSUyOsWBp%85>8)uDLIBZw zK7L^AhltDP#c6&M^3~HPpx7@FiSW5ygF*xaLTkBRAdCCzT$R|j1GA`(@}lg`XIQ^Oy^0` zMW#-MjF>f*I_n+GGf2Z#u1t)Ol_Feq9T6vjN|qVbaR*`Oa?j@bZ;2q`Kcg8Ck>Rh) z`Y8j4*tx^oRC=so$bXbcSWXRwF7W1{lp*q($rmIYgpmsTN~eQ})XrbU`V8*vzP*wT zf*2QzKavN?Km~>zLUPc&qiD4t9jwu3%|v{PaZ(<)QL>^;`j_}swk()*hxUxRo`Ylw z(|U;qF@H%AU9NQy-i^RQ5Oda~0{~tNDTtL4VoSOp0?PsFT+{(N>(549;6!9dg2Y=y zV6N^VGRYvUqtAgrUBN|O9u3nxkY~wDIvHXBqVk)MAK0gm-T8SHXy(FxRTR0|#saS| zqV()ujm5YFL|Vuh#<>9uYpBIQ1k^@|t3`u&vob#ivQ)^E%#u6|%c+L;VPFq{%DV_u z9Ra(a8e*m715-q{)-Z%HJ3SF8@#4ifw0SiE!qC!%;{sGI^YXC@;i(-JfGoT;m|8YC zfLG>dD?BSirX_=|Bw$T1Qd}ArfqL}KE=1_T?iR-cGy3jjDZ>~b3RVg~9zSBT2-8d+ z-k>1?J!c--bYQVs-j{7+TE31i7Z$Ma)1iEL6E&Y1UQiUUXs3c5*;$NJup~l{JxH`$ z8^t!X;v(IVLjVKr+1G32s zBzPROV<)~W^G_6y#(SJabdVup3&-NTs$_*Wj|2o-@qz46fp3y3bZ}|&2 z7_P`mMk);kwm9``c+ERhoBTci)V;%38)x?BlakUg$Xt2DFn<(N7}&kJ!WToYK6oQD zhd={@{am_ro5-TTxEWEl>gzI0vVWv1WgcAC@>Q9l_hRaUu($>8S}_Gy*`m15R8A;5 z^YOH2b1gOzI#Ba&Ox5A>RW5mO{YY4v^1l4UwOP* z`R3Z3SWD??YDcw-Y9&oejkN@uojdjIC|^n8G69jR-yC*D^FAil*zHhAQ#dU9Ok76u zz7&YxGgM2&Hf=)iK-!MoR#m|AwWj^H6ivyILI%PRYmO{IZO+Lezotn=T}qDRIS_`q za@1ngUNpQC(R?7P_-sz@17R$?MBy5``LRH+xOG5gH^0a0>?DEeGnl5y9zB*LY6*l< zEMDp&WU2}cjV`sK2)0fk^&-X3Xmz^Nt+hJsQlrA8M(!Dn`68}m2|OHXlHrFweN0Q1 z2yFu465{~8pYeX@5lcL(7PLf;0?78EpW$b^!*1OntIA7(A524d(T6h|b-p1?7gQer z$!OijOiXQW$Z(l$^4FJwSk+~$85aiUh)7oR-dF5XNc9-kir+D`U8@~GTyv^}!I#sK z?A(e}b|Xdc&(?yrXI1c*Cw~G_&ZgXFnzF_v60E!n)rYOM8K_S1!CMQf>690SEE=53 z%(vvwC9hAO8nLaAxg4L>LA{L2#)^Zj`cPDT^#6P(pKb&_bZ!=tTLAK zT`z`MPKuPMp3;TF4)ki#S5vI8rr;~wPov0h^NYLk-laL?$!-`9wOYKP48#m!DYSx` z=6$i#q9v+sYZQW%NJZ*qJ=42@t?VzVGxe$Mn&=Y6ro2N}LT6lnk@TEHplnk~j*uu@ zLstneOXMi&NN%>CdH#!}>r)hbutYX17Rj4r{m+m*~Y zhxA7U$I!2&huLaeIzwj!GOlH0Jw(b5j5k+sB&UNuzC)h^B<_dTo$Z;1V#uup!i7(f z^1~IetcOccjLVjK?R_=apb+;tv@jsq)i5)x?8qQGN|g7j8Ho5^2puNLY^gW+9((^l ztcPt9H5Gd30LBhvDRN|2tYtYMD-I$N!ATL+CrSAMnX+yi3U8ttST1Txj@{I<+UjCfx%M6&s14S(er`G){g4HP)3tI zCKFmjL0e%44om205)cH*b{q!HXtKxZN+d~gAl!-V18GE$76_GSikcfB{*-sT)hnroU+l9P$#+l@p$)=Y z4~4j76g#6eZZ2fbQHs@=da%CHVl)>n7avn6Qmn|vMVb}a@UOP5l4j?zsS<@sy&1{2 zq=vO95E&|WJUvUzUlrN9YmjjhVhKbVF|woRgjbx_wEXI>H-2qk?;5jCtQZ-#u|134 zrAJGgA!*(9#yKkcfOPMLx4mzbbG}xrySlhE*R=xaGNDrqVB2((gNwd*Wb2Zm4c~X{ zQwXP8uJ9g3Q!PHjmC*|?nQ>%}0=aakLF0&H&M6Me*Y4%3!Q%3#6Me%2tHf|w7Fy9V|HOe4Q{@${Y*0TnWq@`2$%- z%%ZC))Bj?Cv4U$!^290rj6QdiGbzf7 zfVBF>F4;+6HZyLy8|g}~9pQ@{nuhm2e@D81Wl6bR7>sK{g7v;)pF(Iere$9Yt?;A_ z=lwoCS{5FdA-1C&De7L@c9bLCJ?DkNv{am)2SS@;M{K!~H(}Zq|0#i+!;xw1JEZ0F zf^HKa8{`7%$(83h3P*uR)7?L(mC-cfLUhz<3?VKuPcF)0vpgHq+84CFD>m*+4y0*9 zP5=PuGE8*_H>1s6wxp2u22zb^-e`R{85eXE5Pj~F3OjUh2a%%NAROan=ey9T0jzKl zG~(=-N2(@1AhwbfyGGx;X^NHg*d^pd5nAAEcNcouzf!Jk&nPniLK^9jitG+v!}o}1 zTy>s`1#8dU21pz}10n+?nKjY*PLvhlysp^V-q9MH2tw63KqFPud9rffu8_G)Ct;Bt z{se-g&%NS0cO8Sq?x}|m5t^<&91S$SD>~xsDjc-AOS&S@L{O?M*J#`J@dNu5f*K95 zo5`t&oLQiMTe<7#HWTX-tw5Gz z!Sao|&Oq`1xfckyv+|tixIQnkZE-uJ%MCW-iznDQ1`nIO-MpZ^crYc(0Rjuj1K-aC7 zmdI_3m{J7O(T^^vnyuuEAnS5($0X83UQXJvi=8e{aK%*b%9_2LU3949tX5>ifOLzH z5$yLB1N$+5$n6R~?si;fIGku(m*unT{?LP&X7bX$mRCi=~*z8WcW#1pI?NHt}Yh-JIU=p*q>q$l570#Sg9kpEIoyvjL z8?FGto0rlR`BNFM6nCi*LH!9UPVX}-^RDJ)>9}Y;;=-|@%cYbT6ssJcu9J$qvfHK! z&T|&tJrfLv?4_@?Spnd(d{nAh9xT;(rh1hL?lc_yxWY{zKQM40RIw1hLwEaIYi-8Xd25hugH87{uG=HR0#Dpf6ryqSG9TPT z7?jP1oE);FPo1I92X0$*9ZA>4eYlZP%@z;BlQe7GVlW`*Mpk1RVJ7-z zU%2UXrWpv9xvfy)L)UZRLQ+@ip{ZTt)pBZWM&OLE-g@StE0b}P?fnv~#d&vZDuEoT z!>=5D1#*N9FOQXJfR1)}O>{HKXkUk&VfpF`1UIgsMS~(#XuE+$&f|VOLxdls^J*+2 z2t6*;pNORaV2wE_|A@7Hiwyz%41J50u2aBXb!Wt>zf8|>*r$+~%5jj*n z*`!Asia0acvJ_wEpV6DHK6pR6DGnEvJ?7dGU>`ayi1+G#>x|ZP1@9eEsRN|xSF!1Z zz635ZkKH<(H`j`)9CWHXBZ2hlJ%El!itonDgRLGoI15Sir9;;dxapEhKz8Ngxd?5L z7WJu~1Hl5X8F6y-rCXR&ic+w_Ta`H;Svvrh09U{bT}=$cNtU5om~iL2jZ7ez#Eu&q ziOfO7Qk;$I1}EXH1{&36ELOV|P#JgOZSqotKziY?94tT&y0SS5+lN5fAep!jhJEVJ z#>_}7q6u9o+|AhV#+V1`#v-P%YL8Qwg#_eS{&>a-0W`14`c(GbP})4$(88?NP!$Tm zJ{7vsWdgRU(3I|onmMldiXJ#e>Q9(S@eB{tPv7(_*87Tq^%{$+(83~U1$BM|TquXG zbl9y?Lxr&`9h%rg(?uc^NDEanbbkvvJH!w>Fa2TH4evx}?ZZShqUBkq`+@d2v0$CS zZuZZpHIPGD7>`{hbfH6=ogVEPGJ4Ko%za-L?hJ^tlZeT?i&pxJWzm=Jyczz(yvUI@ zv)xb#JJmg=oGbp#Gp4iM>U}h!OF%}reQZ>B=FphLoKqM5-IHLsUc6sFD7rS?}42Cm^rQ&%Eij{*+^T$yZCSLAgV;fX*;NA>9I?xQhi=TCFlFmS&VR#?)Mq}kmmHqC z1#p96g72{_0tB=U-D^?6NXBEP?2@>TAK0f5G`&K@Ax~`43q|9ypyX9FjS~JY5InNN zjt6jFICc*&a4^~V!2bk0E*>2t;w@ctCV_-$!&b}>jKN26*kJAv9qkOD{}(S$@W*-N z5S#D%yTKOf5A29NU?7;)yk)HHFZaMU2J5Mz16I<964-E#J-Hlm91JpXG(m%#MRFjj zu>v@T1ZdM$hHN*-C+v2hC)z-Vuo{jVkOkyLrJJM!kr8W-aKm{q1cX)hW;}!9z)QSY z_6s$2zeU=iD%0ac%Ez_E$X8%)V5Zb>&>r~BQ)Ihdg>?1N$zCWIsF)R9>gZGlHa%ME1ZP(t$swb#31fP zY9(@igiLJjH;Rrnd`VxnCY`!!pu;kY7mK)f&&LP^J5_Il6^7i|5Cr#QZ92)V-O~)S zGxpKtMHtva?Lh}G}Ul0^W{ko212^~%o9N%1nIjOuMri&r1nng zkRy{%mXL$>*vQs7(lu4Y(NRBQWifc`4N__j53^0^;xqQHCj)*&Y%ahv!jMrMB4Y)} zQHyv+is|DA_9|f*J>94>Lq>Q{boI=P4s02Nyq3bD!_k$1(7C7~*Jr>hsc#luu zuqPlsm0mOA{e<|H^ScaR5eSW}^Nc;cls`jWdW}ZI25t`)Q^+M?geE^wJrVYmI)`)K z)_~h&liXlEv*+>PVmUc7+1s3m<4=h6XoVdEL<_*2i7Z=^I=%>clmo|}fT9tnPZ;#- zT4S#Sjs}rLLa}b9zgWuQ61;s!X zkRD%S2z79a?dvQZV8o(2HnDWuHfvwB6%47Ktw8Fy`aO(;G~OKD13BhNV@AsebF7Uw z?RjR5gS4@uREACe&bQ`0hKWEh$DG4ITRMmc#E)c_&!Hg8l9Da{&Wm{ptP0^ZI}Jy4 zrxD)6gc>qOHGp90k@b@4$c}!E1GF=P&~?`%a|Uo&0k5$~0pu_MOVPYKnHT7^agALd z$Iw8To_#NN^gF*A(W^A0TVLT)sOu0S?Dh*0cHBQetS8aouL z@=8Zgm;EmwLm$^6-;W;{_zz2p==AWn(T(-SCy^zOszwGu`m`}<`M(9sn3_j{m@Jb=!^Zxm$*Wp!T5#QJa3 zqpm1qjkp)EvnGo#j$g3|4`tdRwmaRP*6w)@HU-QapnX+k2{|5DBrG)pL>0UB6*~SM z3jtN^cBX+qD%E}E6fVYlu$(^zh)4*J321*&ig8|&qd^Q2Y(w5*(f~QSpz$EHKZGP0 z5hs6}fFCYe-W<;TZVE1^@lz+t|aCP5HZqOOR7JN7B$@F@_d%-BD0@=cCnp?@Gu2b2Sv^#*gPI2Dv)M7+`!V|03Ju~zDV(@r*j zmTon#uLHhISFYmgKK%@27k=H5D`ciKW_IH@$X=h7#xb~{U0#Vo#NHn}0Y2)h5)uHu zT_W0rMu6B0n4p%nlTi$uJKOPII-WSJ7NmhyojinDpiP4_q`?sNY$KTWfre~ z<1^NAi#I!RQf7!H8d%Zxp2z~yt|VOyVc_IuF#2K$1E(@WUFjeo#_a6F;)x%A-JuzF zODgU!k*;P0YV@y z$3VpgKAx|cg+o&hoaVG)&o)ehGq=l)et}s?(6O#p$C*{xBOgC7aNnMq#l4SXsXzmV zRDFdMkV65L#rpS|w)h@09lRnWATX!p47xOvShZZ+IVJG5(_=C=Hhs4 zMFBbH1=iUP3hRd|ImuzgtqKhwHuKPC5F=dC&5Oub4JP?sm(9ek_YWKm zcIX9d1{3xnM<4(QC~n@%O4KBa19l-B`sINqFoiY(nVYNbATc`VLCWBk^nDRh*u6A{ z?Ft*mjn?p{vCqH3J8T}t#Q>&OhAT2n$s$~@JdbmDwa!U z{3uR6^-?&kS79bPz|F~NIqHcnaaCmM`%Tz4u5*Nrxo+L(Tp4-rn|b#Q-eb252v}m} z$fU7XphTFbUYHxLGx8`OKd?_A%z;%J&wdf(29+jv4}@GYqf7`Te&7;%YdH{b32qRS zd$e^DyWX4n)vJ)NvGQZP#3II)Tf-KJm54>*uDpyBD<3nhHCR1%N7olngh}CSogb|3 zJw~K+5?E*RACAA1Se$1^apT^U%q`}?Oc`~DiAC28U^te1TU8oZFMIY|=LIoQm&Kub zTawgOKRY5Nh*w|NSwPqZcK-ZVWkt6 zA7Pnoy?3E+UOP4| zUUwko5oaOPQBfkqi;nxFD|gfNyIZY{@GD1dcsG;8jGakdv$VD2F`lMHzlJ3*dhFyQ zSI4u*;t*ot-kCtHtS8o*c4jlc>2|z;G%JASZ_Su#i7TqVVV^>_Hp2>fGjprCS_iQ4 zqGp!-%og9&P$iuuz4hhU^HwZTr618%kCb5Mk->vw^>rkIw{3|ig9Ha}!+A5)R9Z|0 zL@K*V|=nu*G-n- zlE`F*Xpu3eEYx{Pck(V!NIkovy5LZR5#w3X*yE};7$9B3$gI71noO2%3j|i|j#Enj zmV|H^2kJ=;F&H0TJYfd+CnUs@5&Js6u1gQdBX-?+;AP8}%69&~Vc@^TE12-LJ7``R zimNWdoLVwkVd2K8S2$bFcJPuZxeH;7tR>SszuvR88PSb2^X4bndp26P&L@(@EDuyV zLNm;p$_l|R1huQ2gLMt6ZG$vl;y^_;g;>z#md~?qV4HV1N!!ID^6(0uX@N{FVUA*H zAYF*PW!^fa%?Lw?&NaoHeOk4Rlp^4e3y;=`x8;Wy9^`y;4G2)xMn0cNlZH|5w6G!M zkRz}zQY>m{N|vOl=T5goMDsIpaZqtEN+44Xg|Y=iEUSkxjEK-P2(zCEtU!Oc&_srwkv~twYFpvc z;=$HLSs&})Ihqvu01Zi2TPuu?3cm@k?+PFkuGmIEYR=Rrx5C{>Pr9%Z%1E} zE#AUBq?jTMOr$6bp%8CLI?70cB>DSGvaXnViDb?7?HS1HYqS^MhOXJyei7>`8UKYR zqNSOpmIEze?54%v-arLg3T|k^6lUDDNQ5@kwr@gY*-eZ0TE;H_B~}~0#*@gL_96Wa zQ)%?pEjS~e#rjg3L>v-{tt!0Phk=wm0>O*@VR~A~lPxd6Rv0Zg>`jD~ zc=AG49ss6l_OEJ|+HF?)h1ciHO_rTbWNSv*%uuW5I31}kyx9vOoo@TI@Mf<~t+C=; zU7m!m9VxhaVkj1<^coSGMEi1CouQ6msnqYJ?x+$k=nVFwr5OVU}%1`ppW*oq8;><|x;p*Uai3bq5qKttQLgYp~Gb`15!2&d*%u2|wN?W8B2)GTVp0}_>k zTN2Moa?i^J81jtUR12EOB$-6rVyg2#ftRK(Y=WvUdC$AOtnK7&Ved$Bw+fhv%x)Ia z$2*T?)3vdnN2*KeG|d2}g0!(%{gRii$1H5|DJmGI(mrL$R9D#*Hhq)<5Rb?*g>mQC z48?Asxh=EQ4ChtS^!~T4KtXstM}kXVQ)DJi)PU`mNaM7zY^KmrDk}R@7q_G!-Oqcc&nTIHZxh#Vbh#E*p7;%}(V5 zXN$p=W!L08o~5`97RXD#>~HsLLoE|expG=&5Esa7y>6stn@e=Ok$S_!=?cdUm%|fb z5Hu_ z+A~^~Zohfo@J`s1Jm@T2F^xd-em5F+`>y)-^^)(WdQ9Ses)sU4R+iB>tMq)_e-p@Jrgpr$=y-Q8%h>L{jxEkM3V zL0iS5D3v@#B9=so`4==%gnq*0;^Tu{i}z@NnQ5oED*EFq@X0^L4p(=hr(zc2$Z7L9oG4$iasL^DL1XUW-y zg0_ZPCaA>+5L?hT9ohO&YRL;EA}bG`7Fi0 z3R)o2R*o}4M3^=omrc|Z5quI{(W)%th^`Vjn~8#eAiBm|J#k5>-Pp|IiA)pJ5kM0) ztL}jaRo1-Z!vk}oIa5pHHHFkZ%kPn=i8?^jWm6vN&S}dkPChk6qz~KQLVA*s*?l0j zWOg7BV~+r;GS~KK*-+8OglEug=cUUdotHH+;5hwaUf)^o6&Xa9EPGqQ=$@F0=%V{u zLp<@~^sX!&Pg!ZAeaSP>rV$iK=#@pq*k9hvXRGk~JMie2KL3MO=-oX~kiGB2$yNhUYg7+&7hy z+xc=IjzY?KaI^qj7pFY0;3Hm@KqO{1m08(wdkT@^k`I~qK$gB0^Oz#2{Sx`}=H#l? z%T!KoTwa5i6o=jcPMNESul7K!G#%w)`$c7;TOeCHvb^52pNcB$*l%I8Mfs^AbQ$F& z5=vn4svTZDJT(W<{^KnKn8_ZLGQp#(%C75As{kEBf8Ph4apaxQ@(D6eG?D|X!Pihy zI$s-UDU-MI)!@t7kQC9zyq2OBH3BR^R(VTjmAsXvyX_T-cty=5Oqa{ow(?W2MO{%X zw%IHK#c*tcXI_w^A)9HpO9=L*uHB?tUX$4En+wNgixyYjDtzNLOeE5QQc_zy2Nj1X5IdGGaVH zirgCIJ_=haZoYalxK3m`5ZsKgu>`GY>0%%-Lw1~=D{Q1FLsPlgQdk$y{ZmYcNOSaL zUt~mOL=mz=_30pdVJk&RCp*(XT7DP9Xq?z3_smCVlbB^3JFW?&k9T=d)J~GF{LX>w z{LT|4D{(f$&PA8RB3nw;=R}sAS^Ev>h?ry*IY3sjXyy8509Jl?FiVyLWj$AT_vc&q zr(~tSK%;#JVoB;?K+(1LG;vKSB`JEBLY@HOnrGK36tqVi)(F|Za{enh-$Miej9u>x z&_=OI)=RdQq9U%iMSwt+k7fH6Jrf06_IKiSCJ(&M6~c%VIdI)gZt%? zLT?^oG6<)*8tWRB=$dHz!X_k;tyrS9KKdw5`4%eZA+kj{%32k)P0Y&fPAB@lW1m8t zOSZ}cA~U281Gi*LU6qIo6(QM|MQ_E_Tx_LftuyF9XroS<7&&4kXs$@}(C=WJ7;>n4 zYbrZNsPw7^GPMz^W+-T^*rgDp;R`w|x^BZJ2oQNFHXzYPF-gf;P8J7(cT`3fH(zAJ z)pUWY9ZdhZ1+tZ)QZLlPc8u0(vXj}5QMr|%oi@Uhi1Cf6SE=!u=`gP~chP}FN>`ak zK!$y@c<+jkk*#fXUSxgl4VSSOqhs<4PXQScoI$s}geBpq9}w$3M=H^5u__d1jf&oi zF1?EF!*w1UvIFb@MviE!Lqugbh1H(kt6?`{gb@tHfw|-wm+#o8 zkfr2du-*{y+>$9GU51PGH;}1dn9UuuR%D=SM;;4E_qNLvL~q5;8f@D(Xr$-}afr&X zweUC9g+_`^a_}N7J)ZOaX!05qI{zlQS;8U;lA8{4#1$q5eH0z6vzrCPg%q)Wvqexl z$Z2*tS+o$W%N`mG;GL6j|tKdA}6*U`N9ih{MCptGtSQ?YLE~ln5cmO~13 zJ>u|X$vk|;t++}j{! zXm@Rd1F7tqnBPs&vgN75OZISF03IB>o#DLEYamWaWpBe~e1o2KHS>Lezv_tgFM36a9*sDGub07c0Z#Cs-W*7qu}Lk zXHno{=SwDtLtE{6?kLe#EuI(}eGi8g!{UXV5Wgf&(fDu-TP^;0m%@l8{P=-=3K0uC zxdgzq@g-(D<2;ak6Lv$CTW$9a%@4a$Zz~3^SO#m(W*}X*wBxCKD1a0 z0;`N=ylUDDdLK6ZDwdE@uO1dt)fLpQGgigT5gC6Uex^yVMuj1ftt7W2B5s!m!Rl-Y zdm-j`g@$H`L(zX-AV?&N1wA@@wO3Eq>bzDBiwTG;SSC2bv5r1vKW#=Q?;H7Ee8zhkL5 zob60^_eKlr+j$7IK1@<+wky!+kVa_~?h{!miw|xb3RO9%kMkKWYIcGOh|RkY9mA=w z5pFoni)1BQ%?#+-@_4Ji0w6IO5_{%2D-^6b9mc5P6!GAkLni(XuHSjQrDJq1g+B_Z zHJdX1{b_EQ@=X!%vk0GxVzA;OfZFWt_z@jDTk|f|R9FMA_kvH=^v?QPhppnteTCFY z5nOVti{%(D8~2-6k{RS4Gez}%4~5t-vXynRd0OMt;_#teB64JGyvskQ3bg(O8_Rf> zMawTpnFQ~y9@S#8!lWlvzFPLJ8D|+{C6*Ijkv9MMfr01n(k|)eRp#MSB6lrR_RC;{ zMxfE4MRb@3te_A}yz5 zx3Y7*TU${KAYS;*TY%qeXi6U0OLkwKkfz^hj^0c4*6k|S?Q^m{mcFS)4tGiK;c5zT zjYCT=tGsSF`yxtV%s|SG&d9U{Qe76RxdZ9reVyGZkyeC1)xxba2k^YL%cMsDOE$jO zy~R1lYr!-%Y^3wNN+4vd%YMyAAKCiJGgn==D_xoDm3cM%<;|e-+`cM+$d)K`FqLf+ z+q;v;CW-Q0?WChgV%O@e7vgey8wfyLk!%`ZBSqzX?t5xTGplVN%X-@jdMxdsgD9Rv zcF?Rv2`Z4O7u(cDOT?;VsL2202lfesm&B66yvTWmebVD=QPkF7Jki`UrdWAsUgqw(%80>rx8cK`x0vn^d&1H?oK ztEcPhHh7&u!7~n{yZ)4j$PO0aQU!x;fUT9q)Lojfbq5y_X(<%zcwV0A)&&qL?iMdw zl^tAn@ilE~0=g%^K*kNt(?Q^^x@j)5#0+8pZE~|5OWwLSB;T3=TKIa6i!dPcl3rsz zK?q=Jxy*sAAuGJO!I4=AJzSvzM0Bwg7vWtFJO+apK;J6nkgj7?00f!hW|*p;UL>!o zM^shLrJy|y1Z)pPf{`x&){3gspt8=)lrjypwY~xnZIm2cUs5FEHO-oI0+Wj~r;%oI zTLBD`ZG>Da`+I44lJ*}zuumd;X)PpS5h;MtLS!`~C@5fAcoDLhd3kYP&APt_h)Pfp zJb=edGG(r;vOukVLm($HdHH2Et2~`EOW6pDIZ0sJ8w3P@t+vuq4D_^d$uYB14<5vuqF$oe9w5L=K`T(NaUehW8Tt6J1OiS<~1kM22p z3G!N$$HiWlM-YGLo+)J@;}5u0=$>W((se%y1Eu(T=Kf9=xR4Yw8dT7QD40l67vEP^ zXKhVpuO%t)y@YTgOVjV~6*ujs@z~dbesgs3PbNGfXigfn_lwD3P^) zUN6+#S!Y-nR9)0cS}uBKvDO;TR6iq8$Gu5`42vc?d=+JQ!=hksBg<0Ik_aVtZN3W! z^s23*REhG6>zR`lND02mBE0&(WGuq7HlnYCa7SJe+*CCHV2ja!ntDy81*+{TMz$zU znF~ZaibbBXtU#JYo`pRkA{Ke78(~Cbhq#Sjp90DNQ z8cTO`)ux-{h>$WW>+(WH@Z+q@lkyQCbzK~TiR%y~5O~2l30++J6gFJZulCh6Dr2cA-fOm7oGAQ`eG(bAAx&~!*+Vf{QmQV1b|Q8HPlwo49iyWCgAE8uE^3wxy*NppUz~+?MJF_8f8xWLaX# zz^4a4zr0xfCAGR3iCweA0ID|l_$ggiDj(NPFvo{ibX31<<%dqRgKemV{R+z_GClpnEbI z&LPK+kd17IpatB1M%VL@bVLPvc>>{!>4E|)G7U#`M#`4;f<(Ioh**ymdHYStvpC&y zS<#ZlKE(Eln`H8>!+(GI-_*jk8fEn}jxpAkXELLk{I%wl9m3EldH_0&`U*5OUg+GvAk9OL z`!yR25G}W}-qWoS;)x4Ca%uFcUve9WOft8KY^7g0DaWd@k-~l_0+uPZHw_PDruinQ+HrQ4Z<>@1)QZwm zFSi9qnAi#d;R?)DWxOXZ*OqV32G_&L64S^RY^ZGvdr&}ri9|70Rc+)e9?)vNKD$bI zfFRDpnNvdmnYQ&LWPq&wWdTvgXzAsxLLH;UZy*uESV1RnQnpq{IVd3Z>w^I6eAWV0k@3G)Y?v91L-xt87V-v4PPC?z|E-C2s!TGXiX(}FY>|_TFY*g zX4Q1)3#_cO(ybK-0EVvc{rCo^&--Xj97 zt6I4^fFvaRb}Nalqtq?MwVSQC>y=x?b;m4j>`7Rw^`eGm0=1b!npDTaZ`1(XcEif z!Yq5hiYfzHtG zvhNTWsQ`&m0a7AKTj;!sP;<*pGDlBy=fPrX=4U*o?|CU?O*n6fE4I6Y=-x!F>tUps zJ9#718cmVNzNOpV1XVv0%^$`iPh0K}dkF~(rbWCr5rcnh3rQaPb_cPqYFOo5XnATK zA0Jr_LED+WsloD_LR^IB1#-gJ`bWd={B;j_zlh0ymy!OBy|&$1*92935JQp@$V!8;I~UG2H4m5GkT*`*%F!GUbxTK*E%Zu^n_EZRq!E z#G6V4739G0>}kYTkES z1+yNF-DBArtXbn;NrM0xD=v74C11qme1u#&P-kEZ!m^iWZLrdZnM``+A!^fapV zP^XlfR31zqZ6BIjWo`D?2c9c8m3chMx%xwv{!mKkTVtT&QTm|thr#?&A+p4PB&oxpp(2xHVoHwx{RjIY0wb~O5;y&9JJ6;*J6P!Alf*@xsb)LSKUxxt zH?DzVPbGYDH4s+f0^>gj5J|;|TOcB9tqw-(7WK>NM?k_iCe==uhBR<>3}f6PE9LkNgOUN~u%O0!^6wlvC~6(=po^agTM z3uqAxW|+1Q4KZAs;vLKx-5C=lSF{c#opKZTk$!!5IhLc3%jU{;8hu`gCpH&|47E?B zKQ_jM9%7Dn;pyDI>tbb(oU~y)axpnn3GD7!A7&&X|w6+$*YP zxt5oVdLZ=YuPrvFVzCr4G&sksmYm`LP&Kib5Ya6LgS9x?hn0dlit*lM(gWEmfg`R9 zX1Hn|EJ5b@FLGRacutenp$LI&lT2P-h`^XNc_VVx@1C98QNBz$l3vID+*l~>{X{)& zBg0mn?4#jg!bCJ#On8+$DvJpC>-{Jn1=aOyYby0&s8fV|^lc}4-U?aaEdk9pvWFwfR{U-Na!O+v5%%la(dCo;Ny zeHzDIdW)&Iik~P(4MY~%^f}s>HFo8v$S5EQ`&kq+^>%;kz#{^OgIu?fgv@Flxe+rX z+aCLL%Fj64)O9X^0fKYcRuSz@1*zt{)7Ge z&vc;TEf1#21uYDJ>~urc9*}KUU)0(|$!;E2O_UZco3Tc5Nh zN{+|YQhElE_}b!*fgJZ*=gepAj@G^3HLe>GWZu}Ev>1?ZzRKj8$S<>Vs{_42x-C70 z(^2+4y;L?OOT&9MGc@}~zGQ^}IcA)_ZtA%-u&f!Bk55k((g30~<*1s8e6rYadRMEa zeUn%YB+hn_b|aM%DHEw;A+y&o5@%cH{NI1D*Y3j=#ASTgf3r=e4kUyJBp$fz+S%4s z0ivXUB>Pn{cOVJ#>2~>v95c%_sZ}7N8kV!^W;-5_Tqp)4!cv~{L`Io|WV)Ul$n@LA zvP{Hg?568_B_P}UjmW~;>x~AAvH%i#({iRa)4W!Y0M`8UO<#-H5;aK*Kt}n@lLm5Q ze}2`pv6-;O?Ca*bD&q!7_|2{#9j98Ebp*itf@@Cz33u&|kLMcI;%erQm-;40fOuV4 z29Gcexk6>KMz>Rh$koizY^B{5KiW+`>PGsTwABY9fvoq>`5faq4@#SOS&Hur*bxMt z8Q(4$F?c?Qqopk{*3I)>e$~3>s09n|rZ7LO@E{Nc`keVY;gxJTH{zs#bVtN2)uv8| zbIMnKwdZHT^_*2C?H!%J|6o5vlFsZAo9*^pjKoB0*!VONfedFuiKv=01Vk>{n)6LJ zSgxT?eDaSZ`{ufNywcEf?#sa{D*{OEPUW7yS9rT<;Sb>g39S zjVt01RWbLGSFM|FYRhS@D;VV!%(X5xDLWI0-2@AVb>4{qJxBsz-bX&OeNEB1pQ{2y z=TBV#@L`c5Q7k!DJ;=8Gsx-fe5K8%6>^}J|g?)@9mn;qUo73T)<~t81--?k-z{>L6 zIj@nbc|gP>FLSALtNsm_jg-dTSCD(@Y@gS-G|R-nY0Eq>+LQAdiQCTeT&hy4_wPU0 z50RME@}lM`*Q~S=dEVrL)!3=OsO5=3iWP}6Y=9`y>KgP&7Te=fMd=cccjn1FNs0)^ zG<_79!>T#O@k?7_-V#3K973;cK3VeLE>?0c`hyQ>mUbSptEl69m11pMFArO9Z-5wtxOc}08M_CU~ zV6-e%{7pi&=fV^|!8)$E9tCxQD1^Cetuph0)3=JQK|!!zE)ft?sw06V)CQn4UJRxV3k#g6;VsdFF{Pb+D@ ztN1L%%9RVN_?!f9`zc2F%?KcN{Yn{f2r^2ytg2HH@R+y%=BWr=x}bhmop?YbO9llH z$bH15rhlblrikY#Hum=)?B|8(`W7PGra-{x4yLgYm^|=@$buRI0xn?G1WK0wHQMsU zW2-7d8Z5UY%R-J6KCvf@5eT*!5XHh4;tmbJO6tpMI)(t!QQRjG$VVVDVpmha#WAzF zR@12iP;Wf|T3IR0xSEa_4BmY=jDRBo*CXp?;byl9q}gCyO$Q1Fg1a*ath{kjl6fJy z>9s}Yv$J@boEEy(Oaoe7cj3;Gz!DHpi|`6{t^^1q7@SMpbhmhQ+v^!@Kg!0{WZ)G#TBp*i&maQ&%1cLqokpc$-#Ykl9Tcnj~WJz3f<@nE;5r$>_ z`h+=CFnXaF$7^WkEe;9Q>mJ{+i-z+b8GB&PXA$kALdYUQU z#T(ehpLGvN0l`Zbt4eKczF*jD^9>o85L*@oQ%Q5{o{d~n+4~SK3Sa<%qXa zDR6+u&|H(*``pX<8_D|+0E*Quknb-$0fK`D&YH^9$7b@lPi5+3@5tv~Q&t}qz2f9R z;B_um8$U)sJZ576IV1tOd?hZXXi6+rd3kHeqg)7YY225N1TUQG(f2G}`i|wPCX+t9BnrOm=cY;zd_#erv)1_T6h0f-V57xH&r(qQ3gEi#WlusVUr zK>~t7hFPlRw&g9ZGa}BAuk%{2>*TgdAP`YNbd!r-@dBJJkH3-XvQDBIix+~Um7L53 z0-gehCwPk^+OTo_Zh3$kHy(7w{C;Dv&Bv>ADt~9oz&d$9xioGarP=Q%r6d<`)@W=; zZUDY?mpgn%s$w$&(v5(11Y*_Wt2aLp6@J^L`-_1fqkfn6@eGIyARaP0v}+2b0D*V1nHN5YRBotUledit0qIPH1|twGqTO;;J}2ZQxPd4e0SIh~ z&APv8M>hZik%PM(5!fxP?0!^FZui^)z8~e!@1Faf_oMvz-9ymrNBQ%+=XMQDWqUm` zlB9wa!A|sCmjl7^cNuxu6~E5f0y8-RB>Gz=7P*1e6e1j}Uu%#i`p> z<(c+MI2el!9?iy;hx{TeNcbWfLUU{*h)ZnNCE}=7_c`~AwLlN6#Q|s{r}r&Nx{-bJ5;Uk7FMl5h zoQ#9xIW&QQfF$FqG&xOyXZ&iqoyIc^=eY|N`{mW)b19zPI*lQetM@`}xxhwd7c5UW>3P_Z{`%rTl(}a zYPmU=U(jpkbuo=7b>8$fn*tma(`6NGFxUfqSSAaBU}TACVMEka{3`d&K}1310nw=# zAd~OT)wVz&oq@=Mff$20L)~&w3PA8LB2B;QGzdNsDIHWLS26++@P4P~fCdn(4;DAq zOblJL55(g>mGdxj8&bUx#WiWo|T$FGLFu2guGAos7P zE}~|ca?LTU%a;^Fp>SE#KoB}Wd2#VHK%hGLcKt|Y_s)ELm>&oP$rSu9 z^XfSKs@oRaleI8Wms^zLp1Q~gm9gc&K{deAIP=^uUgV+pOi?qNGWz(~u@HXo+z}{K ziRt{6v?C5OzhpG(OnY>eQr1}+Tk>}?WgSJXWpG32!*^jJY}%pFIh27bK{#rm*M3Kl zYvp?Yp$x=*Ui8GEVAxTUvp|%y4n(n`y_B?$s?xe?^0jKYAW$#b`Vy%&_`)5B2?_?9 z6Ufnt+F#HQ0Sq|Wu?AhrzCbN#5nDh&oTI9RxHN zUDAT}q%}5MMUT!-Vm1)iLn!+!YJ6|q35#0MO8f>v2Ap?y%k*7;GgX>lf7-^lqQL-$#Mw!g|l!2n?)(n$X%CaK^^c%OwO*?z>}bQ~?@@!pdx? z2f_YhJJQidE|OY)0q1$rtER+XAlPg~DD2K74uC(R;s&zWEu@#r-u#XIyb$HN^MfcD zfQ)<)SLu1=Yq4YO28<$Xl^4?eCv4`z`qXM>Zxp%1pp}mFZk$Qa2U=?0X14iCq|Q@RiRk(gXvJ z!f~As1g6%3I4ji%bq7SV)L7>TJYZdj0#n5h*^t4>mBO9q`Pho4LB2?7zxXBd7tRTr{yp=kY8 z)juVo4N~Rs^H-Egr*6wT-3%^dS3h&~J%?d_t}nVjuuY4^5-TAHfsG{j5d^wN?;=p% z0rxqYi+bf-X{> zKBC>%GzHwSn$e~Vc1o0|8-dwNS)s*@Ljn4lDJ254HxkdECze2hNeyqVd`c z7H<%8(oM}V5^0VZt}5hs`jk>#%U5n(^y&n%8RM?=*UwU`Jr+PrLK27yy9 zl{Sr7$<_b#=1wb3JIw$@r1!NtD*8E}-?C``5GV>S{Kj58Z^+)J zAt7lxl;ZxOJqL?c3E*}ZN^a#B(_4k7F`n2X(+EVT^plXnd`CWWk;&P_U5Nw~PT3qXi!TDGUEqRwv5h7-QX#5;b z0|0vUsJ=3Q8YNP_PH>*}D`5(R+pw>jv)*#5HW9N^iT~xD4oK1SW>e<6~qm zuOm7n$7K*c_BXO@x-|^lAs|;bOtsS^GMiQK7IDUQ^f|l=`s?qO-7*ze_>H}`9qgoG z2`+i<0)Kp!#uJ%1ky=lL0wOTbEEDMs{hR z2ImpYpkEQF5r50$<*Mm#33*s7jUTM_c$CJ@M#x^Aqcrvxa=fzOa%{J93`~lo`WR3a zI{^vaqbznJEzej1Zc$cT@s-Uqi+Fp4L`FAKD5UU=0d@LVj2)G+eLd0Big*bkoM7!) zJ~JdBi8Ld$*5$+cYy6|vZdNO+2cV{{QUek?TR-VWcvrN3RD;mkh7_4DmodU^ zSC6{Qt)mYHF&v}?SwW~*VPXnEd1rQM`!`45hZCGT2sdwgv{|*4mRf1*H$1t@XYwbd zMm>2kmj?znfBtv;^-FCQ7CCw$`?d*&3ds7;*OdLneuU7x_;^*9qg{`T%-CV9!4}+uttWyk^5U)K!Y`R0FPeLc#<;K7uOnuUVdHqQDtdoevR8j zo{#7I*+D40Ga5wbCGg%>Ax&QlTikE&|Iq_LrhN}W0SQFCs;sKZ(ODY7Iwk(9tPV}I zUv=D!msYFU9hDWc_^g+4-Rf3dit}o6t6$!NP*+s@2>O>7*H+8O4Km_)wIYh6J@P;F z9pyLT&FV2_HiKTCM<|trXe?THCwfM((MV;(UIhqmXpkR2f^e)i)ebT}>F;N@C%yV} z=o0c(j}eeO>UjQk5Bz2vF7_IA4|?&QUlP1TnrGaC3;~Yfb^>fqc=eB1GfSJO2C1HL zXHfsfu=$Y2;SZ|*pboLdPV^n*_T0}P>0F2fN~b%jEqf6?+(~IJ{$hOe&rbaZQ{qY(jfNE{tc`FG0L`qSs~L#VB|i|H(?|?<=TlORY56uH&2ZZI50~@E-%>+vVoQ*r z(GrBl1COZ)LHJX>9y^ExMVDh)9%L;Yy|}BBlOwB^XAp`ze9L`?o2(5HpD(0prdrP| z%qEwx*%=|SjaVeku9<2x+I9|!yVf!^FQohJ{UXzEPcNo=+PWAuB7D`l%`6GPb~WBK zGw{(ZWD2_z{?(DV!#!v#2*urNCwnT^qpjCw*2yXocg@9)+Z4<>}^NfE?ONF6aH$1Vy1sJf{?OrJ0cl*QbUNB6e`%FlCs$>8qb z&I=h5OxQ*NXbkmeu<}fI>k$Y3LY4$BuSN;tg);r4E%Dl$B|&-2GxPwNKxV&TyJY58P?LiF-}f#n6~SJh$}Gb~+8t)9N=eO_v_EOj`H$npqEzyUel z0FSrdFYE_M|Ic!#yPk+4q+f5Vx!LW3FY2Ej719n01j8bD^oTkW9CMfcFvATy#~eTJr}T1WX+wIrSPf`DWhOBDf;6k6Gx zlEm8f0h-mcw`=dV`ljv4(ue%}?!d_lp;^mrSrBw{6g|dJ!2z0Y1<|)VamA#DMJwwf zT-M`CDkODTzAd#g9*a^ttbhN(euQXY;8Gp^&dkLq8K6-tUyt1eAjgQ64>Fg{HXecO@o5&6(Jj5qUA_?0WW4Ap$TH%|80Iqiyl-FX)+kW`NCrd8=(5DHJab?-eIu&h8fYSG);p5r7%N^-s)58^jk_ZdvA~bJD&rqx)oib`> zW>rbwQKJlS$*d=@1=xAFfG$Zpu1Z-ZKSoSL#TrM8;e$lvKVbq4G%wF#j`J6WeTU=E zQ)8v!THQs>GQkiONs_7$=|o#^CvnDCqCW`sgc@)(0-RlCekHU#}mu@47q6U4j@#MeYk@x3%eHJ zc+L7Zrbn>7{m8bZ%K(Fsl`pPAP7t?q-0f;bSsycYqj;+Vp`|+>ul@R%F2T{n5@e1K zIZ>Z#^UqiA{QU>}5kdx~C%RDK6nTwG_|~U;9XFc|Kq8c;-!{A%@1N>tT!qRj--SFY zNVBl$HOTgS$}X$C1j9XFL8@1hgk62ij$i~m7RPec`EM`#{qYPx`4#dvY_S+9w@;c- zAeOZG^F$nKV37Id;S^s{k-VWt;l!!M1C_pLyTjn2Jqa9?KdhqrHfojIq0;U~_CGau? z`eT;pu~MwPTyk>;m~jn9kZr^pO=F}!oFM&+@Bt$8{z=b!v+NBm2}J%+$qMM=QyOcr z8{kl2GW~(WK3sTIAQ}p@d_<1h$p=mkMUO=3>k_?|I-n!V*Al?i@VhLl`jI?l%3YAS z<1(r12tL@VVp}+_d3JwW%4 zk%bOq+Xy&D#+#JV>VvoC^=La4nQ39_y6z0J;Jp?r-)q|=3lS3AdC4KE!OVjd>u*$IL8#Mn61VySpHoMvG=>~f<> zdxDJK&q$}Uu=NL@Ztcz=IGKLDnts%@LDja3KSiHpeSE0(LMzuv5yiU6}LH*uly+=2q^ z`P+uhJ^`i|i43}??A6baV0mHB-9>tgUyVem(iJWKjFQxQwTec$_Tm=}BVBUyWkKp= z%g{WvZGVUL*=^Q7e$UkRHlMa25|b}ISk{Qe>!_9FocOpKk?9q%YmkHrt9yBFs8A~( zMcbQATQ9cyI2GgkcY$Ry%nP7C7A`)PP*9=0d9jrfWEc?xkLv5OTUUVU6){hcggZS` zh(>uuNQJN*d(uE!km|^4twB8O%a5!Z0PO*eEy>5ocKXoD=b1ja;aSvTcT~{xf;=Yy z{*-271U|$Hvi&V0Pg-+kNsGo~q4m7UziO6r&uzImPFQkO;WvhD*Sb8F9>WAk?9se` zIP2mQN$gPL*OXe)6NhNcsU$be0Z4?&bStJtKHhz?tDVM6_?Kkn7t z(&}G%ds{%71(%Hc)=il7nJofAV=?cBn^>WnZUQ7>LT_s6jZfj*lS|_Kdm^&9v>^L5 zMUZ?`AlrQ^Zq^R4*BWmPvo02}Z+e9Vao^Xx7Nd{y=}}v9y-+?qfzT2l5kGzED2{_Y z5xQd2rO{82&>&VOquPx~z_(?=_)|tGkItkOM ziF9;B)dqI>@;03>(vGb>AkhnHCix=G_8Kdzd;ZnYnRJnUA9?4Cxa)Ixc$`wgy6PUC z5nz7rQru7ApX>l`)dF@VeWXR+Pt$ho+#emw8CU%+D6_s|O6coW`LBFwA6`jgty_a6 zi!DgIc9vhYn)}quQvgXmf|WBa&vk0vxyadH8)}U!J~cKg2_-Fm#&J)pVK%NHTFEb| z_j{9HQnLS7vPtd=UEw;eCAQ8Lr(O}bZ_M(`+HpT7bz*S>*_Cz6e7g*MQS% zJLWHL$`~uPOSt6En^}7wNcx)9;BhjEm`@_-8rm6$BYBjZR90no%B=VcAl-gV zda!~cK#q6EFyaF)kzxRp1|7nT_0`?5{CM1iUW`<~YFdIm_fxE~_k8K((I#Fz4BQ(8Uz$!w$0iZW+xi)#jdiNQ;*i zj!Cp2N&w%sIZ<$ZI_LQK?WW6M0Gm_!h5ZQWpHCIshJ3uVkKZ=0y(U@%NQ;*AuX5yN zdZVG7ddb?pNYi}f&*4GNV4N#iy>`mEoUv9m3a)30dw}_s){YA7*G^qQZd5>Pr`D@J z-pKJN=T$xva}yGQBu*d|!m8}?5ZunVGBSUA6G;kmorK{}JTN%@VPRZbknUEz*z0;r z69MNcf*L@~!^*;LCK}qdA^@`dx#BBOT|GXnH%Kdz9W9n#Z%X&L&M8W%KcBH009RB5 zm=Q^SQNIc>ul7-wn>Ys~G@Ql?8_>LiC%4UaF7pX;ydv_eWx})B66noL1aBw^vf_7M zB;mQoy*f8M_eOROKd2K}hhGtt-k)ot6%#7IFl@XYJ|ZV+diSB28z1S(q3wR4oAQe% z)w|EXTpz7>pMSZ&RTuU6)+i{gp1*4VPlLy}uPf%OA2C1COa6?}=}GA4(kqsA{oG)a ztOrzHFJ^*e@bqCW;x3!v^Du8wGs<<_m!GLOYuO_{+O;x0a--d}<+Flp2YS0-J}f4Z zssp5Z@I+4mi7~zWJ?1NNfC2Zc$H>eFE=$McrvOQqtp!*X*UN9(?s@!DRA+DYX}mMX zxratBu*%n)kTVxWx`I?A9gax-+wUdy6N*V_ap?6h$RokdcJ9C z01-L14_3LSfNUQu=X+d(AGhQur`z3HVK743vp#$MM!H>Or{VypS;-|x&nVw#!g6SI z*0|?JY@MvI8lOn=??sxT(0V#~_25(b?_t+wRtG$!V~yvd5dcEw}rPX`Pm5YR|_6P6F^jdXpvl%VfS3n}@Es)Q1g{gaWo*P87;c-G;Bo!7&%lVTP zWccl#nv=6GHA?v8tjit2V_qU57XX*Q)>s@f741Z(;0gotTeW!mePh^uXTEc^HDc#| z+QowUh^=VnzHGZ+Jxk@h&%flG_xn_jpE)-)sHKZy>g9{nW_k4_rPLtz0E~ZS2BZ5n zn}YJ{p=tUK5}M|mAkzy~DwE~a6Q%OI`hRA}B;Em-rjrUq*^1<147dAUglTtL%(VM8 z(?m_qWw4gI2f6r}H;1tTRC_Od2Fc;V?$2>@h7KYa$>Bo3s^rj2m~NI^_l9&QN=amJ zv;Zqi{0x%m_r#jpNg_u3Ku+X?M!j4L!@Vl+M2uB}^hmuHWPWLMlw|LD zx!ZY@6COc?dA!>D2{J7Qk2~>RxYOY5+r=ixX;Ay^P;RdGvnF%`w#XbB!`Ml zem1Q~wQokPHxMA^7nR$eXzU#%V%VKW?8ja8La1Nv3#zu4^VO?5Y_>O>2BZ4eOxsRe zVP*F(vIfZMpZW&{Sh6K9uySbE4exg^FA}ojF><7M+s-m*&s9INDp~D4O!R#wyZT&Y z8<7-7{r9XU%~dlY(sOG9kOb+xM_LGxq%;9p<_;`CTEE-cd#&XxP00k~uD6`G)tI(< z4<+VZ$@I9x)20QQoorOFNpjit=WH8@;XFt4;hJlO1G)KT0*>wdb-(!B4f7422q%XND!7a5)TAf5s2uj6Vc5kI|dWm>Uld^{}ws$T`3myiDv zhjPm1H}oUm8kHr#O0>@_xzDT8pB7|!bUf#MU8~Y_)z^*xd1|^Z8^MJ5S3ZC9(XVr9 zcrV<3OiP@sxba*P!oM2jx=h{xqgcjWNi^PB9jyfkF>m#V9J-_e`kDTYV$L9;;uUd5 z-S}%oo*)*U>gSkOPR|}BM10y^*F*9sk9GYaE2Ob+KP{EVzLML5a_oDUy!uz?*PoZU zwTzk1n})AJR@fpV<+9P1L$ijB-ue4m_#z5n;PR+JwJk{d#xZyI~!R=xaW%@HRO^gd+1Yv~t#V zu!s(jyHs{D>zRl$kY+?5xP2t2ZW9Qo7xwsO9WRU>-X_PDfJ|QzA? zP>ZZq=4-CBiMEg6)T=VK&*0Q~n=wm+?0Nw{aZ`&kMSE&h*gK++5!AGqOd zyFsQA13qt4R`%X;5=l)s4wch%GvB@qo02Ix;L7Up0&E2ypSCG8+Tr+il9KFqAj7xi zc_fZc+mx$=j|rHP(*!6VUwrSUt%ftj-Ip9S1~Sylj@J8vu=!5zE{$+F`@h^OyDy@P z`En$8oTHvU3G0mGGdWK}Q}cQLt>me<9TZLBrSmE+L}XMUZU;95^Qul&4k=UDp7Or?Ji_~PaJ%8NFS30D zzI5a)AeFhhxcyVLCWuVd zPFVgCDnhYJL*}9K01PfCb!Gue&>PVjW(j)S;ay#NrLesGA70Zcsfz0IsQEEdT8Bs% zqI%s0wd8TRDQZK>i`;A72M9N!W%?TVqv7()(athh|7bAU*2fuvBHRCEep=ikLn>rP>}`J zWB0Fk=mpQHE+G+g3$X?-!p0LVxPAG^%m;#t+L8F>U81TlEO_EMMhpq`dQK>0Ph(G^hO`vwSMCSpM!<$Im2w4o=)?SS0kRYoBSr!Z)C&7L4s`*h+ z-5q!Cg4yxd3?3dqEhLqkij;HY`=WcO8~Ouy0hTB%1cG) zP3D%cYD4!ka0<@z{=Uh49w0^D7wWdZHWVsNREwg?^B}A=;rW}q2>xBMtDtT>%7vYI zSJ$KsyLl0J)on#b_sp1Jxmi@uI%6B1hU=pi)PO}%wwVi2Q6?6>Linv*1ohuA(-!WV?(XK*7aGCM z@CR!ay3)x|ZIyK)OnCdbm)ReX63ToMr&$sOqO|1Jo483WI>x z%%EB@DvTm?>+v(ZOM#^;yW8POjLl2)R}j>iq;JrL(2d?tapARs!t5wcdsN!l$ZIIq zTY$1ud(kuQXra@LI;gr?pU7)xqt2;k7|0T$JLk(%(I3<>wVB2W$FFz!B6K6DB)n5* zlL%_a?qsW>Qaj4>?mIO=x{&ht0~v!`D9b)Cf|9$bM^;cvd8l}<0+xO4KU$tQXQbC`@c!i|XxSnc5h(|_^42UdahI%$kOE=JgU z5EKb!3c3-klU^dJQK0&@br&NDGsx>xTz8!Seb?1f?~w?~5w~$ixbeyp{D(#7(&;UH zgDo)Dxn@P|)%~NzlG(Q6mQvjoGT*$AbdU@qXd?;8YnE5tt}9vip_S#jRb035L;qlE z>{$SqhXuSu=EjcaxY~UwLApwXTlXxTCC92%MT>&rXMyq5T_y6eT)6#Y z7XV>_@mveM!0Dsmas`zx(ps$4HG^PtAbRP+>bwO4GR=k_*T$>i=e_AWX*3|}`rm)B zA0g;GerMUB1KyONUZUeso%S4q0kb|ABQ7!9H+UVX~r~e?xMM?Rpgqx~VWb zR0x?!Q#1GTczglR*v?~}dDOix_f?bWY?CK_TabGAOm@{IXEVXSiZlZ9>M_hTd#>6zD%AyfT zG_zb(v%q|Un5oxeg0WPD#H2ht7%*wP`d3WcAi?GdJGcZD@6KjJC3ynoFBXfZ`~j1f zRfEC9S>Gzm<=Khvf547}FkEGd>$P!S%2r(7)t1TzDjpacch zh_C$B@sBDc5tM}dR3MNAtg(2JDa4KN4Du{VA42hW2&VEx+yX(DSfZo~p_9sQSu4m( zAc0$6k3WWSX)?*O!+<~pKP$%LRy7s;>h_X}=_KOI2?Ei8JDImzX2L%RbMImx5NF`Q z#!5KSgEGqv8k(ewA#5(wdd2$qxuXv=eN|BKcr2gl7 zJ%G$k#PW?r<|{wOa$&Q;3c_JFyih*=^#rce%V;vK4v1HpO0Y1FCH)GI?j;h(UM{Lh zQtj=bN z7m5m&Bg|c@UxoaBG-Is?pz(>8j{z_G2cdfhbGAwqATDpIx^=V&i0q2L|6o5tUYiRU z2xj57vVV{|VDDxt>k#P$DpOA6WeN-)T{Xgdg5gTvMqUeP&_WqO4v^;h$u9)=N}yr8 z^8j8V5t$bzr?zfsLY{?V8e3=82TSN_ICR4e^EL7-h9`kc4=S#_+Wf%m(9ZZVl1J_{ zjJy-^V9=uZgH#dO+N>e}8ZX#X=_hmghl{WqdF@c7zj!JJb61e;Vp9=F6*6RUZq-;B zqrIQ0>cgdv_GtWx)$itInfQgB%B`DMku6s8QJ|nj*#fC!TePu`9!=8o^fYl zlJy08r-r@pRdNM6M;D=YjhrI~47RGS3?Bb%K_CMAHI{%tT=3E=b$c>bb}&z;27z$k zO&@A`@|C_bYn4JA6b$aL>!9vgPhIueeo7)BwLymVBPs&$ZI?PK}Km66~iL)e~@%)h6xqr z8;}{FhZW^tKZ2eTHvYN>T_4dVu^CT>iAbo&SzGxSH@y;K9J1%qMMC( z*~nT95D!+`_N$n#&y?VD5m*}K+RTg#ygE@Xc>o06V)29?1hRo4a((jVjn(*--A|T~ zN6Ymt=FQ}MBDMll90jT3c9?-c!l9)0^xK)8KWKoRAoKMu7*`g-oAF>|rKew;_m(4b zz4aahTZ#OF1`H9I*Z6=gwSL^ZIT7D;znQK#^6w+i4ge-B(Cm^p*^m7Tqt@0>1RS<*XFhbl}9@H%(%N~z7lmwu&6;mq!UZ2im2A_Y#|PdqA2|9yKulmuVPL3KRnqY^B2HtQR8F0D1p3o3%M zv!}(f9*GE#+CBL|2C2W0MR79sovq5WcO2Zio!IHt9)1;X0^pg&eS#be;S>IpxfHJ< z1pOyr#zOLqADCs?cuyhDP}-UWve@tkaQJ<85ROXA@u=aRK_EQlB`uCBoS+#~Fc?PWX&Qz0u|8=baK{{CX9OL!cQaccCIYx^S~DjNib`|;PZ>Kp)*<42W5fMg5lQc#|=wRlst5{^vT zg~!kHyPkv2(``5zY-X2r-UpEk-eA^wr>Sg&5o#QF)=vEU4~CtG1TMbJZsSpP0w4~F zvDW*mUt@=YI4Z-yv&*unSpK~W>28OCZ6cPXgK=!m@484kU(+|}_4BxO^)t*p=doxD zxWU}>uXk;AYsOze!W%^1NbM9xC+lks zP2XD;uA%9xNeyDkr`}~k1_;Ch+VRF&WC75QgMujej;_=7-$5V*5fZUjM7oX^h8-ak zeTU5J2~z(32m2B7T3WcDAv3sn3WVQi6}lPN!}SXeuK>aB>Te5UGf0jxbIJ~?yrUoe zn$kdCBiwmy?h0}S+c9s+qV9!XX!i|BD{RMRJCH%Z328^gMDX(4Ftft>Do@X*?+?T- z)lumX-ezIpg8(4koj09_f0~FrDihLseLq06vGZE)69fXIuVjlN!RNgb@HpJ?l6X4(azI z0szM&=OucW0p6_w4@2m@euToVvQ9gPNjjw>!5q`k5=kQhJBTNcj8t`|*^aGDU9Une z0IATEw?+iAu4fxoq~0IRh!k=~UVZT#Eq@;a<~=u>5LlWJ`J6-`!ExeQ~{*(uFx9f=;d;zDo(0>ERawKk@K<#Nz;9gGrm_zCQX|97GNrudm>GdC zKvJW!GI=GE3C~Nsj2b=vn>R>+LS)!XBQk`@-m5rq#r~Z4dzgfd{>a;?xMB+&2+y4L zAfvHI#a(R7IcLk$zZw!Sk&Q$^1~lK%{`WWZBLEf`QkFcIXrQU(^qWuf?X3lYC4x^c zeuhZ^9KTtEEG-+Qo>iBi?!08mUntf9!E^6K9cAY&R_=vvjN#jhMoh=9c^TH$Xz21L zygi$$i%4j34Jz-NP|MGA5%vPMP74BA%DO6kJCoJ%D+S@JZ+T}s;{*Xq(B863wG(vd zm;1H<)2p^+MMw5JM|qb36fiNED=*;Jo3g^X7y;Z)?Cq*LOlYTgC97@+SC3cN;7QZY zpwgft8LA@~2IpF{pXZ$e%{mR6zM>*`u&nk~Pb*9W4btNK?WpfFx-1c52pe6edq z9Y0FaVzQ8kJE~Np7qTQbk#WC*z?*LEDzzcjfOSDfkgnD3)ijtF&y`{+IgVt`yc>Hy z>Q!~UGZvW4pLQY1j-SfFx zbjbZtm#!@K{fJQR6x*5=#pJgdjxn~VEr?jAtSNEYuVPs<@^pIbEat?smsamqXenc2^DgteBwb19ZA;U`Gz7lNn*#g+cLCxbFkICQcS+6~$qA&}oOp~3_3EQx@egl14z=Oy=hy(~pIf-7EC<@P zvPP}=rf$}>yCgSTj9Cax&~c`U`td_cC(~D0BJ4xap<4XVC}-S}XQh>5zYxe$zpR^4K;G(mTJ?QH zKLB`jF*o*dJ1cT$rk$htORScNO;1}=C>KApGL+z0Q41bya`P=U1gQ9)I5jLFKZHE$ zs7i0(M@l`ZDEnTtDn&sPv0+f%Opjc&iH5T8k7nJ94@k9Ce*DFgVz4+@;RWbxhv&Dh zI1alwn}1dMalQ6u`2F$6V=5C z#|Sco*m7pccfHHH9QEAG`7}rhMW%-4>>x*rOEh*Zy1n|VUEM@p;CzKwzly-H6W-PRk?WHLZX*6-ix}PYLR()t0|+Hvi3tVd z2+2n4VkMeyq^StyyglSc8|7Ju2Dk4I}67U@Re7~?CAyX^TP8KV_ zYc(BDy6UTQRh}NiCdu}gsvrl)boh(5#Q$4T_MIuV-BP-ViW+tU$k4uu(ooe7J|op! zSRkAuxb>q^Bo<5jlcK_=95GMv5K&Q2MtLZe0sZvW8!bJzivYx$FnfBmY=G=w6z(`* zqG5D#Ht%IRhNMvQ$$uhked^f4a{$&@MrL~6&P7iBlI>$ff!dBjE%>TMD9)J3v<$S! z8(Xrfm_@Fv1#dIhy_k;-(ej^HE+R4%2KLNQ34VCkEik5%89v0>tTNerM-zc1z_t!* z!@E;DMO+K(bbLxdTyv|{UpowFy>`_~Xp^BMIj)CjzhKO?B7$9JA6 zhm&WHq;2tC85I@X%P)k<40k>L{SEyH0Le|M+w-ffnX|EmBJYn7W!b)vCUN`z=G7vp zqGeW(05&C4*3e!oP81_TYx@Z?4CH8oL`bhUnc>k;X%4n*8)dDiO8cWM2LG*U)=s~o zjn# z!LR|(7L((eBLrIc8r35%BgZ)^>c3lX+6X|k_s7dg-W;pFH~z|Y3#+|<`7}T{$xr%K zA8ULqc2s(Ak`7(81S-8R2|=Y!5V6LvXH*|kZY81=rQQ9AtULhod`jD@VjNsvs|A@x znx8RGahFAX)QIvF@nDtpuT_-XvCWDx!s0q6PnHn+6A(m;ku-yUd0?B{^ zu;gRg4nvW4TW`1BOO$zY0+L!;EXZyH zz4-%o1gCvWt#I&&bU;V8S=;u2^Q~#ej_Y zsgUF%C(CRRN4IdO_xA5?+@USQspQUy0p=Kgzbs0Dj8A7PFuB8?!g`kcGp`HNy ze62K9(f*W=eM{gJ-$GEUigC~b@z)H~71x}vD$haE#qw`lcH$zH`35aH#6-+ki;e#K z4~C65J~#~htjjZYr85F`eQCGRW0yG=#476g9y6RkrX4BovN2I5FNZVO$e`{AYx+^$lhNYXcoziCsYz@pSuqx04j4BzmfKz zJ(>IW{@P+V1f{iQzZ8YfEf3A|u@w3*WL;OapCFbT(QtEJBE~=3nU|#~Co7+8Y)pos z(0R>nC_%bar&rff)&vxa_t?6OMYfCzZG6tS%4&QHsZ}E(qlQ)!SMyejt3^;eRnOJjGb5K+@O^DP7KFyza&O>F|HHTFx#d_ z;q(!=WCt;SlU=-ysNDBDRjCcGof570jr|DmlJkP!k8Mj+>L`-#rI9h*m$Qf&v#SW4 zxYGb4c#4}*Dn-qOTNNeIH5Pkbph>?@?{k&f_#iP@Bi-`L>uFDsir39$MRY5ohsedbu2c@L`=$A_1R z`sa|6JXl|XEFr7jXKboDH)Bi~U8lbIVPg&nFVO zDbt(v&$av)FAOi$denGvNP8X(8+tZ#w;jr{;owna(C5`g}t zyn)R9IS)X#xGr;-D2o29w`EJf#HmiVS5!$iHIp$dPpBE)hgDG%y?NJ5GXfdzsXwsP z%NbX7gm9;nvE&VX}PS2?b@l0m!jUFI%it9nol)&1dQK_9>Sd;x}H&^2vd?;g!F? z7qW_He5g+#kecuY#tO2vkTdADM}7J?BObZK(Lja}=a>LlS~rd(06F{9uxQmp#0~!f zF$>=Es}&a9ikijM?Jo`^M?CL)#^C^e@w}})>8E{VR8z0tOHw9|%Lf{mcF?+;sp*8y zzSY*=BwDx5`-S}ovAi{**?6bbpAXWL<<;w_bVV`s65@FU8B&9iflc)@KKy$iTPwMF z-8P->c#|$o)jZiwamSo&(IU55gIx`KmG&pS%HmNe@Q=7p>rXgsTN{mc^GjHj0A0ra z=@*&Dy)x1gm+~@D;R`P1bCGVjUHpBfF|M7}RMdhtu{0r&Cd$N?AnK|+GsID9en^|abaE=h`AUC z2w6nk{K$06Ba~jcKE~xUy#vNbLY~d6HdahborfY4Gt0|htV9THsy1CQ@YSy^zdUYO zWg&GvGV-_G0nteS9CkMq)8?BJ^Fo;=_IGA)*3j@J>72hX?7pd^94wFHwp&6&+Oq{gN+M0xDC%cgq+=<@BaeHrdD0>1K^Rf@}Ww<1}mkT->__2JNC8H z1=@bJKW!Ck(GqV<74^;Sczc!X66!gdahJ%CsG9v=e;V-J{ISFR**ewn_R`vJVT!W) zHZSt0J)Sp>uzE3N_XuB|U9`ugJVi>ewt4*$7JE8+X?F{y&CO4H?Do2rn61#gGjA

=)6^ z;+eG$>t=^p5m`A|`)iCD^?|k1-vZIH0iOc<3&P~ z9PCSEN6F}0t=h^JGE-Z-u0O543Qm+&-GU^J!@&61NwEEnDG{71>YYo8c77&$B_G~4 zdBw6)Uqa-OavS^eiKoGRZa##ql}Ip<<#RLIGS^Fp9*JjUQfZ#~j|=XW0xgpweCTmJ zGZVW=HS`Q`7}4F+R5Kz}XIx}k0Z!|?KQJu4u%r^9Si_R4k6$v6OtkjC$g%asB4#L( z4g(=0L$&3J1{uHAB$A&eYk0Izj(9CUW1a-Zt=ejybme#*K7@eiN%efV(v|E$mKz!* zTq)+M3a<3y8~3a8v68-R09Deg6*;LeGTBP6c2A!{cusn2GOki&`Xb><({FWi=dGBp z7cp0APEhh9(;?6O)+Rj8uPj?5W23JjO7Vxih>6nUETHe!=&_bQnaL(fNQ$IJt|DV( zJ+>CqRXuO_ea5s19I*u1o+Vy*-)K>gA&YN0S$k`0PTVaY5XG54>GYQxO|y}1WZThT zrydg~mET2|&gDxnt{}^y-Fe3BsKsnkcNKxIj=Cpu?6d6R(Gc^aBzR0HTu8whff#daAGsrl)=Ut$6_j$bgo@vFU zOs?UJm@?%Y2N7kiDd}gNGmG2bZ*?heh;1Xo+iz#lV9Ki}_LLE1{kFlZp-lD46jP>J zGwh&DZm9JND3f)MI=+Q6#jpJ$<$5bropw2svtbZX$hc$bU!=+GQR7H!;7kr)5#eah z_}sJWGsv;;Tcg!Nnn20@Et94kcYYDGrlM2w1Ww}5T%B+xA2)gh#bf_PwjnK~=~@q4 zsZ!{dgaFxztycHwKsrZDYoL{`nNbz5^a9~gv10*Azi&S?&84$RYl_*F>`^1i_9A^e zRe&6eT#pUplBJ%25UE4L@e2e@!9y4tRvm%M2tGfJC(y%&j9J5Of?*%=l zz@E-;qd&R>1RNZ#6t>CQ;gZKEhyFZBN~0{s=V#W(V&B4MtSb$dKfY~xbZCi^S0@Nu z$b7=HHR*r;4f`b|3A8k^lmMK=q;P~b9d&n7h zC{=NSp3o6Vef2C!vH(F;S`^Tn_K%=&2d<(4yz0zb-8b zp+|b}$A&jgecaaJ9b@;`O^cqExo=u@eGo0QD3QxQ|Aze%vb~FBIY@WFTxVxZ_^@>IBimp-n-QAVKCjah%RUW^~-6f$<>;D6Z;m^rKGQS2uM!e zX;F7wZSZ|O+jIcXypHrgFx(8(5{Q=lDl&dQ{+hzRfW+TDUB_cy8S&ZsSE#;BZAkh3 z*jq9JXy&SZz1r8k^Y`X$-?Xgny~o$x^IHefRIi?JG#^AQy(b)PXOQ~(II>zl_vi6Q zdy@CKTjMQ2qVJw#@Y!ySV(*_VQRHkkUIR`@BqMLe+eNsUW5IJr#X|>_jQ~t$qF5 z?yPz423rvV$m#vtq+5?|LkSf{j_>%g#buDuyIB>hGOOKS7|)`mK()t;_~)MxmfGsq zLihMn$86A zoV{qO{{ltXkIZkb;wa!o?&KzdC#fIlg=3Y!fof?$7rjjnB#Ovz2dWa~^gA)f7qyo1}Y5vl>zV72<_LqS!z=_#feNm2G-6MTb9h-mm zN67nKt%qbMLf-Gkvp|{&NK7Aoqs%wc)*7;WcN?F@dXeS3*cs|s(CQ~SjU-Khd_S^LkmNgb zUt2}w`L1>mjuqr&bLN8Wh`r8Qr1~DoIOAu`nv&h7jLVvQ`wNlfxF0{_aJ9z=;0jWG z=jgTS7tZt~{Cb2ml|*q3UZYdK&Kn@nckkad#1L=diKP)hv~%Bbzud6Z<<3t|fjzFC z$x@D;6N#^T89CAo>n^jX=bWrzvnb{Wbp6DlsEAjPZIf|# zefB4rHS?|WN%l>Pys)U)PRB~X|H^_`CGKwz)vEU}jb&hH)ZJJE$;mM<{FUgm!~`L) zw>LVn_aUu!HJ5N@*4+b^0LwAZ9^T8CMyCHd-g{pOvlE|om8BUILn;N78$ax^+tr)E zgy0~ncQ%0@g{{zjP7?u%>`zR@Fk_-2+}}=Y|BRyE(_3#vZU6ie!ou4M_eTZ2s7<17 z!pDL<-?b=Q{q!IwE_2oA8;MdMAA4e-7&V7U6pQgQB2k?DGswy@el;Q_3UX7OaqNkG zMi$YTcb<5?UJ{i!-w_h^#7#CrqMjOpbk3Lmdj^TcTIjAT+?7)!sPszWri^Ms3L*n&QonlyM{VRDkSypsg0jW%>TBQn;}d&saU2w ze3F3zOqi1EtRSg(PBV&s&&!x@=alnF)-s7`r1>6k9INCoreqr{^D?Gbb*C9qNt_k3 zdgqL}+j$w2`}pVIuwOvTqH^w*NRBuzmt-21tb7HTzPsbRrjc#`cQ#NnG%C3m3zB~? zcaSXZGc*cR!ASWEKUW8ZMwJA(%~r4f+a1)t!u}=Ykn20VUB8Fj-xk61lBjs#ko-G` z-aQT4SImE^x9$Co?+i#nH@2Ti(0{@yklMR>9;m+E;cS=X0XaE{;+GQh@0?R*UK&+w zO`0}8J-&5W#kA9j#N$wF5 zgW`#+iyWW4w3HkP?@vq#Qhi&Odn~7-`*{>ofP?#UB%a9fw(Z!i`3HuT2Tz>?OVwGk zUE8{La!CIDIDvs%Is3JUNQEICxGnTv3p4R;*-at$cXGsgiq6Ec#SAbnr;4w0&hr(5 zpuSkoCwCuM46VenId?-rI`EkT=4wP(Rk?G0IhL*1`Z6!6+TLZ)ORAR5$H@LYelt4H zm7xD}-&!|p$y0LK8=I7#1)09%{kHgD=dMn7&vr1|v(p*jRprU_H?iWH_FFzPc_U_# z>f07)QBDBbi1+A~-EFTd7F0W)*PM4pqVF87wP?sGBl%E~_gfzDWeSBf-%6mFt?)F3 zVy;!abrQ@rEtJl4&6VoBFsQQggd_ZG;zN<;JMQlb$o)OD8cx^3OqSO&!=I`xF*Ee( z1~vfsGNU8o_w*qaFU#W~wrgjYp-%O=&V)a(UqX&Ox-5EyO%>ltQkLv;wUM@2ua=PTe}OM96}JzquHJP{O^^cDg zWVwS=pZIAr=aJmo`}5*P$S2Dat2M~IcZKr`>ArK_gZorr8L||rI`zvbE7Kg1B-E~c z##{>CUYFcIH)X%-Q^(!xJSWJp@L4W-UYCYA?Fw&t*8P?aOMl>bn(6br<#w;NamyWF=VMopl_VMd z(z@P3@nudt3&7Y2CAS+KvE8Y7qC;*q_`?SpC*XM3FS;G6V7% zxOMr@;~}|JCjoKD(4AO*1I_EHd;hRZb;$BBlCzD{o-0&mnV+xuXDC1NbJyR5mYL3% z*#`-`v$}(vPh4=S-X%IY=78+nk5gN@7go7BL!|$aoqO1Cl4l%t_C&8CJNM%ptS!Ly zzH+!2N1Z*^y2#G0OT!W}jqKb-R<374 zhs$1TX$ot&#y113IC4Ad*c=ed$4#OE3n*JVEOEUqvg!~yx4oKtkM4&#S? z!Y#;o$LuDMt2-x=J-lH))fY4oAs=o%YbD(0a;g>bll;B~iMbPkBoYE7VQ21}u%GL6 zU&oPXErGm9%uVInuEa9^X*pB8!hqU{z`6`*UBt0zC59^G<$jW`CdZjLC49=j+70K7L7$lVKGk=63J&{66uS_?<-T&orv^t9oNq`2+g} zWZWZ9u1;7`Pn9nV$|T%jLDy8Z%TAPFfMb=N-QH%h%5Rct%Ok}{6l}Faf|ACy>`Q`T z*4`mO;r>Y7y}a(Fi}&R~iFMyKH#F^A@bHd0r@4{LJ8|QWKjo_hu3dJA110_mS-PL! zd!n8kht&$%p+JvspD#$;-E2V-BSYHm$EIaZrB=TO_#lgS{DaGg!}rU`YG~t{FfMR% zMAUWp3g55(4$pIZdDf7_J9psh9^`mh2e}MMTYKd2?nyAEFZFVhS>&1WNyb!lc(2}z zB&u(RB4K~)XB?@YTiFY;cvFejq&)#*cV>4n4oa)x6G-BnoW`CJ;Y{$pU1VqT>Vn0Y zYV2;v;+jZ3cXZ>-7JoBWAk)mU3PLhqSPtV?zXe=bNU+uVsKWO|TDLzissM8BHK33qyujREPq;{%#5xm$VU zG$@cHu@+lK`tBRQAzV`V(^L06s zY;(x+otsjvW6r*ZW!0ybP{opZLa1tt=|GmlTf{Sv(|gzxqi#k{Z%<~~i%$4di9_s2 zH-822oo{ri`jKHVnS3zk(kY)cJ7H7R*9(_(*;Fzl9kVIyb6xJa!I|SC$JA098tJ^b zKwI+6AXRtbAKj?So%q`I&w#iXwnVS>nsrL3-rs-m#JTtz|Wx{4^)TsCiqB z%-q>%Um!2h674Gueav^rGF6ky zcXDp`gx)-fsyU%I-9|_x*dE^5=2*fX*e@WWJYNLtnDWqZvx4MEydP;_8N4(Gt$%Xg ziliITZf6_40w@^YsWXsa)JBFX$AmU6;mYSR56k+##L>F2sZ%g+vS+(u8Cxh(+{lk@XW z2n%k0U6kbY9%}PdndJz%n-Ubrwnp&sUXGA^^ed@u!*|c+HgQ0maGRS02U)e}ZyN|? z)y~<1<+psc;D+D=Nsg|(wLhMko_Fh5pT-w}4B8>P+6DtT`!_|no%@z|J_+&Z0+YJ4 z+s(b=LAb=`D%kDw1y7EdB7^q$I_it`*}1sX(loTDT&1^t60szt?S$62^5HL6FP-P6 z7Pb~Tj}6$jzr$a^22>aGm(n6OPrIk)+;iYBwsI9C$%C6CLg$Qo_{cN-@|WZoJ(s^^ zi+L`8IT@3aJh(Y-iR9U>eN(sfxfUUO_vqy~KK56UZaXOzFOZC< zF2$VZ@x>w)>9@Nh!HyAIgNoB=61jJW3aL4$=(wEvTqfiL$}duHkGrR;4;SQi8zM1R z6?KjIQAwmueZr4I%ZQwKz|_z>tx0SWuSmz8q!Y)_C@v12p87a@+q2WlW=zGAFBSQ@ zBM!TYX%Kl>MY1@i=D4MMz7x!b?=KgEv_WD-4`*YJ49@P&wN2=4^?q0tv5iQ8h5kA$% z{3xgVe*Otz+4USmea@kGP=UR!<@DQe?*(Y*r5ODwX+@>_L zh=$|jBKYfLD^YYYf#Zg6)o=LhV$$E$=Mtuq89Dm38(O*yXZ=q^50NCA^-J@TdM~T7 zY@pa#4xmx7!OS2DW%l5WV;a3P3Fh<3B`SJk`d~qFtrNMMVtsu2V8M!J@{W|ReDZFD^w{&_~+j+EWcf^?Mgki6Bc*U&-?2%rbj1i zDd+7gGIHk@GLPwAmr;AB?sb!USe@>3&;5BU&hyDthUWx1$s?jpJWgwytTmNeDL10~ zt@d?P*w1)~y^2GSa#d?3G0G}7GH*PM$M3AmnAZrBJ+;4Vew5Tx^$9)@r+$wpb&`Nxp|E zWPJsL7a<`+S&iiqA@32195>TnFTN50%vG%_xnWX{g<4F7Xan_2;X=-!T#L!j zDPIRIHM2;l^+-|m%Dklc^dO0(QJXFq@dZhYFfXAV_ zKmUgP0#dGL$=zP--BK5QUI(u=l`gWvkp*;n+a10rfF+WDyO#pvfaDv^AES?p)wsS$xTtT*VhGaeRZ+|mzRpi?K&8k?D zYdg_}`S!lyuzo4023jf{Hk5Qs6{)sk;uu;rqka;nm}hE4q68pvZ4VEOm;JDpH#-xg z+Riacue~vDEbR0%xfH;8hb!`J|8_}gMZWEl*u~++_dE7WNUm(~6dd1fN)j@kd-ABO z88deUWNTC|MRIzlip1Pf)&ALTYM5pu7bltHmCKJp9*g-Ar-{02&Ks4SFRzei$ApNrCH=v=s@rbFrXj z_UiY>9~U#O-Ansmq}=ZNJIzAQ?ds}y<*gVf+=6en1Zd#axhloT&WVAN6|~D;n;xlM zZdkIFRhUtIqHsfvoN=up=eGU6Ry(`jKyVj3ZdR`8%7iKHbQPFVPQA4t-pdr%H#aJ+ zDA#Y)$$Ij{%X=5hDVH+)Q zHl*M#F~wa(sSoVPtVqh8+=9(W(wJo;1VBrB}jP?Htb4>*=Ahm9(7a+mX4_tmiDnTb+kCUpL`ik#f{?30o6WfQu{iJMQ| z*Pd&$)w)7X?ufEs#17FKa~N`RKQa3&RP0aemyl$kkj6uv?(9=M!P=Jrar$fXW}(P4 z^D7IhMxvQDH)nILNY>pP<|sjgWZhb$&NoIR@yV)Aw*|2(WoJdM?(Vz>657bs&9P`D zk5mms+gW|x{?)cD-;k?Yfrr`4BUd-&TX!C3BHXC-SmThrd!=M`b9bttYiX`0Z;}JU=5Q>NCps0!@-0b81RkF>6+lRj@ zl5lf5?wFH+kmYQnVd_Ew@i!WH%w=%*exy^@s(eoeA=AV@YCCbt7`9VhUO6P1y%) z!d5FXbI&HkT{vYQ#5}WHo-z<(WG%lY^E5Codi66h5Te0GmOQGJAxi{kA7n0Y+cHU7`5~)U2?k;(KB0q*ShX7Y{ih_FJfjuARF+OYqx1IL`MuiB7-3d zR5TEvNAGujk?z{+ACu$|bA5w5ncZ3E`_uVN2yIOge8iqX~8VH1){x!1zi$HY0 zjF7Gf4!njLvsQF1e~JtbBYDmc^8x2&=h8CE=-U!>`3SLU>rIskI^k7U9p zBGQDZdi)ki6UJFv`DW6D88-Zqe66g`4ziBsb@Qi0njm{Lo=wzuegu^`ts$ zS*`nqIMmnDL`rTh%@ub8QgYX$%1sw5Qj9rSE<#bUVzNL=?%~Pa-6WY9u|#BsL{9Fa z+G$VGl(Uc35tnE>ZN>2vBS-pePL%Cy1!^;i!c^q>4kB2d?GoIk5Go}%cR8{$wj@fd z%{;2+s2ve@`thA4wV6j@k}sDd9@TR5V?_>bDDQT6+^s$ODfQJ%qT1b)HIpbbPIWPd zLZ=l!BEHmerw|cr2hrMXM0^QG9M;Id-T91j z=T>Cku6$;v%Ca)HwzE3B5|OkXF566)ka$}r6#NU+8kLZKMG9^#PxOgrV3$P^9jh95 zSrpOU#|6`($b{Z%W|u_~kM`+>_dE7W$mV-KG*FS38;g@Q^~dCcMQf(pB`YI3H_yn* z*xJsD7;?hmFBUsPRz{}rRu>Lg8PVOV1UYPbJm$#P4eicn)IX+G93(Z~w5nY)3xs3Q zYo@YkRU0u|AU$_K8XZrBq3k5BDNMUIvntNC0BdQq^dWPq)}PEuaVmUA8wBLx#_~kz zUV2kbShS=Vk&O`}^SBt<7}2BdtvPP5yN{=Glb|-u)sfGY`PT&~HwixFiD62G3VO(= ze6Gy>?q_6W(u-kV2vVTpd#=O!@7#_Zx(zw`F9+l-IT!$Z;b)jkhwBpyYgNdK^lmzgZRKk$P~; z3ybdY^4u~rV#-@CZkZV|DP`V34)0bh95gA-tFWxT5RODMv2LPOsGmpg$O+5YrGYqd z!eSP9E}2#}8D5FV35#Xx>2F#^@#y-AR(+f7rd4QpX+gL=yUtWrWb3A^7}@f4vntGs zCO~G!uSwA503y(4$fN{|cW@iU@J-}BUy8hGSkv^6lpNBpWZ1Z&M)*XJR9=J%Gg}cdOy>N2Jv*u20HQ zA~q^Fm!nK<&~D4mnE!N#&DI|N)13C0$R$AfR@W?SCnrXpA1@R9@$dibUybg%rcs%Y zh)|(V)FRtM{={dxlNNF?DAt>AZ^iUz%f0Dmkm7%RQ%yiNM|U`I27j7kO8O3c3&OIy zUj~u4qclsWf1b9#@deasMbL6N;N33Gr%J;6hhqs?*JhWf1GLv)TnA{K5`WRIn5MHJviIf zv>>S`S)za*`VgYk-RYFh;6)GhU3WTWG9`V;`Ex;)#?!ygwuv)-^Ec#eCK=&)@)ojc zG_O=v7*wg7d}=rsg3(PGxSqg_3O7963A}(v06B&YTuGfi9FGgG)Y%imX@$Uy%86*3 zM$U*TV2>_P!Xx2QwF>{l-o>}T6QfjA(%blMhNtPY%-)Y`bHoLP+&-XA^YMhFy#hq3 zZZm8$^+wxh(O9ZX*n*z#DiB2J&JwMvmlySCs@;ADVR>7Ee^euTSU~9|96m9t)!g4J zi_`aDf)DvIoiyrPEhx5h&S;Jy#3sL-G>$ZM@C{=33?%>DrU`8y>mCIQIUY(Z2E2;uyaN}UPwJS&z;IbNK@!H*zDEo6ikh60CHJyEbH$T1ibKgz6fd2)+XCvRGJLK=L2z_$tYfestttbG8I}v zmeqClr8_{>#oYm)?&o0jcg zgvjRl{zZtqQ|gxxjUr11E-Wd_>d@uP=w_!)=$yLEi;}>$YVJP3jVnu}ox3A@a6!p) zb!a!DEtqpw;l>j8v57TqEV;^AKr>$(C7JdA#C{Qxz8;QV#YHAl`xECY>10XXdrUnO zmelN+0CG6Nx=)ex%aXd)04_3V)5aj`7hGgwg!~$C&k*(q;6DjBJLwB7tsq5=x zZJjj9)LLJENzwC!$8{rL44YHqrAeb%$ZOcil$yTIrjsanRtDJR`#uPFnMgr*2mj+P zlgt9m?Rl)9uiU*fX*fwPE;E_2*$g4&OF?VYL6h_;J5_;5L3d}J@8n5UB9HX1FWrMc zj?3S}+}Z3E7neLSX>u3QFCpqa*4!^4>JCT7#U-`5QLgautQa-rAQPRHCaoQvw5a-9 ze2cV*wq$z<`=v$I<|`ml(9M^b^h=AB3>HXeQLkc^xVogsSZWs*5G~MZkpf!8m7nVh zaC3fbi$vuy^&n#7H_j+0AjC$pdcz zTx%uB+V(Nffrjf$#O0poCsHN9r7Dst$=_1_d&{Sku>ny!b_;9vQNqRPcaXgOpr1%H2k578DM+cb_qMx^YaD!JA;+gHl`M9`*1p0}Oaxj<$ zr(vd;9PTYySTr~eRP`xyqo?_h$WSCr!Ev-&3>==DPJR?zTtfPcLv^$n;^Gp{3Y-C? zL>^3SRe#{fyF0q9X7 z8=rztmHZhum&~_7oMR_h9^^;k2l4_;mGZXooia!-P@ZZ8ozAQPOGd9hv0r};Cg^^@ z-o!ic9^&-yOk=0KNPDugD+_+lSQEzNq8V&QRRm-b_hUYkkn(7XyGOkjM3o@N^B-s z6sqSFs>37-^{r13uqdYR(87YYdsXhHqn^c>SE1la+Jd`G@ILZrcs$_&cvtt~b=-Oe zx$WNSz`jW(jLS@*%$dr9>Ij#ayhQr&QdkZH_$WIaVa?MBboogD87?;gk;W_-6jXz> z>P6r;Auq*6CeOfJ>fCz@fieeDxM3KyG`%AZYo7W7T(b&U+g{zL z(SMo>7Kb{FreGVuq27+enet&|(iDaRp1~esU|-n9Ak*RJ*irl}Uru4TnR!5Kt%}-SLw^$gXiRP$Kx1 zM^xuHR!1H>LZNURZYiAoPwZWN;Z;v!U4W2-KZ!jUAyzo3rL_iPr5ifr(7^2`WjPXa z9V18C7M#=&*PG1a_(Lr=5G#dA+mDa?O=>dxJwc8G0#!1tAUcDh979^Z@spFrWuccMifHR_4RUl5ukhxi%uh zo*+`@!|9T6nF+aeoz6l%NUIzMq*aX&4#r5W4ER1`+X%wqOGomXQ6my(pim6_+73k@ zmqKl4ngK$#&FCq%I}{2rO&U&UXh!5E+yj@H$Q<_AWHv~mNY{p9!El)g)j8soRArJV z#fYfoC=c2k@hIW|xLavB*2L8@heCu7pTS)w;@ixGF_}3P1oP=yFF>fwTN2?+UK~(W z7ctI1pkIICY7>#ZIYnS9uBna?t^$eVF0OwUZMPehzk=1ub|EXLjqa42wqfO>d_SK%2q;uRak&rk|Y zre1G~W96d8^(GIGwoIQ!2eNp6ehhaZB7&HQu^$gk#grj?O+!tr$X+Qxrim4^iB^4m z$TG%UdF<3W#klV!>XX#UNq#iN5G2GP`|UjUlQaqnU~TQ`ahC}hHv~D0!8dt+emZ%? zG>a-vY{o#i$pL$%p$=D>4CWK6>D1OlxRDYpdFwL2*SnaK8z3JTgfg(%>0t1;;4&EK|pMwHyDl6Z=901^3HuGS>=Z0czH@j!b;rzhFf5Lwo2hQk|_8>@`se1=Owz^LsE_7KJ1 z5ncQ(c_}9>%(Nr z`mia};~bN?sf5}aX;f577!y*G6d_p1dOS8d8%K)n6v@)UJaL*Y%TL{i2}|9 z`sg$sGmHr|P;)hi5}L|zrk`XVSC=#;w6#;^=ijh*>5)eH)S7E} zq|kGO1GkwBrEjt!1-F@W9SwOTQb3|)31}h#lh!F7*svXOl0_BS7`R8kZ6<@qcBa!G z;5rkkbewEZzmrFGotbDssJ~(1;MNg0nhYNL+P=OUH=0m^1JNuFkHXQpv5kmFJr2^E zmq%_ijAnEli{K*+bjw2qz$i<+KaxY>lhr7|66jGIjgkAUMW zOEn^%H>)B57g>}JOKI+qM4>wU(WG1B86%xe_sXn!Bwk-BP;bxPrbCTXtEwZTY zgKd09G)M!ikV z6=d$AZ5Bw}1K5fbusYN&V54^fOH zgHwIn>2XG4#pU{%FJYw}A)BEeNH{58u^7ejmTOk>A_xeDg=okhCXR;;OhO1tvJWZP>34I+0vY1hbit}*^D4NJcQHaek`{w|YeGmlhY65coA}DnU$k_0|W^a$^JJU8AsiZ|*H{UkX$@5>PHiH7t`W z7z;h?U@ii^27y{ZNUxU`8IVpZHL@mpa=@fSds%KR!Hp?mf7REu0ijNRN|rY1mCc9# z`j$?As){{wLn5=BWbSeh-;?90xE+P|GUfvlQsiA?o-8(#<|xRA=?hzdV5U*d=%r@z zw}zApZbyl?qzN#OLjI(sQo^H>cy?VLm1EwxA7wsHD8tVtE*F~us~Ie9kORh8O*^i~t+Mma`$ESHX*!;L8<-S@EWrU{Pc zZXJHS$*ziQH=NtJF@;LKR^O|-nb@?8hRkW?@LXZ;uG&1Y&$sM)+~ilNPqj~YUw(DJ zb@^3w`28+EFI(;V!<{J%*+M3OM+J8&b$pz1aO*y-f&=>1zn6*~w8w7V9lzAaN3UEW zr7KF@^Gxbp(-A#`GTB76!*9^jwXv3u`GNL7%4v36s-F8S^nxZw@9Cx*8qjG)~ zt}Wb~Qd%+%ZzCs(`iGElQ;}8`V|Io744PhGSH7S{#ByJDbuy-iuA&ibmsI&Egao^3 zjThJzvwd$nel}avg=hhEouY+FPXnl9bcJ~c**PXx1qm0`f#gy^5MahOfJ=#2I&Ka3 zq%_HUrxC|JDU5M{bk&FuR;K%6rfo7+knz*S9Q82`4FC}CM>}P;O>~<}(V4|kXlO#Y z)s7-ufWpXXW`@->U3{APWVew?*IKQXc_vAut4nW9^J&~Zz=lI$v*ESonPoy<9AAnX zP@t>JliLetKGYDRWr)R<-9>oa( z5P`_X6W66|U4xNshYe~uH_B9PoO!Rx4v%|K7-z`a%cc>!;E*^^OW-)*tt5OJ_n^q} zIh_9%_n?qzf&_7w353=octrG)0VN}p)atPuY6ne;^64dPDV*$m5I^2yJ zwb+2OY_3CO7Xe4RG0&AsJ+anB6r2-loxRAgV#`{0?3~0MD2)Z<3!8|e-H@t@(jSQ2 zZ3xj=M4GL2$wiM_P^hq=iM!nFe`3G>f~B2AvnH7v5S#G2Xv%pmp=g?0u>8w}SAEX% zJU$t~R7gR@*?g%54eer9RZ0R^qcGeJtZ4`-TAkoX9AF?a;#DV3f_a{+6C_DMiv!M% zpu=2N``k<7=t1b7%U zRgPU(r`l5s3lzn`VW5HC^%QvA9gADp|AtFe9PZ{-g?mo~0}*vt z_Vpcl$GWK0)LV&o+s<4>j}Rl?wyqUFH34sPrh=vpCC4+dr5;*FzOfO`Cu%xcyZEV= zfVUy(0bnbV&WZ(>tZ-VC=Cs@huVTC#vm~jQt|-WoTbF@oed3aOy)|@TgbBz9Ow-IH zA%rQTBxj=*QcJ+wdGe_Qye;QzgJXwceL8&)>gx(@qhP0mINiQl#__3a`)Z%WI|Cujgfi0j^cF6bm@MswAADX9JF zPs;Hr0jNtovK@Muea-2|M!c$U=fgwrR{A8=K&;NI%N+`MqYdu}xvttS?-1=MwBdQr z2|(H$4hRC5aQIRwSW%?RA8&zSd*K-p&=k#!Ay;j|eFSY7p@;lQI#O8FXv4$Bpso#X zM}j3#CL!F&0@KNf7Zd<(c(^c2!VAQTw9`qZY0}}9EXjS2aIZo))bmJd0HFyF%1**z z+9`{G2XZ(V4r#(Wi9*ATETnKqaCi);&x=zIo#|r)Y`0$W(aI+mEa3(g1z9~lMGS|w z-Q(8fK;)6rsH|e|c(O&qDy3l5>I5MOVWTR4s$)NZ@TATSFN0NTJvQq~l&%pLYSYeP zSQn?GPh8WjNfz22ZVX!%bvf9Z8nt#9-caN)T%RKQNCKce-=EkoB8+Q7gaJQxDb?`3 z(72X`^;wRxIy(_?+g2Hvff;uNlBM2|u4hP^8i8lIHn)$zV5l_?+kQ~o%%Zh=MnqDb8i3Ry)19)0X^Cr7x4Hry5*>me25Q+@&1AU6zO3y4m z)0nBW-M(mDiMVSne0oT&BxiI9*VCNSxcDSZ!5uAK8KKiVZRIKzf5c~q;LpH_cOc}$wkiv!MKoxia6(ac>;si`_-9Ap;SU#1umH^ zN_tkEF&L1bm>X5_Ql?zk{*W_?fp`%ON+1Z;wvHFy?-&-}pf!;MLzkk$2LlpgKq|5E-cqsPbZYGn`nUf%L*21^ri8*G;9k?EKd%c}QG9~)zHjqrorsf$BG9?yg*|3@?Ms9us z9YOVQ_}T9a-K&_(k{KXBGr*PS_j-RsVCZJ3FN=sTdY9o$|Zpxi22Om-OWl={Y&T#@`iB2uM-?3jp zwDr9Tgd_?`?uCCyqV$aA$-*?iJrBvDd39tM)AA55G({H>!L z-rE89x^vxr7|q8b4povJv-naqTDgiJ5s88h*1hi~Eb4K#R_@7{v+W)MUnHvf5r#dJ zL}>+;kf?jVGjGnA<`Mq5NmOxeJLWpCjzH@>NW6zq?z|bGihVFlCkfoIhm4x7+3zM! z=lhpvh&lo2Agj41ns?t+J)-5yRNf|Vn*6?yiM1Ik2n{{SLQXdilf#x{J;NONO-{bz zuWu!vtmRfvdNN)r_t zqHIO+@m6F|!vkr@X}-9d(RuAcZ%z+Dw&l%%7SQ?a?qu{#5PR z&_RYHwxo+~i_&)#-&0AXh~eo@>mv3<3y-dwrpG`^+$(|k?6~9W1{iUMcdC0B;hjHp zNvdX=iPKWBED`$a$U>%TBH{#V>p4LffL%gEutUb_ft53kbUc7K;c8vaa}y`t57UBx zI3fLscnCrfanuzS3opb;83N-^)ix8`6~+z~2bK{zI#oN1pTVJFJYv>{Wdmk6w@(wu z5R8JS!;7@*@d?J3W%oPwO94)< zJU?tfAUXwFrhq;M0u(c3FSX03?8u`aA)l%dX2@hrZ>R$f89gKFohxJ!lKmt~>I7N# zvwB5@QN7~bylzZ)$doUd8@eu+dx{brBxVf$8yDyULo+&pnjT%c()4Ol zg~^%kAKi1aoV$fc4z6lUY&A~B5 zmi>XpZ<#_>pN!=B18#3}Z4gg}kVEAmh z&2nUk?eA0Ml3eg_pNEAu8c#XP=h4+f0iB| z5gzVt$89*~ZArLFSLq3bt7N>@hyp_`wb20)5*aJQ9)fZooD?k-V-bc@Sd;E03`L3e zT45+!bmVa;!cYog()eJz@h8_A0%aWX)E7-TBpmp$W5kT1#*Qs7Fw_|FjhXCAL9)OQ z3NeEtBpi1bgxn1aYq9*SUtzmMpu73}A;Z#JtP^o6U@P^XV57wY+D=6#9*u=j)u}$n zMD-}I>iJ|;m5Ym=5bG$m}DL!}t6~=>r+P#ig(`%}zXIp^@0#x;R z9?+m_q}aZ~ST)Y{-pOT_&ME<_s!|F5Sb?f$j_JLtlz9|{p@h*M%Ve+OLGbzATW-Lr zbufxy)mpJJ1+3Z%)ggxf9UFVZR5q$2zL7w6wMrC-r9_c1rr;v471jB6#Wj)~D5Ejf zbq!Dj2SW|Xb`>Zcd}@HI?MM#NCve!eqXkIizzM zP&4#FRT)|yIPwU|@~6=WrXCDsPI*=&X%58kXat4|)?G?CF`C2C$r~|cw^$aq*jC-1 zO{nBjtax>%fn;OktBj^%olj5zg(n~ETOpu*d93IdL26S*5aC4>cOm`FR8$MAlrV^3IEIB1 z<*V3H&1xsZ!3fP)O&LmBoN21DRf;lRC_y5X;DM0SotjRox*A!*!zb$>>X=ZQ=QB~N zs_w!qAV^dhvO}+cPFz*Mie6L=Rc-PuWQPcn8jsriagl%(T+uprQ~@g(LDFzPuuaiF z(k!646PA<`7r~lN7x#1%)rny2vZiRGIbE(Q37FcrS>jnArO`ym%0^Mq}N=TN!wzrqgJ@;V~1Fa@!M4Rz^2SWLf@%cmcCCRdvbGRqtsu8wk zP(1dJJ1Sq)*j+Y&)I+iz04M!b4Xaelf&#;;V@(5DuA}j!3cysJtZ}`wj;L4a^4GbN zD?>I-513Kai6mzE1v)!w_lXM_vBysa38R37U)}JH_gq@=w!z zt_K$Wrxn6#NQeq12ha5B+OvDdloWFSO%C2lm@&xwX#JFLx&*CIuEI_}A6u|YB;|e2 z7AdG~ce7k$E9FofVqByRpoU;OK-lUSUVZv2e1&imkN56%s1loVyE7Qc87~|qQz?;S zX~v#r+;qDuKuN9?aZ!|KFp`svD#vjH64id(@c{xh?Q&dt-(*;F0i{+8y#Z{&O!6K$ zWLHJvB*Y3T%J~V?hIN#G4@{v zA_NNTjYA%I%c;H*qFW`&3KDSwPzFhPaiCeXq^gc^F=-|x%4^!En@QfvY*3Iv$+{b!C9JGNPHgW&#dZNa0zQ ze9$Q#@@5#tum*LTtGpbjjwOL$6bbM2lDW&t(Zg>J37s50PCCtyiQz07P(daH-^9}h zGC@*&tNqK0!k-0*$@oJdG%XMlB7@aN6{LBP_R|DnDxoGI;Q=^e0a_p?#Sc-UlnI9m zQ9@6op16fXmh13cgR4C9u%aJBrW!|dP?PIGzJBEpaL`-Vmh|~U_63Q7R9oH(ngA3} z|3b>(E2mo5cG3bx)rfFwMo}%!n_w^JH0dcGxHcI@daT11FlyX)=1E0a$`YvF7B2EU z7ii+#@_QRJ&2G5U0yM3N^Z-{mjUa2q(}>$dIXyKbOhZ}`LeRqQwBj_-0yb?2h&00{ z9CfR2)$MR}F&9dxt|MC`H&OS~pyp*~n8e`H77{AwYB&z^a-LtRb02auOoA%*MTSX` z=;RFvkFm`K>N42NrJa+0R;lJ57zwQ8*+xu38%P+iH^XHLo^mlMmiR8hL(t9gq%`9p zSVy}hODB~Xp^A`92eEc{vt^H5EpBB%w8Fp(PI9It&7}knN|x=pGBtvwygQB~Br2N) z|DYFZ0HR|^fnu~}mmHY0h zrgbv=b2Cm#JAy_aQS4CoE}C%?Oi%vmb4y337WV>F%0jfBPR2^a!MX}DOzK$u8Yv+v z%G1VrGpE zWo?IRZC_-x#MrAI66FK;Xp(>VorKXrNgk01{&vPij3Fx_5r_2-?PXlV@GrfkaZy?k z%mY&L;x-CFhJ?CdhDQrDN&xf?MpXFyW097m`H z0P^x-bg8Yf2Vz=IW5}Q?FLugk>+VKOk#?8CT`uKq>XHnq@@7ctiD1M;1J?@4wh?-` zA0Z}eGX4^QnD&aX2*kAOktmW6o+ZC%aU@@gXwGhUgs3$go4er=>~@~cRTW7Qkyb*m z9LOzb*o}~2w~KBR%139q+bEO|p;|Qr%gMg}Rw{@niMyG$M=Av|gP1({^u7F4Cyy@q z;yVd5<*1;S!Ax#Hr8Fpr$xE;_sACzL6qt1+)2PMu?!U{h{F*W(U{#2lH7fZNG7GM9 zD*33IM#-|86@CPJIhB0Wd(0p!ukq0Cc-iXV+-*vh!w9mkax%ohNMI`$u|*{9FbW-3^=rQD!W8F_9~6$`WI$e3tx( zBnW3hW>AznjBoo{A_pSuB0V5ginAajv_@{TJZ3PI)5o>rkO@NaZk7(unVEEM*`aYk zNKQ?@&(TzbLE+6(2gOHq##S!tL zAS5qlEbv|z@TtYovX8G~15)*~ zyNF?$nHR#gkT6vu_=Iz}^(jS>o7@9ZwZPgvAXRtS@Z1@-rlY*)*P2o(ZNx`k%ZKn8 zd)rb0Q}pAj0#w1_Fhim*(c_s#PpDL2^%JlP779zM9T(v+>NYnq)j@*h0MDaLcRvhS z-d%vInpBDxlC4b$NFPTM)PaT#TQyFBIENp3)5*Kz`G!#yL&8I_tcK(x1W$SQ(R2Hv z;&`pt=fO&Dx9d0p#cNqx3}Y&KW-SqZA`7c8QW&2@UM<-Uw@-c=;U~0_+8)MF*+s_k z5PV`HyspU#;ydgSl<<6m@M8(GL$jta4hYHLp;;#LT3%-0Cl6PyrsFVl$|GEM!?q?y z4Y|!Yaao$O!_bMLPwv@y5i`X>?=AX*z?l*w(kVeuu1Ku_caU(yo?$;3MpL-Elm`gP z+cTPLDC1Cu%^VWPjU_j6TEqyQIZ7~gL?i|1$%{>$#a9g}6mSQ*jYIf)jyESFQPi=U zI0quw*(eFqgY+Bd$;Zc?iw7$5I-UvJcjL0%$JlvC<(?*FFe>KY=ZPW=}LjX1A3k)*e7;tu#gY45y?C-!bex)1Ta+b zL|O2&lC`LxM&)=}IU;Fq6xdyH6XTr<5Z@6kO%}5~ar% z9?8bw^VEh@v*uIN0AV|rk*J1prFk=k?y+b*l$5*5twgtbmopjhbryH&7$O}EQvB8@`#{QNW`IKs<{lV z^5HY;l%U&>7*;_LlQTAGhLsnR9ck>omBRO+q^Bi@PCa>YgPB~}jA1^Q0iJ^XhmvVf z=BoldwQz)hnp{o<`{6)Mo*aCvZ$1M*!8R-bvq~9*q~EeT-D&OMAg3PB^K>%2JR_uS z22x596fgrSB@?Y=kdSjb+yRxqLLP8h`!ysEs?b~q3Axm`^Nwejolw9i1XSYdd`o2~ z%H-u<6sAWWZV8k>dY=NPffDnETS%s3fv4L{C7q0LsDgsLI=ZB}jjc{C!n3BWPKTQ@ zPhlr=K5E^)BwzTQZJvyiA}Gmyq|r_R!S(@9XAy9ePlww0KEhID9&|6=O1(rAr!Eiw zeH;g(j_+V2XDD+EA1v6&i+!BKoha=g1;Gj>`~-l$dR*hEsG*pr4#5Nh9+p-d7_@DO znJVEb5<-2r08%Fe8g%4T-{g>&q+5MQ<_#p`bP9+&50EN8;?D!5;(!W5a{3kJUBk~E z5lDVu1?Q#1Ede(2=5x4rgzn(H5#hx%c(bJZKu$hwTae!cwBtjc+CwExuNZXQIZ)Jy z{254=^ziaU2249#(I6dnCXv@);H5oc3I$%;q0XnxO=+FaG#s0^BBUFf<3!fmbxJ9r zQ8JyGH=Om5BYg&(JW_h+)c4HC9_e{DvmL!V7L*|r%%d6^A*fsJGeFciJ5u7{& zMD@rx2PgS(g0gq_08uSYZJ--3Hd9-B?sS-9nkD%RyUZRS92b{yP~uD@rW$b%;2WnM z7{`ej652gZ0zCM}X$nSgiH6-Cyj%ktf^VFbg-CgXV7X(z!m?L4$F{q-m3M5r>zJCt z&=1Lq^g#*oA%xJ!TLGBFV?>DoQ;ys~NVa#AWl6hDVOx@Z+`6u5`Caw}$*?0Sdmcct zZHgX32hDBS#*oxb!pl$4MO0 zW9BY{C>+R^+lZUP_0RJP?_G=NUl5R+6GR*9GKezm4JFPY?dd%3vUxbjc0fR0B9bo#gj22m&fas`U&VbBBrI1^8TrV8v6v_!q4mkJhvSezEI!v_()o*vIAA3J|;up0Edchz*{obM;!`sjCsU0?D@h z+WT2oY6H`T)U)sti61O*)@Y3*GziJFvyVKNx>6fpD)*k(oi=(bMN0q*@9oj*&Kj-Z zrGkXIyX+X7?yS*r7L5TEe8W2XE(0j+Sp&YGB!HX1(V6_DxR z!WEF|IMYE!K7ut(&tuGV_y<>Dro&;hru`{i^#)9E-T0m6P+I?vActkZl!7l{O$Y7; zyCfw`0=bt#I^G@1B*nd!^Fy~`>xBPh156Fl~gDmI3X!R%Z4Q8MNcX)vyg&BDBPk;4LI8h$bX(c4!W7|IW@1O_2t%1($Aq zpq-r^8tl0lOyo0+yYAT8q1BvGpFd<@kT_$sEN>^fB!S)YQ=cIP>H-mYx2;*|Z7Uat zAFuf;r;C>03xI^Gyo@7px@ZYY_cnmSW+&|hBJ%8c8*Q8~nj=pa)Z|mQ(yHIaPgFY+ zIK`oaJrfdT={oLl8$IC_v=+C~6LG%;0#Etmy?};XDGuQqhD3TiHdfG(cLzy(Y=BLT zJhpotntakGpe2tv5|>OWarA0|!Bfq#GOII1L7zTC!m~{&F(q2EgE0s!K{zh9y9kB? z;rOZ45CSHOmT)9&F(m6S=8GazG~mk)=v0F?VFz?7#kd;`4l?gBv0wJde&ja81a9p~lL|0NM@K*Cx z4%j=sLrAt~ezHOHn+(gYJBTl@_@XkJYIa#-JXM^Ov}J<{bq7u-GKA!a3EP3CggABp zse>LYsGagQ|^&ZN2*a6x02nMr=mInPe4>gAY0Hjnjr6atlhlIw-6ORujD~H7j1%rR8 zJ4jgO0uYcZ$T|YCAYo|M>ZgqpMOQwOVA^Qs0jFbCg8%^3U)e#Xp67y6cn7y|rs#}N z?Y*2SI)es+E{m_7F~d;L(9DnnA)*~w(}y=j_I|PD4HT?2$|1Zmnj)t?Z8sW{3XaxwvMt+ z-%f$Z))XZfNo7Z*Q9zxZ?d2%Ugtp$NMY^OwQrRx^0;bsFt%cvNq(D-|j8l}%F!3%) zoB~mu^jVUTRJEzTFyY&K9hWO5%cs`mHbzpdpO-L_>SjVH$w0>ItdE1u3bNtNezp93 z3f6<~+Jm0A8I!y`N+M_)K0K8apsC9OQCJ4khFX7=;=Is4g=0zz%oOoTlq^$J`l4p4 z2cH;9DozW9`p|$Er-k+;2uumjGtHo+Btxb)&P7fO?fE>-mI7}^DU@tyRVO`8bzW%M z5uf>8_63P@ML{2~u509q4(^cdqER#6U_RWt524nAMC&NNAnh z21+FvI?>On@u`s-I%3jR(-?32m`ZAQcBlnWO)JM}7$`A+MGx4b(nE`x)12C{T->X` z3>j%A{-lOQw7F_9niCoNjum2Dl!lE71uoVsSK1sQP~24wNp~UxY&n_--H8m{oLvPr z&}92$Ss{_7QI*3BjH0T^C$D*7C~p0@i$9lSSd_>P84{}GK4V!K0-^uvHq-vXB^zPk zznm?yd~-XYJ;KI7q`p$O!#SSQ1d0W&!(x4GfwMfv`A~vEDX5T3G7LIq(E^Vo74j}I zjSmcJ@wmfTp1Z{=4;Zvte7OUIdVJjjgJ#Ttp-?=SB;t9tBYsSlRDf;hmH=l=_u6~Q zu=b3Nc$QS(#zr(TNl+BEu2-1#m>sSKRgNh?Y@I4!;~jm}%Rr`mE3L+|k^F9@W1SB`+7WCmT2-@vJ%<0#gx)X>pl%I+W{ z-l3)pi=YwR&30-imayAIYN+X+3+CZ*7=}Rl&j#a?0s-|i(QQsT{=z~8XB+nn!L}>V z;vBk^%!Y7h^2h7^pfYiGuA+4567E7^uWHi$&4L69chC^V57&NaAHyA}RhH z7^s*Dq2$0oS)i?8ZB@G#s-I8A9B5)}Az3!rQF(m+kbOb2?4)o2w?Ih0a8yB`kr}Fv za`M8g9v)JhG+7L_9|8$Z?KnlxV_d|%Z3!YV)F<)cqdnshcnT~)kD^R7>Ml6#b!o2Y z8###qxw3BJB!(Fvf^@3hd*gwf#4uyp=6olHYKh~MB=4-6Oyp6d<_bkXhQ<$ueE7Xf z?CXNGnk@d~LZ9C14Q4o(dn zHAbgIYG^rawu7fFkGIXkVm#i{|UfCGQ$(-tD1`^INGc* zR&)C`^$I{iO>OoFNo0=rGt@`|ZN{uQaM9Q?fWSp2Ant)V z(3qr6X$<^$>bRMGYZw32kVmp>$q$(1iPTJ)v8GhR=MNbcUUOFH3dKn_Gv_n=fg>q& zoZCAobh&tU$;MK<7>E-DR~`9062?;8dn_@Q+B@E&mt)`X821wPjcDRLhE!q=bx{+C z3AE%eG38MG*sGI$Leg(J%t^`7OofGlOr_+B-Cf-wco9qP&TNRP0+bv^2emPrB6`;Y zj%+>dOyB~I7&)QtC(KF#|MKz9*#cX#@f44sdgKu~p=Lp%Wcyg)@iLymYS&TLXRzC& zSa8}aZc}GSwhzGD{TNS0LFhsvgbxu+sGI4m&`2aK#gxw;_G z*6_)nW;z4(oPZ%Ao(jyB13gv8$(0=Fsk*3Q$+jwCxbh5%5KU- zC(b4G#d2C`gvL=KAH|A=7LY3Hy%rXXuzgiWx*V7)mzc;qI~u6QqS-}zws}!XHl!kr zkREwEv0?9Xkug;&G3vVqk@@gNAr*^29Er@2PMa+y^(e~I^xKJ{(>&6p z7*UbqwT48IKPJK{C7FkKIEI@sc%LlgmL@ z%0X0dNCKC5_Dm`v2&RqUCgLT&rl{6x2|N`wk4gzVh1{SX64I|s`|?XsbrLR*;ioaF z##(0jRdaW-kei=%I4JB2Ldx%JG&4R5T^) z)~z28V)0d~?2zl3*UfpMH2_R8dZL@z{Rlk~6Z?U;43PDH9>b@${iPJ9FNPvrWb_18 zs6p?M1R6UeBqD1H8+r-!G-nK`(NiSb6!3;qi|-bXXG;{>gxxXOzEq4rBW(0UYC<3L zzR9reXx$|vpy#LoRmtOYq%b{}dr}+2Czda_q^PWA*;d;{aGw$xIlv{(GEHU0OonaX zgT(hblNZCM5|;L2^n@?8+(eWbm>)t<;06s$zO5z_6DZn6MZ;kz!xn zOx8Hzy}gNxd7e!4)oom1v^xEa5{~H1YCenLs_VP$G!L z`_kZe=@~wuA02Lr;S)AF&(i7QSoku&xr<}f6?4$=35(MG7(a30&X7QF<0?Oo!h2cC zz}gC)zpO#^MJ|ukO00;btOm?ZDf_}yM6%I0-&<&@^s^@#En$IqE-j@sV1WsQL9*EK z`B+P74VatW`i++OiS!Oif*{|z=gwvtCNX z^$B`s?b3KZ?9%ldIjX|%$UZHc1IcEa>a$EWf~uvSy9+^~XN?yg9;QlDC|iR4f;`5$ zN@UXHM^2WgmIG*^wZm1Gb0yKWZ0Q(;)Gf&&!8UE?XiAjZKvrd6B?tx1HgtlMl$G7TXhS&pmZUarS{T!odYa_=qR zkXPH2tDzFE(Y{a(m2ju!isfNBOu>m*N*6Dk2 z$l@v$$Raa&3CU`@yO&y%iy2ofw-Jo0QRS}iV-^qnkt}~^Zz+vt!k{>(M3H%T zjKY(82^dD9XC3ycaTMOmE2}HJ0sk-Ej8V{Z31!?{B1j788DoL8exN~r=;xVf}! zHITwBx0|q(13zdB!SYz>#8r)%M2$`XAyaKLrgv9pUX3g#N;EId1~*8x%I_&nQw^eU z?`TuJTR8ZH63q)o-IQt&1&N?n6^O#E+zU@$>?K+ZeK;Avs$vWHxSm=@Q0R2I6QzXW zQ+h`k48S5eea|7$`m8b4b+#pwx=U1kmtpN0Ry|(aMk!AJ9g@{w>vJmC0iRc6GZn9g z&+CVtU0X=6@xf)3!o9sb=kRCfM=~`@&K4);QVeMP+%e5HenwPWe!65OY4WyXK?57; zNxac7`J_#`Z^^3O1th56vt9hOfI7TPO-AoPt80q%@XAyHD&9%sB0mZzxj&r&6}L9G z5umDd#b&pZ=70gWl3x4l6W$ee^13W>FXn7(o5&$pTNmjx1MYC@@q6A}h^kvZSkU}@ zj>WqqUEe5rRcIbpo(6BrhFZIeyA-g5a}#UL#!t|MOQVFl3=%zEJvZ8ZI+ITo@Ps#O zooq?gCf3_SvSWy|By>RY(@hDgr-W;|7x07^zh&Ht)(=kmX-OB#=+3b(APV=8YfAu6 zxHMk4slgMT>O+@){*Zl1GX3t^UGKB8>D&bRaDE6x(CBX9>xkviLJ}%Z8#w60yL(p0 zx$09?$7~kRhf|**yd;N&=mYz>CEfFO{<2{BON9OfdwBLR`_{`-HhyZJR0p^;C8ulh zX|M{tAN-io8<1>%UbF2Nkcr2}=2tAmSkF9p1>E7bBlqn6 zF~z9<{Fs`4=S#x)q%WzTUApANgn=f!j@Ngrip%4EUqZ5;8Wg-=W0T1kNB{wX3!>fEOyp6=0x-KX=(<}8txDgCyH59xR`@NkF!R{TE{$b)^L!c3I?Xl z;HHtfjC-6meD!coa@r8%r5LblEC&q?+d-CKmv5}x9#nx~m(R2Y?JRZD$fu7sL0sRs z^kF?%VkHE-d}EcbWql2H`OG@wD+_%=vRQ+DD%GRm1Vr1^bi`QWUQbhok8|LgFWbfq zeLjRrvRuj7(k775rle>s2(ktlRyECA;A)yXz<#BRuGhrcEW=zIkSul_AwpoBA1po} z6~w_fUujwCA^->Be4<^fI|~q!O|waJeg!z_2Zy4?6oh`~t(xtcV4Tl8j8)5$MZ;no zCc!~JStGtW(+QOGjpm{1bX8E!7n*S*p8}NgiRDp>{mqbQ+_8Ri6#}PhVAJvgxTZle zGC&&5zii_iU`Q6tY1xcu;Flk)){;%I0D^gb^GM@ttSM*%?x>b%+>?!sAeh&gY#rbNZh6iM_;lB_WL1+pY5xTinFw55@@F`> z6$JA`4ALfD0>OOEj)d1s?0yJRYPUe+UThWyzkJ{J`WLl9s9bvlA%I{$v*Y4wV2~`u zIJ>wNDCdWq)FuW3!F*HBvd=ysm@myq>9bq1ixYwP$elLOEO!r~1sLY3hZ$G0DS@pf z+x@Mpx)d>!CquH5vmSM;AwA5bM|BJfo>P{GE?QcRkoYB*G%@Qd=&J2;&nY}N_K!X# zj=Rq(Z0&ZC=6w9Xw(v2U^++PG_2~;`O05Nvtysd2F8f}NYVOAu$^?#=FO-RqFJCCW zgZmwah`{z{dqc@vn?s^7#Pd!icuQWcP%=;FkSK310!YFYicmER%#Vxh_~i;EGrFCa z;>WE{OFOPmy6NPUkSi4aKesSFZp+6vDkENQ-ZPIU6tP%-MSDUKRu%r!o8xWxDtSV) z{VX=&9S)u224!hedme)x*Q(;ULCNNNyFm}3;Ozz-Gu%M!rpNVIh8uL|c>ZvM&Is#1 zZqPZ7JJoJb`&hyU8dbn=ALw$mklP2kMtp#9g02-GAe^8(g`d<;&>aWQ;{@G3oK)ci z-6xzwwmU|G*q18X9pXIv0>=s3!tWPO&@>|kBpjY80@}jisbZqPKOLT~@pU^q^Em#) zaCk-r#_jMN;R!qr&lT?JaCp`fj=ykt)_A^fc%H!YoCD|~$6@0{6ImgDc7VL3Yf&Y<_b{hjlK!-T)nOw6~tbCu&fw7WBMB5!x+is-fD z?%e74GVSi%Vaq=L&fOxwDEyr}0-(a*xp%yS{hjo``68R=(sA#Hc`l9k4)%A#E9R+W ze`h_ZcH!@24cwQ%6OO6$^moGT_L*6j$?}Rt#I6!IsDl;|)`!>so zeF@)Y&C#u0n>E~d;o7{NVd2`uA=O^`aBbdZ=x}Y;$a^`i%@%op;o5|K)?P~cHd_rh zMEEw_G5m*bGirq2zRlK;-_pL#rqT_!YqO28L5FLz%`oDIYqQO;1&3?1S@#{!W*8xk zAtMB^WXOh5KK}8y{PFMC|I+oJfBJ{tSdow>nL<_Z#RIn_*nkM-qD_l{5t!5eMjQ8o zo1zrStPaCw-z@A64yHJ5NN0z> zNn-uSZBpbMe*Q*ouGe#e;;6iy>9je|4Q{%>(dO~oNNJz1=VprV>zPiQ^W3}q%{Gtc z)?e$RZ^bs%$91R8>6;N|f86HTH(*Ywk1^qX90l@Re7#2PfE88U)8A_I7!%f8osK_O z-_4VpAduHZn;ba^H0Awq8~3AX8M#WfV@$e?u6Nw^X~TeL_Kox3AGdKorX}~g^my*E z#wj~w`gONq1R47V2mc?paX(_E-0RzOud=>9Q?$9Cdyc===K0*a`d!X*gY;m&o+;Yg z&%M*%YV&yR;<9P?JYiPRYYv`>^bB&ae0R@3<#m8C0h4 z`LF->U;gj^__u#OH~wz-|Hn&j{yXjeEIYKu^GU#JhL8DplF+snoJ*JJza6y;Km3BF z;vc?Gh_74FmnW(Gd*6Pl`S0JaKl7|gTuS;tGT}$>F~u&>dx4T^FGe)_I=`klIj5Zu z`fL1(zcMx8I-%&V@$38*Ca@Mg$FK8OFv(p5;=lS={FMj9YbNNg@$3Ax@i9LNNny+5 zxkK`7rDBHp(JCa*R#WKrF$4jJKkrZVcNS*)*so~?T>OE2OAIz^cOn&WUfBKg{|I1(h(X;@z=+Ue9X@igL%)$$NcnP|IY5iRP@I@0b#GO8_o>ZJo)E8r9c0rqV7(v ze@egl^@HSt>rdHo{PW1KM&*`YtDlqRx>eIW!#)0T{TI)2>7wfZ$|&IL%!@hsKg66I zXp8u+asA~l$cot4f#sT-e`?>RZR-^luDeA{-Zk5w{Fu8mI5)H2(X0 z&2ujQow<9jd6?S2t@-aO{BHGJ^WT>E-RQCAf9^313V2BVc#nxze|L|GMvwdbcgz{G z1LMVE0-cLr@-HRfLt&%;Rp7tCxBE+`kk?Z_H|6PQHz>pZcC^|#35IKXl5pIj?04>*b8-exTX+LsttSaen4YcXJMWnEQ}r|ijkLb?~7;cSw(1u&~WZ$9bZhGZ{E79HHrHk%G^NE(m$3~9ip!E4cw%CN#d zo(~A;OewE6gnQ-P50YE^rlioY$H2nUp09=E)}?9C_4yE3=vVir zxy}zG?blVHW14D1i)Ll1q55j0e?5i=(S`NZF)F*R=WBs1WR6#xMYr1|Gw(7uin;7T zMId3_&sWEx$phasJTO;|?-G3M$Gu=qT;ut1V6SZLIWgdSO#RglOpf_EyJ1N$&uRJj zLw2n|7%_K$PG_=@mFHT55i`H03$nE4c+NwF7`FWE2Ug6zze)CZJtM4`c|S*y{MU_b znnrQa?D!OPdd8m}cYh4TW~nSGP*E&_kkezuRm+2HI$jA+~fB!BZx4S`j~~EKV)B&%=Mfb z2sP|&KCVNoVa?C&2C;@|KHn6{8&&&8_w5n)vtIADuWz9@O?r1Yck@%bLbB#lmm*dy zR%yLs#X=Qmv?zhcguJ_GT39c_K3N3_io+ZsWyIRv{+gDv8f|AEVcT&*QCoF zZIXLl^qD`e+ScujyYlZ04om!~2)B*+F)8;-_47N!#o#k%ohZFKoV*wfILh_m;pD|m zm*u#ZgvuSngAO|bHyV(i!d-r602!5g0uNdQkY(r{BxjSZ1d@HJTGaH)3TQx}Xuj?R zt~JNJX@x-2EFmKp>WMW4YynhVGZK;!0cBL~sm5CYQ*B9##*0Y^=(ohGK&}SH{gQYQ zAfOD&9i?IwOc9vsk~9T70aKMliJJ`Rb}%{mae%1`n@E`=qKvvdrTAFHRGl}^jxpQP z?J4tvNV2CMuQzfm|-x*Sd_(`-GQ|S7;?2BP$RQO5Jg1=L;n_hJ*P7gpUX@C@d z(lxX2&;mcrIExkHngzgFBN*0Oz$}EExZ6o>k0v3xUi}&#NaD3N*C>nHxt~pKk5YI; z;Y5U4{R3tAw!)hLvo1Y=0)NG!U?iS|LqaRvAPZF(>x`f?pl?*V+?riO^9*%LHy!*8 zF}nr{C1s0tRD!JhfwIFpMbH^`TNIKW4se@Xp(rN4a)g*&1Bn9fRwf8ByZ+P>m^p_f z(CZzMFp9S`$m*n{Qv6t^UhjxkSrJhN3Oh)eBfSc5iqn&qK0#LbK=jmh#27to_=C_} zGsbGH84?nVIwzh2`HZKq=Xowpt1@H!i>5l*p~rP){LOCYrBDo2-~rpr^Sg@rFk9 zB!PAZgp^&Y8Qq98q!~N`{AdCiI|0|^84^UB0<$c|&KWxaq3AU~f5^TVW(Kv6S9edq zQ`h$gl8Q?bq_Z7srY2j?yEFy?910-ot zf}TNU*P4S~@}3O8@U?A0S5(bgPa>zo&BDikbHfn&!^{KDO6 z3frNyb2pmeR>z^}MpN9NhT2qWaO^&{stwT8^*m&KY?j~?G!i$eP3KHu2q`yVMwwj~ zVKHYtpukikkL$FAqdvChPB)msnp@m3y1^8djb6PIOhMAAZY9A6*`}gQA<1+tVrdLt z1rswSz1BHQ|7d_9WUjqVD*Eg35WUHD)eV~%B*{pCjt`BIK)`|m@Bo`I5{Q6iaAZe{ z23~x}_k;wyR%5kvJXb<~ZcIDU+p?Z#1!;UxUT24P#8J3=pu>*H z{A+3SBuFE-7_=k2emsPC<0xzresSQa>xHoa29LkjLKTnvSX`FmHr0kJreBlT)b5hfhH_f9Y8wb5fj>&3%VmT zpXz&Y?Mi~34Xe<*DN)n)IOV<-0@fELo)<<Hq;L`@$t?I37W=bUyr_I(o}P^EJrU{WHMYIKWX05)*Jk043R3a-H2EQvX`_Jwod`A>f6^x&S>S zg?O9aCx-+m3PYW>Ya>)2gF~usz5_z_FPMmtm1(w5EguY$a9*c#Ia4xM_;&}eAgB|& zB$EpYBjAOP2)b)dV+4i*oB^yb7Gu-k3CX5D@5GH99q@WxXaMggVAbJS2d4DT@nsEN(X2J4Xp5XL#k$J&GCKp zX@JzOEdX!lw*ssLVNJr?Io-rNSy8|@{zKvmW9&;lMrRqdN(VfO`f?9^4ApB@sO5=R#9 zz~a;*A4XMJz}h8;QB@~-x~`Hnio501y*70@_C_7@2VoWZDL(ZKauQccgoy`XRo51y z&rVo{HrY#N7*?T;+^55^syi7A62U4+WZxKoRax7abO-{epv|9cCbc;>!M#GVFrE9h zC2kNyQ6Mcm5F3+p_?_G*2T~U?7^I;M2?mpUDYf|khQeUn9TP-lK8{YmgCI&0*@GeB z`n+EhDF;}8BM$5X*^I9iL%JNpt|6_{!=BI6OzHAb&Q*)1KD3dw1x5nu^3&$?hwNH^ z$Zs4&5~fl>LIn@i%FSvJSXpWCckzd))-;1<=_@CXcI07L^=#9m-=TcF`q2cX?n#mi zDfrQBIDrID@$8vl*ANKm48p2T$@Bwme~4zhHUd`NZ3wHLPs4Pq^}II~a#NeEfYQn( z-feb~gt+fsHjIa#Y~wc%5cRl<{@vHzCsD=oUd!71?im|{##ASt!TJcVF(rzs&v75w z+WU<1V2T|+u#QU*NO@OUsUWFb3XheJ^v0}-;s+#XQa}DQB)Qz2gkv;IsJv0QUSDg- zXiosB-D!|pky{9DrXw&@H$%oanCVb!lgUy504KD z9JSYT^1!Yv9rG6⩔oV|9Q9hWNO^36l<_#5x{07#lN&IKYj*J%00{$?p+s*1 zCoaSEIJc4Vh>1IkPwZn?qs|)7$NCjQlrr1EbPIDH5QdI?kifhSiK;mb;3%wO7!|d< z(<&e=wU+L_G;`;+69W=X-Ia_NVM-?4hkb=@V1S1297tCu3s|~|_m}IxLI8sv1Txal zV2-U4P?xVxrvtzhxFCI%jJJTgI@M3s4n>=3Q{7B5$PxTjJ&w-LfV#b_pDDPH(AqsM z;lRTxNw_r=i5h`@HSTb(z+eN3-;-sIB@xz~%&LU38tAcGLiD*)+#Jve+D7#sAkZ!a zfne|ia>C~Ml3?Of(iNooU4|Tj&YhvN_B%%dXbQX2qo+wM$QRq)5`xdQJ)z)_BKX|N zXlepYVMAEkCOvquiUw6iAw;slbIw8K4gm?*=$Zyx6I3D?AGi&;u;Cu#8Q}V)lgC-Q z&;UOn;f@ap;U}WgX>w#N2jC~NnztmRpMyY_ad;Sc5b$wJ5-chn$+B*~2>1Ij4Nlfb z)B!}E##xgO0^0{?NQgc`zswDE0!&REy}0wt%8Hm+Y)g{|emz3|?&UX;$62&!We0>r zkiYtzHDQn9!Y&L8f@B!;7h~!PFg0~h)%*gMBJ|wn=CXtmh-(tS9tF@3*sb9LZtB{u zboPg25r|`l~Y5^mJl$I=O^i29Z+WB$Z*#wF?LKusB*A>o1?Hp0xV(>uFiV&X(i8KS=w zBiKnTcQ^U`F8ZQi@c@)#Zo}TO+pFhpq?wK0Cpg&h6AMEkq=Mem-s z$Ng@j@V6U5&mk}AeUzE_7c@8-B6u%@pJ$t5s2R9>j(RY^jxuv-9o}GS0!(#1kM{?F zDQj9mFi3>@vmJsHV5-$uKkFcT>F0@A+$8ZHJN7pnJ^`nO;hwhhnXSX`Hsy@`)=ULk zL^qJ^l2j}4yG_%Q9A`<2>^qEm66iFT`LQ9~XKAb?&%>h+Id6Fh-*FL2wO1#yEk4_9 zVeD3IpI(^-$?^Px0V^x;4HEg7AmM2T%EA{Z@QqjLR>V^JP>Lp8V1Q^cYU^0AvJ9{I zygW;+thl${rlVYt`be8yGwaXFihHBWV@^vn;>#Fm1#0ry91<1)gh0oHRb*Si4Bb56 zt|CY6TY`pGz5zUBr+GMKNX;Akp&H5o@Y$3?^TxQJ$01Vy&T zxf|K>*+yFf%t^M$S@M8M9TQ|qaeU0G-Sbai*M7p`g zgo95idqWstZam0w>{{XoCuz)FT*S1x~u#5GP4J%fPj!qU4@e6))0a zthr`A3Oo8~GMo1j-`zN=n?8L7Ou7X_EA(;eX`6W#d%&6s#(h4^w#odyXiGDniwu&P4}gT|8En3qaoh20nC_aVTi)Kz@?yMdJAUn0=oS%Cdr1_(cH83? zLK~pTj`Lz6a3KqwS_N$du<@v+Zxe{|fTt&p}Gsjt0%`ADg$ zy^|u^ZlmxHM08Aan}|q8>PAGd0}&mwHB!Q5A|KRMkSL^$?((I6x=rK?VIm8{H`x~@ z+=qvwaW;XHPS~=S?m$ZLsdM+<@YmTLrg^vnDVb;jl5IQsxhf|++QRa(36;vLO|~6< zTaoQ-f9zO3XKoaqqaA(QOSA(j;qDqTX6>$5Ki!VD?Kt$E6@vYE<_j9hkgoTGL}6`s zQ@I@>ks*EBE4s77+AxOlNbQnjNDq_c4zPr+l^YKv#Lw7T3Ep=p*6P&&e;3(PAd$&( zBM7uexh+oBUE0y=$yaqP(-DV>t%`8nSx68}A7z$LX#2pYX+JKhFQyb%a+@u+-Xlh4 z11eFKb$jMF8-`okrRiYzDMO;;7XmQDh8v| z=KxlPwE?yIt?D#{UJlLP1XG0)f8n|ghF(1M?z#_#_B#ZaYQy$YNCcw0!PIWqAUYx) zb}PS(-__0MchR-{h_4zY{=@`WJQ+kc_Q>KQ%^kAq&Q}{ny50BMO}PwwKn*himdw^ce30ud)p| z8|Z$lhjQM%TcyJtBKDObPk4_YyWNLXdgN1V;;a5pCg5z5N)PY!?pwI~xN>&jtK)>( zBi&{(JrD3zes1}DDCd$cJ&o9?_Pm9gbQ56p=Y9_FOM6Qk*LH6+0kFpOxoro)LalR+ z*ih2tW7``JY(sQ|pV=N*l+$yY?NF5*PdFXeHnYtJJHXUDUuQb74Mpy>_^0wF*oFa1 zd&;r-Y|{k2XLgMK2AC@I)uuCIn69I&yF0S&aTS?@J1YR|k(Z!1JW$%xrUTnpGA<;t zM{Zk&KYz$T17whOUk8-6rA-vyRqPF4c9QL-a5unN#z=31EGbe2)9=-N z44Ter*a5QeCA+#A@`euwneR1^s+Vg7#6|Lkcb)M!A(ousihPA+P9X+b3N{gze9uB^ zI}jF&AFGWK)^PcQ9RLdsMK`Hd>WWf@L|K>-5eP}Qb3EJS35k@tVpJfJm4kLg_Z*>Z z*}!q{CG%wRF?=6R>CFG9WTl$rC;HE=9%M?Ahb<*kFRw}SWoOe;8U{R0#-YK zL|&syqR6&mO}HdIT)XEg#I|YY8NL;{;Ci2iv6qAu4|vww?wRz}v}F|c%yNHE39>fI z>#EEGF3+Ab>l@%I8G$be%Ng)_ssyZNz{4n=3Y7Thso8Z&SpDQBAq&iH{8YSNBiee0O?tS<@66TBXW)P}cHijtjQgFz(pzKTJSJO(AbC~?p0 zD&n5kFdO8I$a1o6~!u~j8m z%2!~V^?Myz6;Din^Kr*ilH6~oXPt6cP1d?rZi7n#hmnq+B?R6tl%7FKF^8bWosi`7 zaR;tm5|SF5*xp;^~$7F*^;N!@H#@+O?|<86`}GoW&hkgWZ%(2!+s zDDY84eyDZZo^ge&nad!m9>2C?6GQ0(-8^hFpWj7TcEmd$cWmM%G2R)D454K2he?N( zzNa9ihm+N|x2~c~K_rs%-9~t4Ov5iq=6=|C$k)_moAC%|1D-KsPrjD=FWY!zOQU49 zhaHHe(fJwnefO!)ulUIestMwzfwi zZ?4U;eV`0__UFAzKBGQDu=DHIFdePeE0ikD{b<`S?Xj`hIIeDx7|!7eT6LoAt|4=SGvcZw>kB*y!ngmXWkL?`Ihf+7B`h zmJO({$1`|h=ur#F?(d5Povp>2SzwDuq^3TRoW8P0JJar5-tZ-qr5M|F~-xVcWTfbb#EFdw)yXO{~JYFIIRfKu6 z%29ehGr1Ae#(N~HYils7H*us6t7C77duw^FIALdzj+~%V)~e|H*#t$Hs8Y^*qI!j= z#Y3{xakrqxu*+o00vA$D-nYsPpHkerYjsXLEXdpK)w$wn5QEG%-h^0LO8P_ICDqB$ z3YMDw{2>ExcuoS^Jq{`*=UiY*^iiFooQne#j2Zyobh6O_Bg=x!__`nE>GZAD^ zW>pSHZpiG*I$O4NDCapBQqw6gJ<5G#9g}47ro^@mA9#up zQ;*o_T#T5GkAUUFobI7mwT!|$$>+FSLNd$qWQWosUG_c0cvRl8n>xNJ8AN55i+e4Z zxE^f;nff?i%aBQ$ivl60XA>53rRl)0UW-hL{d~|`ag##DvIyu@!bNz=sk1>Mm=)VDY2a~KBa*XOtsBd z)nCrR@rf7JchY=Ki2z3TlxSTWK{mkD2pWS(mm=v+e zPbVZ)^8sWO?HS{>$s^HT7Hv7@Sm-i4_Reiq(yU0KfFW@vZgmrZqubPr5fv+Vj?M>2ZD%LMDU>r@)p!ZTdWAl!@e(AO%++`a0h6nQ zWT|JrI%@gQEZH3Rz)DI@p(BcIVL90B@2Rg|jhOD4QH_{xGjla!dbU~NuJSBkMW*qz zAy?z2dlpvUCAr3y>zo)b-E+69U?J_e8fHk=w>DL-gKeycYPoejJsH&q3Rc^;LgL_I zJ6bB~z9}(CMjhTJ=a3Q`SRpFE96yjmCXdUvTo6j}LdMZG5Y*jGQ98m&g`&iXDz+ok zQe+YM!S~XI~~zb$hs~K^4$r+`j81Ucxq74XW@!(+@qhUxp+4lB{15 zoDo+ERE^?55SF^qoBBY7lF0RaQDyZls(5X(knC?)2~?qDZJ^blD#D~$jydZ+tuZ0l z^)2aiWWX)%g%dWXN1OS}VccF5239AOnq{`8BeJEgtAG_iGJhIZAx7Gh9k|LQ4^nm2 zxC(}PcN+$$#G1vF$lwGNJS3we)o95 z73mQ7S7VnG$mXzW4E2;0`7m6xnN`S*vQLwyaDfr~WaXyyx~R*` zIKrhLNRX5$>F!*$K@n!;lWMf+3 zKtUyf9BQDTY%5K@K~VJ?3=ouJ4elY&Y!2%WBuhKx;Fvlh7M^xce$+K#2s0vDxlvaz6_Qn55KTEL>nv&vvdE%lMEMakap zZib?GQY;s+fID9H^s|0Bn?N4|B;ZNIV^=36`c^*EfdjldY*Sk`NWiOSftwf;cf28XJh_*z$B`*xO7_TvQp z$x8B|!0^W)4)ota^WzT=_#?cbaJ~#`-7Keq9l?;;72!R!8UFOZLoMJ>&|zk9eP@NP zM>hd~f{->z3Hkp0~1Go+2Hs?XI>@W5rY2|phm)q1| zjvzg4m*?O_}9XQe$27KSI@J0x>;yCScY((47vtS#F zSG%LMKnPp}031o#j4P~V!T&u4YO3FI^k2@6@Z=f}S34(XkbNg_R({FhaJA~N<_w`n1yKM9zC(h2G^S7IdR*NQ|-$ht^ z(*bOcdpUruoG&#Uz*f)hKBtgmjngb7Gr#*;`V8%ULIK&O1?3}WUf1G1frVE@+Yj28#4@?IWIYWTPv+yu##xAjOA zt2PeS1&^;Yp5h(0g4IT_aZJOhRscKZq~z2blP+|x+6h{bu~>B)7@mAu)!jMA;+;9K(YmQY*qt1u_JqZ z7y>1@qXxY@bklp}WB?G{DzNP)5pO0R);Q!sGDqsx?QMd{8--e=&u>*gy4~E9LkjMra zGY-&7dtN+pZLuvnG_xC80nz&7RXJdB==0aB4&s0G;~@S=8^Nd>J$J*X9=zun1mL5- z`TmsA5$4eMRJufQ1#%plEsG%m}ugYB@>e<8*{f{Pgzuu1r5cM7kL#F3d>u7H` z*`d6PGxfg9u=c>tqWAPn>Gr?gZ)FgL!$x)+MXWtWrz>LZ*@oe1kC*5z!q4LicZH`t zCW=8+?`N0kGpyx4j`sjjk2dRA%j4z-QFj}Is4zk)CGIt(fuTkm#Cl+;`}u}r{>Rx( zvDv+!CScT~&4E$ze1W4L_nOD;y+dHH_vvOu0*#Gr1o`#V#xQDxb*0Y}^lzBQB(>)u z5bR}6sELOO6g8cqNXcHWdr!Gs(NA@oZsVK1Azc-*U$>g!`t~UmlDXe));9|%$==HA zs=!RglG+0^1x02Cjhs)Z4&VUQTorD%%@c%&xxCxd6KXCH+ygW{Bt2XdPOa!SXo_cM zwHdYL&*tL^RcGiP%5Srpp@X2 zw~XyTwUfgFYH)kN9fb?h@9I#eAwdZTxQ!8zY#oU`I$!~(5B$-lg%8{)9Gu_wfuEZz zP;KV><`JmoPcsaqX1;HA0@Y3%K`B&L(cu=7HC{K*Cs57PU>G*d6xeteHqEGpM2Qnh zH7`H|KHPD369xXe2mmF5O=#1P#DND6d;tyk%pTPqzY#g7Wc4h7zv^)%^-~d#t3#h^07#l?3Ri3aN54e8ir{@j=9}W$d zhq2U1=V{tWhqR*soZk`6rkEZ`A~nbTv=hzd!`CpHx(}kmXzJkb(N2Ek>DclADdMj{ z`rW>DJcA?pbZmU}cx27`nG=&+baI0Z7^^`c;|C}np1Kyv9O3;8iSkotN z(10f=?aPY_iEWiVj(*={SbsR;$$lB5F>36Ww$6haJiWq!Az4oCPrix?0Q00$ff^jT z9@xg?1JzS0iIp@I()N@HV$Bu@o}ok+;2#^42ZM*%#z!egSUBUp3j6=2#3A9sAZwoE z1IWP{XWYUBJq)tuIe-m=EVS`v1dz4Vk0RZMQP#6(1-8wT{{_iXo0ti3?sdJFcO#&z z{isfn!30hPb27_@QPzyWz&wnyW(j-zFv^6*3WC52#yLYE2X~f^EoYzt zZ?AA}P=OcO!%sg>$dM5R%;2^fueh_b0FE7b1e%(Wf(s(>qzyk?L4!d$za>Uf$1nvZ za0mT6B?3&~ihXo)5(HkNKDvM!d^mytzCc00cw1sHb$mu6z*G*4Atc@~JO}oS4I}j7 zR$$wm#yA2?CEL_Lf5^ThaYTaiCZ++_ouJ8rpE6Up?`ebutS$924eG58!4+<{QtzJA z@am3}orYH@P<9$!J)0=1ZRp30XoT};8L8-imO#Mju%=LAsyMIJX<&8YjX??Co&mdH z1P`~kwi`&c*%Y->r*Tyeipo5VtL`Xj(0}{%V}}yxzoRsW)*K{ry+%7b{yz$KWYB+G z%S_*DM;5+4MUX5VEWC+>54=0tNDChH-{#8jor>fCYXkyAvNX#bg);+I9d8@hzpG%4 zBZf z2Vgorx*723ArU-^BLkSdb9?tYA}7yzk2A2){WO7v?$@kK=ary6`}`sMf@C{C%xPm;+d@3BYxdw z39*n1{Xt+XbSQ)KG!|+nxo;Zxv~ymVLvd&f*ms-CNq~TTKeBO88@A|8!=6KXoTp$< zi{gTL8umcae37Ei&M9^p^*kjCXMxo>a&j&%2eUe0Lil=)MXdNNyT~$QdB$e#-zs_egBV_Xn#y zB})da*eC)8r8A=2v1um^1@zs;oG0Ftgo0pzl#OW`1>xA^B@`&A-H+_3wHhB7^xY0B zx3yyh;z@xTLEqgJuH?sAMm$f63J%=c6eQ$_dq@<>*2aBz1+v|X92DMJjCR(-kSy;) z%U3Co?cRmJ;oV3BejZ10Y%MAsQo=2<#0Y}a8%h|I$y#a4*awu!#gc+q+S2LR*as57 zRaO`qN>?s-tT?tK`TQaKf<$--53S|5jE5etVLa68`8vi!t;J+n!b6w9&S&s?lR&)3 zo&t%+-IEzi-%#hwbkdy+hguXA%*%M_-b|PAP(QA4PLpw8KwGJaor>g4NrOtQ}1h$Ts4nwG4-DTnd_R+s++Q4w`S1 zy%ob5eh`(Jr&_({vJ?)vou7G*t;cUg^T^H#Fm@w!_Q<;%}FA zaQGmIzmp)YW3?ce%1LubGKjyM&LS)BB_IW8;4i$UoQfsbQWoo&ecUA)GN`~El;(c7 zR%ln8>*se77N4=z9U-xdt$Gij0%~xxh&j#)MBoy{_7D4#4It5tSaq@g>*;{3y!{XN za!3994FXv`+Klk+o;EW`#7-OM0-VLTPd9*fr~9*b%Mut;Hsz@ zLJ7;ZY}NbDU;v+*w6>dq-Ma{X*h;zsMID1V_`a8LU%WzYu^7#F1a|K#sN;zPc5gBw zA5Rb1y-C@e&UY|A%HiDrl{XZ1JwA~weDn~MOs$MGEWbF=&~goPJ&mysv*PtMrBMk( z?ME90@z8dr}zs)HB<*kq#cm!zHAHz#Y%6s*wG<%=i2GL-qxU z&`*o#u5IvBqiQ%MJXGsG20krYd2N<{m%#6My{@)&Z{QHbzB=7R5&WkhP~L_;_j!LC z_B7C*y)5q}?Hzp%Z28_V43OWRlmK|HV(XWvV9#4lpaBkQ2mb3_tihCQ$+<8&kNal{}-ou%S z$6^J}Z3oSjxVxYXs}1WTkqYSJj(`6AA;W?*ym|C(c*C4+&4`)9m}o=+iBoB8BLFkE z&QS3hv&IG=pCSxLCuDpZ;J`?g+;P_iU(Sn7mkr1Pra;4O(^iVd5nV1Ou|LlRaOV4> zExj70Dl;gzi%^K6F(iAv+lVcaO}4Pi zVb0H>+|J{DQ4O_v+O*KC@lIQDboc3F8_cwAyYDuZVI>4#9JD<7dP?-&KN+%|3L6Bp2Om->9@ob>m({Zsn!?jx%r)1!~9?8nDD zGMxByxO%zvmzIaK2ckaQ-N`HLb$_OZ`ysR}X15bMF0sRUvfP68#~n znRD-(*A~MbHy2cTHj#zs+3|>^*waSTxsNvopwoNGS6IN|o$|Y%tzo}kqA45U(FVrI z*E`^(J|6g=5)XU4gQ3#N4gLHf!`f>t(qgNpH!QlZw*Y#YuUXkf98=E&89qJQ7(PAv z5qxUf*sXy4d%UMyPmva@LqJKwPmgsS`03F^8IX_V7YOQp93`c4AuUT>FyL`>8;S14 z*2mc~;_g#Nq(?tX_KL^dSNH~X_9`Iy9%@s)pALo4k$6h|j2!!7^<;t1w7ypDU_JsO zy8P-xH3iyswoL)8cPa0VMWFk52|B@FLpYR=@ObrrR>_v$k{EsX?s*-3?nyUPQh>?O zdiANa&NB@Qc)gQ)7O?&g$pMQVZ3K(j^qH=Jsk`L&(Q9*$t`TQaKf+Wk` zcXnOScNgES>;Aw>`Q1iX3A{MPZIo{Cc#lF>+{Yu9aXhcl@d*1y43M$X^HxiS?MIs( zycIF>z)JIVRaKdR$0s#ddQ2#TrN?A3Sb9t-gQaI12gDtKDDi(z%tXA?`NK)DZX5HdwkZ0$A!#gayfZFVY(roi>h(JJ=0e-C3)D zc}#(fq&i~tx8d`)ff2a6o0=?7gSMi8>ABU4^R}@r=(}Bo)%#u!U{ua)byrgQ|LXdZ zBuR1|*?pZNPmn@_^9g$WJI)dJ-+tEtbn}R8c_L3LkaQbpB%zoTaUX};=#Q9NYD)I! zke2j%&4x~sf3)eWD2%DyFW?WWv! zQH_;QyYFpctaQCuQD;q_)H|kL8j&0mSyw36aMan7)F)reVChz)Q(~r6+psmk(!4u+ zD#z~jTZuZAWA_|G_T1;K_N^C_Ia-aC9+z3JH<)%p1vtCiJx^6HlpJMw7JrPTe7eU= ztd>=T`4X#V7n^(Kclo9l<{Fnys#r3!jxZ;6t>j_|t=+XhuW^exO$wU_ zIJ-^7aI7*n8w)%yvy*qBd#5Fk>dI0LFm`);iWVrq*lpT{{88elxKEQf>M^G2xOj|l z^v~Myg`>71T=k8H!E8?S9h+zvyLn*hW2dgg}*2)&0XGmf6HDPp>c6B+`9-bJ-1 z>2>)OeMtB2sxfD?^-1W#!F2$XBLX_Zm+eslG;Q5AL#+eo#vw6Jj zk(d7UMwBwZFT@`{>Jm9qypy4r4E7|Q+LgEr$#=9Ij!GjW&F-5R>0k51> z!M-(=C_osX^`4DSY!3r?yc@2Z)RqAr?>Z>4wF1crPS^I2=qh{&SXIXe$r*=AH0rQo(hAUTy1Lqd>xPi)|E_t~cF5OwIeXEt4j*!H&I z!QuTn0a5a<+%QUB|Aq?pTyUEaSRN?e5J#@VlZ`3^EZ#6pfI9s7j$DT)3$p_(-jf2K z9!Gp|GW5XT4ZZ#PXWLPbzydi*>lR@2hTaAjfX|yFui;sDYaRt(&%EF1sPgvAyNCgo z&Zk6Va3>r0L@SEE0(|Lwh6H;1WV@eehD*4mEbJz{bh1xzG~=a{y-Nc8-9?k9qG(D0 zm_VP&OxS1!OqgJ4O7M3#o$5B4ngA0%ovoB6z=Tg{CDR0$AW@9*>zC{s5`ri!3-2p% zdIwjIRW}4wAw5?hNWN$1dK1w^fYQ5DgD7bwnjjP;N|<^{x>oV=Rf(UtijS|#fGj8u zY^{RNI}RnPKMC-8m%;tv4GqbXstP{}J&h0;34zZ0b?9Q3DYH4i=UpjK=$8WTOvU5_ zblxwc1d^PXV9_mT5tfHE9TXQ7LUN=6tztmtJ*OlV(9Z}~gq4>ed?HUm-ih#u=Z%iG zCisN&X6Ew|KH-#7ygk6&4W*4K(tc>I@K2xUP1p%Pv7TzePLQZpCz`Mms1=%*zJL;s zLw~5oY%`4U5zqvcAkm4`gp_cqDtR@UkP?O{Eu4})bQupJP=df15xm`fd_E1GjF9+f zf#fVc-|=L1@|S!_h?F4lkqPSVn0g%Fo%yet9e)O9TZ_KNN~!IFJ{fjK@Oaph;sp4}l0T zxk(ozXgX|8gTEWI9@n`83HB#w(1ss}!B$-(GZ`e`wNbLHJPe&$77hitzi}eMiR}}6)0H?|vT6pHzUwCH z&ckifm55*ELKk#Gnt+ctW2crbqOV^v?7U6yA~{WbL~l~VL1HT%4B^|L-&1Tn1v*|I z4#rch-&fsRz3e|W=*re|AOi=?1|^MFF1Wv;%v<*9i!SukuEOd@PpHanmXI0_ zV{9jb{2N;oq=3@gApd@0a{S6>F-}7K>BSB*aOiR?6k&<&qZ zFS4%$x*U>xV4)=hXoOn9^bOUGJaIXGA%W_aY6r{r)W0jg;Om#{8xp}M(C+w^jFx(K z*NJYl#GV;?2g9YFU2y_T-=Q(y4Bg;})kv?Ry&Bji^k*^Z)6|& zkdS=@96t^LgT@=m0BT=>B1rb;7!e5vXuPqj*c;7bCihTJPHIYUp7m@?6`k9XW2~II z(GO~$w#Nwl^lJroqo00(1Sq?M0@dz({a5~!KlRW5{?C7{sks~IC4hsz{{vKl!iPkV zg5Zf`QnNO%pZpah>M_7EG?@UE;Pk{8Ju4*059hDCuH31CAdx);@Pu^@iFOol5j6bs zUX%3ze8M5gqU{ceTx>u}_+rm1tJZK`XA~qTz50wCjbBy@FpSMy@_2U7DOr__oCe$n>7G4UYIZ+af##>Q@F?fLGc(qA8A29u+oVi7;X57zbq1 z#NQ9NR9nkibzOL{Lg#t&L6Gsh)g(B0kNNr~d+ouc-Tb_p;5?tGN^(B#&010XvkoC3 zs9DDI61&nuevXmR{~RMmx96DVm2zKdt1^1AwN|G@^Y(a6z$Jg-luY^x9$$DbZ_#0O z3UE|=eZJ%t4t`!oij_~O&3}ql%3X1%GP&yU7N_11;V*oGX>HFj?dPPw(2@4&T?Q|7 z1W@r<%V+R#<`_aK;3Y36PuN*35ax>#h5{Yo1s|_<BJ20tp&)m+I~DCAQLpqbIf8O_&pf_NToja z4J5fV2cnENEz0U_gCQvs#CakI^gnOSW6&R^{?@xDv z`YHRSWG^WX*?>S&vwhxwdbPZ-%>>2Ad)57MiB0+A%fN8vcj!6mwu&F`9hL5q=NMJ? zLLy%VVbqD|y@IV6o&u22d|ajbD|E*V0IO1`=Z|EPK&LBP5U?tBdR}LFoit~O0%#56 zhrF`9H;Y~|j)7laKT-r30%S;Ih>|0Kyrj~bz2`t)Fl|VvMe_wXOA5T0d;mC$tD>Z5 z1MO1a3kJQHrwbttd^s@JTOy8ONc`#yjJzfp%&vYyafg7dEMMX#UIcI1=+g}5+NsW zGHL=*H4JY7W5N^&H<1pq>NjG3A=RW-0dNzn{>!oe2?A0i$JBQ)^#mw2<+JR>Oe zt8ywym&BlY;;E{_w>8&|n_x;3wWBx6X!3Z73$YV6HMx0+Y5Np`Hk?&uS+MQ3Q&0@O zQ6_!B$&rNKC|Cm}DY4KR1u78Ed!IuFO$fHAI;4|K7%_D5K7D5L~j&WWFWov z=>X7#a)*^&lKWC<=}n~BS5Mv|vFxD{N{IH5Hu#ANl3sT&nYGysl152}Tu7j+(euL# z&>#s7N91$p21$JDilS9nO*M zUokDQU$++;pne7q5aG!nCQ?;GOj>^4@Zv_1B>X6 z0$>NAs1Rl+Y-)dikgdfCoBp&*`3eC(1uYycOQ5FH|G+3y^assR0I(Ztl6k%!Js2Vq zUI>6qFBQd@il75v(`$MW1d;=56w%c&ip39z<|vq7gy-}DhhY=Kg<5pOunB=n`CW%$ z6MG>Oag3rQ6!vQlU1v~TGhoc979>E_h*qm#=_ratBE~JCfc_|OOtC9=)7{nJ3Nd&& z?}lL$ByxaaiDKdrxz~Ax{wPq`al4M87Yb$}ZnrQea2nk_kIbqNXD1p? zgYxo@kV}cJO6jadGZd^eHva4yqomKYJs}aRBh0wvdkH4dQgXi0Pucf>II5uKVVlV9 zjRq-zk=TGDu)jmqyS=LBdbS9$0Gn z0Vh#5S*Z23-0=%2O=v0;{eS>H8AMYrY{#;7el1XYA$qyP%W0}AeePt@WS-w9VD)JQ z-eP#Yq0)4Q5K9U7%E}`nGBI{2J&d%2h!&ot^BRezPP<*&e#&0kFYy(DxGp^n#Jg3{ zNPu-RSB`xI;1NE_AgAULk|oRda&0YXPwk2s+^?${@tT&1){XwRv{TlS~`K z5DQ;NSw_PUi=5Yb9z!fJW&0!VO2EOdOsfsMjL2JTloDWza;eapJczKgoUEWX8{C0s zTy_-lD~Y>T(pw_GlDK zcFnvw&=fKZMrJJ{aT7{?_G#=ijHVC)@lMA|W7gd;3>rpL%!MP41qSD|M@C7ImIS4a zJPu)0CMqF*Ta#@KX-RV``^Q_9aOzJEg#)<%f}MbLT5BL4a%`~D9pN0@TJ0@=?zN(slO0KzoDBK9We znFd$@&(d4SFv7P0(jI=GB{V*>chD^A{sT)YUeUd6+o%Og(L^WG`xcUOs|ggKPYv20SPUqeI;;Z>Z>F52WtfmSy_Kf4j_)Y?$Ee>a;Dx?v81I zMHk-G&ARp|VvEE<(*TPOD1E^$#(X$t{Hk4j+xkpb8Dpcb#{jt0X+2rC*}2z+dI)!3 zpaO=V62GSr7K|!OjId~2=y{B=aP(+8rfUPq?d37ST}qs%Psm~(ankwBaG(!ZLSBbC z6lP+t4ywD!c87ydQnvRrpu%yR_gZva^SCRzvUvWP7_4`PQ-FDc%kj%eK;`Uaf;ULk zQHqh`=aZc%m9s5hz+_8doktvdlzJE19fQTf>>CRMDB}X=RLiE>)2OA1ED% zN*}H|fD3JIpr<8gr?<|Mu}XZ;015t!XsPK}@X{@!C9NF*Dx`*>!N<`9 z8c^Y!(}%c#s^r>9K-GtBXy8r)ZP@Gj!~j%BSx|CVC3IIJ8@~kr6%s8Xo2?LXBhxaH z!Ejzcl`U={fh!XVUkL^C0;-m0@Bh@@;4eL6Gs26}%uEIq` zCDg?sD*@GV$;nDQb-S=5EiFOvpbbXpM=3jeN9^E(6q{VhT<>Wn^00=R|9 zrXSjnig{;x96&0-OQh9@exUBVQ z={sVqL5bquYsuRHD6gU@G+V*E(=sUY*_Bl zUDd!6!7m+h+W-rpIN9CX0BhV?-6~!KDidNx{}r5?qa-EZu4*9(r<}jFxQov8S2G1Qm2qfe#x&aQVa_p--&U z+_CN~k9e|obwZ?etmn3ye!aU=?Sx2}TYZSBB0W;Kc#NPcdtipHEaK=x9M}mBD_s!@omo6*zMd(h^vQgr2;8=VJ*@Ac`dDiS8=UM2H8; zXM*l3k-QyRyTDBVnkbK_g$4=nL`l+rbXTD#4?2d)(de#1PhL639O$l6hrEV@{gBX= zcXNHwU4@9^Rso~C3R4mznLhV&DjZ@?9%DoS7q`~)7H>aG75U+};Y0E9xz)0l1$w&d zb{-rmw-m z#hPOVXr;o4Iaz16C5Lm7EU0Lu!u-QX&pukI&~3*JsO#vw!>1D7-=-2kh(>lDBm|m~ zX9jwy5Z>1ek)fAL8>&KAnCh4$0FX@nEl6OVvmW2qQ5qOr*-H3EGZknpfVAe|`%l^T ze`v6R=>%{So`(dOANG&R4AEd^lFgyqF^ia=+&a3MN(c~S7P5rIO|Q3~M->E2N~D%T zhn2zZgu|!osaiE^W!x>HCl7d@up2#B2sPP|?@-d@$zyj_&JU0i(-ONO1bVK3*ebR; zv`$s?wn#n{^k7jGG-+0jQ}hth$g3z5Zj?OcAOX;Xrr7?~;acfCxe`t&b_+-*zZCki zC@FEeDjyOY3rGr8S2J{KVOHX7)+XrGGU#5*@=0`RL2XGN3FRQ6azkMnS2J3*(397* z8zx${&`;1Z@f59E=*a^@X}XRw;d(3nOXy+P)<2<60l+0HW=5A5;!GG9)OG06!YFM` z4>TkS(`MlP7=5sck}uhm1lR3cghVuV{idWtB9~pyuZcJdT$bRBqh7~>zC}c z_quZ9;N+Ay8U0&`G<#ak=-)!5*)zN1xZD!CsX}S!--4Zh6f&>euH3jjlH~{uT<~A; z7J09A<-uWn37VsU3%>=*>_gXa9^A|>0qEdDtO>#)O+8uGtIP@gYB&!LiKslP(ZU5v zy^CHN0;R#NV=ZxpY6`GNyxQFt3O=Z1iBh!?hRk10ns@I6;4>7tMN;kXm?b|R&Uu{| zL&gX)j03fe4v6i{IPh~YLUp#oxRI{5Lv$qq488hRnly zAQ!0~T1^C3gZZ1&lC9zsxR$%F>?AlKb5LLkyJ}cr;6S#%Ne=)5s(yJQto4fUM@`rqY!LGFBg_v+}5vgBR$iot$eG9bTj++(fnzUHw75h?0pY0pMBb3aV)N!XQXGHYyst z^g++T&I_Y&7S)&zcuJs3R{A|_A-a+}JiZRn;FM3}m%w*vbY!?mWg)tvv%_sPA=!f^ zC~oJ44lh7GBmKD*EnbiVgeG8K&O}&*f9~Z52}@Z@wqPwpSOkQ!k}6ufDE{PrZ|Lw+ zg*tK%5MeQu$eqLs5tcCHv;-atIpy?LpekXmyPGi=JZ(#oZv08#QM+x~OMSZuNo-4Y}`K#PCL{gOGG6j-qlqmF5(aNP5r1>ilNm1gy?C9k}AXo3V zBa-@f3nD4PIQNr=1gqll;z(v}1a@-$RrGS{!3oWGCz9f%=e>xe_+dPu08*PDGfxoX zrjad9C^?G3H@}vGBZva_nY-^(hTS*hR}^11f5tQ<)OfksaUquCK5~m)NcQ4(bUWHY zEcK@|Q`>KG$kKfyzqKTo%CZbfp!gBR_41m`cwL!WVXeE52o;aR|`W z;Km6nnz;}Jjk`(-rg-MMPaT@MG_#sdKcITy&hqyyfVckot}1%D;AjM`rW#5Yf+-rf zIbTbp$15qLC;@Upt2cGGD+E)Ff#ljHn4)p*E{Ms6!FTw*CIUZs3iv~mfh=!`1>M`#_{>$MOz zDMQXD)h6RH$KTG&BR+v1fxJ`)_wP#yVKKC(;*ev-WttcXxF$-yQ23C zaNg{Bo>b$gk$%65-Y>-lQ;(Fm&4pXZqW6ni2r5)oD=YV9oE86SuysMpP%I^M&L^`% zMfVrF^h>U=T2)N|AERFsnCbA~jFkeGbgjR6??b|Gc+%8{wbCKQ16h%kiasw0LZJFm z9g}M)*m3*|!KKquc~)9CR0XoLYo#-aVHIx~^mw7Ye%BTxs>O9X=W4XH9Q>;_!P3lD z$Th)IOBGz@`vzE&8C%ifh1oIbSNi%Td+j~6eStDZiL;t;Rs*P>#om<2eU`7)7^p?X zp3nJe{1o>kjGy3$p1z6#wYP+U5@7^6$10k>z`cRrF5gM`sU;w&Yn@HB6~bF_SclU2>zC=hsB+0cX% zf~QQ#tLW~+3eDTSz9x9etjk&ro@%nEQ$p}`?vze3Ah(i`6y06idwY3bO;I4fyHHoU zqUa3Dj|B^bQN5fSWRTkzl(!OidLyH1@U-f?WA_i)wd9(sjEnV419QqhEVn6{B2(})_y_C`Og=7&m z4a6!)MM?NFjkfs-$22H$X0*HHqUp<&i!J9A<$qmHx8*BOv4HpY15PRPw{F_%zk5+C zn!eC?*RPt{WP*MSftyyy)?SlJP=&|K-@tFHhpFCf=+L@z=>mxwC+vK5)fx!-$^k>8k(~mYdT2Dtf#$wV6< z#|soWDk-$Of?2}ECt~QWX!7D>Xu0eu!3JH)Wl_=h1*&{*u{&3Ed1330xjf7O$d8&pX zRl82YFrlKhH%xW z$>?6u_XUPF=n<3b7aIcjE#FC!Gi9qOCI3(7!Jej3B5olT7>*$zMH1PS9P>{*>e=<3f69#oFLo0B0FJGs#rBNFu z)u9B=c4S^nUq{%g$JG+XRyX~+l6A%%Ro6_()`4qp1{h`7CHlQ`4W#DPT45k{iGV2C z=fMzF!$4~Fd#J3S>ulY43YcjS2liH#nTBiFTUCzH zd=Rv&w}p?Q?FJLoWuY~MtUe^}FwyR7A#|A+wZ%5(v(wN@ zJ%}hEvO;1({z(VPx+eq3Th#D0*O75mzemndAFg(dxiGA1*92^aRcJtaB&fvNHCy!5 zW>i(Ko`HmEn>`VF6RLtrQwmmXf>2af0^8^XgGwJJJZ(wXN`euj{1qV-&*NhWAr$Py zJBAPnu^?+|Ff74IGLl$`k}b!Dqg721s^89n6^&oIYUre?n-CQ9L`tOO$Z=usK_h}f z?yeUoEASQOvFEliIp*oOfP{%aGfxwg|AXhDWmW6fFWEOF3kn{&#Dc|W2ZIc!Hq^ha zq8kjIB-u%ok|p1O@fxcAhc8ntsnqYt@5wPCH%YdIpk#loWW%@K#uu%!1&%p1%;%!N&UcPYi@Fn2R7A(GHQbo%eNYKMA@ex*ukaJQO>O@w*wv$4_fTU)`$xN{+615w!ja|s^-K0G z$v%%ROSK79QKxKQY5rAYz+f8`=g=vr)bmmireYT(Z!2Od1R-iZ4>6TkwIo4)nR@5Q zhy}rU(U9B?f>dheBS9$WbP~ZdAu8TUcb+}_?by14WUKF+Q7Z_~kwpBI%)e>`XAIqh zrx*~46dWaP-|KE^@sc`a9(K|z+hn&D+~)BNhd^-Lx=TtNWanEfKwgl>Qt+rZOPahR zNyk({+-Ubmp1rGUm4qY0jd)vW?y@DCuoU{v37>-fu88-dw-mrRf;v4PVrz46t|S1f z;4w!7OQ1q&+eX|(mMyRI&Bk0L0`qdPO9~Bu{F!#Bo%c1`K~L%aygoYYkpjq7`~<}2 zfO>G`dOr&{fnP3jb8l;NmkJPOQdrw0fljO(``vj~pDbgXT`Y7|OisGgqbY z*q~*#^BDo9Xv3wZ!fmN8Z0?{I+q5orp*JC_PWxr0FCbeENcXh;gDyDaHlD1rC7 zUA55ZD5J6K9o>bSkeq76hry>tub@raE_W2QxY;{@%Dy2XoPv2FjE&G275jBIAs`iU zciNcfLQ~`(^t2OAv3YUxj~ZQQ^KL}u{50Z&m1Bki9oc4!5*(8_x$|+R0v-MCGQ+3! z{=|Y$s0b?lk>JzHzDTvR5(s_R<7gPSwfzMf9$i7mt zWR<6`5oE$_bSXI`L*+}xfrfTsE=&#q+45wVUzbQfxR zenB{4oXWOy~vT`7&ri`!p{wIGg0nEP1Cv-$z;Zs~a?dJ<)5$pb6l1 zUCB~8s+|M?C$MK~IK==ydYChhh580fJ_hA%f*_B|*I}Z??c@foSY0;tk>C-c81`AQ zh-&lkQXdH(LE^N#E_g&O>Fo*#logMqmt3E&a_-`I7e!zohdLrvqnKrPAcDcSzwdI#P$1Sj)XLzw`H(Z7Dl zz9E^)#-6SWq{JL7&ik#s1zc3k*EkLc5-KGi&C(@o(b7nFcP#8ulFQQFlG4&BAgPET zN{L8^A|fFuNT&#*bp0>-=;IULH-7(j_X9ikOq?^PX3osqd)s4Mbz}zB!J1)I*IIJe zd$#B!t-2(lx{C|HnwAIT(F9GhU1`1BDzhTB%INE0YT%CN1n{}=xt@R zppWhdU;p#$BP!=5>rmW$WeQ8>8=?y_jN2=`t~{TDo;l0)5YAW2hKD~e^lh%xsho{} z;xQ!RKrNc^iB%hV;Z7vAFbRS{l-Zjtc)0Av8@8guHYaPWGOmXochzI5|gF^5ewo%465mC*m~L?b+~p zM>EYD2~!zu%;>+=C)ONHlQ9aiS3B7iCzh5P8hT}1sxeF&+4UMv;@I+lVdY+rGu^U~ z)wsp|>3$-X<9ZmqS)d-t+>kF8#|k|8=@2w-vazFvbxo73_OQ%$>g)bH zVL8N#P_3A?+gB7xzSzYF6Y38;U`v??El%COWQIjHi`6=_eyHeV{fKnjQ3*4UU~Okq zvOa@DC$U^*r9bH1+?;@%i9sNbV%7NtwFPZKhU9!2JNhsKr)*~ZSGgs*<3`tUskDnPf*?psvZ}=27s#@yo|M2U9Qf|y4 zE2TmR!u_C)NRm}s(a4YOX0~DI#8((w+BPuTLjy;-s|0zPutb-^fl+stQ3U@V^&GlfU+*gAm7xFlJEVSzzx7|t}uS~P| zRQ%!!vPVOp26qV$_M zhNC-BMA82Hlg7rkLI>hmAJ^|ZpiWe+gk#nh(L5)^;V(ObM|rZ z?q0l5B`8&g($1dPrGhR&!qOv+q5?JkoG8tT(3;le-j;y9ee62Zlm~&wDS>ir6NHOm z7cCD4O`_k|4W~JMK`h`475g=9Xs-{VKt7(2KzdJc_uwmzEAKyPj zv}#TJ6;~s9;+BiW&dJjrC13M>&eNlZWSMY>MiwZAP8zCs1#>i4-@4{uegE$GzHTqh>?HAlfxG`U)OExb%&_|w^X1x^5_Dx|sQ<-E_z?%urO)*SM(S!9{ z@hCEAIuF|E&$(S4)@c!tRrKjjoB_w1%MaX7m6i#KIw1Z;5;BAn_XHx-GBwi4N3RdQ zqcp=;WxQPHlCYZgo{*~S(H@1Kb#`X304nmMEbbF47fs#(uiMF=uiE5o$;qq_)3X-q zxrma8CN0R;oibuVuEvUZj}V7mUaRUA^YhaS1ZhNmviIH##g9{p@r&TGmA#i?+?Zqq zS9nqlY^Al2(p^o*TJGD2g*c9L+z)%++;e43SUALSOb%ypliLKb#2OCE_Dxg1Z&`{p zY!$tkm%_?}{n2#K;Tv+Zf(=AsqHG{`2OK@xMd1^)NIGDVrGrcOi4MzWgBP1?f?aYZ z;*PzflhkyH7hDWmUnn6b$B9JDgI1VRhPkI-u0_glO8o_=?T3SV1O>yllpa2lRY8Av zaPt%K0Y&78Rx=ATKK?W)!(-EHwa9VWd$8Kc^Ze8=no^=X?fq(o}4Z$?&70Vj+#o4DhqPG2o0h$K}#t{v@AW@#UR#{5h$Oz`s zR3juUcQTfF*qyjNhJ2(4WA+zTR{w%RSHi?Qxv4xdsFu#85<`gFs_;$x33SO8>S>MG zrTmE&qSw=eNd5g*o*4VFO00=3EuNZKmKP=#dXzVoR$)G|bkjJl`EUt!AV5s!uH{;WY2{&? zzB;diOA&tILR38=zlg2t!W~c62~CwxEMAnK$<3_g6oZLgu#hC;~7NBPwUewHMYND~uetJ2u&XdYdsWRvXs^2bngO=CkW%}S3H|qINx_6 zu)zyY(MMW?43hcK$F>OEUhY9i(`v|g>~On^gXx)|)N=nANv}?`)aO!Xo+z$$4Rc-S z^{lKdTtZec-dcD@fVQBr-|A{bWZ4P@uBorKOeqPs(vzKlFQg;4pO{*c)S$QW9*Dn? zF|e2{a@|f#`t0=~0R-8$)u~jqa*WSTHXTfVtC)3soBQsqno=+p?xHHaGit=jz-`a zFV+j?DemePi!QZe4lDlflG5uIrTN8alxg!wmn_0l8D&QF;P^IvulB1vsa!GkL8kTX zel}x*i?5}Xi1AM7SzdnQmySfPzlN%f7lrFoGepcMNU1PDjPYKOBcHMWXZJIZy!Bad zky`<&+b*Y_L~otWDJ!SD))Z?K^-`5!&L6?j9Ip_7Wy+ttb#GRp?qc?Z)Y4rVtNWVL zYND}$6ymJtHzJ}5o62s}*;vNLRm3*w7S4F2*Cfh4&BYX}D&j_xh;CcUb_^U}p>Wxk zeL+t1IFy{LuaqbJQ=Da+jyo^Y?MD=^H+jduET`!KNt2r12z+HX4051nSQrLeLHjNW%Ruox#guV8T9O#J~Ol`%qOUIMby5cHe4NWUSAEGnTabw z2Tk#$DJb@dK+YkL>A~l>vntMI8{fcDK`-6sAQ!R5nHu9VXA9Ix6K2})p?y9cYnsTJ zU4AfP8*DhSDOn(+BZ>MvA@aUWgJgG|%BxWSVLKIhTEU%{g@+cga<5I3Y9jNjZro4| zI2%Z0#pP9{3fxN)EWWzLam&>|X=c2`&D3YLb@xeR>0bOn^31TKhGCf1+DM&@@P#XB zvyb`6GQ-mEZWE`VF)yaZ9imenj9LvOP2%VtW^iuc>bfr#YVfD``_)}m%@epFZQ63* zEqdeGTV1C^x~mI!OJ;n{Gh`q+4_8bhYxY;o*G-LLwI!tr!hMtTIC+)&8sxl9qD-w~ zrOlQ)sWPprZybnKgkwPlnJ;ECfhWfqIi#F zrUV6e$AhS$7|^1icxz`dyXFhv<)tGb7*)WRungksDq@@!x;i)RaZ`P8{)p`v7(c! zQ@xFozr})U$Lc^Q*V#$`9>h}TobsEJy(ui@ohDg9DYARLy;pWcb41$Fkd#HTX4%CzG|QClTy8RG9QWv|vz0ib8&Y|~du34Cy<5!I6?2T=R3k~Y6~Lfz`q>l`w^R}^Yq^VC zD(ht7Km^ydBFtN&Q(!0BG=;B^w!OfaLcf+ycT!e+5L?oDTth1&N>W>Bjge9NJS5}o zWt}Rt3WcXrmJ>Nn&j%B3X?dGrJ)WHO;+HYostkBkbNrI5WjH@!A$DqChVW$YHSo4AAQdM*y% z{_v~yAY8r%&dJ0v*8AU}3XiT?g)ErHB+Q8_)RDNyk&(O@np2g*x_4|rS=#t*2HI6e zvM*x!9QiScK)MqZAgcYi{_$Gk%w?Aa_K-#PFY~k#h{BdENq*9Fxn!v+W<7-ii;3<{ z!m*VM0!eJR1CO=i4M~3BnJ#1PIE!1`U%p(-&wpL2GPIPZr%cPs_uA&$w=@C?<~o(` zeyAS~L%N<+eP3M4d$aBHF?D;#lyOX53+EqB^SDmfKiMbom~?>=l=VMVF%4)5DGL|^ zJ4yRo%(rS;ZN=8~O@HJ6QCf|DeRQ5-5wBdT-gU(I01G~ee?_VHuEx{~aVc-)Ere8H z)W8t_yA|IV{>w*vq;6rZrj0YyB6pu?d0kWL>$QFldlGmtx5}F&e%_3n(_Fo~wf9*$ zpK+M9fvpuA)6m89b={vizZt#B1|eER-Z*L!8arv)KFqy46g~9uifu2~TdA*xFQ>yN zt>;L|kpy|Dxy`lP!1*b)h8kA~Ci}i*p@@s@u8w!PVOfWpv^8mY2&~a9cGZ5bezFV} z{jgi=q1=m`2dVwsojbUa5gcnu1-F?q3JJ#oXbdDb7pL@fBa2Hv2;*m(1XvVFRi|m9 zaK{nBxFwqz#3JGMavMy9AD`=;8Ga|~k6U8JzZh*KpE#pBftP}A9I3S?#TnS|%_XnS z;BA}kujY^%y5p8LTA1`OPd^gTE5#I|^PP*;PMuCp0EIpUQoT@%G&68$F9s<-XQ?}aua zPAU4v-EOCq1`pmiaFkZkkPngralUxF?VNXAlW(0>EA6ek5X@$tEr`~ThAk+2#ZxqK zvGYMBmg0WKY;PpmNLWSQ{FoQ+PT?PWw&b@TU*Xo~Pe!X>w}^xRU2nkmz|Y+`#Ncv9 zUlrwjSh`59`>Yl$W6G~so~qrdJw<7Bn-vxd(tkbrm4cp(X+`2(@xtI|iEED)p~co0 z4%uTWlwT~!+CXEW`ceZ4cagnU_&HTW3In)I>lV@pD-_;2P+4(tw(B08a*xL*IW8$e z%V@Kpw4HYxk+JF&p*#`#yJ{~o#-v@=x#sVtGs%nzmNd2;aCPZDRftcS6RV+TRU3J0 zPTiSVVds&})uyLJxxwyq#4m8J2BrJ%cy)>s^~CN=B-U@Q2*3 z>WO-V#};d0dQxotBVsd_<@p#AyI1mL#VihkqjFEV6&I?-N|AA#77q8caSI^|3Vsx! zWg0pespK73#?A9^5L{)NqMC&Sa!|9TZC2)zAmiP_n`5{s>;0I9*U@!u6kCsU3+?47 z&K0M;8b7BtceMJdG?0R|cx{IOl29pW+l;5$Q2SOFnwvNlz=ogMm2>}aRpOk9QbPh# zOxyZ(N}585e?X@HXq<1Em_UlVNGvHivA^b>R?>!HaZwz(cSgI|gi+P|^O_`^@zKP{ zjc4wRqM!Cs9UC4z&(ADhJr81rB`5ki=SOnD?)6T^bTX`MkP(6t}NvY@g1Nn z^V5oeCE%CiAfP}*amAPY0yXzI%dV~y8`0tCtxctLcQY}+swv6i3|>Ed#u4Gx(qVCh zdqqlRbzSNHD|r!Q(=-qJ{I#p_**O`s_qPQE$R75iEZ>Vt%%dzQV9F1~$Nj>#I;h2eb! ziE#tPC!Y@oXZLic@ZI2HZNr{*cZ`3`jPr61VoCaZ+e}X|{2k3Gfm?E%*q!-XvdY5U z_aNA_U$oldkEGMsD2s?8TFG;AkYmeK?13xW-F^LKlpV@KkFYlCQ-QmYwQ7+2v^{!r ztgxI_8yco`fwP9)u4iBjbZhD|0{z0`0(cm;j#))BjdseO5~U~3hTEHtX|34z<_?w> z?+W)euq!C>zHw2Hcziif4ov|Tp2ub0_wzd}B4T+4A33KtCjwETeXENu#-!Ji>bnt? z@s~D~U%@Tp7gdlaZVd}+E1A`{p2$yO_injW=y*lI-ZQRy~>< zf(2O#Asf`Pl{v1LM+R3H=dTMsZX|wzb?Q?$=V2C8I+-)kQ^DS=8RFQymddL_=2_uH z5hI?TS6-w2j_Ex)GcQHw!3A*1YMm33?hdV@qXF{pJ=TcN8#Ej%Dq<=zbrVN#u3hqF zRj=`6Xq-6bSWofP2mQF_&g5rdMYM7=twe$6!^`OKZaQ*aejl=t_G$a3DqekeOx>L0 z@B^YZ7enOLIo~S3G=1BP`3!ZS@SO7iCNb{<6bw8k>uQ_k;zcdb8wjp>7SbBYq!TWM z1_ThWEL?PPrU8ZLIz{g(~7JtK1I z>5U45t8#@y(J6s-+{_!uCXF=Cj&%&tm1c z=~P6;%&Ds^#!560U_l)*ubQv%CRv`qC{QW;n{NiC0)Y_%$5~GX{f#*wEF|#5z~F4Z z+CJ+IS~+GUUW_&a+o8Cp4F&4ch*K&JGxatQ^2G=}r7WD!M9P}-5)^glO*2;nl^Oey zS<#a4fg5gfKN2h0=N*Ze!i^zl<66X0lW@-)T2wA)oTlC7sjCFx7G<{S1=0Yg5jX^T zx^l=1G9HFs4_Z(|Hl+eXh4RG*7Z=+Hd30x3fkoR=vb}D(Zd1|Dk$nk6X;)1aSjzk!Zz#k+6lM8F!HOPJ1UPnrVkzmR?cU!e1Qf5!Ju(90CMUBN^B~2j^sub_WJ<=qDdQCo@^ zFgmK`zH%l6g*+|ox@J+CW-nQJx~BoPf()3zKhkQrMT}B!?tVJ0ZFOPCk?}RKc=>B@ z$8Jb0&bbiPsGz>;?U4J7BduiT4b~10L7~?!1$;hfi_-1@XGB!oJCJydRisC6*Ddz0 zyEbH?U{Z-pY6i>URamQ+S0Vf6$pFK{KnZg%4 zW>(*-UBMurcWI6*ih_?Uu`y4C>qVmxjdvU*QFfPhjd8Bb{PPq%X+pRSoAB{2qqp{F zt>@IY*U$TO)|$sJS=T3+r(L2V9WXBq~M8o89@twod|i$7MVQSYddp} z?MV_d)M4-C1*S(sJBQ2>SsdKa-xgcd9I0==r_BfHln_OS+2c`75juh3_I> z-%#X=B^OPS5uO^}e7#7%2i$o@t0#rimE0}=Dnjjmt)tl(H%NP-~~vB zk9o1d&d4mEkP!Oj$4@0NAuhS=q^U4I+GA$N9&uK7s}g7BuT1KY*t*s3U6y!RRAXDl zo8@sgl9hb&&Hf_AXp6!v>0CZz$#a-FIk^C_5EnBXe{Qhj!|_%%+QW*OVPT`&XvhUISkYP1TPt3!?|j2j%UmV z*84rPqjW=}`p)RCo~J`MGbK+Kb1gsGT}EcJnGVtsz+QQodnc4@)5Et$fycfY)5;L~ z`R_V8ldC5Y+B73_K$nR&*KKhcM4s4r%d+A<6qF>Sy2@Y}2N;DKNO47{+!*Q@2)!VqC*AON7Yg(>~sc z$N*`?jiZssB1jhqS76>gbzEJJ=|SbO+=dr-2%26UM)r1dOJ_N3x5_XqwdPjSNz;Us zIQy#ML@l-tkWWXU{-szEG=7jy303N`TcTDhlo6eh=z6apO=RPAQxKaw{)_PxZn4s> z=?%%@YKkxPOd4{N%C1k_v6g(^P_Jnz)tm71IN<6~&|5}H6Oq$3-MKR6ioTHaFoL{j zjAKy1-}bfwtNm=dPfGWj8pwt?Uia8GO?dvZR5^NttE@Il=-|VMLh1c!ED|bbK(`$- zZ?Cp0&~{BlXO5}l^OvcqRxbZhRl-Oi-$IU&)DBy8WQ_?kn@@@Ux2IF^Bd=-LEquP+PG?2j5%(^4SiN85y6 zUn-go>sRJ+r>S$~LG+e>vzw@FgX^l)*ir7FW-=b>5-jtKSzs`aZwR5!|4GzthBk109N>&BDh`$ zR8oGNXsMf;V?E}`t{CZY(;GtFT`pOrgS#Ly++A-$sg?MZt^e~_8ZI91jh@rAvD1^? z;FGn1Y`molEXyBHXBI%%p}2S5iDl{hVN%lNum;*r&%#E95yfQNHmD zNiR%i`(768jU_b`RbAxBwddJ+1Apk)D=?=*jLn*tpY>Slls3iiMY{1!Uy}5|`Bhx* zm7tMp$R(%y$HAAlH^!w+_RvX2wJ$E3+L>uFn|^dSmUN33 zTxaiR=G%P|03z`<^L-UevR@D5HJz}Ls8zA5+qHfs_u0?(-k4Oh_$d5syX5G3xNAPs z32}pEQbY17{nlRC#d`tw6K*mAFkj0o_x9jRz7{kJ$>sF|bRD-dN6S{u50a9Wijto1 zZham#ukW^Sy8H1IKOP+4jdDSHV9+RpGZBz-wRR*D0zp7$zrq4=VS%4Ofj@xa;$S^r zHxyV4VTS^%qmT{=SyvyBDFn!d2?+5E3xc3R5Pq1TIT26nu-0`25Lgf8g8_=m`(PAxF$fF_XyHc{1y`UtRQUUaq$Cko4!8zd z^Z*I|1pPtr8HzKC#l?Zv0O~;B$@2h#RUMEXAXB0<;&q73K|l+hXH60Tt^H9I`m5?6 zHRTW(gp;e?&nEt$ULA!&Ab}j9lYhf~M&1wHKN$0?8$@7DEp-r7Qt~IJpL_)vpd(E5 zy<5N0@mo7OP#6&uc7_M61BDPl&zO6b6d;0r#}3vJArd)*{Z{>~_#b4*B0NxMtOEm& z;80c6=GAj>MtOkGAlFeIHfRSoj4K)h{ob)3B%fswffXFk9vC@$1R5kD2v$S3DI^8ZXTe=+~>!np2WYl{Lr2H+x0i2&Rfgs1tRGC7m<-+QVct1qXn_J>H& z|CEU6e-?;<@SpvJLIr9DBBN3``iCtCH@8n&_O`L-wov7a?TX>%*ucL2io~* zID&#_Liy`geb(VKll?bd1xM&9(85cVz6yQF(6*_ z>R&4XfoSC>oqnWrufA%UpTa-Yqagr`%Ob@pXi8s@#-@r6 zqM~`2bT4MNmvSrqV!A>z_p;m5V2q$9}aZo0{;Tqn(mdDbCmea$^Y+ZZlTqA?d(@@g&No6qu^&5i9R9rtD+Q z;Yc0_>86bt8cbXTreHfRnR?Vc3+q<^Ba>Aq2TDspw{U%2bSMg%h zpib;l?YMr@4IlV~&FI(*1|nC*a89v=D13Y}346ff_=H{upZm+Yg z^8m|rs(s_Rq`;TuK9?wK5yf5HPNk@W$o&4^!4zRN@WrJ%pX2)L9?*s;yA!h100N$& z4gMmZSaI=q2%glX4=q6(i<=%kcprI|ipM0IUMI=L3u~$2-+n4dA^{(dozZ;~&rR(&7xZjnUMjzdUL+KE2z~UdEPcmem8!IdWI(AobQyXyjiei_crn z%Urp=u}tbWTifL@(LSSpt3Olj>kXd^^%tmQS)n%%wlM&we$ zV}I~??M;s*(Y^HKTfy-4(VJV9Ja=)*(oz};$pUYW>}Lv%_-OHRN!KmvYF!wvew7Kb z4oH5PtbMzu1ZN-O^78QIwOiiSx7S!7+b7!LnL9ivj;ApveynGsc;b8v4f?Ufzax@t)qAQMP+$ z37)~Rdq=q^!novZD5US%P9Na#{GD$~Wp51@kvEZr zl?nTk?cJvK&M{KPHyNyQ%+uA$4;!uDF?t~3Gr68gA{4Cvypd(lN&A|FUFwNJyA`iR z!@S_rZ>FO=1#YAa-FA{GjVngjnx?C-gh(+bDS-@Opdy5&XilKbxryMK4q_7Sc(PlG zZL~pACJ%J#D*X?|CJy~Z7*+}`2YWY`MEUyZPq*@EvdDuZ7**e3 zh^%AmC%1&c)5JbL#mBHY$p@_-4UzX2CDi!`=17;?9qxWy8Z#WrUJF@$LP>uaTAEAU zxXDAsT8S-hg7Ji?%*fzom^6({jJQ8?AT9f{GyIH2AqMopDoG@(k}j#^{*AEr6p}Fq zU}6DHEWx+AWFTuDQY96YHZ`Z@3T%`~8dV@Xp2!WS?X&XJASSAG8Y(yy?k%y;O5_WY{SCfx4jAoe8H# zfj2q!xST4(c%6;2ZLvO_r!D6n_nTQogSieU(XtYEuQ4X?xyI3(L_XU;NbMyL{Nhdu zVK-~OfG-s+dVsr#`%o(A;KoXFZU+*PZFallk_)fD_oqYV?!Y^Xc5EjF0iWld%XNIR zY5NenT&FSIhVWaYiMh?>wi$FlCz&`aB%5$=LTu}3(z;T^=IYz(;3RjN6ljfvK3;lQ zO?IqFccyZ%#ZB$45xMG^3AE2^&IXekz%!*r?>@N^q5{6!mtsB;Bz_9qBcLPTUhaH8 zzqP$NX1VvByE6XVl)@wDTdW&NMfI`p*!3e)Gf#ZqS;upg!>eNfD1#D~XS|ggPTqze z$6vbK>rsB}KVF&h>486V3d###lV@+f?oB^4C-isQMqKYC^yq?!TC+2>=Lw&D7k%n7_=qzEA4^j0>P=*MCe# z|L1cq0RhNwQ!X2%6~fvIiJTwc(~Q>~c=bv^0LxuJSP6cTgg9Vs|8RWmlVXRa(5MUJ zq6=e2x>Qrxd%hohOM)P`o^A--Nch~B3!Z!{-Mny`o83uaizxFwx z__|xn#8U_!U)02-GvaoA`Q)T&C}Mx|vgqQl=7ZIqjXwJn)qUre75xTN@65HO8vI+1 zY=o9R(oIx0@`}m|moOgr%r{NUm%o}^S2t(4=`82H=T&iCv8 zwTi<8g#Uwz$Np0BpkFF(ermHtV)s+SKfaAP)9|JF(*cgw)|Y^W7j68vDh_F2dz2O$ z8u}(9^igVPOmZ^&H%0u9B(D$fq^J{NK_9onb-y)TdLO?%dE?4$Ps5&5i*|#lydegr z)bxC&$;rMqBa;GwXxG#E7_`3&{ffolEB9OKUw21#4n}J}d-X;sk6aj2Gm@;-O#Gi{ zNad{2=YML*Z_eWTD&~KRT>o`t;irC_ErE#uK`;>M|5Okt911xT@*fc_kn_8i2#LUd zbBjRr|DYyN*nb_t3Y^8oKOQ8S9`)$zppL@?*PEhyV?F#MWz%Z?%Idid zdAooFHFw*1)K~1r=`eocJYv$a5OF6wqB7~^A?6P|kMXcC@a)LkNypjN&PH_3+;D$W z51Hgp6=Ll|nYIZPc|11-LwQ}|4$oyAp;IhdmUgdkE**-pF_V$8DJwYcRMwycCh945 zpUNMZrQD+W^2VC<{#{k(a0;Y#l5)VCp>1uSH~l_c7q4b3-vnNYaYMP2J$<6>C~PZ} zU0Kz}pz3B^+;}k$_?^Z5NnI+sT6fohxB^1!#wTj&O~$o6yn##TFeUaUR%_g>DWD7C@S=!O%fezyL@pZV+g5xYYy8_3T4QdVEf^@dQ+x>uJqc0b`^X$5oY zWv=*vK;Of{lBZAd_*VO!_3L!L8CCE#%zYJY$$#N~)iF`ml)CorrK{4O(zSVkH^uJC zf3%922){UHWM@CWCEg^Bp9XrZs=+5>@u|vc1wZg!zTDFrT%xa6%=ImryH`%WH1qO6 zGEOchG95RXDjTkS*<+B`O*Ey%?c48svoX#)q4!wcU&(S97BKTXceSS0I51oY3G@??4-uk$ECzA+pboF}uq(OE*>|U7conZ4YRwEPdb5Z9T54k?2 z5%A!qTMZjJ48eJ8m@jYn_YI^GqYV+H8m3iw^k~1=-z;&Ma4}PArj*ooQ&OTYPG3s4 zAXoI?!@WhlCd*41<(0ZG?Nd`Z!pWK#+KzcS+?l2B7LxtAh`h&$nxoT>@yRzisf%=h zCEPlLvILFBEtds_Gu73j_ulo!7(3V5>R!-NyxTdj)!uXIg<|{_%FLm7c`aOr3>=TW zd$bZ^@#J3UODWMU`&S&UHs-@(zm_DX>>$YUwVFeQ?M`0KMln)DiI2?1j7j9KYRKGj zHE(dAe6lX5P_}Q0ei}}t_KZS99ztxfU7kI_(oJq-xHbmb-b;h;8xF^&uO>JKSH<67yZ)Oos}9o2EpKa=Y8;gu?P zyS-~qw0q@-YNLujK7GCm$NdWir*DmS{li{GbAYz;?qQ4pUsp$L+ft2U(-+99$$gH=3Svf*g<% zoQ8tx5Op^>l)ZzJ9~!0Wr=e%#cf&>$$tfjCBrb&jHtSG)J_t8H+wW_Q9w1SHGii(PYAuuou#s`$(^YC@SAbj{-JXisI-wAOr`c=)vga12C{5G!6U|z>b6R_5Y2^{aBbJGESHu2`7g$YZP-rxY$W>`tTu9wg^ur45uU*O>Rf7j5Tei>L>k>K<`^Sb|7W%+H}{ig%r`Zxc<4b0rn%n^{wnL%=07dx|N2n+@X zyp_mzL*|4)IDuk-!T&cU{xBLYv;POnH2Y;rQ71116!6$FBizrcWUaA4!~Z!iH7 zAWr@Z47h*-O8|d?2@41a0#V=JV1S$YJ4{dr4hZwF#Ri;PB1a;syw;>|*N* zI atlas_matlab/ident_results/00_chosen +% * Ausführen von identification/misc/plot_mpv_12_20150825_left_ICRA_2.m +% +% Beim Generieren der Plots und Berechnung der Fehler wurden folgende +% Messdaten berücksichtigt: +% +% 'SI_E048_OptimTraj_Both_Arms_00' 'R03_both_20150728' 'Ident_Batch_20150728_SI_E048_BagOptTrajSpeed_10_2015-07-28-19_59_1.mat' +% 'SI_E049_OptimTraj_Both_Arms_01' 'R02_both_20150728' 'Ident_Batch_20150728_SI_E049_BagOptTrajSpeed_10_2015-07-28-19_59_1.mat' +% 'SI_E050_OptimTraj_Both_Arms_02' 'R02_both_20150728' 'Ident_Batch_20150728_SI_E050_BagOptTrajSpeed_10_2015-07-28-19_59_1.mat' +% 'SI_E051_OptimTraj_Both_Arms_03' 'R02_both_20150728' 'Ident_Batch_20150728_SI_E051_BagOptTrajSpeed_10_2015-07-28-19_59_1.mat' +% 'SI_E052_OptimTraj_Both_Arms_04' 'R02_both_20150728' 'Ident_Batch_20150728_SI_E052_BagOptTrajSpeed_10_2015-07-28-19_59_1.mat' +% 'SI_E054_Opt_OptimTraj_Both_Arms_17' 'R05_both_20150728' 'Ident_Batch_20150728_SI_E054_BagOptTrajSpeed_10_2015-07-28-19_59_1.mat' +% 'SI_E055_Opt_OptimTraj_Both_Arms_18' 'R04_both_20150728' 'Ident_Batch_20150728_SI_E055_BagOptTrajSpeed_10_x10_2015-07-28-19_59_1.mat' +% 'SI_E056_Opt_OptimTraj_Both_Arms_19' 'R03_both_20150728' 'Ident_Batch_20150728_SI_E056_BagOptTrajSpeed_10_2015-07-28-19_59_1.mat' +% 'SI_E057_Opt_OptimTraj_Both_Arms_20' 'R03_both_20150728' 'Ident_Batch_20150728_SI_E057_BagOptTrajSpeed_10_2015-07-28-19_59_1.mat' +% 'SI_E058_Opt_OptimTraj_Both_Arms_21' 'R03_both_20150728' 'Ident_Batch_20150728_SI_E058_BagOptTrajSpeed_10_2015-07-28-19_59_1.mat' +% 'SI_E059_Opt_OptimTraj_Both_Arms_22' 'R02_both_20150728' 'Ident_Batch_20150728_SI_E059_BagOptTrajSpeed_10_2015-07-28-19_59_1.mat' + +% Alexander Tödtheide, toedtheide@irt.uni-hannover.de, 2015-08 +% (c) Institut für Regelungstechnik, Universität Hannover + +clear ; close all; clc; +tb_path = fileparts(which('drc_paper_path_init.m')); +path_output_figure = fullfile(tb_path, 'experiments', ... + 'eval_atlas5', 'atlas5_plot_torque_ident_MPV_left_IROS'); +name_output_figure = 'atlas5_plot_torque_ident_MPV_left_IROS'; + +% Versuchsergebnisse für das Zweischrittverfahren (getrennte +% Identifikation von Dynamik und Reibung) +tmp=load(fullfile(tb_path, 'tmp', '2015.08.25-13.19.39_left_dyn_assume_frct_more_novar_6.mat')); +dat_mes = tmp.dat_mes_out; +dat_gen = tmp.dat_gen_out; +% Versuchsergebnisse für das Einschrittverfahren (kombinierte +% Identifikation von Dynamik und Reibung) +tmp=load(fullfile(tb_path, 'tmp', '2015.08.25-13.19.39_left_dyn_assume_frct_more_novar_6MPV_004_compare.mat')); +dat_mes_MPV004 = tmp.dat_mes_MPV004; +dat_gen_MPV004 = tmp.dat_gen_MPV004; + +% Cell joint names +cell_joint_names = {'shz', 'shx', 'ely', 'elx', 'wry', 'wrx', 'wry2'}; + +lr = true; +AS = atlas_const(uint8(5), lr); +joint_indices = AS.JI_Arm; + +xlim_1 = 10; +xlim_2 = 20; + +% Cut indices by find function +indices_time = find(dat_gen.t > xlim_1 & dat_gen.t < xlim_2); +indices_time_MPV4 = find(dat_gen_MPV004.t > xlim_1 & dat_gen_MPV004.t < xlim_2); + +% Run through measured data for all joints and plot +fig_handle = figure; +error_tau_gen = NaN(7,1); +error_tau_gen_MPV4 = NaN(7,1); +detcoeff_tau_gen = NaN(7,1); +detcoeff_tau_gen_MPV4 = NaN(7,1); +var_tau_gen = NaN(7,1); +var_tau_gen_MPV4 = NaN(7,1); +indices_position = 1:2:13; +indices_torque = 2:2:14; +axhdl = NaN(7,1); +IJ_plot = [1 2 3 4]; % Indizes der zu plottenden Gelenke (nur hydraulische) +for i = 1:7 + + %% Fehlerberechnung + % shift time starting from t = 0 + t_time = dat_gen.t(indices_time,1) - xlim_1; + t_timeMPV4 = dat_gen.t(indices_time,1) - xlim_1; + % Gemessenes Moment + tau_mes = dat_mes.TAU_Rob(indices_time,joint_indices(i)); + % Generiertes Moment für Zweischrittverfahren + tau_gen = dat_gen.tau(indices_time,i); + % Generiertes Moment für Einschrittverfahren + tau_gen_MPV4 = dat_gen_MPV004.tau(indices_time_MPV4,i); + + % do error calculation here because it fits in the loop + error_tau_gen(i) = sum((tau_mes - tau_gen).^2/length(tau_mes)); + error_tau_gen_MPV4(i) = sum((tau_mes - tau_gen_MPV4).^2/length(tau_mes)); + + % Berechne das Bestimmtheitsmaß zwischen den gemessenen Daten und der + % Regression + % siehe https://de.wikipedia.org/wiki/Bestimmtheitsma%C3%9F#Konstruktion +% covar = cov(tau_mes, tau_gen); +% detcoeff_tau_gen(i) = sum( (tau_gen-mean(tau_mes)).^2 ) / sum((tau_mes-mean(tau_mes)).^2); + var_tau_gen(i) = cov(tau_mes-tau_gen); +% covar = cov(tau_mes, tau_gen_MPV4); +% detcoeff_tau_gen_MPV4(i) = covar(2,2) / covar(1,1); + var_tau_gen_MPV4(i) = cov(tau_mes-tau_gen_MPV4); + %% Zeichnen + if ~any(i == IJ_plot) + continue % Berechne Fehler für alle Daten, aber plotte nur Hydraulik + end + axhdl(i) = subplot(length(IJ_plot),1,(i)); + format = {'r', '', '-', 0; ... + 'k', 'd', '-', 8; ... + 'b', 's', '-', 8}; + linhdl = NaN(3,1); + linhdl(1) = plot(t_time, tau_mes,'r'); hold on; + linhdl(2) = plot(t_timeMPV4, tau_gen_MPV4,'k--'); hold on; + linhdl(3) = plot(t_time, tau_gen,'b-.'); hold on; + leghdl = line_format_publication(linhdl, format, {'m', 'I', 'II'}); + + grid on; + if i == 1 + l1 = legend(leghdl,{'$\tau_{\mathrm{m},i}$','$\tau_{\mathrm{I},i}$','$\tau_{\mathrm{II},i}$'}, ... + 'interpreter', 'latex'); + set(l1,'Orientation','horizontal'); set(l1, 'Location', 'Southeast'); + end + + xlabel('$t$ [s]', 'interpreter', 'latex'); + ylabel(sprintf('\\tau_{%d} [Nm]', i)); + xlim([0, xlim_2 - xlim_1]); + + +end + +%% Output + +shape = [length(IJ_plot),1]; +n_cols = shape(2); +nc_rows = shape(1); + +set_FontFontsize(fig_handle,'Times',8) +set_y_autoscale(fig_handle,0.05) +% set_NumberOfTickElements(fig_handle,5,5,nc_rows,n_cols); +remove_InnerLabels(fig_handle,nc_rows,n_cols,4); +set_size_plot_subplot(gcf, ... + 8.7, 9.5, ... + axhdl(IJ_plot), ... + 0.12, 0.02, 0.07, 0.08, ... % l, r, u, d + 0.07, 0.02) % dx, dy + +% Legende nach oben +set(l1, 'Position', [0.35 0.95, .3, .03]) + +% Rand vollständig zeichnen +set(gca, 'Box', 'on') +% Weißer Hintergrund +set(gcf,'color','w'); + +% Alle ylabel auf eine Höhe +for i = IJ_plot + yil = get(axhdl(i), 'YLABEL'); + set(yil, 'POSITION', get(yil, 'POSITION').*[0 1 1]+[-0.7 0 0]); +end +% x-Achsenbeschriftung etwas höher +x4l = get(axhdl(4), 'XLABEL'); +set(x4l, 'POSITION', [5, -26, 1]); + + +mkdirs(path_output_figure); + +saveaspdf(fig_handle,fullfile(path_output_figure, [name_output_figure])); +savefig(fig_handle, fullfile(path_output_figure, [name_output_figure,'.fig'])); +saveas(fig_handle, fullfile(path_output_figure, [name_output_figure,'.png']),'png'); +fprintf('Bild nach %s gespeichert\n', path_output_figure); +%% Error calculation +% Vergleich der MSE-Werte für beide Identifikationsmethoden +fprintf('Error MPV4 (combined identification):\n'); +disp(error_tau_gen_MPV4'); +fprintf('Error MPV_frct (two-step identification):\n'); +disp(error_tau_gen'); + +% fprintf('Coefficient of Determination MPV4 (combined identification):\n'); +% disp(detcoeff_tau_gen_MPV4'); +% fprintf('Coefficient of Determination MPV_frct (two-step identification):\n'); +% disp(detcoeff_tau_gen'); + +fprintf('Variance MPV4 (combined identification):\n'); +disp(var_tau_gen_MPV4'); +fprintf('Variance MPV_frct (two-step identification):\n'); +disp(var_tau_gen'); \ No newline at end of file diff --git a/paper/figures/Identification/atlas5_plot_torque_ident_MPV_left_IROS.pdf b/paper/figures/Identification/atlas5_plot_torque_ident_MPV_left_IROS.pdf new file mode 100644 index 0000000000000000000000000000000000000000..601560c659b61ffcf403c396c4ed899fd40ff9f7 GIT binary patch literal 84658 zcma(2cUV(T)HVv!d*~<-M7lH~v;+_kq?gc}^xl)ur78iXNe2-KA_#`wd#{2ZL3%F% zlwJjtqVVPSJnwsb=f87uB`dSucG!?Ohl4`cYONGJcT3&hy&r^ z!67F{A*$mHclCGUkbrRfpBIIwn!A_3voD9JnwP!5vx>7L!pWIJL4m^0-`Ck5MiI0q z^h4Yjg!fFD*xFH^fsmW|UGBHf$Jw4G*tG9VUy1Rec}d|E&TyyyqmL`$Y*9%3KWrKY zdpmQ8>f5_IQ-~@f;Qr2Ve?N}@oHC>kHFWkv1o%2S`*Dc>F93CRa<_km2;#5=;Q(<- zF%gis1cx|SLPQ24VNHQ+#urzgL+XFD6%;uBk3BKm_5Y3Wf9;v;Ie0ib`csG+1vvQs zj|XZ9Ul=Z2octdRFm_Va^=^rlGN|ilMTo zy}y^epDpaaF9%WQAa7@1ci4YHh&l(_d)fZaU8(<7lCt&oLipSIBYb@VoNe8ma9Xxd zeN$U6XBU54O+!7S|Bq@S-cBw8|Hr@oh|>*#IpF%}|GKORcR{GQJNk2g|Ch99{|~|- z9O4iVj;Q}Xv;XzGzAwVj$l0I664wzbY8;}*&O!bhI4#v6e{~~&T*v=Ub{Il9ApeJ0 z98Wl!<>WX-4aFomr2j*4B@l#^%KNUhR_pm>R;oTc%N*6A>JYOdD|~}rzWO2motKnaiN)9YlevetqI9EY#%AB5 zNUkdxXwrwBe$gj<6TSOqvU*{1^7QVH?aP-pdUruxx4-UQmREO&MHM9mcO{!W(GLDs zeRp+ed)HR80{d6>r}5SlcpL8j_vu|whqn9B{;OA>)vwGiZkL*Wb&c5!UR~d8zj^wv z@B!1^)#>3)bA8?^e3X?15Bu2tU6 zB!&Oot^RXR-y>>$^LNwsa7i6$`{d8nkSNXPkDE5cV_q+Av!AlR`pZV#e)yd$xq!Cv z)$Ns|@WJn=@p4aO^RTDeVZpDiejl$17SDdWyL$hz`tH|Ij?LVDNcHXsDcUgn9}B~= zO{aGy#oguAq2Arq@$F@^iHEhMflDH4^TPG^?&00$(npV5DM6O~w!dflA8(hwzfw!R zyB=!3yM3rr)h#pnbnxOkqO;1f;moh-71g17_O{&}^GdRK^671W)&=VQU8N?I>g`}d zJXbRC-_aX6S)+2h@X92+!o_wgi0!wJo=V+ycJgb7ZMwguKfh8i3^VI2PD9`e{k*d| zzJ54+{Rh$2|1<<{3!w4oZoij)s-SI~CI#O%hr!EFw-ZU_=RWfB&fOe2YF7P*r<_ZL zj~JLln_Wzj=e}J-5k<2p%g2TFqiMz(vmdvvE%#xV!t}J; zu8}sghjXElT1kJb%|fq*j|tP&nqH%kd^HS&1swLIZ1KYjnL1OsD&mt+35 zm~9GVA3OSMjLlGKRsE40&oh|)nQ~rdBR*2mR~EcNP>o*Kdn5Iy@y>X9`MKs(F;xT2 z@E72gwem+OR-@8^YwABMkN^CLs(y-zKFYD_x|Uwa3T|IATlf4Vwm-An zF;}ZL?J*nD|8wQ}nb<1vAJ_BIW;n`B>TCjIFRN!nle9#CD&t_4#=teJP1-qp+0 zce*Okb=WKHu;q9V)?3`i{CT4uQ*`p-yHt*dq$?n%&+@~CH6=XBKvC%xM8wy*YFKgj z)aEs6j=Rr6!ow4T_KqPRl)0PmEq~u<7y9 zpOjymSnHSxsn3-x&l!ADdGY2g{%U|{#`3XcJze)~(d5AXd$k|t>G70G$NQMGLC?H~ zef{iDBFQl&0KACk*@rLIrRZKDD->fpVD733AGmS^#f52D^J zZJIZi__=A-f6XzqA%!PuBwQIRJ9Yi4MZZI@hOja{H>%lO4RCu&CF!a27_rykm{?Ws z5xlv>T3+xu|LGjIn}m0cwK9eWvJ?~T%WKXZBh+hd-DxAm<0)hRvD*Dhc5|Bn<*GR% zz*Kl?9~!V4-f439djDR!^Vp|}F3D|3`#-BcR+Z0{wKsz*@J$NFE5?G?!pfv7EnKsu zz{W0sBEl#32n)QS9JAbz%20V0Pa7YrW+`ckj~-IzR>wZ%x|Pa~&IP#NfS?MAG^7WI(S!wRE+eWy+vYuOzm}|g{d`4v0LV% zYviSf=B9b|;q<5Q3eDj4&vR0uIf53=ZXI9!PWhQ79+XX0x<0MBwUa5|Us!lL)Yjoh zQaHMkfo&|H+7j4*ezw;`Rh4zrG1nIMNxmh1>dgEJHV)ulnaI{UG%0r!xm9uXUBIWp zMj)&A=U}|%@SgU8*-zG>1?{?3!+u5)&j;=1ry=PNC@oqMfEq_=CE*QIj^D3Z(_`I= zrTy@V&u`LZ+NYdbYS{|i)|6THo_I<npM4yO9dcz}f`JD&d=2myD@JOs&iPn6O^zK5+HS^TSp? z$mpikW}L^C;AFtWKNrv0n{wegKC{Bfw*ch#8a}h_fnM6J_Fh2{O=6V5FsttN&s&F^ zS^k_q1vXofGPB6_Jxu3lXeDYjN7~wQ%jb;OM_7-1woX^m&u`1)iv^PuBI#{fQ?!h0 zn$%{iOPU%4OeoN2>-_Y+lh#bs>-`BUZR{J9#DGG|ZNul&DqggV6=+}f7YGeMXjMos zQ#NC6&Z_`-h*>ewanAn8B>T8M!y@nRN(z%$m`&ox`DQ^i*8S(nVGe739@D%sb0OnA z1}tu2Y$w{o4v_CNA|hO#pt|?lIhKGW(+@GfQLS61LrsmpH6PRZHU8_dtoD?%+PQ4q zy0>j>E!wVGH+cW!-(S*M`&aOU-Zl~oS9wo3)2jS*Z!5Y_HtiGDN8f-5zBQP&L)Fkv zyKVOrhy}xbPgSE$)NC&~tfe&}#1krf^wP7cb0PC{s*Rahs)**?vgNV;1vjrB48m_z z+;HBAU8k)lDn`%9P0R@UUab@)S7~pH?3FRNCT%Du5P2?D&8N)f6wmoql_x8s&aj@( zKLq+srR9)mzVL(#Yh2}&we$x@&ov-)KEXae*HEg7oc|JuJmCH!u zTc@#EkOj3BV5e&aD@#Ul=l4$o3z#J-W?z+dJ{!t#a@$%ja49B2In3Da8nf&K#!x?c z$8h|Xj4wf|p+u^(c!MkanS4QA3w-3~oz-DmA!5GkB6_;3vCkW3om`Sg6R*9gTIo@| zTW&2}XT$QRb1d820k9jR8)_W)zVDM}Oz~{usV-&c)@*#x?=omhHJ`qK^jw0V@x2MS zLQjst^2PYaHn+w&_0x-lT!n4^9Dn{k*ohTGyr-h=gHP%k!zV#I4xS0swUz-wWfR-7 zZ+schugxlDR1a%|CS>O_Hu7S&f22q!D{uboD*U?pob>0L7oRAWc-9v~$I5u~E7v80 zi={rd5JPsz!p7nV>81MV)1(^U8P7*P@ObLF=Q}?Al<$+P{Ne}OliHVdgz)*R`7hhk z(Q`?bsQp%S#%x4C>E2mnRm2l}_2PW@tf|a=E>C9rL(A)yhkj52si4x_Ttn?Isqv(7 z>|xN-G16lN*$hSB&-wwX^CQ6tT z#u-2N3T3m+(%%-4pXQ?agqKuSq%l%7O|BRrfn3+Q-+`6EU*gPW-AYJ#o14}m%|^>- zJJR|ze@3T?ys5VnLu9bQzc2E&Zd*zB8*EwuDa|mrRCUh{3!ZaZJo4sFO8+?YT2S%PjRbOmhW;%R8q;5oR6=z9&oVE=-WMNiWS7@4^02A(-1@ z^=S#9TJo4^u7dTT+;XlT7c?w$#!!B$q2RMO*sA<~>qS*zRmLFYji;oVs6CXgG-rQ( znwf3v?To?7POhoc%`ovVSi_&{0zdYys!8fnV44U zPU8Ii_epi#M{QsCZ{_AjrzL;d;*2q+47Zc}VYB`Cn?*lr%34?HAvK|i5@o6HXWju_ zjQ1>?8}oqNL^O+Kdb|+bNkjLF&nxCTx*lo@Lo53iQ#*vJC1rV*Y99wHFW8}`0=ca* zJpCkNV5?!)Anl*y_bP3Qzc4}~)1D0*c>O8>yi0Q-bZu?$TJ@~@wq?{AwLFx8DGs4s z-hcD;puR12yFMVLInK|WMGm=KzjQEFp}g#AIy~?kA)xn%>dCjoCo+kdNiOwz6D|QC zLH&ST-Q|P1Xoqr|K~mx=wTHPW=HEgb-=Sul>!&-nOrEr4Q&-0RnQ_AY5W$pJf$A%o zpBuZ397IvG3Hm)hRek^K--bD~o@O*EP4c;P0bW`9+`!_YK{lwNLNzt?XZV`9Pm>g0 za9!z%p^xyo$^!4Mr0<4itBdIHsX`^+stBR>+Xm2)t~P=8+i9AkkVd<^_L*;1FEX7v z+|w+N5oKFaiEh6lA1X>!yQ^G~p*~x*tUg_ex=l?zD?fO|qum~*>epfNowd$5dm?~d z$IEKp)aHp$=Kiz&j{qQ(C!(Wuq&=?~4QI2_C z$u{UY10^L>Lfg@LI^}d)F0*1rZq^%ZU$^oK=K#D+k=eqWxzVy;ke%(GtYT6{ggd6} zWvfrySwQDMm6vm;yynCR3%Dsm4EdZ=qT!< zk?)sYWtrct=+%2+Dt1;=xSsDSrhr))krY+rabk zO9**ZEN;;&Pc)m5qpbIn>m2=<*g<8@N}51uM0GRd0p4_O&VvxBRI$zC+U(Poxtav@ z^G^30ICHe>#aA=k`s%iGb`JphljsJ%w)6CT&%Lh)p&^AHa^cIS>9cxl5za?P^lZ8Q zjUg!8wDfdp`U}^7Uv%-Tb_9v4HH~a^S!n}&@^`UF3`xKT@!J4xUEQ{}u_V?$z;zLE zGf|==D?MPIgz`s&-g??=K0z&!l`!bX&DqL$uN+%v&sn9XjtuKVlZQ|43tO-Tgf>?A zIF)r@54*?M7ppe<#5S|;g?&kF^RwGFsz{CPq~21LqODpoqNoV<#t5`Yqm%2jef z``yJyJn3%zul-rFR18iR*QYxiJ?48BDpqB1dxs;}NJPuG+XHH=^!V+n#-uBO0{5w2 zdtk_$R?dW35ntRY7?<{=!b4}cHjrylu^%&2VdJ4-=~nM{LT$#yW9GTAmlnlvQ?A zxqAWK!!eUJTKgEqq0PE!FWNHDcb|rSjX|Lcdmu<-SG&@)mQFQk_Scw2SN7^o3cUu)s9GO$~;MFnMIkSdz951+gegQ24~Gs&NSlRxZdqQN$^RCc-xN;Zrd=9Rr=_<9K&}x>sR=& z7%DWhEA}>m66_4?XT2e7u`?PxPbJ2`e?C{yHCMS#56_{3j|O;bG)|?npWe$2TDdn9 z&upmMF~Rt}na7#|aZ!E*m}*e|5zlK3T5wPxcqSx$m^42}XCWpzbbd=`p~U^A2H3?e zuIs&Qs>H@y_AS zj3Z_0J*aH-v=)(tzi08$lyb3st}uEr>?8r*pYm-PagRLwB83vkX z-t=KUo<{x@sNab{;>l%As(Iv~W{h8F==pT-eJ#|W%qL;pg&OO)vCfj2@3C`>&NT|c zyVC@AFIoba`i|jW?1Qp;fCuxLTjlWPtzWY~Uj^swP~)<1IVe3k$6pwK#}tZ+{F;x1 z%-1T05D`6RG^+?_RJtcA`F=x!l0dMHD5t&t^1zbOz?x3CKoLm##q_n2{;+Uu_1I#? znQ8a(a~8;=opGC$nyc;n2&3PH|G7R#nyX_<%?1^7-G{GS81?I6ZCrhy%1j@}kkyR4w*;B%y-7a_ zt58ZHd+Vd1M;Kc(P7kV7=jO0_uIGM}vt8P$Ku(Z!OR5g~^tVm*3 z|F!wF(W6rlB*}e;7t{N(#msUQA7>Y6^$Ivp(h|9K9+J$@ti=A#7V8R4I**OGNf0lT zAfYj~L<<^psw%1s0J@5qt5P)e-dcJUik| zYU7x+9S*8Qhqh4xXY>ML1CK1(rZ*S_$S8lMbN+|C_cRr9K#g3(Df@pc}38+7QXjm*sWX|~HGOQ5QYeMn9mWa@% z+Vne-Sq&=eCHc% z4pq%QI#dP#0{qwo@~X)N&*X%$-7&T%lC>U}Q;E+d88J}e2Z z9)wKWiOCAD8$^nM7nfH+P)g+2*L@4H+QRweZi?4-nmUPZ3mk94s9 zY4{q-{D@Ykw<)3KA$L|}t*ZWG-WJKt#lzD$JBq=nhW@Dsy^Pb3P#d4SUNQZ9Z701h zz=-sGFwPQh*8i~7`y*>H%YZ2;;}HQ|&_O7N5bjj>%!}9rYxoJWJ#0Wt6Tb!S6GBgG zzM$;rQ3j%C^C)ew>z&V=Wp|m4g&W`jHc3^F!K@q|eQl8*NQNweHz1P%Q!3KAWf5_i z&HSRv%3jjtBF?MB{?uJ8>#oUr2hO0Gb#baYFYg_9ykwU>=Mq#GnuH30Z4>Uj0T$Ng+KZ?% zt2*1gI4z3?#j8nOG|VP|C`i~p6dZ9SMDD=_tH=topl$mF*wJe7qF3zqV?yGXyF>K& zczx|Wd0V+P)CEBVLLLG0NpJ<0f<8YDji455tsUn>U@BAmE!?z%_PN;4xXI|?{<|kd zKZmzM`|q?@KuM|)7m9y&ym@Da-uQiKpIf==KADtjw9QD(uq{00Z*8Ek!c?*G^*#I3 zhWIY1VhW0F-fC}U*{sxO)n?SjW2hcwYo30gHP4Q|GZl^Pr_bBpP5HsMKx^Ks!4jlc z%=2hS);POA&GP0!-4L~wphOO1mj&VaB`;V@N<)4UvGU4OBI4Q&*n zNN1{Az4NFcY4A1EV1Lk;)R>lCmg#+I9=}EFq^8dn-qIz-mXprI9l2P}{;Bc>ZAJY4 zf{eLg^$1|APImkSHn6xENknWt6W#9;-N5wogGqL-o_5xg5$}6Y@!Z^P0l#*^BMSZ= z)%U#Kw@tN+po^>zto)ekkZ!90_hp4fb%~0Co7s?&UO>Kpk5O8`k{s{1uW0d&d>-3l zaGX36i4&k17>^p(aUZve`nRYDg2t2rUX zXXL<0Avq1@ajA>3CxWKa?+-3Rq}=udLPMu0tM6dalwkuI(dX9`4w_!4Ht7OZ#B5s(fxS z@GBOsHn091<9Q<{SqbOnw9W|p8Zby~(O6F=M+!n)m4r9J9#xiy{WUFnf(Ltr^(X;u%6GS zHeENYGgahY?DlWY>ECcr$j0BUG{@6}M@UX6V@rR$bDxPEZh>V~5a8-7z1qHUkfMUP- zlwkF@pSyfw{R4Id-cp$I9V$ul2sQOQPXX97iL>X``HLk!x0h(9meux^^%`U&JKECe z0@l{qCoO|zbhV>5T$1LW*P2a*Njt9>{8ExFlm!NlRJTqT(P2UE=%GUoWwy1KG{jqf)jxLF#T2#?dV!A3+9XQRa$&k-#F$Sy=bHRmLY}0$8WA@lAAx$zR?cY;wdD{ zfsPgvL6ziZO4k$KelGNLw`P^1a!;}zp0Qfo>)TfPqSlkcz1N#0<@7!f?h`CO4weQ~ zMn4?~`y@aR|!0q`;(w=eHD>Kq+q@OD>W`p2jt0E7*HAV9pmfCcw=EqIHiJxBMw~)t0=KUwOmi2p(DitHWq&pmTLiz2I#! zH)sTG+)0z&4p@tb^qgw^?Nx;dZd=7JT73bfsVrIPp0Bu}cndP?Ccy8l4}dVg2Nn+C z#Vuc_ZMCK4pBFzCm)RRpo_6cg#33lWsJ6)e|(T83TZc%hOHbcFq) z%{50EFjzQN0H~*+`KT>9%6)5GquTNTsZ*6fbPokvz|zRKUW`_#i7-B`DgckwVVY-D zxym_t6(;s1>&GHi@W^4fk!4giOuhxo{p>p3GfMmuDe;_3tTa6l@H}z)TJ#g9VO?UE zO9H0W_ym*aBhn#q6h&s*@eRuhK zcZprV>MpmYxk_+#O9X?3`*WgPqe4`ElIH6jB4cBY(J_-g8Abl8#zLSJRuusbY_lzp|g22*{ znvEX|=lu$Aek}N3`LoLb`NN72hHRZ_@&MG2pCu4|k0wRY_jFKP; z+FVFX3q7y2GXZC#{N$McW4lv$q_eVdjDMj8OlOF7t4>go$S46R=;VtG;3sB@kQGq+Ws}*NVpO&unQb;rK|$% zLeF>+HB}y9#7YoX3H3V@r}gH(Y#bQmK|W5W0$hD-mBF#t!x%`B;1~w5C@KA;dd{(k zJ?cv!n&4yLO>>i2vDR!*Iwt!;uL9f>i8FWn1PIj+W95d?4sbSU>%;2ar+Y+g#hNo1 z1J9pqs~Ex-JG%8@i|*ZULzpt6*NaxNXK*xN){luCje%+Rx-9lc zbFxA~Fz>Igu|ev3M&CHKkU278B@ePlzy)8h+{MJGi|E?CXy@!J#);8p>ponsLo zIkRj?18ANnsX^ebEb^HHqPA#PKCMAh1U>4FYgl(Ta877I3PpyeYXB`vz?0D$=J;MX z+eq}v-ahO*_7;bRc zyYfs$Z?QGWWPwX!ghIt(xkkV37RPyYtu#R}yJOlr-Yl>rrKSTK5Z6`lC<`oK^CGTs zeZ`ih41f?BODqLj+hb_Tpv9a5*F_Sq^P32cBfoIf;Rlh(B7?ie; zo0NKj(7%c1qU-e-fqt;af2rm`vV<yvnux={`M;h*OA|P26`6tHEHVx&4C)ycnqFXBKr|>jlF#WtJ)l1`I@nI z*Q)0ci{Af!n&3C$m)zXuFM`tFyuigqNgApTYq?Jr=2!;cVf%;j@RLnDVqYwrw)V

rP%5-9wHEfYtV^*P*ZZJvNDo#Sne^|r^%vqdiKkc5*9AU5y0ZqXan6(^qR!HG2)AOYkZm`0PBFksaRj-?(_oiH5XMbUPvfsQLia;yKYW;cggMUZU@H$ZJxbbrL3&rb8cKaZb2Z?n``AlxXpjo512cR@J z7F_ThF=G~P_>PI>xl71+Lj-fSkMf_=)izFuzaz@5Q01wY>PuwwvR(VHcG@4&bn{he zDL@VMx}?;LPLDVa$cjj^(=t}kIX8&~G7o*MpYu?;9Z+7nicD^4rh`Z;>^{!&CPc;J zYw<1j!09Vk>ELNPxvzmcf@Uj=!VY`{`qYR%12}Z5zz;F&$SPVs=ULD4og(~}oq=MPG1qL}eeBJr z)QVK&nO4__6HLBOL0$4^a6;67D8avC4ms&kfID*0l|(<#3D|v{B$|KB0WnT6uIGg8 z3|=d>+V6bh9A1YVH}E-(03Zo8BY=d$uCEy=j4;IrCSf5}1*J&%3ODNVm-D#}Nt9Z9 zze@7*^F!)C4`iTN&IgK?N2i{c+rdGS(3;ZFr75E<-}H~pS|fnXK&!zFATQlrkUo42 zkCE@^R)SM$(Q9cl(zzYn+&XAAs;p6^BU#P(DjyQCHJw7Y6@KO!+Y%5Y)dBI zN-h!z9fzv0!X`0H`-W-oD)Z)af4?vExkV_UG@o>ThE{Q4fS-_?TRQwG%RR2GmBulU zAi(c?{%7WZD4qC?w`d7*`hJIL09wV{GrmCAhvLy*bT%X38d*RT=t1JG;)>UvQ9hh` zq)_X1oBi?_CsH569abOLroXvbCH+PcEEx=?lIkPoN5FCk2~ z=fX2CQ3E!o`{8)WwV01G;I4e42;nv$#&284%s52B)xy+x6d{GWM)sqv_F7595Owe| zXhtm;xU5; zKyVy7ILEU?;v?3aE%n8kVHk_w#&VjPj<=%E;Ss9@8EvL#`BDTVIojb$hkL)Xm*87T z(D2up1SlI>4Q{V(>MA5@K>qgS9>FI8^1+$@0)$(`Bs(OL@HoA0bzv}mn>|l556Mct zjWg`~kv_KH9EgN7GZcCN+IC|MI<}Vc4PPY4Kn7lv8cM(>>8@}O?4tbYIm3Hfkn*4_$d`Y4`&?kgr@Umh+J0qINV!~?O_8Dy%<|h-+*d=bT`-lWRZF$=LUH(Z<`+I_vX0}?w5jw zevyIPkFi7O6|2;fj}54D6~d@MKN4bbcS!M5P`x{ZPPxMeQrvkO*WPPl0fij#%|;Ha zvL_+W6?{weqX{RLv078pgFmBKIe zEi>^U@I};(MgYY!R9o&D7OtPnBDuBFK&GI#3djxO6gzfVJg02|E(>D8eJlB_mG_YC z?sRM)TY$!!K8_oJk;}%cps2BN4zUvw^!Eh=wvHCoEHf(v#SB0@FlI0ci4yE@#1&1_ETi{pf0;6NLGnJoJfcyq;>RP z5>W^Pyd{Y*X{ZNCFYv}z>?GRfW0%SRkOZr5hXo{`w0-pldiliY1=~8&`~ZOUA>Y3O zb9bq=;Sa7GC`o>iY>`#YBRkdwrk!7R*vBT-NS#0FsmqhD$e<_>g;?BLf|2+YokAuxI0^)-F`t4`*6 z;)qKFW^zW)o*>RnW-$bF9FJ*iHsq!tGMF$>H~Re%zpEjbt>KkVMyULbEU&3FcHQF#hlsq3f($ZxES7klI+e(&Nv7Qq4@)R&p3)MhHO;Um7%N{pht%HGgP zW2~BcxQI_kwyf5Myixb4F#oOiJwUFOgk}MB z2Dw`PI5lxK)dQ^XGo&R9in^HGVI@Rh#UPQxIIR8X0U?58B9N^Ib#HA?2MfpydJsbx zM5x@=3nf|A|HMv(#jp^a5Um#3nnY+dH4_3lZZcU=gGPS96{Plnr(@qy;P&ubZ6M13GE zpbs5DUjpms4&aWXOJvrIC{_2Y2<}y=h!sw;ikCv=1fJ0?9QTYezB&5Girp}^Z=y2g z2-WYnU@G^Vr(W#5opwTL@d7HUOUl z6ACmpphcIDPWhTX@vK?}mvgLI^%`n!V3>$XcvhEhT`u@mms4{d4xnD*EHghZoMm}I z=+}A$`LuHK)_Nl)D^MBoo?m2eB}?bTaT9+1z_^}c6)RY;l+e*@GDP|dy@tFZ`vFbf zSy5Sa;(&4?vN{ezj+$H5`~T+beJ5wEhAVaUR*nvfT}0bLKtk%%z)Z0!wb^#XRK5%J zBX5xsh|Y4R;y5q?uiuTTb3KM~w7ir>m4S!N2f|5OI;vRC{@dW9xE5gUdi*oxH-Dv@rph_3tqW*PvYT}s(g{<#wU z?g__YSJ9mwu~4bq${alB6Tnl25*w*Y^w6AjdYE#YA~)Y!inwbu)UP_}59y@~_Yy&v zvR)yt*~^OBR}qNIALvE?9xT`-k3fC=?b}GZ0;%@1vN~L;4@jB>>g$ zXV||HEP?EVJWVTw=olMXCe>6DAxGy?lC^w)qUqDU8M`LABE%6KC@e5QF%_C5z9aD|H~oL%ji_`Hl1bMRK8JcmPd4p5Xl*t>GnKTnpjn4iKq<3}l#T z4s_agq-siUtnwVowL&^ZF07hdOX!smptLVo@*MzSOa_gi%}*2CyGx!mHh=f0!;qM> zLGaa9jZ{!NVyiNf?<(5H)gGqP#S$MIo{v!MvYVn0m*650n1IB70(}|WK_MAhG$3kg z2~*jD!(H}_#K-Ihz=7bMquwr-6 zPk47B#oP(te_IVADd#|A_#3csi;NFK2=@*3j-SSVkiC)XqRi8gWeM|ZY=x+T>{P90Y{tnQc zJ+`}af|3cZCR!QQKD@#mVUc%dqp4t*mMKtk^}@(EzX6qTO_p03ox07CDwr{+!g(lg}7zzCxX00K`p8`(~dryC~i zO6VP5dV)e4C8ZD%K61;$@jCYPHMVDh|ChF+w?$ZrET{A#MUjr8_l`=&04-bAehVuv z5ovK~XJrI-oN=g~lsJZh=a`9+P5jQ5hKyRy!rGio*}GyxfkRq@HK%QaF*mRzf=>F9 zKjK=HRvN}1Bugd@W4r_76<_R(;bBjn737n^-;yTtcMLaa|05fy{B^8v`pGu9#p>TW1t9 zs-M4>7ui$V{Fpher#IVFCruGMElnI#bNTf^un;sb@M@*m*8DX^f zH=Qh(b$&|)iydF#6(b~d_D`jgE{WzPKt>hb(2fn_?%tSidC$u!`Hc3IvQ=sJ^eTNg z7AKeHAevNoN0iIzl)!`KDAc8)CCUu}-lh=c-m@*%B1l3!_zMh+%m^U5MF+l;6v6$W zvZ;CxbW4)S<#89+jc;Rm{P+YCFz=Oq3CxP0H&W^@y*+x?hp^+Pf5(r7aJ;Qcvs=R& zwMmLRx*@p_cvoxBnEb1^t2FE10mg34xaHJj@BpYWM)Mnxpb|5Z72c1k*Qr57eBb_* zc>rWi8%Yn3I?ca-AD7;ORVTw;y)~b1b8r>VJX_0H(@n~o!8+2L=#O$-&w1t{Iz#r* z-mZddjUr$@!b63T^afoPuGCf9THEhJ_n&h<7z-RpJ7~?fc`n1&EZwPTm2q!*1O*GCbEQR4N z0cy(sn*P8`5FW*Dd`xtWwwd)~2=9L_yecpbX%Hz(n1Eaa%6WW3fP~%L)^<>7L2QMH zczH=+xY1wL8cdf!4D!EbZkd0(tX=l^{|6uTBzBcX--Dk+XC9G3uFy8Ut>nL;QujR5 z5m-OIT0SvIuh9)|1P*t(``kFKDMCJ0liu*9fxtKD?7{X0$coGYDtsz(CG7wO7hZQ+ zYrwnYxj|blEFGZkh2=V}ofptGFF<^L%paigcj3RG&D(zUh_(lZxJnPQIu;=Ds=;-L zK>6OTU1UCvtL9XfeniN)_h^^9(tFKI=#xe}uS@8eOi(`}r&Nl(+sC-iWo=;S3;2d) z-N(zS4&k8~NAS`J=DK`>+A}ilL*!V?lXn-qO1n?|FZ$y*mrkW_P7y8oDTKxAI-Y-M z;#9s}NP-E&{@^((K|=c)kYUsNI`U;AW_{slCJHGxhcmpcVLT*z*vvg&+MWOpfD zTh1jgsAG`ymZU6+gAdtVu&JZSwu$ig@sH=0#BKiy*^R_K5yT=q`d$#cib__YSYWtB zErzjc{RR9@FmfL4E)^R{dqo)br&4@tt%qi0H;atzT5BOs5u33@ZXVZz?_+g8JHqIh z5R`zrD`?;m4IXtzr?C=4M7k{n6pz{pQ^9))`RkU>EVH$SS23oP^%vzUtIKr-`6Zg&Qv|a2s9sF@rk<)ZoV9Qy~G@0r28bB zA%gHlYyLC*9;EilJR70+xOB!b^lN;jF(0K6O${Zjhsojk4diKT7i0yDBdium{;85?N+O|uw&Oz`c-7QZ0C zJEGK6rw8dPnxaeVy=VVVh+JByV!Jac!l<9;JrP?j9-4;_+mjvoiq<=yDUOPPh|NQ_ z!;IG3L$Mr!Up#-FO2kIuQlmrfJqlUEV{=@@#VLA6{Wo!vJ?|2=mp(YSCMiJ)z8!2y zgm$kNoL>yA4Fq zyE|v*oS8Z0$iIFS>BW^pL|c{jxR2x3Y2nwzp|A_T!TZ_lcNPDFjzYC9joJh# zJhGc`F_R*Lwg|tyqx<<^+j)F#MSp|C_+mz3KofpPgEj%NC-S7PiKi(+BR;)O7aouK zcqrBD96(m>VKrEtHiST%(6|q7Ui5&Hd&MAP7B1F)2FS;^Ng;}WoZ@xsZbeM<3yA@n zh}RojJCFkc7IQ>l`S7sXCzb|NxVr!FatZtzmjr1+c&Mu|d;BXY zz9NqK0MwN1keCZsH8(zwyKT(3cuCpEgHeI$?hr9i$!HyXi-HMG&VrwKzWNWd4$l8@ zps%-(+qWqiZxp3lE^uFL6?{u|S4nR{Yt-_hov_c3B0+`_;Ed)r4U{l&PHKtyAgyn5 zKVf(<#xBIgt5A`|qO?yEpAt@iTL%t}aqWW~G;fURMQHPG=m8G_j%iA#$X7FAcYKib zHCxprwJ3a&~|O37U{d3xsjpf%jcsFS~{xLXpgdLiwkTJMg}03X`!TuX=GGXal+ zu-i!XUakY&hdM>o$OXrbAp+Vy$gpeDd2qLJPxcmRsFFFjCF0_W1O)gpp8 zWglea1)fj_n)WO7I#{qk>reQ?qH>3A7eit3;s~7&{E-aqp*<76<3YreawM2B&7ajXSxjlO(AZ48OYN~|`wRkCh zb07Zs@<$4XpybY9h!(_29k*trulB=6gb$#_*#bL+dvPCvw0kWCfGHLxu2KT$FYgi( z0u_A{$Pz-dbO`&iYWsMG3-g5XIM^XKD1N#w^r5MP_wM-gUcRoG3%^@fB5~k898NC~ z+O=_249nOO@!2-(^0}4>y$!h22Ka~6zQ@`kN7%y87}F@C&aB92au`+G^mR1k4}58zSDc;|U{b zg*^vY(G@sHpY*#gbl>HI{ai2YuTfLtw_qjqH>-j5^;c0j5ZF%%e@yBV<%(m;eNe;m zORTG?;*q%KESk&h*YLaEQE|;`ccSjCQW{#!p!*=du~M}Z`18U=+QIyJ#~;|=Twz6v zG)A7s3_hYSl%K$F{1EDIigWCsG?knQZ?4mTxNVPpEHc|9HN-r$GCMMaCr+0b!Z07j zxK875d)ok6|4p>lrlJ!5GlTAubnTxmV^7qu48GBTy3sDD0isk4-v!M#$tv#R7(E?C zsbJLgJ6Zf8j^^5K*opOJR78KS zgj{h=tQ+mmxM;lO%Gl)O8UMy*25i4<8ygkUrBn)NU`|E-_OT<`=(xvlxq=S&1@PrR zy!;{N$~Cuq;p}N6l$T9T8?UZ&?}83JU$aobLffF{K=FU7<^mxr_HO`{EyLBbN}UFX z9&^|t)|Q@wAtXxME<|7n>v>E96wDiGpP9dduF~%RWN&hkN%sVlWLIUcU5pLx`jYW{ z1pDJMb<0zy34u-TP$ALUFXk=)<`^6ukC9PRN8Uoim2s>|Z}G(?tVy@N;0ku*a{yN! z#y9h}#y7yG)c_IP4ayqsjO~z?n2il)*bX;PC($PK9rfo>6e=~B=F1WW=(%HW-}Zo? z7S}PVU+7ZJb#j>k%dx%RggevPAB`l|EukCq<}9kQz{HqgfAzD{jcFSc!MmkZfaQPq zQ-@Yty9wIDEk2$E3@-0W8AWLmeXhtcaO*u;9)}dH>dI|>c;Z_{@ZCZP%=pIFy>t7r zeOeN<38M=fW2ly{Frh+-#N?Z2E3Z<%MijA+ftAOGK5=c5=00cULX0Tr*d#6ZVLb0H z9Zf+HaGfKw)pCr0BX4-G2T5((7mDmA z`2)M`o`qv)gtR@`8~0-T@c~hG1_{Vv6zh1PFBW+|*w7I(kaF|`uu<>?nLDHPCs1+9 z$=2|mk^*9oxll}-4ZL5$a0;c9jh#Yi<_AOunMXZ+T?RSfyQa8J>Rm`FBZfXf>rbJ) z5a-yYQ0G_lIY{sByEZR$`lUbKR>3D~f#7g|%JGPtWu+;>E>zSDH#pn)ehc>`g!o_6@v4hc==04!T9cafq41Z)6HaG#cn> zL zAF|knIAT3@x|!EWdSfBZSbpZRJ?9}X#ify;2sa7Q5KJVOXwGW(QnkF)!L3~DB+|pH znUFC5g_WUfNc04Mwb(EUgP7tN28)~dMh2L#7*_X_Bfj*r@CRTy)wxz7Z=Y=UHt`2B zT($A_?rxOcym?^?e8)4<2k3|Db7fO_kAtV-7+BzZdTgM!Mbs}4#cR+IEx*+gzcAMk>I<}23$=dmxiXuw)G&zX*Rq}5!%NNs;Vg8Ibu z4aB9IQ36}0riuG8eFJ@w>XFHWt(%AW0_GcE>;T_l(IPch;<9x=S(Q_>Tcy~o@?Bcw}En(nPdj4$+BvB*Eue(8nqqA1$*+!vh%Y{w9%8-Vm335$sqi`81E~V7$WrzJz$v04B#aK5 zYbpCrjSfEY73&Z*7qdY(<_gfZ^%g%|!`r~I7qw?43SS{@tx$=6sr*TK#$6t+PR-ACHu`$-IS&4AF$n&z||8yz?2<~>PF3AV9OG>S}VEW@3WrAHK_g9(5C@;9D-egh7mOR z;itdfRG51snvy_i!_ko#O<)4?;9djsIxPC$@6c~gn`-%J|u zB-h{$)-mWtJL#LG*TJG5HF3E|K>%K9`hi;v3*xyfuBf5ficO1!%q2{IcBg7NYrO_a zg^9nN`oM`3pdx;MhLuVWAsn@RcbnUpDx9pVz$J!tT)jc;jV1b>B(TIa2rS8hyD6%+ z)Y(`_?^3Lmb2oT@mp)Xi8$7tN4!rP3kNApv;QYl@zo>68&z?l$-r}TG8r`#<55TzL z<{W{+-MMg5B?5mO(!~ftV0}}}uAL*3FFygy>=~C;A^ys*x)=EUm7_W;Mc^@2;;du= zgr0sMW$BrxHWpWK5wkT$=YP8QRnm0sMW$5=`rEKok~{4jxkChD z#k7j6TEO%Br}D-|Q-%NL01hpV#aD0(nSKS--&Z+$QJO24nO7w46u?(ND;+ElWo&3W zBX_{K^KJbh)MdrHkpVn*yX#b5VkthLO9A0@Ylu9n@L`c!d$OVHkM-Rcy~Ujk*^!G( z<_}<4alA31mkHT5#?8%C`oD{i;aZpQrZXTThOOYodTEg0)+`w8gN|O18P>CWoSW|h2rFWJDQ*hM zk72QPfv)RTvr&HL$%5VD%Gd#}q4$nd$3c}5y;z7|Z$oUEOp3*dSLq7ccG=7IK0@Ht zIWa8%YW^+QGR{qoYZ=7-3I=4n$O|26K-5nI3|5dm)WNla%hLhP#QHHnwG$pGV1ML( zXYe-{b%Bb&p{?ziDMX8X9{;W|`boJyu!~zXpW-SA@1&G044?RQjr^>%)HF#1&Qe>N zeo)_quH9f<1^xEa7pgE5I>x6!JS$6kQy@A_+j&C`5v}S*yNIu$Xy|)|&LAm;s)JJxp6!nxnf!1Ezn{RjG72*E;fgW9b#z2&1JKf$IZ43Kz?8A4tsnPQP z!-*|nCpLvLR8Tp4bv07)&xpiXS4_jy!?Qikf5+E3BB+m6$8KG9{mAj3& zjENtj9S(pW`Oo3soJ(E~$O?A~1T(5b^MUs&}Xp8nguOn>j6ap<>g*|YbPnlJQl ze}j?^jWzz=wd!~uJAG2W@MPGh_x7hpF&)sU*1#Ey)iv9l7q=M}2`wpuC&w?mL_J6; zY{$;0(C-Z=L5a&*)e}+4rpL$c)}Hr%X?lAmJWUQhK9zm3({^PDJ(h&UY;P8*FSSY}S8VrC4-pi7x4uA3QWM{PE@?L}ThtS|52lRl$ zcfGBff8l>mPFDU?-?v$%ub;j1=W$!!13lMAG?)JeU{fs$9d|UfhwB<{B8~ zG(_rb1J903)Q#~n0kUkycny)=1u8xMpYDoOo~v5Dd8u)Na}X-6B*oN?uc$B-jfFxF z#+bYD5#=(#{a3!X;^(R?uGb`rr0=YmyD?U|3Y9QATW{&c1{mOq7P?ZMY&Zlm;a&a) zr#7!0t(8vF>S3LD`0}VKXZnsDE{>@auN@;}AuKoh%s6r_6q)MK`cHJ8(GbLzfc1!U zV>*Y8MN3CQp%2_H7~kqH5vo8{S{PL~WQbb(M^?il9i>?-lsfzk(tdb_L$zaqd>G_r z-`|mCbF}H%55O=OUa2X5)1)6t#GR; zWiu?pL$bK;d1Sk+4XGp%DBy;}Tku?w8RGd?^8Me}Gar(77m9M3TkuuSOK0f@L$5?i zGPQ9>JoAS`9Q!LZ$E9^EUFmW_c-Hg};{{DdmG=J)&lobuWeCTXf~;lazkm8gV86q2 zV0MDkdxf6icOZ*{L>b$v=@VUGKo?Y8VxM|GcWb%uG6B?zU$R7{8C1z^-vCboMhv-M z1eW)qm{7N#*&GoPqQZ4!;+i~ZgK*gSGu6Q(6e^b8V8+;D#&xf3_5g|8N`2V>!CvoV z0O}X}cu`isp=a&-55fn{hXi`yom(sIR!Saaw|)@}&B9*)BE)KpH(otOg5L3QUF)fE z6;PIcS!vI`LSS&}Z%~yFkEkq+t`Y&RI>$<#_&k4$SOzBp)(?su{)b*FBbea<5-DPVt1&ina;%KUtlREhD?q5%Zt|jl=X+4LW43Ivt9vm8LKSFzgDyB z)-nf{K?yEo@e4mWlA&UcUwWy0#+$Zg42*p365To0vZ;O}F;Qfa-hBT_zTB)wFP3Sr zIs~ly!9#-pn>DK19if(zQR3X9DNw?Yj>y5X{LC7q2- zMs&1Ms$AAZe?w6`)LcWgGRoEF5u**$Kz06u2fl`Ra)d*Key(YH(88Heh@)&q_oxP- zeZ`~|i8l{R86q3hAZ`Zd-j+vH+jF~^)4Kta*M@PRI;TgzQ_Du_MmKk!T$Z3e8}>=) zKEcrLK`xLQ%K_TW2&DoY2o7fM$4}}Dr$7@}KA}^f(CjW?=yi>{SyQ0%lDF~^>1iyl z(J5>AnYUgkP^N6U|CNS*7PYCC9G2|I)vQsnxs#VjN z+BIm-cS9Nb&1S`$2?ptW#*&LA2I&@mZ-^LGmu+|*rW>T&GrhFC(eIyR`jZVHG_RbW zsBX3E^Gvz~2^-6@JY8;FmjYKZn_G$;`rgIqFB3?K37Y!%X9Nr$T5&Vzt$uo1tf&Wm ztz23^-Tr`aUZo%Z>sh1)8$fgbLQ^Z<9(9eY56>F+jmNcLPS5=UV;_DtMLwWGjVoM0 z*pOs1md7b%l+r-r`17x%Ntayo#tQEYy%r*Faatill3NJ%7nF7Fah5ZV0C% z<=tZ5I7@d$Xl3MEn~mud^7i8E^EqaC4Q(zw9u1qZX=niTnx$t*_5yQH`mo(v33JE* z@Wj*ydKZJZ--G;y?$z;M(TQtY&fgRnd-2?_;Yn3t>0G^L+;t=ThOIK5_j|3)g#W9T zN^d;&(w0MC;4&ZQG(4=b&WyCKmQ5_ZW%ywS5B`|#;SebY0)y6StP{2f|ZW)6+Kcj4D@&q4aWDgF`5Fx^yFp zDP54YrBv_xlyrJ)|1o8MIl6TGk9CkW_P!iT`oxq@G;gQ>M~R+SXdG0Tpym&&~i^%&PI;{m@fMVb%BMiaKL~`SvcK7t%vSLH=cV>30$>$Uz-~tSEOm?46K@h zMmTG;C5()V;b39>-W;c4dLB-Ib5OmBp^DzQpD9assB%Kvmp{{~UxFBhHa~ymtt?VO zZrYt!NJv|5y7dwnkF&P)K2K7K2Q~?>BV6L$di0zM^D>`q*K$`1nae%#RhhzHOnZiB zkB36*p*q1oMhX%b%UqWoeOp@lxSjh$hhzbYbHhzI4JD*Yp8<<>tV|q#x{7R_WEY+p z4*iqmWDuv+K2*7Cx_flLP*uKvEn7iRE-Mi|R>+^ey$ug=Eb_^`(c?f;sXz1lH zqELP(@)em%Z$0b%6d$P)&U6iEjywZj-NR?y=P&m7V}8*9`6ZWCyb%G2d6deokf~f& zur=iqV?>GbviH zi5p6|9ZB|A-+7^sYcheuG@)(;O-6WGnEH?*QF3t1n+ zFLvNtxw?#XEA3-=8UAChEPGTw1hOs{Rf}eN$h zwv2{TJg;x>W9tR`%tYj5@0~uU-LYQpSLaOE(ejXj}l`c&$ z`WK-)i0LE#g0^$pPy=t9S<3ZEx#w$*0}@(4Wu+B*EKUdB>(CkAX_m_+K4qovaDEQ` zGgxSJPR^$HBUd}#O{Z0{9j{tG*nre^6;AQiIG1k7t!lO>yB$%`0{A2#$I9ZD(lmT| z6xY^S9HlqXo)G#}MS=!+?$8;6WHWUPo1}UWFbC z_z^7hejsro#mDRwg(0_m(;0(Dq`gf@i-fe|YmrvmpWU_!76~67-8trJ#`{*zhZ%Ot z&fce~8e&mf_e6Mfsn(j$8L{TM13`o~%_BhljkAgbkrG%IOYfdsjIt+-_iOW#{U2~Y zjqD=?)<9yU{MTfbhsLz5w$>Wid0L;8smS6tkiDeLp5j1Z9BN3ik^61=yH(5m?~vb8 zSf~p+tp|&Bd&%+rxxcKH!2FF!yZ$;M`G6vA2ley@0{fRA46%0osnya2%a$_odf)jP z@LhU8#}<)OD@u%3@(3+S_HtL9XgfLIB7PUos+3zdb)?z}wcN4RuD(S(aPARjnTQ16 z?-p`NSSS|yu0vekrihQBAUD)cR_$}7tD4G4#UfU~Ui!l;&KD}*?Dzap<*P}h&>Z-dAky8p@3`5k~F6;0gke2c8!Si`Zocf@O~;%z{x1rl_Vi@UoSD<&Oq|x z=Yj^{K%nX!Ap1l-#~2H}9NUVdBK4j<9s-KHqAnUm$qLv8yfL>abR5oIj<+W>M$9RY z@qQ}nhjI1>c!Ef@sFh`t>2q;1-ioOdPe@y}xS~E9yBX{amp(Xb_w=?lG#3NiSR$F$H@?)IE)@CV4@t4WS0JO?S zhJ_Gj@NNW|z-?=AsU=5$1Su$ddPnDD+O`8tNyyzK3M1+X)g1nuYHQ$&f0CMSxliXN zQB+A#|FXT_Z8>&N7@1T>NE90thS%ZG$(Wfoo9%JR^0m(lKv{F!stDUZmRJ9_TPj8O zYD|nv(rz+$mvrsA1=u;t+E7%m)qSL&DS@+r+l!3-+R&2w*g(+0}*d1Mdpo6uVwWs2G`A$NHJeMpyRfrOz+JatpEL_j~0nZ z@};-7uiQYSqhN0>BoaSP$WBvwJ{ET0NU)2e6FlSngx^!4myWaTmo1n4RNeW=wJ^V! zpb_VF`^G2yIT-F@ysbgOfLrp~NUY}H)Qi{NyacM@xuXOOJ{A%z3{y)8wc&4yrS3ql z-KCv7b8scvlCNb)d@Q_Qp;<-94iVh!we-hsjktP4KeCqJok7Y^Vrwf2cltMFFw{h{ z0M2ZSpI!g$*SGD2#0qj^wKxD72$#|Jg%&s_f&ea4ZI-OZ(|4hIK2E@#@X()$Pkgc{ zjO7+CM%CgD5%n;e`-{kkV>vZG@4%jEEu-=>-`3xXy5)rty;S4ZvTAZe2fSqbhH9#o zZaJ^fz3*IPe}hiEmp@e7yPJi#!3?CmbjDb|>Vm!xZ%|r%b(`D1KY3@}VyiD9<+YTy z|C(S<2a7TpuYD4RmkrUvq{!C)C)`JPV_bT775U~?IWrkQ*SVPxxZYFyon%(Mmra&0 zpqk&igXxv98k^rkl&@;@+XA8}bY$dVV)<&pr7k%%>tZz90+geLv!Si_!!9Qg2!en$ z`csnDbw@UkIGV??hQN~2O14vAku%nQv5r+H)2o!jMO+5m z=YG)7RYpv(CwDnU+V?M&8hHCdq1CN%_Wg>t9;~M2+j#$kHvkl8XDTmaQ^OZFDdyc5 zwC|tcz2*zDl2PcL{jB>@+V8@p2E1=Wj^eba?yBpkUg8376!pZk&Qbwak1s( zQ*-980cmtM*&g(hgY51ELc5&PcF}>*Z{br8sWLz;lg{qRdv69gwd>`Q?fCe{tMMJT zP>8=B6&4LiwsOy*@C&zVPYAUKzrV*jNE=pcpKCL-YbfPv!;>6J=+>>qP+r*56GGbK zlQ@U|57;j0ysdz}``0?HwghRmC&HRc;PrZ?j_ ztf4e}6{c;=d@Hl}%Jr!SNYJ^B1(MYm3_x6R!#ZoFi5FU#T~AWdxo;BkcHQRp!BaO) zpzhM&Tq`qCT<#(PIQNN@UH#Y`o0bRz#!6ZE1EkD6jwk-1L6hN)kK6~y*$dqW-d23b z*kYI zF{8Q5fA{!{Zgd_XZKR|*o6Ww}FgN3mJ|9I}$@J;z8+FLqBrxY}5HuzPj7nl7#W=y| zDkfO(MV8bFCm=q>KKP{&NPG}Cn)@#B?`E2t(VB_*uE5{xzD4w&;wC@nn2ZCV&^zk! z_9c%6BYx?W7i!;)WlfcRa#1~uFG(tU6DJjKFa0W+F>#p|Ocb{ASLA#-v@rlxd=4KW z#7~6aIGM7e8R$xYS=C0_P8=F*vWNJ*6$)h0;ak0S56w2PFPj+wDUzF&+{oku9Zv5f3}kcC>un%&qQS@G zY6u{lmJ7LyDtbt*EB8S&S&IM6~6JDUov zC|0`?6G1WQCW(b7x)s3dwR0;(KH+sIE)7VNv>0z`%L<@ehTi8Agw*vS*lhc&RwOxV z%`R$)$t2h+CxTc!pvLTP+;Nsl7xV)9Mv!iLg3r+f0}c5(o&^I^V{VbQ{h>yTX}tr| zPC7*x8L=Z}ge-cJM`L0F*#jxPk#D(GNV*wkTk`l8E6YcV&WiAt(U$ux%XKWa29S1z z>9Hkg%{m$28%$Q#S#A3{FH-b?gv-hi&;)>QxW@5z%dzW%eL**5fa-7eIQ7SC8Bs zegPUa%YoWrSc09jGRc#>9^X_gl0|Q2w#Rj6coDg!u;~2~W*HZmgk|?#ZWi4LSphqj zp?s?JLBc}1Q4b|ifL$v>Ru*6X3rYFt>XF3qe%W$NbH;wvcfttI2)p+@@zjZ8S z%6bp&_cyL~JmsyazM|>)&E0aWqokF$8h?i3ib^VT{gUMps@6=0HP7%fUxUH)pZHt>mHJoJx}@e2nz# zwE8vd{+mvTISb{tK)HIND-R}q#R%`gFx{*rgQ)Fbyp})CkB%}Jx~!Z9i&a(lA8<;U zbc__-eJ*h`37!QLi)_cEl~)Tw6)@rPR$KsvO^*n@i7-Y_m5T?hjfWC>^da2|*2@+j zMxXuAFQjbL(MgVh_T(aW8OPjJd^Y211#ZA55^FBlN#5It4#OYZt#qyy;ebN;u-77tOvmq&rhk}&@@=0HG-F{bg4~;8 zu`qUrzru4rQU~#w9#LNeIRA2K5&dSY-)TYE`+uFQ?T|N8GWg-G$5_ZX0uq)dD0~5} zrfT;Q=bIk+T0}n5{@u3?;496d`qJBHM?wceqaFoBPXjq|xP9VO(w8t2fv}lv>4yv!faqxTNpeU>K98s7=2QEq%8Q^1k!YR#RS5i zIm}TE)>sw%eC`uMm2*0?a8CGkQNk^kNH7mkVfH~u8Re-yIf&oB->XDKxN|!pF-5$=3_BTJcW*kHoq|b z5|1|Dp<6H_jv2i$Affi^Rq$vAFJd2}qZZ+w`Wrz0dAwv5UdtpHe(vv~)?D_vWc@<$ zYpJXH5O%Y?NAzfhcQp_1DPR^eNF{Qaut(8L662r?J~FlawTQwzTOlK2wlZ+rPL+HwDG)IX=}RR99iaN&RSc7CoCA34boc~Q{PZ6FvzkqP6p;C# z?g=a=DV6w0d1rM_gLndS+V{ra!D|qgIP|bNsE|7w>$8kC9zVT*7hP(80`nuGa>2`* z#f#7pkm2@YZVacsQcttu=z1bY5)^o+V`woqI;u=ei#Ld+lW}BS{|&7DK);; zUz^3{*#?Yol?f3&&d^_-1v@kO?mnmTEe1nE`RsO5YOADys*TE;uyIg?PMIW7cht7O z*5<7UFG?8G$fE!oli1h2q7Qj54N$qk8=$&P%vXI#=Fm)3T8m5dXK5Wi0f@EJ4X9cK*?`~lwp{5a`D_)DW zW23)6>;TV7enQnJViQ6{F`@1ExzXc?P$H_9b>5j96PtALW3LVb$Eoj}Pf4pk8&kchIU_94yhr)tGS< z#O>tEUYiB`1^NQ|nNT1Kpq#}jx#Un1IoKt>xa%z%?0c^-Jsw$|bu^0~;nsi{4df|- z<{Zu5M7rcsvg_)_M?k4&(ZUQE1%}C1;WCx2^Ba|XMm;Jej$D0#l z9o?KPJm+gSt}8KTAMA+DM}>uWj(dq({-0yg=z8t-=RBBu-yQ<*LSOHbn9Dv39g>(^ zy&qTG@${)?9PE8K6T~9`WCx9ay}vODu2sAIp$51;P6XE?U>fg4!eNE)52vHhQRjM} z5R8awZ@=P=h?`moI&(vtH-K>$_?rggwxmdoyI+au1u(xfyibrMFv)T<1T|C}0d8Y+ zaw!IP5`L|A)OIv~`#%t@uOtBH&UgBmW(q9!jMqW}fa>DyX;2)+CA6ukO3V!@3D*5VttoB}Rdm+SmF-n^S5;EyDipU#+=C@A6Bj`owwU zgx(zWoT@<~g)i`p&YZnolEm10X{*$0*!yb@0CO$iYP}079~FPJPpgi713b4l3X@d+ zplUnjq;H|LFqNS50X!ze0)6tmVv4U(FK#Xnh;{oEM+-2=EZbctdX5Vj)tA5~(_0GX z+JE%B=sIJPRj)y(aKq;e54Woz)A+65VvZruOmJoE@W7%B0dRJJ%&!=dRZR0m4Z{dtOHCixLarYxpVA2mv0xt zD&K`^Ve|kcb{;In_o_iLxQu*&k(hAr4*AOM$?)?H77(q1RBK}`j3cAx@_43al+rim zNt~tA12>oR11!}%7DO&z!I*bJsd?P!F0m8lv2~UoKB5?3DXTevRecE^;(BvJT@f7p zwH{T~Y>P~R&VRB4@-K8gkLaEIAuNZ`ArUxPJhhXHmsF$Y z99{gLfiz>3m?L8=?_x^gBtS2dv~N6~ z442y#1QjvDKg@~fsIDadHIbVki2YO6Bk@h93DED?(n>({59-01xiA(k573mc|5$0_i$Fcgm7d36rqH%PtJp}9Nx+?fslr+b0=%M?l3^C{yG1SDbbeu|;} zROlTi4=F_#=Sff$)3hP5F5V50Sk0(*o2O=dlAg!Wm&07=K{Q1-#_l@AZKU6P6=vks zzTa$J2d7a;oHyivE-VK#@8~*Xl!PJPRPpwPSeRb4@Fq4XNx96AbWGsf=7pag1x9#7 z*qx+fMC!oXkCm%2s-TZ8RhWQBYM-ky3SmcenD{3Sb(9AeP>+eDq66La;b>-T; z(B}%Dh4q73HZ%DrOGPA*kd|d>qT9`-QbHNSi$_iIDaEDT*ZvXkC z-LRzb4k<@XEH)6qa;}kH$kzBkNxBUPTw2GK^Kkt<^^c3zHJh>m+lI5|4Vw?WfyUVm zW^r-E8YVh6zX08IWk2%|pLqSE>T_)_@c@pUumZR!Hnh!u4n755=Mwz z)u!gUHm+8ly&n3<54V4!%j~%VdOvbMZTGH@4pGss%ZC2)qgbNX7hV44^?lV@C2YCu zZHGkSw!f&80DSsKKusd?!*Ej)QP#k2uwjq)=N)W$ru$2(eQ$0?KvbrewrVg|K7cSt zMntxNiK_4mIo89J%ctep#G56VYt-&dsc-J$HBCTL{%$t$Pnk?G7HeE9|84!k6O&=e z+nd!!5RQ`0}+4QjCz?hC8l|H85aZ>A?ua=BiR)Kx2T} z2t|NT3c$3QZ_Xx)W%=vUEC#Tq@W;a2k{m$+LZj|?XhKhgb4=h(=C6^B2Gr*U@Q){1 z`f!_9&kW%6Lr{TD_nXW7HjQe7f|Y?$0?wNCVl-h~`*d*;v1ZC5DKJXy`=&bEJ#CM7 zOp=E1Ow(h6%NFjk{Ih`x3VNh}m}2ubLlypQa~G`!|CUv@uL@_8ANeUi436{-e&H!Y zfA`PTZy-PL@gQ04_`_Bo`P}`2W4~MoZdzZgDllNT-JV_ElzX18b+6nHSuqZ9-|2Csg#4+W+eX|Y0q{ws@dt(TEidx)Og?oKS`V9bAhvT zkttvGo1EC=*`jG0$pbUsWcyczj&Kdh>pLK)d(y9iqXL{o?ruI$eCHhT5pue)Q2vql zb7=m?6gb43Y3tI;Sha-f7D!R}=#ddkczLDHTYC$q&99C$ho4lU1(~zmtQV^5*k#jtqTxv~um|bgTzs48%>#!#;Z}7#Jn(H3+N5D*Tg} z>zbly4i;AhMHw_*3etYi0nNuY;NR3aZ>_KEG$ZdlNa{5=qRExY0^u(b-$$h|?$I`E zLE7$}_q*qOxhDkvISgExpgfEDa3Lsa`1CLztB~d>(K`VyQpk|nr;G5vHEaU6`dz3? zb4~X$h0~N#35}Z}&zDT#Ekk+0h0jcEYdxF1aEF#{B~P-3f078cfxmy3rwhQQoh6nK zmFsLw0l-X|t@TR0=@@vR(A_m|tQZ{iGz#afyUVSQHdd64e) zVgufdb$J_&G4Pdrl9?!NM{k6lwrF*~pfHyh@bkg_5eiqdBLZ$~7o-LcVgY#PlG-4)@9BbJvH;a2Is*VaJ@*zf)>s=|)mSIqkQR)%G@;qkePAS&(jJ{?Cd5U61PPT-HHJ zwk?W7R8H@)*Y9%rewfaY5hp#nY<}1=tB1p=w{iYhXPXT4_}iCz-(#xZ2c(K`#{{hC zn(t5#mh`N1A!$2$-i)+LovW;YQQM!PIINyL&rNv9g2ft@I{fniAh(lE)ZoW_(|{a) zEBPWD!oCY>RSZlGCo<8fMdz6s$>Ro68>E@9k=T*^I%k)S^`qtK^Nr-oUX6vsKYcyd zH$gt`hfZQN3-)^k@W*erMPmb_2A8kV?0wcj82Xl`PO4)ys-j&1ZtvVvN?C(HbXQ)X z+8_R5ZY1+-=W-+9R<9U^HbC&&da;f50rf6`(`@nwRY$-%S}VYPkk@L@2*quudw@b1 z`ecTUbtnc1q=Ni7qfego@_7QS+nh}|!}==KKC;A?d)D72OLs{1fw^t5HE=*_vb}9Z zYua$4I+k01AEyWc3tWGD(tX{h8rz=Ts;|Qmckr>c3`Jv zD~g|QM8s0u*zb;jc?urfjgtO0b6_kD7rMi3DY_2oGHwc<8cH(5S>!uL{%oxIt2#hRMSsIR@%Sxs6V5NaEmIW`#rn_xAL875$@Lr?bFxunpn4A6Uqn1|`y~ zAoNPFRw8xL;L)?*J}^k9_JII=NWl**0JqP3%_M_tWHLs`@rh!y~IQ+_0N#00NLr^EN5~GB<-_DJlu zdn~aqjL)y@M$D(1qF8Lbs$oq><)p&aQPGYFm5OzeUvzI2s|kl_BnEMw!{V54U-Auj z`aP0~N`3gU0mydomJ?_|FwZc1E`n%r^Crm=M5DrMi=?M{HB8j(pf?OuVJXY6e2eS* z1fH)rkKVz0C;lXGcFjW|%4BE$-~c;Nk6;`)qQ{1sx`MEwIOp>Xh<@ys_28i)KDX{p zR0Ym7nwYZ`&jO#hZ4=6c4V{9?E#XigCz*@b2Iu6XFP&i0;|oN%pz-DfY1u`PvPR=5 zJ#~?B3l8^)Y_D4g&G*+z*NM(pwUNtcbRYE~8%3Zp@8qz54BK1mf`zwiW`> z>HCw$Io0`rm1|?9H?OSu#u(L&8;9;7@{wF&jytgtdaI>Ne2yTYmkxAo; z_lf3@w1igss2_dZC|peQ<~M_E#SYQ?cvUPu*@x4JjcgZVrwmO@qFn+8qvNV z3q$l28__rMya=-$Or9~c=qH^-QH(U^y}p}`!j>u=ft%FG$gY*eEb>!5G5n3f8VLvk z*jQ=m7e~~hU*cEiMZZxapB_0ZKPcWV-n$1B#uuCh9oGDn`4q}<^N2}ivsB3^X7S{p zD#{1TeN+ayg|O035CKkfj(-%{S_I79%9Ec%AN8br0rYKw^xg-Hi(}3jZ0fqdmIiQj zvARjeZv~ccEQD(bem(h8?nuXXPo;YMCm3m7`n{oT?y~ZZ00<7}x#%=av1?pxb$hl- z0TI|?q6Q8X8>%6)T#Y73ecyrY{)yX<6%d2B>_lGW5+8vweS1KbMIr%M^B74TU?yh{ zKKhi3khc3gNM44}U8C37#iOh8J2&cb7>;p21ufiS(sa;K8Z8^jT$Hr{G zj2I>^{|vGUjip7tIg4qMv!sJDBB!twU`qLejS+V(Y^O-Y zBGes``(x3>VLx`N=o)=Xm+Seo#2(Gfejqq+7Wb9ArR%ldci@i6*Q$JgL=|i5uvD=5 z7`POm?J|BTX@W0i3HQ-VIJuh0n$p$^%_N)>Fg-t;+Jg|%AwdXaB}{Q(nNc`IXtlS6 zC+_8ot)*3^iL-?ka%(9A;bqcbcf{7xlbhRZrpqMl)P`2#!=m<9==EVkF~w6X?gOLR z%~R}=0Mzg>mLG8@v&>lg&32j8xOhkAkY=W4FEKlo{dHG@oE=psijl^3L&g_8- zDmU*f>*ry&mh5mYIatTT*hGpj~D`%LnC?QMbZO$>MZ=JGi95s;;rd!#w*BxE`J683qW?Z z#)Jd%#(k+Hp`}sM3E<^qx1xl4$?nVY1SwPkF?%yzqHnRpzB-p^@8ckc=y8`GY2tZE zS&~m&tD4;cu6l zkF$NFKgm&l?``6-nQzR6veTV|e0#FfR-p=r62r1Qpvm|&Rt1Dx=ip4P=6y~hb? zMP4@n^7U|HJ)kRL@OoW9?0NozdWjb+CcU$LB-tH>Wip(V*>UOcKa<*VIb+{V$I8l# zD+w*_eV}=p<5wGE=5`m+BG{4bS3B~-dP3jK$96)$w1m^I*75?tNu{2uFD6I_2J2DS z0M{@;QbxS1E+K9c0qM~u)%h-BOzh!=z5;iB0rWcdsD-}SeT*ac4x(X_Zz6f1mCJ8~ z{D69iN&u*6+y7^wHUiT>lIIq>|4PQyQk8d!a)Hrgo24d5^-&G z$a#_B>|3_Cf^vCH5;4h4W`l+bL7pj(J*cFelE-3K0!JFvY|%_W<`Icm>5Xk4s|X$h zUhQ0vs>!}+guV%OC`dP;oBUEyQ4P!T{Q48oLH#e*=G}~%EL-d7#z^&uH@(r4qH{mR z=n*^N35oHzXoza9ZsYFmhfE+irwYSPT--EsT&Ll=+kB2%^t&yh)2MbO!@wI4J!!oF zi>=X^wAdBWA$H#D`X%6|GOB>Ob?Ub05LC;y-TGc28D<|}L~0AWk8e+lyxj(Gg^K-& z8umcB6d;lDqY3U}5U5gENtek3#SSCWSX}aDWcxVHyslXbIahF&c&i4V> z2M@(FoaEr5?|NwzYc@8ud?Jt`MsH8WG6FK_rRyqqle;J1YeBJCCQqL9;_n-&5b8PiZH3^tPco_GCc=xGe{&@GEnCo@p z@|ZClAA-BDP5VpKJinsN`?@rE{!sW+c&@i1;~Jq(QPF=WJq^C#XZGMJ-15aujd{YhOS{5a9aXl>1m)PkmAcb!$f!%7o3R5ZO_bfiv1C|5KyPcHt)9at9 z=c$rxib&q!92f|$8BG*?V=pvs^2j_M{^h_{p+Ntgt!)7#DmZDGyH2s$SDa#=*ZwxR zPBC4~ra)hX5(u^W%~D{P&fK`%eDT9#6Wg+kO?Qau#iAp%Y6#mqy2`|!tG!!uCNEqf z;R80I$!f%V9DEt#z$ZKaCEUx1}z_|fH<>{I|V&$&EM z!dS}2SeaX=NY8)6o$?SyEr2m{=B{FO_Z3dOUc@MT=jSI1jQFo&G|^Wn>J=I){p1va z8Dn^#;}%VvFHh2d>J2m}+#%Mcy?O$7j>vY4=5cnEfnd@)3X<{(@T%KkX`GlU`yK^O zj4W`+gG3SOdA}|i(2*dr+%iP;;^BgKFNNllMrb)ETxfK}CR{$-)70ff-T>FV*?XA_ z&plCjH#Jyik58tC0-M@e=KRQ}zQ&ZI0w1sc#O^oG06o}pBiYW}3)9XV#udG`s!ywUVWa-O=b%+l051^OMu zSk3pl-mV>h9*qT))-G#Pr2ioE{7h)xZm*{*O#@nChP59kVkFT<=#((Ja9R(Pka{fT z+Pg+rcv;DBtctm|ES^{U455!nPGu36i>GIH`54e zfc@H%G;fy_7E%b;6a5sBG|%tZ#Z_($O)=6@mwOa#{_GTuF_N{`NOh%}nH8;m6y2G( zBylEB-0>%67;En6w5OVKfG^@FcF`As&lAmI$1trrSMMtc-U`yuh_)laVidi}8 z_DQdD>$|F6i(RXQ7uztnU|8HXNV)ZDL+*W=6^v6Rn6<%rdpkxz2U0M+-LRcgL%m=( z@?r8y7hJT-N??{I?v>30J7|E1pDOhNzv@6;nln)@nohHUC(l%3jz;Kj;q?W6yld{e zr=C6GxpU8^a`buMPQV+}D!5}Bc(e>^FvP;v%tHW^)#Y!^!fpQ4xe-G)hryWp>CThz z2mRQDhNgq}b&Sg;ze*?IW_3B9Q|g+To@@>glW+^RYB%DG4{DQemAkbX3nw?o5*v24 zsIE-GRgC_Ryt-M0kw6R&21+QLFZ^Ts6KmLUoctJ zAA;u^&tsNK&KA_Oa~teI^pXonkIHQmrsrxHN8lT>eu9Bi8P-z?q*D(E*AuT-Lv}w# z23)&hBbBiZ;bI|W@bmo2A7${_y1@Q&#;@mrwU46r&qb;pMKiTmu9m^`Q+(r1pq>`i zQNWh0+%NHBII=^@hX|*8UQOpXMYG~$tW`=Xd!eZZH3IiUB?C_7zT`q`+@tNTsKiFk zC+Trf)vs;lpZ1rLL=6Q1V23PcjJC4^=(=sBanU@keN4#a5pQ5&z+5?_3}gRDz!C-GBGx7o>=E}ZB)U74BW_Im5iFoCkeoDwHK3j*5{LIECKLVhhc$z(5OnE zGr_!ygN-H`W?=+^{SIC*0YrAj*IUY{T3;~S`C{8)G+{mRVtGRnQTzH74SPMd9h z1Kmvr%s~a2c_pL4=0bhb2R{5(g^8rZ9k}NK$vAZ-Tr{K+E;{MYG80>PD;rz!iRWFl zM-Mm~n;(CZl8UCG3zvoPn57vgp#NY;bT7D3Ns@ZFe%Vu>7ilfEHCg|fzIZ63g-x%X^MeWtRNlv*5F__E9@so>F(~~l|swoV! z{o<`$N%G9Fc@fFaun|q%^;^}LpSBSF*e|D{TgPLtC^kvM*zv(lVfbOZn}W3M0{}PK zJqGZ=x>b=j8aj6QrniVRc=8ayTgBIe<{3naWhPya``CE6#WXG+-lKaVHR+Q5-eGe4 z^rQ?8)g0cnrNL-QeAg@>4c@>+!Wmp;)deR?i#)*Z?In|KgMh7!0!B(tbPac1SMk}8 zY~H;M+nEA=jTv?~g_`^ak?_DotA;y7hIWm*rqc;^R?OqFX$a=m+K6z0{@Ier3w^^3 zQ#v|554VC+B)Bqhbcy)&uCWoZKoQ^!OjD&{> zUxMrAjzuLWXoNJqsOI;0Udv3l1g@S?0FDXc0wRYrkNwjK>ygD4|qu zpPuBb&skaQG~R*o;R7ZB0*TY32Jp50?vU36jWzjUwHnbQk&}0FyFA4Mupx?md%Z|s ztwd;E&-D}VMP4*13CxcsnP<7(AO8oz#D0mQ2Mkm~0Q*75RO)$#l}!4&Cat*}G#ISb zrSwF8Ykr11bRdGF=?|uX1&DDtSGR7!TR+^U!M)UOO6AAAHIxXL{`wxb?Gga<;RhU?zkv>2{ibE*R~ z4GgivKDNSBq6t9kU>*u{V6z=>3iaHs^Yv9Sa8X1!V21Z4KGST*)brHBMZX8;)vpaJ zSE_%GwU-IN_Rg=q4b2U};KWZPt39HbG4r=u;K;tG*vEbQ=2q1nzSn5pjMT3cO-NRG zsAJVvoMyIFH7B@x;5#mSe>3ffHMaB(_8%VDI?u)~ChFp67Z*k!&Df6cRWa^cL|}8% z=YAJ2)ORtpSraY!hR?R~MNZj0drBVO z6|vMbSuB;DrHQ;*?l4mtYcf)=7Jn1c0(ZOiZPIHd*0Fxxu>~$Fm*OxJ+jA`aJ!p6* ze80CoZ{dYZjz_e(y6N6L|I8FM*o5ah5-9p_Bj9RsX;Lpf$D^l9Mjh^h;U4oE)T|>7 zq6!lm@(i%j^Ddr~R;UFl|J*_hWCfs-PCSzHnufVs^NSZRd@!eJ=m5-w?a70I`Zw>c zRIky+(cA}=dUjC1M!&^K4EBQ*m#44dj$0Re<{Z3WrBJ75M@-t0n%(~K5JTUvtAf_I zBkJBY7^!bkHn_lH4vaLtG0jsTzDknyOTde2lcLHo#R6F*x9}sXh5R8oVE(ShJbV<1 zk&Sd^)T$&Y8qmwSV34o3A=Pk8cTsx`T*jouoLHd<0IAe`2MpZx0Jyu`t*UR{u2~Pt z~p7;ZLzwlF0N8Q{A zv5k!_LmLGPW*tAD35kKPf8RQ&g^!r#gh@i@EHFP~yAqFTLUeuenNu z{0kPk9{iOt{NKqpRl~X&@ch4$k83&%TNiUPVZU3<-==oCa)ku{iQZr@`|j1jpSF42 z79R2Y`0e`P-v_stR16QsKfC|M|Es($THf||JEHQoI>(#a>D+H_dn9ajkuTFKWA?L_J46R z{CA{HMA+5rf0Il%?{>WN5Y3tTHFXSmY-N-R_UHK|^z(dUL;kUq$=hzFKL6&KYu~gk z&ustB$S{r*$3;^99(Mfu`~79a<<`r;s;bp|L#RQ1-&CgPyG9La!|G)C#kJh=*Ne!9nKs+XKk(>nh9~3@B-6gdt;Cs`Dgf0%sr6EFI>@K1;l~#Fzvou77JVKE!yL5h`ezK z7{;zU$kP992*UJBXz^MtUa#8WJ-;NZln~ey9{`H`<(Vkdd;K`L3@r)M5NZl=0p(4~ zL>q}0I^_Ag4?4aNg(%5vSNkM3un_}H*^OJZcW8FfV8X@tMJ@I$A~b)-|F4U<5IHT?!F<$wywI2G=t=& z6_Oj~vV5ohg`r?uhjo8XY{Vz=`NvzKJYVUS)#?(yj7|qG2s!cZn_O+eD@3o`gG4kF z>JTm<5s}+e90@}C+!1ZSq@W8rR?)Ti2a3A^I2acs;h~ z0Q&w$zrDZ&rH6l+qmwCjJC8W((J2lqeUDhaGzN*pKHQXfDAc=GM}{uMpP!{YbIZgD z_^0MXn4mIuQj&EDJo|~!3&x-(Yq1nFkVwA*u~+R4{`j;TsRoiOZliyELx;eO;eAW5 zgOsZhD3}z5xwic@)dW5L`d(s57*^WlKahF55n}_~(8}!W3^7QG0tY7EZTzlsQf<^7 zPtLQvvjxGn6!VV=^`eh6QEoX^&L7*Yx>df_XX`d1Tt8*&60GjT$9aR~nn!k@_<#as z(v2k7!WGZj%)6IZZ@q#XEF~^y=@7&z{uDtR$ihP2;73hO;!RPWajCoaKyqd>O|p_} zFJ4V22%(3JuGZpbQ_9VS78Me0#bNN#T8>Pd7S+>EwPO5i<(REecbnH6$IP_LGZd)$ zxfpIjbS+#-qs9m|YKc24FzQwrA?MH`K*UniKxb3S4-4_RHz)mBGjZdh?!W|(#*CHcR%Nf$ivUBltM0}bMYVVjN}x>X*asI*P>CGgGq_n1gViC0Qzl+XcH_HUbInw zDQi}+w{A}=Y=Y0eMe1v>AUY-J0Y?Zv zcRcewS85gGxM_|Sp)MfIRJpr!@+eO0{6gnb@&i6tM?NiUD$Byt9qv>Xg>DDR4b}$9 z_h$UCei7$A>g&C|@6raI;E~`rA><%AUx`yWe*2bp1a@tL3i~Q|8p}$b+vyYhet-cw z5}zOTHz)|d|Kqw@Fn%9m?v`BD=OdL;W$i$XVQrZG>&)t)Y8~R0Smmz~!lgk6RiiGY zTi6Z$S46kqo>(ag_&>zGeM)B>!+e+y#OEKU(^;Z)bOg{0(cG;@_%gviQk<}F6IqG3 z1_x<>igjeGNOo_VP9zF!&fND=(3njjdt6AjFxh&$nhxrteVut;z!PqqD1cUDyWy6Y zhNKBpY>#jAD4zEL}<)j%ahgSl>K6DaJ1IYAZ$spi)=T}>RGvIrGXGeQI^G@EVj zbaNiRy@Q$%p4Yq6{h2ozm`I9%a~nqO^I&T6*y1}VhBhymG?qzqnN*hH#4((5H|D(l zA>Ud66fBX7`!*~qp2D)47QT$bFSz)?dDrs$BZ^qZ-bCaHpq~_OjvCC^Y`It72PENEn7}l zdy;w_u!a{POpdG$=?16*sqTPVmvyozleKt)27!V#teWmSj3=m??ptP#1_9FLS4}s0 zkO|{XWD!!v8{wr!WVkd28QE6pHMD7e>nUcAgtW=1a>s-; zI<{|k0nbU*1OX>>VI#^CkD<~{(jaj6sQY`eHtaUsvA_e;ff1)Y5gVVWFsU1`;0dCTOl0YJVXw5{j+B1Y)GN?yEDF2M2}?ye&)lwwtk==Zf3QDv3YsG?K1s^UL zFZx}`H4VoVaS|4ZCxqP;cFSO?em^XnaJLb`yq|fOAl=-dE4;SsVA6Meaf4asdaqkn zmUbeZuBmPWAcgPs{ubc5cPAB@bq0e>h5|GJ#J`RKC}k!jISS$sy7RaYpX6s6lxmDZ z_mn5-qmt@#*E8-m9>ORbAO|7gWx056Avq4$3>N>`Z`$^EhMs~B0_WsGthXv!zvtq4 z!!sjXGbiK*SGaTtFLe-}MyTJNu|Ja_>jHH5kzwyb6ia0kRoUpp}+y+EII@VAu}4GMGx4|0{qdMfkI5esY_A~ z)4V7w{FXujFaQz0mlMd9#>4qqWD^S zh<^V)5YOqm9(g^&WF4ufz^*&&wvUd=%<|VV2DV=fi8=)JbWZLpoQ#&|jGd)tUKu__ zO7~h;8ZBnf$byo)7b5wvf9o>aoF`oO|bD1m_AyqCj(3zwTTNX=* z{p^@HtX~Eph>u$t24V;_C8zjG?9hrC$-D5H~`w&d3q%E&gB_t()5b)(qeTA3Ycbhhjt zcPHfecRQ3Y=Bu|u zF7EN-kB~0>UfwU1klrA?Dp|7&?`G`*fy=_6yUl)#Y(*=oUOBi@mlu3jQ*{ZucMp@T zyN9-tOayY$EIOJ;fD8&gJnZaxNVz6QY6ICdCv@YtqXu;^r=3t9;a+Kvf*x5|vxucH zM>l>^uMCA^*g4}B=Aj1aRcIXnf7?cCO_?mu)Bq8;<$G9aniABaLWz(nVc!J|L(R{a zQFmLOD9~hWSQFl)BET_r6l|d;5DAJDu~r2SddKRER3-!+5$=q+ixUVRXFkPeHbOVjmUZ`h-TPh7Vr21b!n? zm^Ve@+~x+1t3N%#{uzr0QS=4B5-ePg+Dt>FcQ&p6PZ8VtiF^8OC76LhgWz+PuCFA% zmwqT4b|uA+Ah~w`XPVQiEMsL3)J1F#Ipe!ZbbP!6Ct;lNX(`i{xDW50bwzsJJ3hQN z7-a3*g?z<}<_RB_u&por4yrdm?$Dm!p9a0LpCx1(AjS89cDcw-@^TCaa*g52{@rSw z8d}27)0ptDw0H3t5}jXp6GYJ6`R@ac@zZO1m+>OKubU0u2BDaIUZIU?$dcjFF-IVg zoO&OQb`kH0ZT?NR_3C1^xpO@FLQi#Aq*p%_ExGrY)02-Z#gH)N+bg?iqC)9iAvi3; ztM{o!Q=5pV4|%qpX*d|#y$}nl{d$o(sXL+yi+U7#Z;Q?0_ko%Er#aK4UgL;3B zgH>qvoJ^|tfXF8Q%+C{$7%J%22}p$P*9%qHG8&wbXoytcgT7#)o@#k5E%p$SQ1<&& z-QohE{b@F#-9ta~ep>$k$vxRVs|xELa<2C`KLJgCo;(Tma-Yq? z#yR&&iJ`W8_lcb^vGxHd7K+M+FcxGK$ryY>)}u)iu+t(k>0T#V@N*BttlyH z9g)S_Uuax6I72KyZ4EAyj~ic4jbU3KL5xKAg5&~;%9tIO7Xj2+M@ilpnc9Nr4-@u|fNm58b8zrH zun_Id0c9o_5w1RxR%}iDej&&%Kd;#l9fOLcv{1_DBM0ANFT{;QEH&5f?<^-&D0h6(;cAfuX!ZX&BiZ7^d zMHmf2GGd0y20AzYQh-@OwQWyO`0jjZRwII%k=FnUc6)1ITeNrL%|j$B*mzyaQgk!m zWW-!_Gq4GbhSghERI9RR}EUxO?5e2}ASh0~~?+Tak?CIbP49xnaNG027 zurY`09-;6{CY{*zV}bNB9easzNj>|wpF+FY;oeVHxb72_NaAZ|A#8Zu%s~)n#RqJ> z)yG~m93&TmkztwCgT*er2BG9)l3L`fL`zw`5m)$_?rT#GEEeVh;at5g9CFDLqjL?$_%L8Q88w&WO=BDGoTQO9rHU?|`JLXw~V(8pRr8IA_T-2BS z!Rx&f3roue_QTot2}W+rti59BljIkXbQI728uG+&xB1>$)?D)|Sv->mv&Jh3LVe2p zA|d9mPBDaK0Mz$^7u_)b(R=>QOm=7{XXG9t2S7qG>!c4{t&wZ z|5O-4A%+k?|Hs+^JXw20h|NR!OPSnxm3Dmer;y#@Xx?>12Uc9&8gUQI)9oxUp|jTT z$@_}e&Pi@as#4`C>*bdHh4;sHbFeF;zJ1x*R3isJVEhp^JJ>7*nx zLPOWZN3a~N(}a;MjM7D=;m51JNDg6|*A?BLAO)s`2!jV{rshvMoH>e&>zYz3Q22X0 zEczTpowp;)PzI{*5&9hRlIGOu;A)Q#w*}v%-71FY#$c#~l1*kGnMP~JAa_VY>0q8v zOsvs8*t|BJmYSpCvX5PWLbL6MYz+FX)p}>tg7?=x_VxP>7o+U*ZUdRXdYIm=6ntH^ z{%l0d2}D22zD{<10x#AZn|v)-EHs-ShK|=Ok&W4B`UNRv5qaB|+s(P(kc;|#PZL67 z|M9v;R=YHfy4>M)nvfaj@;zwM{od{#`?`4bfLmGG_x<^+>M@dXx}s%Oj54ZLMlcd?uQeyu-Ed>C4T=uL+c}c za8HhgHUGk4@!tBSeSQPmef_r7Zg8-|S1mZ;M*aw4HtX^Ck1XXxw&Vb9IIHgq|vf=_9H)3sX2>UgiA&2U?{tiWh%*D&qL=BBRg1g z*sr^kobvr>>J#u8Nx$v~n3c`Ze#{2;RWEB+qBl_2mEN3?-h(fUHEW=tVB}n98U4s3 z>B%}wFS#l9DVC8_9CYnmxY>ZZqL$es=?JgkGXoqD?;ReN<3{I!VYcslj>2^a^69IzE(Zors%?p zULg6ml zmECoew1TNR$5$y9xG+n)1N~~hUBPki=xU7kri@TE$pp4>WMcw50DXH>3Z6Spn-eZi z3nqWeJSUD0X~_GmU`7xwo>a7tvGg5`0N{waxcQo}^ViF6FpqvQ#4$!x4klW`vf`9F zZVtQB^cV$|K;Jr-=PnZwY(9T>3Nj<8w!oC^V|EJOo?WeA(f9eO7R^!fG+em~Rrizm z&vHL_@>g|6<=!4UtjJF+ka@)^W2cxePjOj5jKS`la1e;rSZ- z2iqQuT9UPnQjaRc;u^tIApdB{hFB?9_{%?Y$XA*lR1pP5*sp=oUtpQ$>3rFjXC6Z}S_RUZ7) z9I*ed(&zX_W7&RAMjsHJjtGd}7yTBGHodP#R*#?`}91S8t`oimWrb-=gKENHZW1#C7AJAhgo~7N=#nw-yT}N!` zD~J#9JxuWv+owr=k`oZE)j3xDAwVH400={txISag(^mVS`!qtsf=K~AY6f>Dx3NbD z_k7$Mp)Q&8HItV<%T3-JOE|av>?g(i+)3>>ha>&A`xu9rz z-3EhBXp--bScxMVp3@v1hGn~nbgxwkuPWzdPU>Ylvt(Nyq`3w*N-U1*N1?rUciuWI+p)xZy^{Bmow%+f zvaR3JFkKxSy(ZS)Khmmp)%t^+m$|_Dw$D-gEfMEs*?W znw~JiCFw{EEHER`QhfLiRY?y`WE8LzV zj_c;9{^(m?eH*idZ`*xw_;64Efxy^3ujcAsua@)Gi!XHBcC)v09{2D@r@nsdYd}hu z`WcH`8@S)5c=bxdG_k_(!B_p2q@&EozK=4!-XLDj^x1r6RPs`ejq);x%aA(Xt~;#T zBl`Y(w36Rc=eUy3cg6M`I9GD2ir2XIgy?eCenKRT_r6;3FOcFf&aZ$BcE$n^K1)G(EOBFXS?T-ek}Z}2MO1E{FmtMtJy%X3B=_TDwB zj-liaC&V{tTU{`~z(_YuY+TaGOuxO^Jy9T(0}MAo16I>ec+mRmx<%c77B|K*yJFh7VA8 zuAP&;Oee=7B{w0I$VRn`Q%N$~ROLw}a@<1~eQ@VoY}_}>Rl7`eZleoCOUBYj$K4>H zJ4~-HWd3c-KBy+kpJJQV?Nq!O+)T!MgG}|sU&eti0MrjWcfCOTf!E%nGI(I}Q23NsrP39RJa<{S2kciin1gqrQ8c>QVh4e13e6 z$h9<$q~_K8Gn5nmB>GK9DTE#wf?C$;T$>h)h@(S_Hkmk((`IBjgbAz`pl@-L(@sUJ zXD3thj%AJ1R0AcZz6q`3#&Y6pD8>$AU^!1R8jL~6+>%;fpxC`#=cUq+=8uJ;o2#d43-&Rj1n3n6CiE%vniUzP#5!#>>tvCikRPV(;%I z1@5#${UKS(>)MXnWciKn=sOkD(f7#=RzFj(@>&Kck&UgH&VxI<9(+|N$7N2R{vlso zowar#b2X&UAV;>CwORiqg>UuJcFwW=upt{$T_$5nHpldnF-gC0U(_Ts(7;KOxvnJi z0?mnViI6ePv(K-QAukV1@`08)qlL**P!EBYdEe7E{3dQoulIED_~>&+Z2aWC_M3FI zO!&8cjXdybFb~1ab83iC7_|5+T73VuaXSk?yi#t_+W&JIFAv#TkzMceXD>1f z7NlO~chL}%!=)4jc&_pf=&xL*{G$B3Oq`N-sy)CbY1PSpF=o|C>VH65iCI0_0( zeQxX;wQ41ZG-k=aHS{QEHHdXOW_6XLESfIL*IKcH9~rt)eVuM>KVTGv)AU`}h9NaC zvLmBM#X0evO;-oZsK#W^+UfG;P`5O?)CQ~DMZsgZp!Xd4Pj8j6=ig(|=~8=0tjiEZ zYE)}<<+*O=h$3?tgCvl(53UZd=*Ou`)3_RF)e*bYOcJ}YWs%Mm9MKBzJ%t&VUh|j; z{Ma@MnoI2Ro{R44>bEP%l%!rz66p^@aCc;H7%uZb42lKK}w;Z1TyG=ksdMj*CT`= zAcm~iur7@{wpdl$7e$8lUU~0*uwoWc%!`H;^m|~x{KW+K@N}(J_3bL@{Ow8HXmC}h zihEByj$g%D6||s-BIsm3)6akn7W^{8WvJuC*y3V{)=mImTaiNG&>wA+DKHOLi`I1`EM*&%6=UhbSvS(_Y4|TzD zuW_`xY&izMJACiVOcSTBwe8!xsu!1#6%}3f{Nf(&2w5d{otl;!hRw}5Eyx{RwL^Ur zQ+L71vMIj+W8xb*IkiA)_&1Cw?Rh`z``*V;3g_SVhS0*@;jcbUfa9u(^M;Bsx9(3(t4>ORf7 z+%HECuNczCwb{|j`QU=Aq;V5T8W1_;c?kXE``+#e{B+ULX~KVu%y6@bGaPo*aUF^2 z_=;6o&2jBicHVxOyGq8V;w?L+_Jmd0QN#C!g2K7b_B-8~9B9RPSgPnOZ>yA#VvM=&tyLHg5g*`*Fjs2 zM+BlbyAZ&!7}U1W@s394Qq)8$uxXesGe+4ko&5x6i&DhQmlYXg zQoaDCpiK_BRtDl7Z4wQcq#9FBcj2X=?Xhx+(_0-?cx1t}vBs>* zw)P3dDF{*aqr23;?BB=~q>ckO>6Wa@T0EuJ#2pom2)Woj)v)8#V%WPnBu~dQQ~Z?E zftogY@=~|U-6};-$OKo_L!$ml!}cXe3|U`hAch3IoIkMWQX4RPOyJ0O4h5uZ69+vl zFjFBtNYD&7pVjbzgSXPy@mLegq`GPEWBfmWhtz@)89YvblIOL z&hiK%_Y(k1)3~W?r=HKwL_z~tctdk4$pw*C)px1oap(GmlyT(pzdk7So4A_rlYjZ% z$BEN!4iXf=HFEgEZ{U!zKjd*o3b|@Ek@sP$%#4G(IcEfdyzG)uqLap0I3dR`7}l#DMDjky4)f@kk_-NvoDFkL&(m z6<3SzG~Ve|_JpRtPGwy%*#KS=Odbu+Cj<}s52qMSO=rPP?uVg_QqJVTYgWiu z`6#Mpac8*#MD^S3pp2nKA8IIcb2~1RYT;9Lr*Wq-k;PpZ`7H z%;)c{+R4v;TJSCSvg$0zIxA=CgADj+P$GyxI;x)d^)m-AYnt!;mt8u2Cr1nlM&_wr zKO9_N^w<%$etmuRX-pzb-tA>g!Pz=*-V;AlsZTM)p6GPrZ^3QRjf1yO80&j3hbvE^ zpOr=V%v=31Zf)o7cDTBe9~to=>5${Uj*%BZv?*quyCga?{K-+4<4H*Ye-*K-TQefn8l3ktrMJMn|R$EYP8chlhnh?xy_8&Id?bA_F!0 zJ0n^FQbB_+^_`TYfrN-ghp^8W-20I+$K2Ll-(i$R19L+*-=Uikr{8_=D@BvC-BBY& z!&HywcT<}2{4ijNWq^g*yWON++^{qSIWa8m>?;jS^Z;bfULOh3q>wWvxz7P<^oleU z&sOPX@D@anyPnF{jLTw3n4LyLk@wAxh3R{j@1@2Py>5?}#3oXt?jz}D&<2xj9KXY} zW^dJW$o*Xqz|z7F%TEhwfX^eD3^QuiuFEi@aqRUu_p)~F{-@CgMc0AONYEEGPIT$X zx5nz}@fwQfKz8fj#$|5wgJxC4OjybmfBdL11EQ^|?wJKQFwT8jj-GspwO&0wv~10e zp6vbz$qhJv_TdJeP8HJQKJlLOH|bSk^!Fjf-$Xwtul~!Ls9{>1qXyJ#iL?shg*pg= zc*NUB?RhPgFb!a|-|l&0;=WKG9R}SdDA?7+?g8`T?wBc_yYL`uHyrlQjvZo2@BXOW zF!k|M9t{9qEAP$dKh($Ig%(Wm9yVo%T%ykbz7~r(hD4QR+An?(gsG%^?Uaw%iB*gU zs{>I_8gHUgO#`m@p#$KRo$O>$LX9BII$V+VGCR4DPd2^%M?JHzARap4vjk4DwHYMDJ&RMUkl7Fi z601$pljjM)pt z;(^@c)os>`|5Hli0hBA9xB=y#4j@r_)$F7EHB^uUE^Syo*7*88IK9o4&}vz9pSd$V zjwuKnF26yc;pjDUZ0H@sC)8;e>s^oI!P@yn_SnQ>|KP6ULChnXwAifOwEor~nb-X` zgCnl6p?}m3*x0@SCB$x8B^o((ZEz|;cvUvRr7r_!>HInWhyiaQK}04C0|z( zJu%X{`YR0a%@aSaKz^H7LV>ul<3Fkw&qQ$p?54WbzhSM~hklemkoEOrY&pFlH z8XI7=`IT!ayC3tvAV<;t zT+E5adKO3Cj7$X%ER1OM$IQLWe@PVaTg!guL)7r?<{axU)nPSEulSSIVJbaDceZ2= zoYGrfb|#tlyN@WI0J7Au9sOQp@GB#+{h1-ZX$Hmf`unRdn2AEEKe+0>*_jg4?tJR* zX!l~#$0ccyM?u9+kP%O~ev{&P|L{3ZiY=x0dj1Mr$xoa(LVm1-r{(e1Q- z8*6<$=}E-!OqC!reu!RKL+MS*%&&*VAJJWTmmc4wu$vxiSG-Rm+6Rb$@upWVmGiO5 z{kYxVArzn}f@Djna2C%{hROCVn+H)gbgZgtlM;2Io!o3pGA^}x{E%yHD=C&f6twj< zo=jz!^aptdd46)S=*|ap?oN5V*INduy5Dt5`1V`sTAIy%wbI$|j9dZ1_+6wI8&h6L zSH>MmvB`*LEqX&fDZaBq=)G7c&5sVD=l+c%pEcpPz6!NwE3+}3YtZ~vRf}#^%FhsV z1+EKOran-@$A2xS&%O>k`8@$sU}G9NUGt^PJZ`A!DRdI2qrkej&8qQ}hm}dgAH1JQ!TT>2+X8%A z*Psx8g0mbHQUO13FF~tGhkSwK|D>++urBu5{w1I{nCDoOSpDxe&Jxh321Nw)%fE97 zO4vJw1~~qf#zPb^Ix2{ucwX(ly75>ZCVgQAmfT^e+V{T~ou8@{;Pda2Ml}adR)4aG zJ8{|BHMsPw+rzabuo{rml9+#@M9Q<-O=+;qwDCX2t{!zOcpJ!-0K@_I)e%g>BQ zL^qXM8ySkv{IEGtU7!A;_Ccb2`&G@E@j5UMbT1oSSA3j+e(9tw&&(v^iMq%@k>2<$ zj;9Q)&(C-U**n%I5^L#ROtgD3r6ya$V19SeXVe*Sqp6k0BCxQxFIOho4SUnuz0{7o zjX@IFk|wMO3*a zjc!zHe|uh`hdYG4a|rKmZ?`LWhM~?_580|Rr@UEus3U==oK7X6p+Wo4(T&Wr-S!<# z1^pkSVHex<3b|}<=JP*FbV>=p8vqq97de@`1@{xs&D-Guk4E1`D{$G|XWOHtxScn4 z1A|+`VAQ!$wvOfhg!vzh7My($hgok7OUN^K(~5F#ca0MMM@+PVskqS)G*^-GtSrRl zrgL`UXz;xhZ2K~fFH#N2|GCb|*ljwJ*uEKj>WTicG(c=`+R0aCX3{?u?r1v6P-I!W z2R(d-zUx1$#Im^O&<6&)FQ~FE?nzpwceD$}H{xvpqV52K!k#$?j*I|jJc5z|b3_4B z8P+I3!^{y1`D$6jnxyfi^N4_c@79*zA!MU-14@2Bz{}!qBj#rT5UpmESeZ^Pzj)Nq zG}Y?{CGS{M3Fzd6huM!b@GT#u@xNyKWhia189rwo@>;`A_M^}!_6HV#MWibac|-fE zRfmvlbIzmCEA`qF(m6^hMqkXWSo{Bb@XbdASn17ySGumV%d)p0@?<- zrNX)x_T>Z&>I-Klg+BOl&l&K)Q&NW>{%_v!1&E06PNKj>3zaz*H^e8up>Jv{b1>Ck zQU!rtj-c>uAos}sO3Ovqim=B;ylk4Bpv_yd<9Uc|=5;Q1rdhPH4(<}n`W}mQU2>w# z2R44 zYkBI~cTm{baocZ&IhkZG#Ap!W{@N)5qGZqDR5LG5CbPg-U7`@Qpv*ajPN9FGBWnX# zVUhiZ#|AJZ(@E<&=FaxNHDBJw0jVB#(~{y4ex?6x9SvY67jMysi$k&|#& z28iJIP=)wg&DmmrTnio-dl>oN8wp1kB)L}esn!A-EwYT~PYJdByc=Jm3R_eaiz@5GRVV0E8D@~sOJmtn96`g$Ugg-@NRZj^bN4c9$%p;0h=-_p$I2fn~ z&QGDdT>hE0d|XW2Vqd~oJAV+9U!)RkIaZ`3FhFqc;G@>|SNNRohc0{Km>%hkP!QW9 zPtz?8@mtvwNXx1^Nd?%ETu;4u{4@6)KrDrvlSb6)%4AAQyk+jBo|d?4JE5Y&!?b*8 zHs~xV8|V zjZLg#i*c#~rV_cWNXysIV5CS$g9Bc>226YI6pUAn)j{Ev1Y2zJHQ~Rr(?(kk|GR*B zP^aJ5xyr5jxS>x-;*RAoRY!gbnDZz@_6P;R| zOqMxmiF&zTb!5qTjjb0jWTg{VS#qSwc~)$wwyjqQ;Lp>}N~(hQ76WG4+ltV|9_=1B zQr^L9BMkYt%Mjyo4If(!VEL4w6*A$)w)p>~6c|XiZup1i0nS(Ml>lGsMd3F8Qdmh% zAI3A<}YJ2S0Yy|2fzX|CWn4!9$XNga5OG z?1`D2aaMqIIW+jb0dgn)Tt-(@UwOAW;4xRGiyiQkyPI~H1wT!K1HRv9(hj3yHvb$; ztoXuOP2D+gBrV_Hcv%UQIA&u@y^@otGwUB-c|#Z3Z5`p{_5Y5HFm;zFj4&TZM_Q7o zAACB&;qc7o8k}4h)ohDbjz5!rKn-#C9#SQasd!D@hgn~;ETd*96}C9Q-sOLEz)K6M@GUCH$tjRGP-Y~`mrs98+Auop zpo;Si1)FC_*;xBYWEB9aFH`~+50&}4zdW|U2hwzQmXr`ieR-KwtrIm(F31y zki;M7eyd5L{TN1a0XLxzbI3OB)3m?Uu~|SHJ8n-J^Pi-w1jZb_uZEz)mks@`q#<5o z6{(5xNM$u{Zl*{P7Yiv#$OHbV8&6DN*5!9CC$mx$Rr>w7EhQmGsf>ow)Z$lFwBFp^ zi=^}9$%L<_M8m&>f$^7M3rm%>UK~s^C3deU>?$5x-_gTt0ip&T1;~6%J!BgLOTY9z(aAmcc5{@tJoE7KMHU;ZSGYv*6e!#Z&RP&gEl_;i&% zt;5R%M=OE?0IiO6W6I2Dqm|SS!?e)1)|8Fscm3{~Q)W6aKl9{a8HjNE3j{PHQ_6|F zEJCfOr=zbtRo33{rmdIl*G;YT3uayyN;qrk}hoSY^5$EC9&lF)Q879Fs12$ zm*%371>fkUJ@k{FVdc3VBJJa4&L2eD`xQsBqL81vzkQ>C#>e(%qGWYCwLGGhpZoa* zG&wwbkTUb1_SFTqUeq1Eeh}0DhmAiavGCo?^LywAH--C&O?#6MH_2{X_9QG^JdzaX7WR2E%33jU~@f-Y1pSN=E^A za;{okVMVm%gnMf~wt8{*hGKLiQ2OM2ByeY7nZ-_&Oc4ZAv6hY9|3y5|`4e*|CuJ0u zdvOol1s8^kLb`-LP$B>pAy-i{^Rbh-jSQD?CxzyTNtW!XmHKGxmg)B07I)ZM^>9KJCzL(@w+D>G8J+*g{k>$QOi8-ubmEx{e94 zHNf+HW$XNre-`o!K#8tJtF7KN=;kNyv@O)37Z#>3^OMd0 zmMY;Xjxqen8hbD=HT)GqpcnA({a7eq)Gc^b34e6FdzCU-*7~Sp({7BDwW6C@Vb3r9 z(y__|BVg(Qjt{@ym{B&fqqr!~YNIX>hOU=@;FVTR!f3&6GZbIw)oq8q!17fP|9fgp zg{fOnl`nBL>w_D_W{Qr15~g}(FAjY#(@j?b=HbBB!4g$34qLO*0zO;(o}V!>QDs`R z^lpaXf3cs1pw~kl(@`=Op8ichbA_+233fEO0xt{zlwW_lkXCXC+SIlb1h0le&^(*9 zFc_XENREpPpO@w$XBfKhlP8XsRM`BrSME9kr8}U!D1|Ka1iT;ioF`lNMPdM{mk1Ed zDv&6XsK|bzkc|V_OK885Ep)Pz2pAM8R1_uadiQpIZ4#OPpIz;Wl+bPt70$&PqV1B^ znuiYl=mP&Wafm42PjdsjVn01JHMHr>Rn&$`%uWg2wF_INxINYBBQ~u7vy?}81;`?H z+#Lp4HGK$&*%WDYQ_v4)cBp9VLvT;mtWXtF@o&bEf_`qibJ9-P(H+NW;bZ0mJ19Gc zd{j!9e}fX|;+NwEWlkn#^LW)w^hAO~nl4^rlxCiSw}Gm1E{1LGZK25n2G3JM3uWde zh=w8$9d+;;TW*oSr6hY%avp6H7{5>t1}UC%^Ay-E%NHr3lV#HrM6C<0{G3dqyo;m6 z_!{X{H&HTXUlf~?h&cm`jQG|3sN}h~^b;LXh>_oAv9dK`6%D_oBdZ@_3rI@5Rv>>Kk+Poa%$-71%9_!fLks4XPN}C5i=izJ0~EEyc@ibV zWl>WULVl_8Fcbi8{m20D>g>~K2wla1*po+z8s(R|j3_hbLy+!J$TxRu^ZX7&rlZtQ zVy$*pX@tf{^tyDf5?e(@trI_vThtf`8bZ2qk>}fb4S=I;FEc~HN&8AXdM_{jdjfjn z?#N|2N^!$0x+_3LRiM+&-_?ApAU7z2&uh@>Ywy(#yN4cL+tFvBs12LSjdDTCW5@!J z>VqZz(oxW?7XGGO5GN@Np9K(=&LF_T#H(5($;`C8arv=n_U{qXw==70{fZ1syyj0s zk`3d2@+kt=4#NmvhLo!Hdze=<=sb2lpT`B&y1eu$S;q@^9?b+C*V4lVChr-_@uRQb zlv&(^-Fy}(HB%g`xm(2y_EtBNr?)Me?L6fIra%(_z|<(k zs?89dz{)-|<3*-B(u~OZ6Gfet{^EC_se7w`etKsr@)HR8gJn;z25;I^r|Ik6P9G!D z8~HI^+2BQ}mZcvZ!90KJH-t0BkLnwM9EV?ZA~oxu;rg?%WRCw<)X zt;@Z9s>kKi48H_hox4Sj89!GiGRKVmJO14j{6LkXdw=k7YeutW(T%=U-iZKyVc`NK zX7ruWZ65a-_S3rHL(y*ey}`VJzjeVh#@7dGABL{SBNC?ZH=aaLG#9zW%=QLv`G)+^ z^v`_+9&jB$AWe6Y-Hr#BYwNdyZB%nU9Ouv4&4Txq%sNZ9g3W`XW4AQp)xc{auovK_ zFGw>jkMniSzikDFe4CxVs7T;EGd&?Q#fHAJ+!uZ~vON=g>>0D6N$j!Q$q%9zS2*c1 zL~)*US)ErtE#HM1?&s^C8f|I{CAl1PSTl(D?&lLXjnkX8p3Cg6-5%j>)taPp+aLT9 zeZm(L+T{a3E_dZuJSzWJZ2XT^rBP{N;wy`%>)v3)JT~KDXpuzN&FRUf+}KtjOi>58 zA-ztT{$2<4w+gjbu1*hBO3Y7Za9@%>9c-k_?`&=Qw=cFCTtlNbKP|l&aG;rEI5s~W z_NJh}wf%bhM|&Ewf_hx&!mcfiP0SlQ^hVc%b3jzT3RBxHmyHlw;OfcRR`8R-vRPbg z*4S!xY&|IhJpG~N6H?p@e!>&bQ$8kMuE~2^9+?oksp(o`ObPz!bZW}GGY#IfSuo5c zP2Y)%`MjZtD22vm$^7Myt)D(9>zIb!$cWk0>>jxPqm^=8#Cm5c%>OV3+?ZINcGC^B zJI=3$G#}?*Nid}amRy(B*k{DENlxwO+D82PTAM;%_O~uK(XCC-)Ck=RTb;g`*ui<$ zg{D}9z}2f`-RF7oQJ^=tQ| z`8PGMODu)(fffI+QSsETpDsye=8i>|DlJoxwW5q9Iyd|6U~U^_Ak*s0176t{#H-Xc z30Fe?2tC9*KLrKDReG*he`Y~QpUp#Ft)D0+9~yaHRq>`Qy!UI0#wK+34z9-Md`fh0`ph2A z-i1 zc4nzcED2EMQ;WIQ{R@?^Q6#J5#J?ePS^FrwOkX$VTE$~+siUg8aML~eUpJh- z=efVWy)GE*HXmuqzxc@Mf@HQDeBD%z-@)j^K=WfCyOYyx<+Xf8?zhLzWyUYm_Vi;8!^O^24p)rdn%~Cs`z;W~b*`Iacq2rSu7Y98yrsbWiqfUCys#}eOt6C{yy8;mJx2?-X z2Y(iW&nCE!XLki&wfizQ)LpUGlT44(&79a{K9PpV_1J^6Q!Mkp6IkrQcc9qvaJOyU>2r(+&Gy(5O#i*S=O z$sCCRFf{&(bRK2WI;_hqg=I?lHDPy&kjirv!+`3nc&;jH z!oBs{2$=}yDWC6&<|1A2^M+H6?WS+S336B1rTc7sZpPCX2xFHn{$2gWfHDcr<2Vw; zPAFdG?zYwWc`I8bS+cpO2 z?nWsG>0EoIw$NoLr&4A~mX|Sii`nkun{d&G>COSh+(mV_L3sAAcS8`nAA7aA%ho5w z&VL|TQu}!w<5f7JZGgZ+I!6rpY-s`)W%r^Q=Gy8cXOtn}qN$1AXTT%L2jSQZ_L5YU z`~`|JoN%T5c^nsZDVn1of)~3KxOT_mrL76l$}3L-D%8Es!;MXKadOgmL~RmC4lv?| z6f<%f!3#IC!nkCiL&Rb?dJ?Y}_hH&wnL@K{$p3EX@<6%o)oN&97d^Scb=k1YFRp#Hrzd^Q^Jgob_@p~r zOiLoOUq_|VK{v17ljML)D!3X>(n3);_lM(dR{ZQ%7Pj@7yUeyKcM~+ZDrt531>CCC zcq!{vfIj!)bz|O5-l+b0QT^J#7Ee-(CYmz1@BfIAwERE_JnkfCKtwA~Oumm~{fxP} zxCGVr(cf&|e$QSU@fXxmv;Fd^ng?pI=@+4+?`yF6t#NLP_iy%x%>6V?yLbO8ic+5# zAUr#fCgLR*ep2Nm&27&GZt|iQq0MkT?x<>eZUt^?7V`wCkiu6K@weB8ttj=Ggc2%R z@?&+lCs9ta24z&dYjWor^2t&fVACG+A1|snO8WtIu;dD^{5sNPvg~K^2ygHg%U||L z`s%W{mrH5P?DL862&!X$g&FcoAm7AB+6VB4;7jBewO7c6CVg(_BTH^a~wc-db1Q+TtBUIIGz1f-renWXLoQA}rz@qj2bIZ_0BdXk<`fJ>Klkc|z&&SHUMBg-18atTd zz4BWs`f?Jo)8d;uj~=(2-C}=?B@)3OwwI zmb8Qh3+Qc{T>t1`zMa%?37wvBL>(t3A46sO?D;K1zK^ zpY&f{gkuxy?MfB_eeSg|_p(i1b=Oz^H;zp{9xV^&Ax+}fQ*6`lx!=t7K9akT7xCIa#C^y8yDUp##QRO`wtx<|uISrpQ628lpws7@COcVSEhMDQ z%JO-A?(iMsPNWVOysF+?pIcY;;fn(khmlZtwB+S#MYU*Zd-0iEQL6j3Zp9eM`?e;< zCnk5yC{3HZnNmpEqcoj(JBc+pD*NxPvpG3xHRu|yD7B_grFTEg%vZb%se|3iEK2P+ zdi!TTtugmIE3PQj%Jz?E7t%!EM%DQ!jj0}bFu%u(Nx8_IzQsF2+OB$El&bPu`JZhx z)sXw?k-y&4hmvcx2c4m}3njqOcmuo9x}PQ|Y8?HJ-qxh<{R2EL^haxM2R8$}Fv`7` z5vraqds#J(+MBe*(%z(zh$~<*rp4wKIhfw3A)R|V8l8PQ{dHZ$HN?l6{2mm#xp$1H z1yaS<{|Q#|@sT}d)a$2V6OM~Fs+d%K8bl5Y1c#QfBCFLyMuvZzucm+AUR=U{dVr$h{ajv?~a81nmA^o)$Dt%Fs0r6PPq zerk*2$jFeZ1A33*_PViZ6Gy2GRi30KTO_F!ye7C3)oKLGgpQf zZ9g18ImcLBsqwTBLyIU#`*Mv9{y=||h87x5l3B1b81Z_q2)$`}4tjNa*HIru`)RE7 z^TDxPNH!FwKT`Gru&3u$LwLCWhdlskO47_A|LO zqi9LMR!>A9rEXdydTerEF;OKM8TK))Xknf=9R3ZXP!upJ)yk`fQa6H#M^nqcp9LF` zHqutUEzH~LjTE>AClppr&D~HeTAHH2Zry{>jCt^8p7&uSWitsmnOXLoF`63V5T#sH z2|&5%qNydrgB>x|U*uKZmypX?jg*&}a*#VF8WHaMCM1US`9V1sMrOrxFO~x6>Sbd; zauh{WX8d6)iV!6w^ve}SRq(FJ1xEi0qRIsxN1y?!+ynE6UrtOoASH<#yzVAv2=@;~ zOWZP1AB&boj;^$4Hz$}pU54v%@<(Tu>B6!-)tmb zLy?d>DNaUUcGc7%A^pww)FORsQGi~Y2cJI5gUMVrh9D`lA+VnoNUPY6)H&X|DLnpC zZ2Z!+Y8*i@AuNLxj+L08@T|$XNW`Uqq&6V0Q7n#dQ&=r~k9YU)7oR_JqW7aLzybfv z%$}A+RK4kf|5Lft$;v8ZfGT<@&JT9?tM{#7jQkz(^cvM~kp|N=w%@r)@iev$kHinW z8K8Vz6B9@p5|N?#36>6;>Fs~MI*v*ii8^kj!P==7`_X`9e|=DE;w&U)R0uX*al~p= zkODn|VWm>a*j5K;Dx?TkFsL;~nA+-C>(o7FKs3C+tCK)57CU~=jD=Lqy*9DcA;0A( z&>|2H5pJ|_(b-+7?f00?YC5=RO^%_%!52lK51}5XH3E$(&IP zfAT7p&v0bO&?bPMMOIinGu)JDMoO{CzMRL{?Z^DNGLmk zRD;~t(q;MbK=nM~4GiL6TNlqkDxHVPKsk}$XjK(1o$Rmfh+DxGzJ2wkOSX0B$94)D zp`NM~T5(}hAqtB14^oW17_moW7uz|g-34G8?L!Bq_ z#g(O`12bEPRjzq<@OOgopSiGRIU}!&D;ve#S?Cdif`&^H@Oug?|Cq6b6zc-*1ZpNf z3wGsn8o{p&zw5JjB5H{0r8}9IfI8kzc#vFD$$wFd9Wg&Y`wiDUEQ_Z97HSh4q=A7+Ya~rKe=Ptn_(ae)a6fo;lX? zA>}@Uo%M+^E>IjX-(-N6kZ-n|WstwC&}5TCZ$1(!qg7;p{k5nRENF&uR=^8g!D?gK z@SZS4L6PVVfVK2oewR^Nnaz$^fot#jC7FCMDD}42QF}s2Z;Ua(+OV`vKOuailnI!R z%uDAM#6#WpLu%9dMLYVwN+1e!r0v8J0`=$w4*8Y7xjlNjNxjllTKU7krV_q)uR@g9 zqG;q-&cC4wnxjaPI^JJtJv^l7I7R^{mW?7Q_*wsD{Xg~AH_p8k=#^S?WY?@B7mB2MbsN&%*l@(HSA}h zg=hysL`8*LuqmbppLPMOEv=*I3Ed6VXU_40?#>GGx5L-}==yjIlH70I6aG%!(JGD>D!ZwU< zC>|GJh+@(C$7zVN$380Ng1+!48uJ>Wj+}pB=n-ov>Z}O_o`{HLak#?2{!#A*N#ZgDpK( z9Vp`J!S-Vm6!{o0!F^6%;Yx}yIE6yQJ;3SU5-~$>2mZlsGW11Hn<|r?&ZY8RU-nlK zcb!DQsaN5$@#4i${YOIWGeY3x%wP$0H*zwq1X{3D`&Axs0;%?%>>NGtj=LNCK{uC> z>2iNfy%wjGcuxo6|K)fCI@ZxIirn0hde&N35uxI~R9#4@5pSkOV4M4v{>{j*So&;a zR8$5D22teont(WL^OBGdje>T0_YbzpN^?)uzBp_kMUT!wXVN`79@{Mc?`LYwsXm#z zk(;joyIn>i5C{Q{A5*a@>1UxVrVe2%9D%+jB<}@VMFs7jVXX*+%q$n#&_M@cr^KqT zVqu;_gF;z6=Wakm%*j~| z?s`qE0bpkHfln?CCQtWK-UoD zn}-IRt|<((4yhQ2Ttsj*MNkOx+W85*d{;*hKMit5pf9Qu3G5Y1D!P}w0Fv~dP7(Hs zN|aPVG=T7@&Y@TT_ zdXl}vIvXug2XW>|cRK=msMwXa3B9y(db$DCtRU8>=_1y0DFTHAp5RnBs{H9hS0Ule zzgp0UMxZc6p^&istWVA|V7L)?L!yv?3n}>$fz?~T^0`Ul+tH3tYDI3X$N3A8|EO$D zyED-6Z;`Pb@~^uR*17Nm6|Dem0P%PgXP34BEs#zS60{k)f3=VUjTOyU>|m~_6dDs% zk)z@{S~}zdm8_)&ZBV5y57g1v^O++LQ|uii$w(X2C7#G{XNParD9}qZ^Uj=L8we-9 z`DHlLp!)zoaMq>E-4#jurt!!=?6ujhiMJy;gfcu~?_l{Gi9{*00~^rYM-)$jnP}2>zqE|L2m?2DN16nXZG$YyX6qcyY%4^F9 zAdq2w@h%Y$!A87h!_gLjCAT}*^61`08_hp%3P6qwt#T^wK~DxwJyjk+t8KX+YUqFq zfCaq{qD72rmzJ;KDthFmEhY*YWs7J~Ysh$AnXTa!;eZ(2RAt&CI3QZ^PXH93Zk3Id z17hs&^JfEU`Yc>ecL@sG?F&A_Z?LCt{%|NZC$+LxFMStzg=oSyzq7Pj@0~GsqQ5p` zA&+_p*0SJb}k6Y>FOX%MNryuz=L)c<7 z-!5@U7Q00t$DX>r9Ld}<7cL3r| zU%!Nr7ZdeE$q2&s)zYyK<`^9PMvOZGJk`>Xj5c`)lH1lrh598pd$M~jNh&nFwO>hF z-mk2EfMBI9zS^NA>Xg3Or=%dg!$8Ykzx3@%7Jr4X+uCuCa~RcZ7@CV{@bPr;Lw)YG zeMP3KCx;XuIBxTDSJf}YuVY^a?60X2bB3_>mCv8GR1@$B{{sBQ3Fq%4E(Y@Flmi3E z^P&ML4k4I;i$kB)0t>6Mb{=Emg>Qrom%KOcJ}kX&dnRJ$@?Bp4;Ej2DiX87m*EfR8 zx2iWEA|h_BA3MH6JS?&{b_5f6XkGH+8>@SN{-h`G5E7MfZXabVn9aKP%lKc|ckn8GC$Rp!dzqzSiRTkX^hm~dZP9kUk#ciVCbnVU zXXd+$!~09;=3LTouR@r;l@+G_W>dOc!phlSc~m1vS9sLlH7re7t}0a{#?_Ka*%~VK zf6{UbBq)olX1j#(j0#*-Z|7H53$1@#g&;j2Wm9OV4ARSeP|ly}UCQeexH<9bs%k?e zJc5VUQdyyftWI+IE`_twoS;&cOitkw1hIEkF%j<(q&bbh4tGX`fJ$6Dzew+5j+v{@ zf8_mZuHP@8Yy_ltLuDLX9oUAR1f;VvZsH7Fcf{sPQa&y{$G-@A_O0%6jBOC=muF^) zav(%%q&_emE3x~>#P$1XkNeZjW4TMc|7cqy0p})z{kf^Mk#8^7=lTgmX z+w<;YAGZ>`7L}r%G|p+Lnm)-=GWPRpploL^crB)OQXT`b}8y(c+Fs z53Gt548~}-pYHLyAJMM~2CL^O{6Ky|MAb$9J*T2QU8>xx(}+}9rV$8tkr0|yuKD+K zQQ$Y>84^p|E-FoHrU>% zs2rH})|%Qaq-l2Lif4NB?Q3L%_oT7yYr%Iw_sgwbA4uVn!(;pf!RM|C1);Q*g<1VR zklrfl3b=lkl{ZoNxO6qdrHwz_?D#!@c!OMT!+(S=<7aUmw?~AeA}te?SKdj!fVzIi zjb^EQY_w6X!1bi}U})c|7V>EMJN*!rGz-2lU2HrDm!AJsYl7p6G%yhl`Leinb#BSX zGWDG)`QFWO$kWi6#%-&){grKu($ms(WzIYvt>%f4iLM@$1i!MN)}ni0g(=Ri>jWYw z)h*F|%x8*Qc}6%l*3;yi*0nx=Y02Md#Y>9u;<`%OV}fP@VJ+V#Nw|foy=O(3;fwVKja2WOl&$7PW8C7AhC_< z*CoxId}ME1&h7J&Vz$C2M4m$K@k*L0TLAJ;XZLS2zvR*KyF&NJV6OV%z>A)dNo36^ zkCw3A4zt#}+`%2k9#rk;;1}E>7yrJTy&=*4H~xb|&$7!f=hIQj4w2&4*%u4;l5EIV z>v&xgvW@tGM2NQUzHG?1KM}lI@{p)he7aA(M92+gF0CjwM~RSu#_C(lPfK4FySY?m zRv`(E^5P zcsb1~(8EFQ2Mk8rqt)U!#wqT9 zz_X_OBvj#wG>*dn$0HRIvx%{>*K7~o!026lukyrOU+N;40j`ebLJ&&a%+G8oe*^eW zgYI1WERaRyEZ+kBFN)p4YfySqx<*t71P*qcehmYMcpVZmLc9#I`3!1WG(4Ue;ca=8IAjj>$F%0z0%$3sF z+~%pet6?yvw-d-PShs2iP01|mhLa+{O&Cl@e~v9-HlpY27Yxi-TY9V-AX94o3U~Le z{|0b@@!!&vaG}84A4jy^BTmRjLk#RhCshm$6G;ej#m>UcBOWc#c58iP^QDEEmG0C3 zNuP~yE1G4%m5$s`@E~ELMgP)hw`0QgFn8N9&+AisMTE_A9Ov_AfSRD*O;%i~m$Th_ zrtT5f$fNk#XqAsbu*K1@6Xw9|+hdS9B+W)Y_{@=6T6lZo`4&(lGg~%-(Nk<8uK*90 z=?ReIi=iL1X@ zfDXgYR~FcbbXU>*4i1OuVnd{dF+1=3qoTs_Wr=Mgm}8pliqhG}chnrWa9BgkR zp46|=hU_JgMptI9!#Cb=h%KVa$4=jMcdMH(4Y zTl&v62IUCL^#84Z``dB!mbzqC@h=%$|EcCR9CuE$kO>}Fn$4d1Ke|#3eD%a>V!d^U z`XAu9LR4O+0=6{8>TW*)_^C0#3dem)J9iFSdLsSI7V7Vztp>-=T35|z7XycHeETmK z1JjVNSn7WLH#+S0+)XHHB!*{B9y>eKhhZd*1pmFPnRC!r-~#PdUO#XkVVV<>QI2>y zNfe*Im_wZcPNi}n14P4=SJ)MB_7}IDDuE`rB6Z31s%nKK`PA$GYI_f`CYtUKlqS7b zfdxYEy=@SX9+2Loh|&!xB?%~9dWV40M573?08+%*uv3GeK~O<#kOT}M7Me7{yZAPJ z%k#hA^W2+AoSmKen{&>bb7pon|4spTY?fu*yxXz1{Qs1uwDjA@D1Hk!fI~#h&_O zW`Jg^$ZKX^Ysk=Q*;{ z!Q+ejxsc-;%)4HoJoZ%OyzCtd3;8GUxbKGnX1U;$lcfy}82 zAB~sf#l#f^Tj7$zPsLl~oV)yGDSlqhic~3YramAZw4X{^+*b3ttFsylpyxb{x$
    u_IKhGGW%UcY6J28(s8_}Bxj&sP@ z0@$3sRb3P~PJn-yLY1en>}ASbOy(CO#T6(Gq3)-wm*iODKCFa+>-6%6o}%uTC<<~R zmeeo!4xxZ|uh5aWnxh)8LAxQ;wcufK=$9*eG7NmhbL43lc*!fT-+&B7jWwabEwyrJ zXFm6bd7rN+LAGxZaKU-hH8!8C@!+c*-zZ}so4rxJr)$XnIJqPjk5Z85j|UqAGj=`f zaviw2Ui@L}n$&RFJc@KFO_GPU6heI61(72+vn1BH-k~@*xF7PlC|QNfY>!;VC%k& zDzD!+ryz-~a~831GRA#=2&94I*W-fCfgU=8h|?kU)u>0gEZy_#xof>?;L5@`S2G+^ zeIo>5k%t$7mm+Dyu->RrF*6{Je(^FLn)DfGW`-kZHqfJ&=>2_9)EzCK zmE@&O*GVu^>ggD-vhX7P_j!0itblF5&OwP-+^LpF7-W0^BN=>SgJJJzv%=HB(XMei z3QpY#;H8C`+&9Nvw_Kw~k2Fs)>_CqwgW`NNv2SuRBqO#BA@s-)*`{06?64K?&XSci zZV-Rcs(Y=eJHVa-miyBa<*;>|6FW|VEvr%XbhytJl;^DvUL8=urr$#;)q{!YsamKy zit!B}PvG9L=2pK7N#8oz6HT(H@I-e{yPeH0z{6dmf;<36TQnL^36o*_&M8D(-by%E zM^Q@jIL{)CSi3VPDonfkom^i>!4=D33u4sOk2DsUsF_WyWsT z4*o$%7C4?+!8n{~Zp7&XDCaG{b2bB1pW!OfATk1&VA!wjR~4b(OjCxuV10QBIWyp6 zZibv0E)qOu1#Ggqedj}et9X`?hmTaUHt(Ka>ph>JM@_D6gez}83-^B~gXP(|bB`5} zB3#051*9f!o-W^-$z4d1p{%x=_8GaaSG^$?fGrAl$Wd~X)sr_mWUwWqufpi$*af>Z zaO-?>@E37{m`CxqAxJRk4Hfca<>Ao|lJP?5oU@XA2>BpYbp^B@rn4ozJ8*JoLmG`e z-g1ZnG-oOm;8`bFz9=YR>jtlAo&#ymUkUZVbBiIl{~Wj`DQw6n7h>p+8(3p>owpRVg?Tce+EI-rrRfTw#?fB}?`C8v&|KsUiK zlagG;LSie3;bA%`NZVz6&=nW`WWgN$yv;84h7u_*amE^b|BSJ?AQF0*7i9N$%Nj)eGcUIj{H{P0z5G9dWp@ZyIN*S8co_;T-hD? z?&FFjWx6AFm?57qNUsj=yk}D~El|q*PZ5Zj{fNQ>Jgqar*HS-34u( zw9yB;woZYx81o>C-xGp_0Bz0+?FdXwJZxaZ{* zu*3H8AU2cj?aC}9PhgddCJ!Cku42bq+)m9Z#QCG4W}QC0vC zZk*Q@>~TH7i7-*Z^1DpOrbF!*Zl~)>5Uv#!q@6m>20i5G+drXTgTBiwihu@Ru_tD! zfTHHk$yGo_t6$l}1U!jHHZ4HX+ZDZpG-hq2B=-xQqu@&1a-jL#LiB0@zT=%MS)q$M zb=;pjhe&nrpx_7r5*pYpx-l6wtiYjL44o9*!1Jt5ic*h)>dT6r1as*t;H!(h4&DGU z=N7AmO=nFVLm*o3zy)>@VWKv0ALR{ALV@&!G0AtPU3~x^@3nsDc7OAvpfKXKpapwj z3^=a5TU8C~8()yyGxQE67l2-p=+DUN8CtRO%WePEYH>j33e|Iq?dd#FfhL`%rC$#^&bI^|)?v@%YjKTxHMp zZQC-Llv^s=t&uLko$GA;X_T-z2Ps}b;ts8upma+81r4aO-K`U8X6O-TS)?`ERCYnA zXYH|Nn-b~Lj%yIXpE~C%h~!5x_qZlcwXIA&t~Di^-h#Ae*MkZu@%*}%n1zU;EMbbS=x<)4xA7FckE<*7 zpi>1I0RcSL_%ujZQS{lG(G{?4x2YQG<^i-PE?PGO(c|iGWa8riESHJyen9`qaZL2_(6# z2QZ3+&p5tauiPV0JR;o@Y* z^By+eQf3~kKDHhsC`@~ipW9;>w8zQH8Q~+`7yvc?EQivho2GQ8DX} zDPe}$_)ZE~$jYv)hJ6Ho5SECrCz>O%LDM=A#&QgXXsoZO;rV}%laj9?|p}a z)91jl9(MuaZt=$o3fMtGKL-b(M0R0+5Cx>MUy)b9`l>W{cMrWRAVM6wJE`X?I=@om z;dKVABapjijZGWvQ;yaSMm`E>OZ zm}rsf)R@{Ox47z~0cwWzsQH$mw!Y{F@lgX-ZW zh4WHOdDIeid4@bH6YiUbS37E($Ecz6)0-KSM0u~Y#_g&ESVkYOcCjR}y>Q zU!p7?^wCw~5~bG^5YOzI->f;y3OHeA-T~O7UFFOGsSM%HO)POSH3qO}UkHVFlII9I zIsjG{uvH|ZmJm4Tk-<$q-F+zV_ENla2f02wcPD`DRLefpNuK8G=VHvoN2;v8>~amr zx@<2=GR+^}fj*J4$c$d9lm7y>w~|YS2*b+A;|_cgx8Ab=+h#jP%IfDEQZQ2Dm4nc8 zd&?(fIr9jlMs7&WxNMSM0L~twVH@%Y+&hY)=#v*96-3t&x|jRGynF06vyC~f+1{Hc z503~s+pq&|urxJ~x-q}|1KC(6(gfH1jCTrkL-Z-s&>c;T>c{a+^4vxM5CCo*$fwtYqfFr?3<29&3ik zAjb=_)Sn1|W^-pB)ty+?-c{2M6i%KI8N`VQ)bD@Wf%036y_z4xwS~zrrs8c24?hk>H`_TjVQkK{)Ulnyq$5I=>7DZ#2ikGx zP+1J;dG89692~1UkMl7yGG*(A%(#Gip2E|kEyzkIQyIo_cAH~c>4Vx?R2dmlF;=8c z?@E3aHGo~rLk`Fdr#m7;t`9XkV+)QuSrujBg{RAHLG0l-5y9+83oT1>@~#sa*;Hep zxoQ{CxpL4295L9C**Xm+P-5q}{abcDu4#l402KsV^b1aBWX2?_Rj0h{aAg&Wre{H@ zD{+C~*W$PkU>8U-qFgP`Tzu{@(&3tgy(7RvWb^XB(UwWo^%JF$?is$Gm;gms78zM+ zuXnuZ?HKAj^-$gn9Dgs#lZD?E#N*D8g@32wz{X2@D^s41awxtaJuh_0+!*Fj%_Q)2YjcurYIuqQJS;J00~2p5z?_colviC7*A6A` z1f=lEASV_}r9GKwYF0khce+k$dyAts*iZcio#+DjmGQix#(@c?KCcr>oY=znJ2fCUPBWuUym2&>WTBnicaNKN1gnvi8KZv>4K;n2 z3`Pff#BN4F|KTO0MXpA5LpyEM{X7c3i2 z&!FC;`;^tu77D#&7@$EGqdei_fX&{Hgpr1Z3~I?i;z1N{y6X{VrT`+-u`dLk*wi@z zN+=G7XoKt7cU=QeH+(Fcxv@9Mp4d!$WKdOh2YQwRbm6JUBS2aKDv;X#?0+mDC`fM&t6ONS+Z zC+C4a5PI;j@*GbV;pUA97(k5)XU&SyQ;&uLWs~7~nfS?X$wwt{`1uQH6t>?4gQ`qT z*;;Z|jhnKrN=c1)f-Cr0nV`wrCoz*kZn$Y5egcFYuif)Y-% z?OGd(Q}p`>Yw~mv@t%2SyYJeHEqL#aO=q>x14L)Lc(@oFk>jiHzJ{zAL!K|kQAWgd zThK7`b}ef1*?D?)+UvQoTGag~yb|oReIM@$Vl@hw`0UBI@>DUrf>??{`WTR~ZMLc5g|Z-eQ|~XGgp({^q6xI4Zrz?;!)?_={~Q?0p$xC)^$h z^=u&-V5j-HQ%(6vV>GfYnAiq~Y0VbvfDdL4LgMcPs#`V7t09ZZca5!b4@j#Dd}IrH zjoy-Cqs=aj*@8&vE5}hJ)8mLv_&(@iB*Yo1nxW&UPYQ7!okOt~rB2C`>qP{X&I@Am zzeov^USwp|qWGEP?Z7>JJge?(v_leKWXZ7&Lx|2bCwpaFnQLD#`P!9(YPckcwTr?| z4I9MH8ND~bWZav5(HtzmB|#ENZq$-|?X-a)R^~k!lhf&wH^P}6Ga4qzj@(?}RnCqf zIlRmyU-Mt;h2He>5H;e|&zVC=S>FN8DdQ6b4U9Ru_LJBge1Lolml)~mntPXP37mFI z49n26!o!7(G@XhERXd&afz9HQFm2rR+68*F-dMkKT{i z4klsq@H_(s^5`2Cm)1(b!wBmql3!*DX$<*zXU)?B{0O3+K%zXF)J)%b0yGj}V=M25 z6P?ua@ekI&!O-8h@HfpUw|dC56X5#N6ia>#N#KDTb|>#w#(cd0@vs0p9Brw*d+5lO zO&Gd-XW2%p9M-oq7lw8c$zplLmLJoSV)UZh)z|5rp*~s=ZOa_shzn9J$;a=s%Gs%p zj?g(1EkGQqeQA3V4kmB}q+nDU7Pk^DXDY3tEbi@hkLLE{j0_7?6W?Tf}H}yXje=9li;ky{@u1f zv0dF~GYZ(g$(_cSA9KABlq0>6gIeTu$s@PBy}*DcUpCNGYDYd^*z4SGpWZw0tA0;LI6`f4!Y_^GNV%jiJAlV>lUXw#Z|d)6eF)Nrdvx{D zH}0^tl;n5qUn~W+VujF40?5zL7`wyj`5;9U1IpotA4> z-9tTPe7@E=BoXqd$a(F7bXH8+XD?pFcUnOzbZ*jV(8n6ER(l%A3%Lkk0(?lk5#&@c z@XC2$1xSedNmv2J2QZF%Axqhz8EFk{=1ht}4qw;73yk@M{Uvw-ej+V!ql5CsF;l$| zA2C1mgfd;CQ|%^9L>^2afEyxZNglZCQ;DHyXvY(MMbBEYZj+cW&0YGg8dijDJ?kD@ zF}1+-fpktUfJSw3O!& z4!rJw=RE}vTwM7!z(r zjc-$&K0ORtE|(KsYZScf6L9&XMJ0qKii8y6k?lOPml!ThqEcf|ZmohT^7m43OHM?h z&r057o)SXYxy4lwDKDFhbFNBHNyhQ)zdR37`-5X?xMFaYaZ->O3hjz+X6b|1e@IHh zRes|vC7?bUn>mS2vGld?#6y=aZYFEt_7-k$cH)|xdz{KuipTS1UNj@US{7#M^V#LJ z6Lu;3i#eveXn`$?@dQD*ACNby*2XNE zm|QlrA-zJ=cEVquV(XU1j5rN*A18Ev^y*76t+&9+H1Ey^&X6PArIF1Opar(YZQNUS zvT46>To$l@Cw-R61O*;5tfm-H1pVuN1Fq-b=4B@`EV)`QjFxuSR6*~9_wc9>0 znp&-a8P+ZCYEVErZc+C&Q{TLwbUm9HmSOL%Jf}2Z8F6CXmy@RC@)dHvK-k@1@?q(l zUmI-U!w8-;8dI_@xA;$TM2%7P}+F{ zE$CuVlTIAFoj36X+)%sYBZ>UZ$;wzlFw{O2k84gp53On{v#FKfClJ{2FW?1wDM@5B zTt<+DKC)clpL(6EB>0Vd2}e92BFOMCi#X(XMy+W9Y`h-QVHXcfp_byZiRfcC9k?&x zhw|7;q7U}q+bZHvOmU5vBu%+1jW{$6KBsk3>$B&mU%-phwYe`~i`aoxyzYmYi02x$ z)cV?uVk}-!GBjfvG%%JqaE_`JHi+ktK(yC*C_!tKpNyO}PyjNlQ(*^j=nY57Q50m? z(z!(dj#jQ`a*C;s=$t$wa4Rc?#Z)-I@x_;*k>K;afmCCAju*YI=W7}(pcwGk#I?G& z35wC;2^A3d|0ft5@oWNV|inYQ^71ddDP$^BwuciM!SUscP=;{KOGMymC-p zVgFjYAnJ72+VSh?O1O6$1Sb^{M6H**tFZ@aLoKQ%kUGse8qm=J-{rmx(Na~h>?aN7 z@#|%7Mv`gMLfxel6MQ||92`VhNY zOYoK1!D3Pf#b%<3DVF=F0@FNtX_q})4{_-8E1qq3&v+fLeCHUYc z5`|DW*l2>CU`jG#icbMFAG{FWJNjx5Bbgf3tTtjrBn}-vU#et^6+nDWeRx%8G!NyMWd)t%hN zq*qDJ#-y>@u`VhuMS`p3nNr^uFz!ym6#98ZfZ-Q#kCcsD2GR9a4z2*wpScFw<6t(;(4~zHexl;f!;ajYps)pr z?I~)!ql+GH73}vtY@dw7i@u{$fyLGOl9*%fzf4eZmh&%&aB)>}7$Q_v^S;XceK(qYOQyN=Oe4vqw*;U2X>0yNnP3K95L=rN=_mM0nD zqvbLpeeJ|@mC~51IVl)z>zbk`jCP0@m4-V!+rTmD_oPV-Mmu%iGaV2Lu6ki7R5hBl zK|lFsKQA=>IIVD(Qb(f!zBJrM#Ey@2aDgglayh1FMq(@$>aq{uG+h!z#;5-KSyLo3woIjw0ArB35Og8b57)$Z4GVvT{q%0$rt}zjt&}~IJ z4M=5>bb=({rzUpzVG+EzG*bK^gEUgYyVipAb=rm%{vq=bY*MLU&9cv@72d}S-*?F= zw{PtIM-Lf;!&(3Ye$F}*-j5}OS~cIh%p)0Ti>UzthVJ}=IeQhem}9;-gM$u-jFqEc!r?vsH9 zsjSyS8nHWLL(K|{5t_wi^}$Ee>tUGZoeF#yl26kuX!8~-KGu9PUL04(3s-Ege~{bf zTFJbFzzc72d1W4BHCc~Q8XDq^M$6&*uWA8_B1pnor^gt1fxao~z4}GPKtb ztJ0YJj_*{C<1YmqsF24P2V2{NxI0&A+iQ4Mq!&W&xqU;gKC8l<@^CS$t^DxWeEJ2m zNsz3$n^6W~sVR7d6^?lJ9MK0iu(8>J!RGH1>~kGhX6zfgV-=eYJm{#6VwenDt$tl= zMlyYPI31wpWi_RPt6cFOHzOHcSl)rb(N{8$P#cI^rr5Kc?SZq@pN@I- zq{}(p7sPh4pvDs2!+gahi=v&aki1~Uq~H#V-`OEW)8(6GfR{yRnPCMKhSN$2#VY(# z#7%!Xfn*$EhOeZAKITZapRiP~_a4MEhPoAc;&0NsY%{lB_kx zHaHwxv9{>ED>;G2EqQn-#?Qr7FY-ze)o5#9(KzN#WDjxd;G>W0pi?c;s-UFI4ceQ) znXPyvG#OYPxKj*O#!*}U1^wKOplpi0xpqGVH~J9jw0g7@BtFt)=h4PY)>e?@9jNh& zgUFn}9#T|3u1qTkW1d?O#iS9kP6zmeFn3|((|tqgon_k_=^8F-9;f={@ob=H3yFR0 zGSZl2iyA0x;+dsc07`fQFlq=|8FD8Xyi>|8Op1{N(rd7`LtMXU?v zD^gq;PO2qa6r7+6A4@0)5K6;q){oHKJaTU3!0uXj#$L<;9>a1#(Rx2CxEF(yV$_B* z&sZd!uA2Q8&^BY^`(%~Hmlur*oH0Ji*w;+6A+KxJ@#)TPqB&u@Rfi$dlH}}yPB3HSLpdYqh z0U7PB;y^NZQ13u8Arc%&o)-uXSPllvQvamdM_$hS#Xy-g$ZHv`aLI=^T7kw?1ebl$ zw7UYAf{m`gU7#;?#n^O7$s>jH>QA_T2r0)!PB*w>xV=YY;2&bAFHiQ(QaA9EP0i|w zh!dQ!8S&zijyNEa5zkPLe|%E#526T93N z&S6Yfl0)kO`L|~MW>fX@p&b`6rsHh^=P(M(hw1^E+r(MBdmvk`13e?yMXKza0V@@f_OA#IO|xCBXE4jxaDx3#WUEnk%x3mYA zKY7*21@3z&yOpy7pD_D{t_PzhHi2RqfVZ?Pd#ce;50;9jKpHbr*&BP4EJ-)eE_sAW z4WX{w$2HZB`pbE z0hXKYuhj>@`|pf#%Evn$=Ia_?59X7!cg9rm?as~scunv* zkt@Ld%yGlYMdO5msW1(rPLDR+a-E`yH|f|DWadz=Is`KLl$rO9viw#8^zt z?F-K*V~!rE?V3t{#UiS4$)26NiV&-GKm*ZnF8hOwAJ+H2-!3vHwsm~=z*XH0-gHl@Ld2|^%SN-B(Sguk`x8BM!zVKF?wTV6G`pBb<|47R2Yf2Z`x+a zxGE06mNkIh;=bYl9he=H`tAVshTZh716aj)tu)FMxR_H?P(=;rkFDJ)?tIbq9zYw* zO3ACj`{WuK&SSnFUgwF2iw&Vy$WuyM9rGMj_=M^`nq&-4))P?lBVFZtDxpDq^b$Vz z9;2t54hV`O2Zfe5;qoS(F>PueDxX^Wh>zK+=4TdJ%g^nU$`1+Z8 zC2zP9n5OLwzeCVS^@h7^?cPgj=a$H-(B<&QRxG|uyN=O2+Z)o+k8W0=nih{-!PIYk-}Hv>x%Y^txk5G+ z&{OcnirA1=7zccM6PX5v&XtI0dt-;0;-}N6nh>K@rAqvHX(OHhxRY9EJ6mNL(}k)^ zg5)3;KQ&!qw)7N(dtX)~s*W@{D=Vf>Tr-+8^u?O85w(4>y0zf3AOzI zRPZCss;&R6us|YRkEZN^T?LQdu5NIs| zPO)eqRrjcB(NbS^xL$atSeW$9pHce|=wt*&e2GlBd-lxt@J#0_mbIzbS^b8SV>9g* zo&;|;ae(mV1$v9fb(>|hY91bUh~fL^@2dwdwZx)A1yiY_FcID}-_e<$q}K{LG|!yA zcWi`dQ(wAECS}YjrtQh?ds~YNgN?eU>MllpIKByt#bEX>BO~fo<#ZoyEY}#$9N;f{ zd`i>FxBu+tx9S_in%xR}uFNseucW>^pJZ3E*j3*|d};DwIe^c5<@VM5+gJ(Tci$7r zKJ_HMTf5dy8Zk*a)`E{(@C$#v=^wFhdqi^CE;{(hbbJE)k(8}X6&Jm%?^_SP<5kOw z{ldQcN5&G4i|DPk8muQrIrn@XO(k3!B-zkXZz{gXYn=VO8vS+YGai@4@r>vD3mfsI z_0QZL-`AzSORXn_GO~w8g~Y^SLIWeWL(xHp*bQJ>u-{ zrKJd^bBqr8zmohYDjKTF&reHV%hBA!!Q4U(<`EVOa}10Pi;Kn_j!}czMFnfX_J(3& zpgLiohQ5ZD2J|)z18rTH-}Xnz4QhaX;E%Af2Fw{1ih-IJg@m~$#KeY18o?aGqmIP; zDJ!#^n*PyW!=L)=k$?(?XInwy1Lsf)q?43{qyg)m_L61yNqA&80u_~+`oT+tL=|E|2@ritf3+JGn!CW zqRgXW!vBDmUGqP2)!xqj2W$QXtfjM~Bf=S?x1j%|H+?AMf1+!k{S&&|7k`4Qr)&6g zQ?<86160g^H&FXu8|dunfv|J@ogpy)#t++6{h#eK)cvV_+S>X*H4vgqDCht6{f%q> zZ{7iar`$-D^kO#kZ_b+1JCeuHzVE@F>D*WKVP)ul4aOk#p(}(|7=l-8d z-HUS{Hl{!02+5tlaMXux{wt0@ zWb{9Q^!|M~^bCGM)k!l56Bv9rG&UmiVC)}Z%=W-({un;ZgV9GYnqdj3u+S*YNX_V| zP|cX|c+D78U~s5rY#1gK`i+a$Obo?D|2i()V)vJE+2;EHx5)j65cvr{9hknhHcU@< zdoK75y}y8iVt)qi$K_wZK`8z!Zrf=86SlwTFE;SVFFn-RX3SrD__MC^8>9U}YwVi; z6Xh9bYeKdCLU;ev3;vt#{$0ZT1)dHxOMwud80u^Ni5|qmKhqv`>t_fJK!|Jqgb>RA z9~f%uK*;|S#6M|I5B!;ehi`?IXN8fMj)9(DM$IxBmGFaaU`m$CFi7#!{-G&) z{i!MbR5BeMV{G^?Iyz6fJ#<_@YNlhNi=}6vw_VNSUfE2mT@`Iyv8dOpwxLZe5WnttmXtic76X%!@7v%a9D&(A}ZV9G6}gpITN}BSmGl+_;jP zSeU@-*%sO{-@T$xR*_kln^BOLmLnM;yEi7hko9Q#$tHa9i4vR?_sSeppL*?z@Fe|f z;te9>%9XVpLNzI;V^JtHD!w`qU)NCAAi4V+r%+XWVR6O9vYOKB!n3Tm4qx$658aT@ zNUwlmi;7Q|N?x2HG&C2omf;EyAI&6p)TScBt?ut6y{2otY~u^5qp7 zg?Z_PdC57F2@Z#xybDwrI0&OeDN^hA<_ zdz>IKwaPxJmD}jZJ0+)AyJ!XyM(mwTQn&K!I{HTzc&X>Ao4mCq_gpZ7!@jcQRb)T%t*>^ViS6Kn1bcv^L}kY9u_4@8hrr9e77?f_YVuNyyA=?+RvZq}88VBzpoFgwzSX@^A#P}-f z=uLOFqcI}iGT+nOll#jNu!ZZEic-gpe=#+?YF7I38^gtf)UNxCrJo|z#uYlGT(#aF zvU_X4&*gYoe?0+6(-2#BztU3sh&(-mx%t&{{Y~I4(17lhuO zb2T~g=I!WF$ziY8oM`^Xt}d?o)m!H+6BRwZFI~PImf50JZdp6iJ}NL-oxKo?9`k&1 zJhnb7@i4Av>r`XIfL^%DGqpgOcLzT%Kbe)kU32ceq8w(Ga#HVPB*}fi-ScEdyjZuD z)Y@82pe(IOg zSH`^@?&5Cr+>&+1wYE*39zF7@I_drBGsVwl>m8mw3ol-edrPW!*m-Nbd@{%pVQoJY z_gMesa$wvGF1$T`+4NMwfC7KR9`7bl2qZ_?$!pSsiry zqztxwxH5C@>L&IQlJ3C8&(XK}+daccv~Hu!3r|q)Z5lQ zn^6}p2!Ei_YCZK>^{$_C_sxrw8IIF}2jJ;@x9rHphN6D5R{GQVurHQ~wTZ><24bJ7 z-2(ggK2G8Lnug6!x?$w~YFY7;MewVS?;UYTXkTSMKg9WY(6;Dc>%9`?(D33t3h)dW z7cB;*#;RWU%bxh%cHO#Ym#F^r(3#z}eaCa~5>9rsT7lxNE`i!jdc+&!o^MARzN_7J zOg$aHsqfJAQpqt&b9I+nk@;O$4#TId_IUxU_Bgp%v`hb>#A5%9)c=& zJCCN-)_G>Cd6VCt^GIF$+WGjaEHTcl(oU;IR+ov7+>c#lMc+SsQgy*CCHL{6N6&Wd zIo$lTU=!BAQ`Rp`bH>84i1VWa-s+CgY7uw&h_tckCOL*EZebyLBRh-Xi{>7yfT4fN z)*sr^AL`%#BwKa#41bxggF^xWg91WACQ0hf1oMBocap-xhmZT}&*MMi{9Sy?tIxXDog+6j1cU^H)lZ!E zKEZd^zkGiaexkanNUL40tvo$FeW)_Mtt>tN_;L9q1j{(j;QEf;JFz;)#+NhQm+o-A zE?RzjSfuKRSKs#oU3=f18J3VLt2it5_HF;ri?@0ynCS15`Iw|AVCKNnC+HH##g!Ld z*GH~?I{GNb?ghuFgSY8rXKZUM*?A-TL6zfagUpX{6uqyWepT&Lx4hN17Ev12eO+A- z>F8P=e4PIU(4Vc_{|Qii@K-=D6z{in4+L_@<4z}yzxVa$%viz+F@@ei9SIbJ=_{z@W-q`N<4WN!+|y23cz}vE70tdJRHjj#3_mI|A(tGhz6F{esq?t1qeD zY246|I-5JrBYTE9u!w8Ro|IU%J52Sv<-Q6>Z{;B+d0&^F&Sw_qS&MwNW_9{kmLs~1 zY(};23WsaGyNcIAwaLc6qec=UF29Ky^NAw(G@glk_sZ;x#pM@nFXq;F6}h+`uK2#> zlZCC-iDexdI&j`U0b!(?oXAlS;0BKLIh}Oh{M>3LZ!&Y_W5XBY@2F}4o4V1Y z^rM#kEUi&;XPzo@^#(nX6DhGwR$F@r7db=M-`6$D;r#8HNmueShv3fY`s0A?myCnM zE5g+WpS~}QY3t+dPRBkBIPu-VhHSI?if$=3#v(QPyg$lW-%P~i#pKcF@zKl*uh*(8 z8!mH59}3!St`Q(gIN|I&(vqw_Sm1`WA4qHsU@_Fokhm+ee8J9%Gig=oW*&m|b-Qql zsqFg+?l;*$2$RZ9-aD`-3l}?gT?|Yh7@5y@PD~`r2_y;DWa$}8-jcYWgU$-XB3T}d z-W)t|uN*5i_55jS)pg#iX}wT=CSmihPjYNd_m-ILcrNuRHrMo1)$9Zv4lYuEaXjxf z+;37gnm^@Iyuj(bJ##1Y3#+9shq8ItG>rp-GB^|Wae*aqN;p)PQ zS;vnJo%hR);QgoM@4eD;2q4=3Qy8GpFOAbImsPRl^Z?GTNG>f0^?_L~>#uc~ym%lIS5 zU#@0U$U%=#Z*^@AJ;=GM2N@-QdWNCsKQ8~j@i}{70#T^Y5Xg=RjEI3O7#9y~Zw;Fx z5fMRwQBm7&Z;!C>7#Q^Lw>GK$>3Y_MTBfZJ*D+An(a`^+sZjDzZ^*@bG<4e<(S^*n zpzy#bW!Pa9>%uq zI2}C*uk8;k>i0NMS0DU)oEB6wG|<1KgD$io@PCN|bq(|&i|&^=Lr_Z_GJF3Pr=$PR zINfbu;NQ~e!~b4~AqdxnH2h!F!L^|t{5?+B;P3q~gd1okHGu!UUJ&Zr-^&BF zbaeljPFLse{ROoQwEm72s0}SB{HgibO7?{HT?2JysND)3%6cI};YE{nK~myqWjSyZ7Diesk~G1$cNl zgES7=uKH>DOEL>!0EpysvQP-n{a{5577MU(NK6I*fbJ!a!(bG@$3YnE0ZS1XOkS~q ztin(jiYF%?GORzVpn`Ls^e@|B#@}h=-DFRnp;wAYOVeyCp+gkc9otum9{cnaN*2V= zN|ULoS=$=ArGM~qFI5~18+^UX`upwnc0;{J?_zy0_quJ-yqB84UOj*6TC!^NVA=5U zh0~2ERIl&XJ@<8B{`RmzufuXQUgZ|_7&)3r|1t46ELMU0Y`kzT(x!>N7{I z3-?-XoGna$Q4+AXWmfm8AX$xh*2hq09um2Xd492uw!t7vL)wq2k#_WcSpb-%X=#+)8|g~+i}ZJz z(HnXz&w|nzs^U+h&Nc4Lt`KYO4xA`(uYlW&DB(sh)p-{+(Th{&Ukc3p;COX+YHz;d zkqb?~IC}cJ#J~S2G`FHXzbQg^jG8~ED1`)_`Ak{=w{X#JZA$KS#ewX+J4v@(A1J~a zYlhnETX(H?s{PZvp=9>6Vne^r3;`wlldP!A`BVq^R1M{3aAdOA{)A>`xpOVLjja!9 zoVi|}B{#0g&~w6X){L~X3Ti$zp3EL?dTFs$);G_2RnnJT#j2iGzhJe}^Y>`WR>@2W zY%FTNH@jH1hoZOayP+Xj{g9i>2Pyu_ZwGo@8ZJitYHcCXb$2K}H0X00uf90V(Zyn< zh1pW?Qk0uhB9d27ZQ_r&C0tEU(eXvMH8zRq6!HSA*9NZ4{{F2>tNEL1@OCF>fV5upBfa`+#H_rI zhNB@EOTEJ?Ikfxdj`=HMACdd>%Lm-Nm(>Z9)6QK9FdSmnQ$sIOMaa=}W^CGRGOUn| zR~!CB)G1M%#2qhBK9@(lCsxeKDmK-vXCmeuh~YI02!#ZI4?4ua7XV%427mxv3gI(e z$@mL=#;D1M~nW1~&N&fKXV0;bs%fVGS&kL+(f-5QakxfXU?2cs!8H zVFDa3jVoXZKo$^TG8G{T47XJQM6(&|EZ!)hR!)g->@X8L5pW6q2I|0MbAf4FnuxF-++~$Fq!sF({;rl}lAL1dUm` z)O1V$ipbPbys`d&vo{j)rW`*OzX-yhI3#AwH7=KGT% y4n|FXqd<8wjE799EJhFvAc&8BJidx(1R!KE>8ipY6f-ddIZQU$&d$@{i~J8%%a6JM literal 0 HcmV?d00001 diff --git a/paper/figures/MechErsatzBSB/rigid_flexible_joint_struktur.pdf_tex b/paper/figures/MechErsatzBSB/rigid_flexible_joint_struktur.pdf_tex new file mode 100644 index 0000000..1b05a9d --- /dev/null +++ b/paper/figures/MechErsatzBSB/rigid_flexible_joint_struktur.pdf_tex @@ -0,0 +1,70 @@ +%% Creator: Inkscape inkscape 0.48.4, www.inkscape.org +%% PDF/EPS/PS + LaTeX output extension by Johan Engelen, 2010 +%% Accompanies image file 'rigid_flexible_joint_struktur.pdf' (pdf, eps, ps) +%% +%% To include the image in your LaTeX document, write +%% \input{.pdf_tex} +%% instead of +%% \includegraphics{.pdf} +%% To scale the image, write +%% \def\svgwidth{} +%% \input{.pdf_tex} +%% instead of +%% \includegraphics[width=]{.pdf} +%% +%% Images with a different path to the parent latex file can +%% be accessed with the `import' package (which may need to be +%% installed) using +%% \usepackage{import} +%% in the preamble, and then including the image with +%% \import{}{.pdf_tex} +%% Alternatively, one can specify +%% \graphicspath{{/}} +%% +%% For more information, please see info/svg-inkscape on CTAN: +%% http://tug.ctan.org/tex-archive/info/svg-inkscape +%% +\begingroup% + \makeatletter% + \providecommand\color[2][]{% + \errmessage{(Inkscape) Color is used for the text in Inkscape, but the package 'color.sty' is not loaded}% + \renewcommand\color[2][]{}% + }% + \providecommand\transparent[1]{% + \errmessage{(Inkscape) Transparency is used (non-zero) for the text in Inkscape, but the package 'transparent.sty' is not loaded}% + \renewcommand\transparent[1]{}% + }% + \providecommand\rotatebox[2]{#2}% + \ifx\svgwidth\undefined% + \setlength{\unitlength}{226.77165527bp}% + \ifx\svgscale\undefined% + \relax% + \else% + \setlength{\unitlength}{\unitlength * \real{\svgscale}}% + \fi% + \else% + \setlength{\unitlength}{\svgwidth}% + \fi% + \global\let\svgwidth\undefined% + \global\let\svgscale\undefined% + \makeatother% + \begin{picture}(1,0.25)% + \put(0,0){\includegraphics[width=\unitlength]{figures/MechErsatzBSB/rigid_flexible_joint_struktur.pdf}}% + \put(0.49741666,0.20332806){\color[rgb]{0,0,0}\makebox(0,0)[lb]{\smash{$\bm{\tau}_{\mathrm{f},\theta}$}}}% + \put(0.77963888,0.20332806){\color[rgb]{0,0,0}\makebox(0,0)[lb]{\smash{$\bm{\tau}_{\mathrm{f},q}$}}}% + \put(0.24341666,0.1283279){\color[rgb]{0,0,0}\makebox(0,0)[lb]{\smash{$\bm{\tau}_{\mathrm{ext}}$}}}% + \put(0.24341666,0.03468526){\color[rgb]{0,0,0}\makebox(0,0)[lb]{\smash{$\bm{q}$}}}% + \put(0.62441666,0.03405136){\color[rgb]{0,0,0}\makebox(0,0)[lb]{\smash{$\bm{\theta}$}}}% + \put(0.91722222,0.03468526){\color[rgb]{0,0,0}\makebox(0,0)[lb]{\smash{$\bm{q}$}}}% + \put(0.53975,0.10230128){\color[rgb]{0,0,0}\makebox(0,0)[lb]{\smash{$\bm{B}$}}}% + \put(0.82902777,0.10230128){\color[rgb]{0,0,0}\makebox(0,0)[lb]{\smash{$\bm{M}$}}}% + \put(0.14816667,0.10230128){\color[rgb]{0,0,0}\makebox(0,0)[lb]{\smash{$\bm{M}$}}}% + \put(0.65263888,0.15875003){\color[rgb]{0,0,0}\makebox(0,0)[lb]{\smash{$\bm{K}_\mathrm{J}$}}}% + \put(-0.01058333,0.01763892){\color[rgb]{0,0,0}\makebox(0,0)[lb]{\smash{$\text{(a)}$}}}% + \put(0.35630555,0.01763892){\color[rgb]{0,0,0}\makebox(0,0)[lb]{\smash{$\text{(b)}$}}}% + \put(-0.02469444,0.1283279){\color[rgb]{0,0,0}\makebox(0,0)[lb]{\smash{$\bm{\tau}_{\mathrm{m}}$}}}% + \put(0.381,0.1283279){\color[rgb]{0,0,0}\makebox(0,0)[lb]{\smash{$\bm{\tau}_{\mathrm{m}}$}}}% + \put(0.92074999,0.1283279){\color[rgb]{0,0,0}\makebox(0,0)[lb]{\smash{$\bm{\tau}_{\mathrm{ext}}$}}}% + \put(0.10583333,0.20332806){\color[rgb]{0,0,0}\makebox(0,0)[lb]{\smash{$\bm{\tau}_{\mathrm{f}}$}}}% + \end{picture}% +\endgroup% diff --git a/paper/figures/MechErsatzBSB/rigid_flexible_joint_struktur.svg b/paper/figures/MechErsatzBSB/rigid_flexible_joint_struktur.svg new file mode 100644 index 0000000..22d67a0 --- /dev/null +++ b/paper/figures/MechErsatzBSB/rigid_flexible_joint_struktur.svg @@ -0,0 +1,603 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + image/svg+xml + + + + + + + + + + $\bm{\tau}_{\mathrm{f},\theta}$ + $\bm{\tau}_{\mathrm{f},q}$ + $\bm{\tau}_{\mathrm{ext}}$ + $\bm{q}$ + $\bm{\theta}$ + $\bm{q}$ + $\bm{B}$ + $\bm{M}$ + $\bm{M}$ + + + + + $\bm{K}_\mathrm{J}$ + $\text{(a)}$ + $\text{(b)}$ + $\bm{\tau}_{\mathrm{m}}$ + + $\bm{\tau}_{\mathrm{m}}$ + + + $\bm{\tau}_{\mathrm{ext}}$ + + + $\bm{\tau}_{\mathrm{f}}$ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/paper/figures/ObserverFlowChart/observer_scheme.pdf b/paper/figures/ObserverFlowChart/observer_scheme.pdf new file mode 100644 index 0000000000000000000000000000000000000000..b69b5fb3a72b7b8003ea23cdec1fb99b8cb6124e GIT binary patch literal 65619 zcmc$`V{|1p)U06KuJfdznz3z}Bn%Faxmo{o<0Lj%wX@&o7r zw1)a0BM%QW4-dfD#^}Qnn&}@AO73>X09rYHCnsYE8|c4!wtL8RNe<=*mv`Xey z<~F8(YXSncZUD`XOmu*c1p!O|ZD?9GMJHoB06RN0t@>XQ6Ev-Yv7@cCgQ2nG?;U;Y zf>v7J$-(?1l8%NMKut%(#==6!zzq0@@Syyw_vHxB5@4SDX)BnY) z|7XE}mH*Gm|BqD7@{g)NZke6=W&zp3aZaHYgkG!`jwm^Esm+?%nl0ZtMUDYHO~bl=Ai z1Ve)q;uVnMrz6BZPXn}(kdOj`;w8kcqr1-8&)E;&7oNJ9Eyq_qbv@6YyUx5%P4Tic zJwgN`;LJEvv9N*>1E2y6{YN+;;`!**lrUh>fG;jE2aDdb>Sq#&a~EIe942=e&Cf|!I9uwWn}{CX7Lp@lrfK$UaWp&)Z&=;V;21KdH} z5~pl@@SsFVVO&ytsr@_dy!gTr6AL!8opK0~_Wf%@^ZYpEqL5+2*QW4}pqYeLi1aYJ z-zj=1cY=Ca!~^+wczAxu6%^Ag_sYk}BK!*c&ISytmqiC}n+kfts+~iF^66Pn3gbH{ zlY@ZU+a8NhFFlVOJO;wCo$z9>T-G8OZ6fFxXxJLISxGLe*CvGED{957svqFuyc}2{ zh~S;(-u3QW0BSbdsHBq{>kvZtkw7knkL?F4gjY@xb<|})6i6;v=!UKj zi@<3OurC}Ocp3Q-Xs()%Z~b+{JztAHS1>nXRX1jUPfCwY9mNPgX0*@`ISkqF=hvkG zF1@=&&3n*S^YYKor-9H9maw8ZIGf$%Y;LXoQSwl(w5cH@8;EM?oA}v8FrX-qfj#jG zdVn!psOv^okXIU;-2;ecPywIz+5>oKJHd9~Ej8#G02oflD=?UwK&L)mR46(X*(R_5 zdlL`>)K6gjSm5Oz97MA3ymPfS7%#NgEAH??v=;;zlw427N;tSQqA*&>jRIHonFqEu&)qhzUQTAR$765+EQV<`BCe-fSqpjlb)zzPsJ#gmq6s zycOp`K*vBxyb1$*y1wUay*87$z2l+tZ2F$(L=GHbK(Q|Z^iI1&1lQ|svev>~Uss4G|j>d5Ct z@QyzBov$__H_XB5_5KSX*Bn9@9V9o{!1^IA@M}5b;#CzCiWK~5_`_=|Ff{-7&G(*~ zdXw`2??g8P&RfU;ebK}2W+maJd|aQ&Z(%K92uEAMx1f61v5kHHzz8RH9N)d(e_=r( ziR98Rq5zV05D;SSfL_jugHR9(o>p!L1N4+3171VPLBM+6d;1`W-sx+nA#&fXBlP)C z49|J>J^`SvW641v0=(W+--W-gkM@Fc&iaCd7~j)APa=asTn8_KniNmn-Q#hp^7{BH z6b>B`HLwtJ_SBm^eUl~Ao6qk*jtU@4I+u1?j32Buu<#|FJ5W|$Ckked8TG4lZ4`== z9)21>@JDA6huEfzPLHMzQo*6kiOALYW7pT?3UC(7xE%YBImtZS`C${7IR^ zeR-&IUwKHLjUSP!Go$NElq>8Z|0Yj1!8Xs(U=&Zfan_H5OiCaUmYJGuvXSC&^~)`Q z#Pud!kWm~6p#hgv14XZv3dxsaulr&|tgk*ZEn_Jl9QQrU#O%ezZ`vfCWT)6~I5CL&tv17$TC|Pl2UBhH%ZS{A9A(Jl4)33 zFYg@?uf&!6Fbh__^v-WZUFr3w+l2*J;?@wa5kgL3Bn#AN>Pz{Y^H-6WKI@=o|}MOX_YsxKE-vM3C*y&7%e}QFt$n@b=fWOaKXBqB4^<> zWEB&To>%#Dx?>Q(cL*Y)QBfb2_-tnoc^VmGWVZ=;FBVOncH5n}llE0KDV^px_+gB; zqu9Fc;k2lDUK+eKhG>cXQE{0Jj}iWr35Fjrx>867(@9Nu2^Q_hrk8C5g`b^L^~3~a z(g%2{vNc2>hIqdIvK&b_k0okjHfKF_h%nBnTdo4NU--1|KCMwG8_wprx zalFQ6_YE^o)TFLmWrQwa@hrqn+@isGJ!ARZVkJv?Ay-3xER zGVW|N3P5``sA<{Z$gf@PIIleydxl>#SYu9Z*U26sZ)#A!+Z(0G9N_}!H_&Gp&%vDd zc^WC%qDsJ?)7%@1%9MC&#Hf@{(eb2TsM?dpMh&%>L6GRpZH;yE0e{pezo$Wj#|~V6bZ$BOg3!!Wi5aA z)(;czciTK*Zrh)J57cn9nbbxr+RD0e7o#2+QcbAy?r&~=CYje&PtLx@=NKcG*5t+B)Tk3^p!b1)Ohwu}Xr@i9yVH|dJ zL>o~C`tr~6T=$82a6e60VG2i&w%i|OS3*Ak#K3u`b!F&|6G@tG2BHaQZJ>le-&jR8 zdR};PrLR<5LSblGU0bIut_h(EM%2%6K`cI@*j^YPJ<5NT5CQjYsuJ|5Eju-tyovbM zzgyf_J8S)#yZdW#T!?Kl$*$mrb3Yg7YqI6Q?CTD3>CyKqTm(|JgO zRf(KXp#yi)o^PPm-`O=n@sKRA%fH#HS@8MGmr2iZc?CuHn;7wys%^Wpry-1H4O-l+ z#LXhNR--237&M2^dG2yYP=S7_lOSh!YIxM+$?TUB&u-76{NyG@@nzX|>|i&X=kNl; zsE~G}%=-&0+{MSPR!=A}6g$M3&T&vSX)G)%gA`p3`a#aWP$#$}%48!$b6GE2*QDt^ z2;&V#?xUDiWtQvk;Wm1$>Uea*Bs|2BH;J<*(mBX{s9;(~0BiH4QD zyf1ueQF&IdGDt62V%OC;HkzFEOZ-gorxyu-HrMD~^7k_-QidBi*mu|MC(ehxer_bo zE8T@AIqL}bbC5d6G6puV3`T%FuzJ~`{K}6Rh%Pa0`hAj=LT4Qg9Q@@9*Qz|dOvN&X zm!{RnTiWC@Hu^DUJilYuh2c}uqSEN{-QDmY4pEq#>cUT2Ddwv zI-#pdseum8ngWd}WL-SLE12Yc=@ISpe82U~6BlOeV4thpPdq!0*ByvyWuS3B`@*(7 zrp+vYdOQRAGEq&EUXn>x#B6Z>)qcZFIW<89`m?Ct>WurynwGx=0YJq;@}ZfTR{A;P zkQzm!)$%z_hTML=OGT^$#l9{R)<-6GEukT#Y0)#;^}eq&z;yvn!V#*3GE@v-rTmlK zkpl1li5i}@um+bXLouZR3XCXdbF8Ri+%-s@@*c@r!~G}e>zjdOVPA->oxN59#_!+8 zg)0Z(;<0bDHPW8((o^?N3Zc;rHP%aD8z9`J=AJtl;U_37i~}a;8l$8yf8GaYKRDuW z%P*+U!)GN%FJP}KVmkLfdXz|8@6KDk^+-G3rbe-k4EV^u2j83_#W-Fy&rN?hEM?pj z6PD3on%mDQY-vbLyJY*x4lxO^9F7~cfS;W0r16~0t7S58WGAjSL|~?mD~@_MaGZ=~ zBu#fKUrv+EaV>0~WH96axU=oW=^lx=m(8ht-V01HNOs3pUSwo7NVpEX=G)Bp{u!3? zbEqoz(qf6|UQ|})tNMX_=m_SdjBf~+zF&{JWaJdChB_%a=#rBd zAs==}1oL@Y-WefX!@nJHOl?od6KuiSCAA71nk(v-KBzB|C=2?DNWQ>i;hcWmh>otY zxJh+5{o%qEnipo(K3)1^v-J!o6G(PM!55k@-K}T$`bg`lKgS1v=4MK_A-0DnuthUu zB}VJA!w7l=A2sj(VfrKETf5CqykIcfHJN#r8VooNlyExkp**y8B+77j^mXf|eawAY zEW>Jj45c*K)%vg1OYT&UZ0jg>vCrvI*;>LPwx|rhtemkrrH-nXBs}BOoB1AI({P^Q zIZ%_e+_^K3xyLX#d>{BINtoq1_hY=>$K*jdC#DF8O`8gbI*P?eI0OaQ+u(B1YZQpCVuBBKIry>ojw3dKTb@Y6rvRK2Lc^2VVE5J;=<5E^@u54ik^H8#XB- z&dZ88mTYQoWk%R-?lkew&wh8v$jWGVmXZvQR;9`BsGh5e1DZY3e*5;B#Sv#pQAS_% z+oo+^hy-J`4Q%l{&Yf1rbC!^vkuyO67d7f-hy7hf#BRF}L{jAb%m`>zBdh53so9(( zF82l4VkL|+&yCU?LxX42m6l$JHiPx|kOuX4^jhB*epjYPGGqbp${Q+87CKt^{%BeQ zQQPUHIg1hd7FAKxn)AkN^Ul|aG8Kg&%57)O-8V|VYT`AGz+4K!dN*bLqrh)zwcIWvq^omn6YE>F5CQA9#MugE%UeOW z6|CxEGsAT_!_LN;Maae{_fn=anJ5lZtelwB7-aKSqv1}pNFm6)sqwCbyH2{hg*d8@ zZveupq0v1k-7%6d!!Fj)@+g?%A(dw8BbW+JeiV^8tNe~T3l(t_;iezE|T*hfv7#|MF1jXDjW{wXxw;ZbX zF~*xGcqsCv5K3Qps4W%6Pc609+hVP0?pe=0Znz9qRUrBqZjhD{cuOBxx;!G2EB5Tc z`f5j~&=xPI&IY4Bs+r=Su2GR88>Tojpq0bLyovY7>G5*>OR@|A7=O^1!Rp=i6gpg*5SWBV#lY5I? z_Of8d@tN((a?17n;pq)j1T|1rCbn_%GS86cpj35aWEa>XU?UcF9~+6$vt27##m$S{ z>{u$LlZD4@rxCmGpio#`;5wuq*m7sgTXo8%j`CN+rCZ2=!gI@s*)LSRHNnZ%&MyDV zCgcf;Y)&Ez7|MyM6gwZ0UExM-@A4R~QjBY}aV^cSlDE%Et`D0x#yi@N2ok~cX|}Tq zVvlv5RfB1inb9f8*8A;;QK#{W^8=eh>-Zc^mGve8^{<0wT<_abNOkVoGLhA2^rZ_*7~IA z$!R#2Go|umdXC#T817~T#w0GkgfIGDRHe5txa%wjmITUvS2%$*Pc3C-f|`0aUo$YO zb`3GLoVWC(YkB_7d^~e~vSmN&lkL+0m?XsY=XOkp9~{vU=d0Fdu9Dt|us2fFz*|8Q z&Z9^aI!I!Ovg>IoP4z&C;;6d9`8JO2H%feF=-h)lEb&BL4_D)>1upsJp)zZAtL6t7 zju!piu590Ie({HP^Tm>o5?t1$E|`D0P^oGnZvnv+&KblAk`e~R(=GNUFHbo=Oub`A z!;8E#qKD6CKr|K^q9}-dfhuC*xse9P6iI zvHK`^2)B*MuJvcqHMu-bA?91H#)u;%iK|;2?oL3uW$G<;+e-ffdML;gi}6bSAxeD& zbqnr&B&SO>p8Ok_f^+%Y;v0;mM5PnxMC+8oYE**7cPN3;lLN_@Fq5o8=}wAN$2)a! ztyPpFo@`t+T~gd1UgUgmlh*BUHg1?H%Z9%U+JgAF10}Yz3as)1%!zF0PEF@Y)u+ze z>0rhXQ??^^*sMOiNr5PX=;oB&7(}L|FXVCm}x+l-PAA z@&>C~l9gU5(V>hYF9-J;(O+F)(WUyyb?rw4zKFtumnF{rLFJ~Ek6ZhXa=x}~{P$qd zqJ^rTbmCDb*V7y_@Wx*fi+50tFLz!~^asNeeMmWwT})d{MzOS&(91F$zORX^SO09xWuOeg zaeaSD&%-J8y>>CCSh25zzqpD3a?SBPw?`s4Wxnf9Jg)@Ef7jb4%cw@h5VuW&Niabo)mcuZ&nHQ4xs)OqJ2bU9leL zRD%p<2cH$lFMZS7=i>R!O^ytzf$<=+^Hfe5(Vo8jwrkrOgbVMB0;O6>$@xRa;xKl405y$kCy@?44vbbJV&FoEVIE9%>OO8TJ!6p02urGfQ)x}qEmkDpj!Akr%@GJTQuPOL)!g+2(T}lB~qadf5A?4#C zg;hq-Ho%Ag#P*WYr^xh_UYX-Q3U++s-CZxDHtMzUS^uQiquqpUHObwx(pi#zhx7%3 z1`<_OzG#~!!L51wD0R^zO=FU_33BA1*n6UBq_TcYL*6S`%YKujOq^z~2zU_b`+TwX zm)xI|=t=Us9Tn|7dGg5{3{>L|DyYxPb$H>%OK|F)OX8oU?qbwnvyuH9F28);*Wwv= zHj4uwBr91u$m>8-@9>#0_2bsfr|B&nY1`&cs{L5&rI=X{w)5(_gkv<&w$L4!I>lXs zQL3@p>Urlw0ak2UN)kV2-d+{gH zvLx98xV#pQ+3BzQ*T&dA{%sUC)icqHQN&bkKHp;3NNbDRe)X`Wyx*XYk7v~vKwcHg z&G~(owh~r=IDxO{K?!q__D??T4j-3EIVavSqt@xDt#TK75}vh*6%7~mZ`T^k^~rdq zIZrmdQtSj)d^Wf~_BM~3wO?D|T`T<*!W+rWE3rEPnV6pHx!~l}qAU9lGlhULP;tgj z0mzn|6Fp>=b;If!4sCiN`Q8X*uU^a z*^>b=otimBG7-{kNPJ*P>%iX&d^AR4!-EHdj?w)~*?13OTFqAKYhE+S>uWNwe`VMF zS~E^E>2tedDS=(hjQqN$UYOM0t#;cB>8{TfBR-IVd|>kVZL&8J5=Y#zLxZprUg#;+eDx0TX9k)F5Mu;tjw_V0dU3 z6L{yf&fQVO--UG?AoyLumwCEUIYFH%uVLe5_)Ek01S^8(gq)ZSxecv$aq-E0{Y7s@ zkT2;r-l7j2KV7<$s8f^Ln0%gd&wq0HfP?`}PFkaW-OUUISSOBNncm^%q#bHsV_`eh zpV=r6ZC+hrCLn4y<|B3Z@4{2KdagYRv6AOt`lJ?PAr%5GjBC0S456DeJ8zzpelFIh z@ZRHZs}tew-9DTmCYivoB%3vsT9EBG+sO!T_Oj+I7!a;)m`}!_3rGMMcBols?SAs? zo1_o%DW7BJ(H%QB&_s2(YXZiM(*5FHhXr@my48k)kbPyWrX)ZXKi_DekVWt0%d$!V z7i$IGTzt3bB89TMxmFWWlPeRl7f8Ig!Yx8f&QTb$cRWF|Fd2Id;Z7bqF|rzj@3Y42 zGrET}CQJ^`aF8_6oSvnDbinhBGtS(y0=$>ZR%>cOdxPS^)AdR@(8mWpV=nDf$vcIs z_=SB{v`3S(vTc2#;PrSWlk*1$d6CIo;?r&{PCG>~+CdeoS8#8!in@{Y3S3^&q6Uaq zRtK(^36bdy^4I5{wc<3gd*o1o^ODqfViU5lr|B~vsO-u?()GL=_mfFLRLtXrsM~-50t`8Ls^ehhoiLeUaJ}36fmy2+bnZ4?u{z znWuGVO;xv&wZ<&cKUUeNp7hzCCpp*&2@uDF=UKhHqoKC$K>%m0>zu1Cc}dg9AO>-t z`o3&|R?KPLgH7a*O~d7Hhq*mq%H9bt7v^bJVRVtcKpnPf>v$t5(d3*Ik}=>4J6JO1 zB?{~9017skcNWQqr2sdQKV;8DrWlXtI0ZNgD=|gB4I+^`$r|+k(D9^bKi}{C%7vG% zPJ|;?duMxuN~=S6ry%CEtLfT)U^8kjp1lHn5wjgo82*fk z`BE&v)3S0AG<8zuA9CK;>ONw+WHgFcV6(OTEIiVQ|B}Y)E>uhVay{V<7V=GyYBlTA zakvpu?hgJ>CRr|X?1h7E3^NmJ9acgfSH>pT;W-8MUsJfhQaXqsvlVmCl0tP_T%4HD zy7awk-==~HIN482hs(}R^)-d(R%LGWF2yM;g{Dc@_SiH7PV5j!t19B1Rl}8*6@5B0 zUpOq)WP2?obJ~aP2;3F>*%dnwIhEtmR*J;9-gXe!)sZz7zDb>$-7DJ4KFz#!WJuZQqI(j(o5Zcae=4x2P_$dM zUw~K;6;fa5+gJOs_3%B@GcoyoUEDEEkS`qeg=l-$I_CyAb?Qj@jI>69(%U}q=gd%DGV>??duPS)hZX`$Jgg|~9$QccLY%wB*)R9G|H=uNdT z?iGcG36%6$NvN^K4}}94(hR05Gluyk!7BO_qKC823zLw}+D;_{Y;1A01vcF}Vm12e zqX8Ut$H~Z1xA^`HWZs{>yu-@8`!tfxvs;Ra&p;`({!?r6eJd3;g)^RQr0YC&4tzZ z7{e`9;VJ||mMeY4$-Y5&|7feTqpm!~4T#1)JlLgm=e*6~E*$qozx&tsWLLd$nQ=&N zLgheG>#A=kwn#11zkTf0*CXI6k&} zeu_LZXXb5k`DGS2E-%kO-I_>PLem$jP!cKP@w}iVk5lP-wAE15y1mH2wU|Irz!FGA z_DiGMm#?7;auRX2sU=gt^UPVYc(k6wIN51T4d5{(N^%p0qu&0tAkW`NqS1H<70hH* zgTmSa4t}SEsLMkM2#B=%W-3s~cb|4cPTFFfwCz!W!bEN&2KB!FEz(1^pLMXcA^xu5 zCjkyuQ#-z{R@NPc5OXvfqkf{5^4cRF87Q-K^hls6>laR5ap@X@dldS_Z?QdO1-};04qA02^C810yD6PQyF>R%9 z>InFtt^BtCVYpB;umY$Vm_Jx9^b8;D2j<_@6n;lTV;d&`3;TzspuU}$vAL<)hx(f) z@q3ZqHfs9cMsX*7D|17B8&fOe-&BbYQjE0DCdLnzji8yngQBq$fQ(j{ z)|l3W)|%Fq*4D-k@6HFt1y`n@!O>0?7u`u|es89p|uYHs9Y<_OSaW?}!J>HL2k85tO9m;nDA*;rWt z%#3U_e~-U)HYP?I#*f2bqhSHC(KCOn!^T2KLl0nOVWnXQurjiK$ZTwkAMzhhCVGb7 z@gFmc05(=804p8K$13!646HP4|8n`A_D}d<3ox*MIIu8&r1_KnuLb`kqo-&7pd9@j z_LqT$o#A5-e|G(+;{PoFbLMwqX1d>d{kO!(%tXWRuk-pn`>!+jYnFwM?!)$HhW+C# znE%B6b;7@W|Ja$BepkiB%AL{*>{T-$xVv$Cd{C?)iUq2mNnm*57=me^Ysw zKf3&n#sFYp_}zW~naab;K+p8wpz=60szM#=ejJ z1OUhhpd$zgN|^!xVr1kwetRWHic@LBG;}~z<4>HgAxV{xh z#dd&0hXEb8G~hsih57T<`LgHzbnxTogFFMl2m@*(BZd(is0_Kf z5$#=Dt!*)U(*W_3^8uowq@=!~#F4x7%iWTLLZb82ThqsDLC!@0(+dgsp|AGtTezuc zH)z1UCnW6c?JW$z!$3q?mX6bfx(GI016IU<2)Xlb1>*e#8iD}7Xlp`fwCdN&iF1w3 zD%fh^O<;!M2Z~@v1{2;R>_()mX9ncTrdN~?kKz8~Yj@_YFDDeR?->M8q~E*DJ?WDv zA={NI9T>E*yPLq*H@gDtO=!{YKt$5sh!yxMP<{Yy9}WQo3=|r?ZBTzAzyw>UZjvC7 zG%7Ms0MSDz9z;ZlrvW`72HQ5N@KmNi+e#FsK@rt*&c}8dewsh9%aBq2O*uqZm$6!OiiTMFv8!FgxB_+a`VA@ru!Yc{{XGrf3x zg|zm>8NC|~_RuYCcxqiw+3|iy3!1^h0D66S?W`Ld9t95;dU)S?EAP&mham9?DGTVv ze79Cq7JdZw|A7SHQC(M>AB4H|BYJsf+blSV?vD-zhGxYXdUt6Ic*QdYP5r#OveRA3p$28crS#P%th*X9 zW-92pM=NSet>oDj_H_d)*cUoX6+;96h_vC*y#v{lg7W z3qUSeN_HSA2{}05PqQ#y%&Oa#OkxD60qK&@W9KOi!19R1(2<{k?QQ~qRZ-GUOht{q z0Lhc#z~0{332$=QH|f@(U?2p$yYDPtq6a7@m5`nR^AqY-E&9q`;NQ4r`2KjOfIo^J zz^v^C3o3uDeytV-fw&IjA07yimwOD$NJ4}SrB$wag7!V_-ZWE(z>iOZS zU-V_~(ADJUGevBhMwQfr<;5v^Y<)IFRaa>nhIWdT!aLEgzDs}e_XUr-DW0eM>?;*z zoyPk3I;advT8K;!aP^QiLa)GgnH0{^QO*52d${pj+l=Im^1Hn7vy!c9lE^&;k6lvX z>|kW7?b9DRFb<}irZDslNQS}c;$S7sFJzGScaSC7-W;Y2-T*PQj$}X{IlhjtddO)zwnrah} z9n33Y!y{_A!K78_aF;0sc6efqWWoS((EhGX%CTuZj_!b;u$Xx&FE+`r!xcHFo;`(g znjyBPkfkCBU9)#v2U`ju2NUObw$^*}t&x^&g`$_n#pX;K<5@Dh%yHF0%J3oR;Wp#R z(~%|UPxZ&7ENtZ zY~f~jopfki!tlD*nJ!m5 zB9br2(;<1NT6AV#Oe=$+<7jnKR=dh$sM2X+;*;t~t%p|ayz4m0H8}X@Ud1O=y7oD| zNrO*^fhP&!(l6A|i09_;Y|OdqVUclRaoPN{Zc>?jazsPVeN9^9#M$Sv1sax!Kr>X& zg$Dl)f%O~nS1#g0f3`bzhk-?Mj#)VNjm!z2nPw2S*h0}Dai&m4_Bm=6hxI5}B zF>a5$C0WW9uqAn~TXU)zkdAMj5Bem7V!UZx7B$EVDmoKl|WomBdy4kgIMoo`1|%q6s?WF*?B$;)qc zW7gD#nqt?_MjkLJ#r#6mT&oRvaV>VD6%~dg3%g2TMULGARr`Fo8s&P40(c9nrw5W% z?%=`BpBd|5v)4lE>{rI!tV5RP=BOn;exuke7O~^~n%(PI^-}f`xc5QC8iYyLr(UQ3 z$<5$q0!ncxbMq-NUEhn%%5@PMAt&42nR^e#w9SX_fv)$ZK00ft0B@(6=FNlvq7vT2 z|0_l#c9}+6w2@WC8?sl5;jLS~Mt>9^Xmadmfm2j#3j(i7jHE?y0;Y*|28Jr6KDV}g zDDD`sl*by;2iRx>pE(Me2k+FLrV!jA-wZ3!w~PT=)R~}Ap9fh8mNoyGtJusom+Xu; z#d|@ME`K(;{QfK6$mGN2Ob>cHb+hTB0$$;dN6+l#u6I79jOr&A5?U5J<5rC2(z&9& z+ZgOqcwdEyW~6IF-Q>&dpRSKuEWW6X9-hEf zWo90jzL$y1BlMKSCNiyD?vbPD;JT@2m7?0I0iL5TJxFb*L3HoU11G}Ux9sQaHUkiu z?H)g+%56Y$?DC6(Rr{>>%?z8@+>Pf;w+>j4l_kZ6S3**D%wPxI2*{s9^RFLK57R*y@mq~Eaoem#og2d(4HSWX2M^qH zEd9A%0UbI33dNF;DYOLDkxrfNU)(zWcG1|vyV5x8PFCpOBbKf596dv>DG(cf-R38I znNHAGFdLSaZ!m$T-OsQXEH61HM5&y-`9<>W8J%RDgLG3$U@1d?hL%OT^w9F~8vB?T znFA^kE1FR#8T*#@CiDqc$8F-5*@~q#reOci+UGUm@^3#@AG{_>xsJnN?)b@uudTkZ z?`=9s6z!eZ)Y7m_Mf8A{Q7X zbxEiBpkb+0uu^~QvS6CT&TJZc%LG4OpXtlxelgE*f)@b4r857G{_LfdNk1arrPYkg z_*ec~$_!Ch(5KWb<9q8IHJ6D|hVDCISDvpy_AQNBf%dH_AssjuIcd8F=4T37t8|e* zCO`?V++~%7Ozu`bGV(34xlb!>pw#B-G`QX${~p$jl&s9riUlR|`ZUm(=M~A{#suIU zE-3G0apikbP(C6~clcf}}O#@ueJN8fwH9+-~+2Ok2PN;%02ZxvkB zPOcYBq>WKq7%|{l15+$N3QqQ24!;PySk=F*k4fwIP^=dUW2SH^^Mo%-?50OYus`#l z1c5C6=ztZ(V9e)?^l;rnapyFpfLu8ZHgM-Rmu=_Lz7Gl+#&4J3C_Ad$QJ90y4M^e0Mb_W)H*D8yT_>R z6O@@ln#!rvn<+J`q9@%giyb%`YYNoN7z_Dn&L{cJb8biJ74zHO0*DPGkI&X&{ftyx z57sTf*|(vS53G{HGbIvE-7;UL41&j|7p;{{my_&k&vCmk1~*3WJrb`aA5Zh)iXH=@ z)OBiXsu$C`9qS!?*UL$YS4w?+GXC*{c%iC{2^f|E>N@YF57UMWGQXlwn7Ic{xm;zE zSZ>i4ig|1N4$sQs+<>%c{AzhxEQ5_z#&Iz;{1!#q#?TTi&AOc)6(?c43lT68cJ$;i zlkSK}Z3td7M?9lfYWI9N=HjuNT5pxq36>A}n*W>yMZBogkCZk9M82*eW-^mTam7PU z)JLCjvH3@?d&=UeYf~nCj|vTNrqa`5p={1a^!^N`uLDlp4UF!y4$6u-W=J+N-I+Bf zdQd0rZ2MSj!3V-=_8Hv_6*CDkRHTSZ(zrVH!Ux5fPRl2aGZiatJptGhBI-1IgSb)4 zLfH7eq{nl8%|D0KSGXfLuzr5F#mbwFIjF2q>Fd_dTa_$jWQp9H&}Nerx2>bzOtIN< z_l)0Lj~r`J>S-|O;VSW=w73LtsM?5+*ok>WzC?rczrZM(D@sv=} zupYuHDOTrZtlhJt9CvR6e>`P*ZAo<5xR1{ zK(0c-Y6u;9gxE*49(`WJ-HpZ+@SlA;4u-_1^VBS1(lFio4*Ax*ON?V-aboWeBZq`o z{uR4=fn^DeA4cp--E>lnHR=)>oo36Y{q<_ShY8Oce9{%Y#F8A5DJ5WiRi->%od@mE zLeic3*YXPDrtT*4#9M!@0&~uZ;7xtWxq$>vAS`ho*oF)Cok*T$G;fmmv=Nuozrnw?+Ii*>lFy#(IpG$X5-IAih$#>O|s%x?-aTJHMD@O9N*7^;RZk z#}4@tdeGYF)*TPC6H>%7+%#eIo722G@uZg^v=zEjRBS96`?>RY!*_$Eft1>aCSyki?qQA8yJb3d z7eyL%PjZc{R73c81|K(O#R}Plk?~~j@&LA17DZ)96-8yJ?X|KE%E1c644764@j&!F zbQ3gI5;Imq+UeDD+QN!1EQJff8xx&ft7kP9(Tj$e-e_fKJj&#s6M4b<$j7W&eanor z$z<)d9PWj%1q7LbgoZ3sDs!dvo1(W@oO&2;+_5Yfs; zYUI~Ve&jqL@B9{H7Vsj>NU|;oXM4AcR)g+DX+z>5)phD`L4(x9p_VeNDi1F!D9&x}Rj#OJh2VSK z_lt>Gg|pDKcARba+cWnt}R@9nC;`QFw0)l7;Xav zgPkzr3uM*WhR<;>+Rhc4gKriknDh@oElr$qqI*8AEAzw>8=XTU5677+CchYc!-)0t ztn!uFW=SVWJPG{!-vsn|17Y#JwF>Ht%%*3hc<~vR^q)Y5ucGEJ(rKJeGp5*8_vxL? z+Bkg@$c-WisUvp0d-wL1vTe9&utgh&uL}}&71gkOpBx}vvNsxi`56J@rA7H7mnUBD`b@68b#ZT-nzDk2P%s|ku=`|< zSh#BcW@N|Wbst$`S@R$zv3xXmfP4K-BbZ#NP_m;6BK0jY@MK;Et+br(c7oIGs-Y{F2QFzhj`mVJ@|B)U^E~OZgK_HXE;B<_ZKQA_ za)-s4gnoP}G@?mVamDR1zAlR`C20zS$yc7>M5SQpnWC~FKEr$!1TxAO3ec`hAp<6z z@kmQ#86t17jPDu9GTZ!6Ao%kP#T+`gLi6TBR^WpRWeF#pz&pwCmj3XLVay}hRyyam zK~$VyL!;ZOvDOHkMoN~%GVZy!x|Aq(PI-re*TvJ8y?3Sev0!d3P!p~0y2tG~jCm97 zy>4sFPwRr^$lo-r(B28PWIRcaE9H$=z;x4y#>lLKm1nL_(^T>4I}O6`udFg^lC{QC zPMiEL#)g<4EyqX*L#ikew zkpaT8ZQ1{P*SkdOJC0MXQFNw_8-q#f(V=IkeQ7y%UfSC$?>B(v((EKBxqKGq2KO7&Z&pkl@A}Tmjl=JxV5K{auvI}Slx3<;FB1cp;8@AQ{*Eo zVtB?4OaM*;sY4@5wnhfC80~rE&mmLmB5snorl{7PUCek7xmA>vK)9)-{C#aZF}|Mu zw(7HDfzrWs?OSKy+OW1iaod(+0=zCXOr|ywI4Rb;jHpo_n>g}-j@nliu$%KXZ^vVQ zs@3*$?ZULV?6RK{hTbQ<%9={kqIOh2`F+sM_9g`U%Mza#@#c1I)au^E?`#$nah_#73!}khB(FDh^5ob z4t;C+Qf~OlJ;r0AuYIb3SJcm=C#JkmeHKg)e zka3#X^*$Il<>UcxBCS+jaUIDOf9O$o6umelwb5tUo=eJ>*4YmgLRZE(cA7W*LGIOC1YZ2 zYLdW&O3)3GXv6Wpmt+@lYqDS{t8@%k>+PL2=>0^a3h?E#jw!|{Z%{Yo&vt_$r?kP8!v(2>6@_i6%uTaN~`ue%XDYwg|woAQDYhK2L z(lPRCquLrIx-crQ5q73+L46)|aj!<|%ZY9mfsNd5_KMfMmNkCF5F25lP-mw>d*WI# zxv%ih*J8gE2ptSdReiJRiu!!+#p}-4PVr$a8*O(b#{~W1i*GM^Y0lRuB?7rY-Rs`- z7O89%@;`2)i#(z|w}Xa$Q96S7Kr-g}=r@TK*j|((xR1g1YQVPfFu$DdLGH5beku~G zIr2;Hd8NJ#nRGF#7Og!tHD%Ey&P2jwvgIs#WF`$l)-ZzTztkXAb`=seBUjXb(T$rX zXf~9MR!d)1<%&D5b9&+bS;%&yrNRe^BE>6bJ&4IBAzDXnLyvdi(?06S&$yOU<4Hy9 zFzHsb3EDmIih()8Ns9J(IN0@KtZBnki+|Vwv1g)fqciHO$Rm!v<1?U9GHjT zlmAVqNVMcjCflSsmeDl2bd8$R3u;R(vfrnO4&-kuMZ8MJBFGuE=tmk%yHgi=!opsR z_HLt5S{0`pGlBXmsx-{`!=!D8E(z7YmL$|&e&t&3MCFo-Ci3^;*V@_!JZ}`2Qsqt> z9FC+vjZUPtIeTja-7E%Ph`W{%@^aUG>+{ zUSprO#fRNTF-Q$TI4ARRX}&H29~5}dr`nE)$e3ki(y7!MJ%+6epe`l9HPJpe<9lpCSR4DPDS+X zs~bAN#?`e)ABcud7n{gAb8VuWnwQgVo5>fw?4nWHqP=AIo;^TspT^q3ER#%w@;$6| zq^D^^ZXen&;+C0Le}wkSM{i!)-BYl3!U|^x$s@%h?)Ls9>kUct3I~`5MB(Bi| zeF8tO!QrZk`{|t>JBu!<+SVmkj_DmlY-*=*U)amcM?`qFFtkBg1{(O%Ry!LKmArOXiKj&tSb$>FB${s%%a|N!fbQx}IExrftMWvHHtW+vrP1YTd zv}8%4R)W}t7RFLcogB4(+IXOTS<`K)CVVsExVWsMAd++VLo3)E#r=BVD|@R@YkgPh z3ssMGlo5gRTsu$mesTY#yHXn7ky;5bCGB{}c(}9$_Q`eV=t=J&zrl>{mR2p7sSP4S zG-SP0t?Ohcd==XuWVbKu6;|Mi)g4ol<<||4F9PMdtR^fx;G%sAM=iPQ+Fkhv7chCZ zVeE76@ul6clZ&Sko1S>LWb%S57>P5i`>{I=E-U+V4YcmsijPslbf}cI)W;!lEsacH z^i=8WT^_^9>Ll-Oy`QeLU`G`U z{wo7kbnJM&O118|L4P94hqYHcXOWC3U5Pn@Y9nbmUK3}e_`86Dlc;V>F)%m23Ui)= znbwA$$7VqbHZ^iF7SN-#LC!>*4W-z--^~w-@(|%%Gku|kL2*14e(Fk z{x2x@KVY*A|7G$2Z_xe!as>az?tj0)@Hckzit2B&!32Yj(@T;u`+x>+keJCGapy*0noGk2KX6%+gMqC1Nkg$bRV!b z%Llm424H1l`hfF)`!TZ6e?a}r^uIm+M6-On2*OU!@-O?p=KhNPS9V60-x18rAKCtu z|Mz+ypMTK-{#yP+WugC_`rn2APw7A7=YKWif4HQ7KCJR@0G)~XZ^--uKxbt7FWDGUk{ONnw~6l9H;a21E^1rq#t2_pp{CJr?Xm|g=A5PX3R5Tk^h zCdYj*@$`M(*kHHJtT(B2UFXbx_BcECNW(WjvKv(+pvsMaVvEP_14RKHDlH}d1nS4< zg9rEuADgC*9^&Npwl`onAKKRP1HrELJqd6C0!}2)<4%W^R2b86N4e9 z`X8*lb9ALao3|U=w%O^}R>$txwrxA<*mgR$ZQFJ_wtaTL@0po*=9~G>x6V2L)P7c_ zo=VlTSJv7)*M0p80u1EYPhhqi6`9Te$i0Sp0w#9|R9>_vugY!00g93yGc}49#d%`8 z8i);w8;I=Nw~2>#JfeLlXMe#SJ3kyOb6DpeSx~^-Ku$;iRDJSLjbViX_?VJ_MPD5n z3W>Nfn*_OQKsq=De(gtW4ZJ3=S`x{<0CNq?Ab@`k^%3|BG6p->64vo!e_2qCl(&aY z9%yVAC{SRxssx6;1$_bBj|(ripb%!pE}-v=to&1A2jtzE9S8~WnE&Fl>~j$c;!7JY zL;xvTR<8vU&IYt5gi`<*C!&l;T#gJA2(I}x3ChJzB=@xUQZE&B1tsa)(}6)iK@=89 z6!;xBn`Qv~Pmt50eK6;Hz{p!U{An`!j*0`6m>3n_NyL*SpL;4ST0ol%{T6>lV<;)l z4xcaf5<^SU13i+8jckX9U1~k9lEh~~Hg(QyiHaL@EG^e$M9sK4K9Z$(}SKM$d54L6#flYQXp%llPNH!Tkmlpc5>5pc3R zE*9QZ&LtK5!fQ;FMi=Y^svg`Adqgmx&)1KmNi-398nBJtvz+_wx5LGs%uF8nqc4y* zz6N!5P;!2V>`*>e)np;VTOTDBQ;Sujf)t z!K3T|!@S@0YoY6B%hSkUp%}b{iu+!HIER43AuRrA>GScnmsb|p@g0;e3tTDa`c_pE z^#Sd#t$_05Q|FQ%Hv(m~`$*nT7)hmjVT6(j45+=uuk%_yNI*RRh!9D#Nkx8o+Y9pg zwg*{U2^uJP6;UtBuJ^6cL{I^UUUDvaNB44@zy}zJegV2jY9Y+`O@K%csQS$IPWQL) zhL)E6{s#rTMML++HX#Jn0xC>zMz(;!K;T7LV8-+}V>6x>)ll-wbMhSQTYJQ#^j)HM z^q~pNeJ7?lQ>6&>-|YesCN9>ebyKFc-Essk6$>-V9?+R~^E96|dCkAFT6hHsW1cvR zj8lm$1jd=f6TPWacIKjrB{1E;NUIu>WSS9}{VA>`I)L!hJ)jJaV%qK!3vYc=bFAYd>Bi1x?xv zRC!9%Aqhtx@H9UJuc5g=s)Md(g57BTN%*YBM;zxpX2UZ?po`U>zGPh!jEt@5I{P~;qA5A;jETlNaw&10m-;0~+Wd%K)hla1~K9UnX?URg$?{6{Nd>d1| zUTbiLm3GJ9h{29&XC+UydISxIOIs4|w>-RNVz!9o< zGSWT9oHvAjsc^bvW5yZPKb(s$M+mho#RM{GJ&t`!>C@LQ+$ppIi;obwrb;)ZuPG^3 zjcDId&57zLC`@u=uRYv9;UQEwmbJuGN(VyOOI06@qusZeSG7-wQNLGq&zf4Q8@OHw_`8F|$R{7$?6<;{`8q!L- ze7@Kjm)~Z$R0mm}I%VrTYB#LxJJw}_P&$ARh>yh)d(jx?=sl*KbUeob85<*oBEnPQ z#_9BlK?MW*a6$JvYeOYnU7AHR^jZ{Ylp$@7(LpUbFt4yPINNBzMgGQ z*3)Isl3+S?*HL1e|E|N#bVt+sS;~N5Nj8!rNcNO=Pi$J=53OhZmD)u!xD(crvfV4?)9}2Dp{5GI;BE{B81C>VCh?^LbZPYN{cHgFy zfIfpKtcekH17ZFf6kZ-La*@`)RF+_lFWH^(pF)hX#4w7A&`V-7Dej(9(>y*oZ*?am znwyzbQ;Wm-m%ILe;~xC20fse5BemMzLg;TP%bFzGIv*K|aLhUPbvAaK^ByQB17jKi zpmk9aMYC05^WJZGgXDh}-ApO0da9eBppcqQ+^7v8E(06A9pRdb7Jr<(jH(-IOyVl2 zitH0Om#W9)M(xJ!v92gaq!$Xwl`qy5;N|czcc3pi4A(exsbeNH)1e&8_*&|X#ad${ zMu>-&=!#Hj-!VB}brofawI`BPm`fXCbGUDBB--$x`G%Kj*oCNDvMfB^DB#9@lcUM& zBU#|lytJ-{JrEDq4^fyI-6coWzmxQ&D(F?FbU$8txG{2dZ{mZ5c5cIds{h?oTzj;v zZ;_=!`aOwYDGZawdD>!vS8>bIXxW?7Ghil0*C<3L!cDV-Jn7hd^*#QFseiudcIc!{ zkeJB&@#1t74U=edN;`BE{U1F6CB`bE(j_r%j``_H;)t^i-RzfZTlF?=5@V zs@}MFjGg-XzOZRy#~BHQBg0^4V7?*qM-E(lL6N-NB7rat-2}pUU|MivNJfHUyfkLc zv{g*lhHBS)OWw)Wqkx(}37OJurnfc)`Se13SDLU7K8?0LB(M4M=*Bf1^}z}=U^tH( zd?7jgiUKjB^ndHxnvQpu2zhc5syeD55VwN-WP<}Q!m$%5rl_@abR80G5-ct6~ z#pLq+IYoj{_MUl23yL(d4vwRuW=CWMP*opkxsZ74LYxcEHPMhvn}R#GDkQ-nsH_h2 z&Wvaur=iHqB`XB3*ia`csZh~o{kW$L-b-12lCAWsFhNI{v&v3~A|A`*)!TCn;~iN+ zq<5Fj1Sf4V23BxecpW4NHvJW2=&U>wN|n%*HaUpI_R2n54D&~5%5yV5GF=8VlGjeY zIDrY2iF62mndM6wd+u4q!nff81#%%OuL}oJ{uyy?Il3R%`8jVby>b_0$W*l=&85Kd z{#A7tJ!9`APbEnw&#bH{tXpHZq$5mx);MZh+YT@&9zOlobEG*gN%6#4%R9X_UfW1? zZzGaX74;$_#wg5Z3YCuotrCykm#DL}w=DK;u_X5dv^*p+L%9sfChaicB9;@3Vq~nU zw}l)RT~@KhM!ug3z4pM^JFa_nK1HU~9%QMy(}m4B6Y2^rhEp}(g^hTw(B3-U3YHim zD8wF1K=41;O%M$`)WfJfXKI;zT1M6Pj@u|yIxv0#OE1nB^jMuh=N+2=ioDKBVzdlM z2+f7BLC{~=0ZUig|5UmaZy824L5hD z!Ue3Ln*;6BSGa~4l;8C(yTKv`gGRSd#zT}V)<0s^2sZ7oZ z$fFs~p_wQf!#$n`UHAsRfN0hwmO|l7rALvuqvzC$;Q1B@uzjzf+~cZ!Jt`Z$kjM~( z=|ff>oLe`dwMY~je0a{*$uWG8O4EkE^r=!|HU6>yHV9HUQ-ba;ndnL}RP zE@G2sN%nm#Yphbf437f4p-CxC_Mbt`OND-~1LvNgy#iI@N;77+xfamXA+P(KcaB!p zt6AO8jTMzFbY(5iXK2S!jW5l6bDQ#>-(AAMe)7k`D@jGQs~;wYUJI`|`2SGzD>X#?#?!Z{45!M&)xu0T|IjbU#b^ysIdmyU zKPn^?zZ@X3`hLnIRS_(|*4b4yFEUWJjP`=+8UcSlD()Pk0? z-$6XLGs2d&W!*sl^Jn%7OK6W=c^*~?(t)K+q;>SYs=us$>@r2eY?5yu~ zy!uJ8+^(Fyi!&7Rz95?R1jxLi4i}BK6`r`X=Jy#Cj^{t*nni1;6fyi5Np!LJnfAQ7 zg4y~eS4Fc)mBH3!5hoVoK03&fg4-gSK#%IALRTB43i<714v7YVS9Qxg7y%FYBg|m8 zDun5z8@JZ9xMb)eopf8m$yJX>ADv6Q9aEju0fSKD+Nn#K!c3BbcDMnB4O?^qk+m=F z1`kV19e)2Izm9Elcs-Fz*p*GQF^n6oqvTS6ROimLa`d{tfn%?`*J7Ik&s0+rI7xb9 z?#ojSI$lFRYQ#QqaH&2@z4IUv2~m? zp_xiY*ol__cf=-n;7WKF{R-&>nlebv8}(hLw~zEP{f-O^Kd6Ow{rBnVAbq((bf}GK zN=vzNMG(0#J>w*KkxbQ@xh|iR!WWtGBH1cXmGn7oW82g3XL8f=PXR0y@2?lQ2_7=q zps4&y6oP$n8Bf5x%noT=*o^YwyiG&4Mub;0ZEL1Sp8|M#%MpO2(u{bD2RH&5jh`i+ zimu%gE%2R=)Rz|$fpuu(Ai^zHGr)932xQJod#R`T-MW6cUOQz49XbZ}7tbM*K;luG zpYxw+2_{j zI4dLg?SnJGMGj`8uhgYzr8Gnl)~lY_poP?68lU9s@s|?QVjg5Log>?~;=rshpld+d zQ_1U*8T<*tS%ci~&c3K^v+TXFsL^^`GXNbo`X2u?2y`)T12amcm zPps_-ZgpfjX82_AhdQ*5 zFtu06(`19E9zkMddGj9ZB9)Do&~#kPS|>;+yFer3%qlpo{h&Bg&2#VVhu@2MQ?YCF zQtrnoPx9TSJ*$g%Ayn?7RhHLXV(!|2AUOpyOu=_3>It*9x+LxQ9z|Y3QC*#R1ne?p zN=0np3T|2^ge^oV{2^khr>1l&T$20oP!E{_J-tU#YtXs1V=JY|s~ZkFLYoX6t*g+?3j^ z#UHuM9VdhlSi?ZS{7Jc04}NS?jTAxT2c!n2ywlP9?5o;WZv@9*KVuN5&IC$t#5q& zsx46&O765!3~1Xh3LuHMm?R4&x1mrN?mRgNNfRZPuw*s}N3Tgnl@Ioop(Vl@T)1V8 zIH!*GBAgi+PtL0J1w0)!o?3?1T8Dd!Ot;NQDgE6Yuif%bWT3b2$Arbw?$nhD#BTn&TWJ~yM_(a0)F$Ko*N_$=DX=-X!+Q>({}mjnNn408M>_Ydi{n&({hg7X85@DWof=^fO>qL z=OkMRk@D)#%_H6Ex1YoE%&%g6R5!(MtO{DG{^2zltUez6?iEsaXKTEEPghG>t6rBr zb5%8kpYv;bM>dl0!eMEjo9Adt0F+$tHiupFV!XRMMT)%nRpCu~M%!3s7o_;>V^*a9 z)!ooKsl^dQVMCZClhx=v38KEn-}PN#E;`Fsc{n>eD$ddI`gF=ex z=waD8RrGErS}8kEvf-3~P`EkK3|!F-B5S4jgX!kbubmnwQq7YGTo7b%%*9DVQk^@L z#X$F^XB0Nvpm|Lt2|Jy)%o<{p#t9i&mcS?C3{l2Jaezk?Bu9?=`&{YL)`GX2KTX!*RnNWtDe0``ZTEL+|4N@jWIa5O)@A1RY?1giMhw><&96?$XH&1AA4dqzGtjO&G48)FQ~3CwLYu#f@;!TtOJVF( z7pPiQUmlp^4(|ov4bD?B!lj6t{t*v&BAo85Xnb9$7C1}6D8jB9%$w|G0mKD%TI8fr z5M9c{Wc3|IUr2g(ITmtqjo3ks&d@QYrR8oMC)Iq04@=WxUu_sP?YX_%Pq@ma8r#4( z-i3-=deRqKyfhV+>!T}RFbwcKQLhTpo8I@UNxmocdE^tAFfEQ;bzvfA;q%-w>25_N z5VqMnG9r3UbqHSy^ydcaAs&?RzC4#Su-LLg(t2a0V12!sTigrm$0e)DZfkP=d?)M) z-}HF7$}J*CueGs~9i?g7FRhu>>z{uEBX3lGA6MLhOTR~$ zYV~f0o>9K=r^nwQb@0&B64ZFDkR70;h}zc_Hw_{dbQa|^pUYsikVjhXa2VECNF54x zu|82y^44*rX2^N2Um>O?KFq_?KjZcjxg65wcJlr_tauWQhWusoD+;*`!|?&<7@TSF z=de5@Pa84zo92TLa75OV$f@wbTcXS(68urUDjc#P2@Cl5b4lh5`izlhyxMawkg@LjlMA*<8b zW*?Q;?=`6DA{HhHCcP+gcy!r|4}K$kz#kkz4-!y8Vm!?scQ(QUyc*Y>wno9Ij#nOj z!n^J3>RJfw5R#38>yCLwRY~Pu>2^Q!F0b4*e!46TuML3nmpZSzDlfaX!J0r>N(_11 zX+fW~Gs2u3%&e>}M@a5bZ{0E4o&&cBx|Qf?5?OdH1lFv`mE^wJu#sK)#tsjR*U>3x zsqw*>q=>^Ic;C0A2&37>aZe@%i4D-Y5&LWJqMl#eGU{(;GNncpEn|GN4kH~$59CKp zY}m-DZ&!>!I(qLu|Gf2~8m8F4=`H=!rI<$kH1Bq&>Yp77+E~e6NFu2JruEC5B2;b+ z^0z>MTVA1wo5A(q|_e4TY3lCP_hZr&eDFOhbk$?Jm^yPb2#jR z7v;S@qjE~Jo33~E!Sr4pmubsoSwX&bRY_am0m@m~Ukx`ukf>AtR6r!hS&-DGDY7>3 zG~ZvgRUD~Z7}C@E>$8X=M4QNv@@?!D{Yt#uI_js?kz!M9`$;}*Ds4Js9F7RL?|mSM zD_-Yqp5*XkDX{1_E%RtJpSt;UpO^t(Cm+HGY(m&dOZba4_fi4bXMtsmhST1h+*`bAsUlVG{^V0&Uf| zL5jU5#wfh1!O(( zQsWEi=8a4}Dwiv&te43CyPz(_DNy)%_JZ~6inkj#mW)bx>m6a}@+P|aIBUTFA-?4o zLuh{6zdSxL+6B|igk`x6F*7MRC!C+gyld*Xj$x_t$UaNZgCm4ck52M)DQ1)r`EZ~U zzQP0B@Emm&;?qGXrxE^{oUqKZ;T!$MfC_s_TbUkKN&bNHwHjFy!)1XhWxcam?-*yZ zW&`nthReBlgVjN=m;x6}dUIt!5X}+GRBUTv7#Tl2&Zk;$$q4t3RWr)3!lt~pvWv>7D8(+fwVw_mSp!jL;mwhrA; z|AMn`#VIt;+jpG4imvAF0l&5~mNy#TVUCNQs8=Op+vav@YBPhxU6D@7`0iFHJ}qD+ zI=vt-n!y?oC!IiwlXmpG2ap9xb;gvG9iI22Baykey-Ti z^+wH!WbhyZ{v__&D&ApbFna+^qznyyXxtPm1yt{4<)E{)tnKD_cuP^ud}`k-=l4{( z4tY})W%%oH&RX-Gx?RrwGRFfEyhk^#Kd&4UN*3PfAF)&x^{d4UQ#Iz9UHF)fjTFlc zZVk~XJQQ78cV$mzA@sOqnI$BA6{$ptP6Z9syd=>!hYzMU7zU`wRW*auYEu*&C7 zosl^Ey<1Wd7|K^=81?U!@*mQ`L}DvmT~wmqtiB>y@1Y>XBjss0@@9M-hWn44kL5%w z;u&7pE(s@yfC*KZsI%=_i8;85wT{!iK&Q+2f%nB5YY)cg;O=~X*nDDtG)@*@f2Rc9 zl|0;%OR72ue#eKWTL?qoM3SRBkS)G`4wfP`PQj=ZT^f72*2`V=RiI0LqPH06Pp2j< z8fmZ0?eST}&tx85*_Sb4{kR0}Y)k!ZCeQ%ERddho9F%F`T*V=v}-I4Tl zS1PkDuG+h06#P5SsgiSFQ$WG^G} zKX~_jYp z-oGIOjDO8`Mt~&F`QN`V1I95E{j+7|U6XX28qe`Pl%s zv9bRh^!LXAbDoU}FvY*N|M@wx{Bsh(ssUL73`~GKSOI$iWE^n*Ek|Hw0oePjf0GCP zwtzJQmc>ED0$Acd%Nqdi7{K@kJb6IL0yAI{fSLtB4Fh0%f2IGw^$V>3sJdVU1Rwym z&CKw3`oC}Ke^YMo&to|L<4_jHe?6(=Kgtc5|JB!LWMlic;)8!ZdV`&jnf?F3*LMY1 zn)hDkpCgVZ5tjigT%|g>OoSNih4{5H#Ku*KThyM27H30E4h{w_7@HU?FL>hfyZPyk z=jrY%=dR22$f~=%div>AYx@p&I14i59R?`~UkM#}_&N~GFCK^-A0HkG2?z`Z7RX; zh|%L__za}Sagai~f*#c~6v*4lpjv~!wCj4N=T{cM2lPwi8Io{~09@E$2E;7&jQ&?Z z_ncmgIyi!YP)n=eE*8s4^=G0!RSECohBw$3+%kCdb->#PEoaXTQm8Hi5rMd%A;-if zXj$I-Fl0H&NAnbN1aKJ0;1z6SBuMThP)T!V!cH}aD4+PTE$MLzP9$*;Vz>YZUJXMo zFaspjW9R}R{9_OZ0~Ml~-?lH#Cv{wa01(s!0ccGiSKm(I*HpB!F#czJ?VVU}2QY@f z_YVP}o$BfC?1~z=K%$*0zAu+AUIW2|P_7U}G`BB-&lCj(ni9)j&{ah@;vz_aNsJJ3&cAxwXA z7POuR+fPjp5&y>(`k60xSf9}MuaPgB@vpJ3uS@a8{>6vptTX!1uVDn2z}DCIn;w)k z&_Hbjd@vW0ov#ZEm=DVW=Uk-J&~;x;RtCNEc&Z-!+8;-d;ZQ&#pL6{)Wem1d2f%QK zSNE7{pV<&iAvA#RU48=nKH5AhR7BU^Rx6wJuDv>RX6F;1O#ZVgA_MOPSM=Bs+Ks-C zc_7VV0zMaou_ahQzl8j~#cLCLB=dpzkzCw~<*&9gA)#P;kg=?wfFe18cKih5K5-gK zzyy%mS8R54Pq%T1i3DcAfBpC@dJ$vvL_~vGpR`TZ<9^Zn^u`s)+miR3OQR0zR7!QU zR$I4k1S!D$S_@<8l^v>0L;4brV`VH>HQq4c9A#iPRVmkUE`}_$xY#HyKlaH46l@Lgp$U21=M7W5AwWsjAkdiUe)A^9QPw9~hMq^GE zPSiVF;nN_A>zaM#rQGkuoOKn~mY;2x+^fYL1O8pF*$j%rM`q~E^5DT|jIna=aTRVd zA9bT*W(k+lsjnHqDLHA{ETsL7UM7_7!^u;;4RfsDMc?{bo}J>2=x9{BAz17hhCR7{ z>@;na%NA%T?-q^kZo$|=c`prLrgOWFp!1o3Ga}C3T`(cjWTHe~!Z8vh|1NzAJzm1n zMZ9udlvA?uJ~OR)aJ#A_7D{qd;i>$cC!1@^wbW*czx?>*1VQ}Ty3^Z4CNsV|W&JkK zH|eP^$)y`NpJS)UHY4M>xyZb1*d9s($a3qhaw@gP&BK4mtSKc&#Umd z%rfj8n!O?rf-V*myKLk248pVXHD7_Hc2RP!212NNMbv3w#p$Rb2l(~8*Pe$oflxU= zQd`9F7{deQ$gIXbGPOlKr(0cG_rO0U zbER4D<=rYf^R#q*nunJbGx$@4>t7Ckq^(9Ehs0pc_7%uwx1e3C53iCNU%VnTA_b0y z^odxZL8~^IL6sa$y^6{Ta(5WkE1@n^b)~Z{z`&CrbB>vE(&yiBbr?h97cZX4(yCSd zQbN$>HpPY;0E4;Bj;pMivj(nXqB_zZRP~M9-mCxAH06(_Keh-4Zj zDuUYN2l`H@)=rhU>zzG zB#dYECeuQitCx@;PQyX8oS6_#3e_=1cB*1w`?xsLsYS0F`N>m)%dnikPt}`gLz{j& zIBEMDWUk|M9Z+&()2qoVJZO!=*S0|5?Uq2fMZ7z~-VRQO%l=>s;R+d9lWH|mB`E7g zY@H2k1`iRO7_LY;;Kn@&i(A(3`zhVn8_`J%Gci-ooc#F_c;;qkMc;VNzHBWn@nk%` zosCO8WEA0+YL>o@koAfNKDi+>hg4^Z6T{#y6<`tQAo37Q03$Vb#Kwpqo>3n4;vZdo zF2jOVb~DgoCC_CwJez7KE-!!V)q3d?6r02g*WpD~=Sp7R|BjIKGB$stn3TXeZRuQ@ zhT}W_5%XtOhXuabxd}G-#SO>9fJX!rY%G#o(nk5HKHPu(wA4mmlD!@T<$53+7Thct zqYhX}`|pazjproBZvJE~5>@T@jP z@5j9!vNn=wk?R(Q1e8CFMydBF#=78M9TY{kC)ttZW@MIOXw?=@PxZ^8$VwiF9`7q~ zFm5xgX;?qf^oN%W;opbJU~cVKB_5`@X969?pzLddC4A#7|AAQ5jZe>Q{(K!r))L~Y zu)cAi-@2)aT+b7!pF3Q`oK-PaC}k~wfnUExcM%jlwEz1feCT8`bd?4uOMF?8)VUb= z`MF5W1#zLJ`sx%9zsiq41vL-~(**yf*#KNg-MFfX`Lzjb`b@>4cuQ8{O%E>KHVg?V zu_x)2aK5F9wd^#bPiGF<=v_e`7IWHpO>kn}yVNgjAhcnLCYR!ewsuW)=>C0zcA1pJ zVyk-;V&9v0f#czm(^a2F|05iaR1SpAGi~bVpU(EFt#nx;Z4&SaevMyl)YI{OprQv8#KI>^;vZU4hXl%QmwiF4qO5Lpc0L zV6#)ww`F)|1pXcuzS!xp;;r0MT;2$c_O3_aRMWMWDs$JW+vI1_?{Cx4Upels=}Lwe zkfDa@^tQHB7L-z}JS4%#zs)Ub*qe%-GZ5{(3x7K@+imA^ep_hBm4k6g%^yhEk@6%~ zd3s5PKW?xinSm8}w0Pr8ASU$3I}X>PVqD!y>@&K`kD*Z=iFj;GR+uOUQR%?n2Rpse zWfyP5(rFouxtqx%$C{NS^ZIGtOUt(Cc#tEL;ejuvP}vo(^}8Ebh0;i$wCSF<%}tn^ zgRd8*c+W~`Cj~ZQ3lu&SXR$EdO!rshYpTV|8${GqW#QH9G@C(KL?$|M#x4a@QWtYy zy|$=gy1(@qMk79a3Sp2nJr68hoSjn1jWa&#{O!50KRwHz_tdC~Uz4XPjY3_mgg#^; z==(q7C2=G41>mcA@0zO5>y`}dZZ+*$nofpNty>%kO)h2D1gMp5una~bqb@|cyA(B& zW8ekvBYr-5TGDi%DUF1gdpXUPYxccw`C;YaztIloO?zsKr_sV-UW+C;>GJXhjXz{WiGCB&^=cKRN4-ikhj@+kR|lq%4sHiKr~He>50$ zV6xWgO%0-tpNw#V^eYWEpCV!%>bOCU4aJ&)vBs57Z^${#Sxlc$7N(5vRvT+rwPy$4P79>xe2zuXrfyoC5b)@$Ev!R0Fj&`roiu?UZ;Zzk9BsS0 zD<^#V{wf9B5Y`o`;6nYKK<06Mt;&T%3MPJctIu8SiR}1vt|ch&Na@$??Y>UI-mAl{ zRsQ|X(pn&g3t9Hvcy3jfOtpimloEb zvLySPcsNJk(;IiONpV`}WQw>8&=I1f9kmE=yQF)3nMVgM!qZ-5Fo}Ku%tU@K&iC~s z{E^)Yha(|sMJ92ByU0nXuX3OifeXeL`t5I9v52Lk_iEjCuPuWYKa(~=NRgW}#Cej% zG`G1PRoYR+e-Rb06fbi}jCf$ZZMIs7BrTa$UGQ=ea=TI9H}(ELRcsKJ^wyshlWHdN z#6-#uas5EHKe&D+@tLtqsuXX}QsXO*zv=8o!Rd%fh`K))kY! zv#~dkse58e+U<(pgliHR{5xK&PZp@sY@k)?-oj@%c5ff^{(a`8yS*0#1wJ92c{ z4lU8olZ{xAyC3syB?8zQb^T>I3X<9-OdXvnQ;qdqOWDaD4=6{1H?yDkRQ9{SX?@_1 zZ^U}n13toC=8#KA9Wm)l11xbvyK%+2Phq&^i^f6PID6qh5Gu2z@9k8SRwQjP|Np79Pape3x`D@@~@ZDx1rU z@seC}$d@3e$Fr=gfflj1qf87!*C1|WbRsp|Xi&|CLvbr~fmRw-BOvaj z)`*3yWWyNt>@PEv9^0&@L||9#6nB^441V8JEA*TkAGWX`V=_gcJ-B@Q_(>>#Bsvx2=zCs?Tps)() zcIgU-*mS!t_z(8Ct9VSYJyRW<2aQ;z-w8hAbx$qV=8SAmF6wUGy?7rb}d0wIl^s z8-7==a>9d__;Za;efR z9<3Z#TeUGFMuhAXG};4Z90d_fwt1|cTMJ>!yMp9!h2u@kz2=nt+n;gY;_-C?Tip$v zzCA7&jlOK6Z!+OPX3Q3)e>An*Dgp|jI$Sa0*-)=NIwXD!gPCNFU7|F9D`&PkoCbol zyTAp}ZJsg5(A5n$+k&P`b{hVDhHG~_n_k_mloZd_J?2a3L$Gr3btf`UGD?O%*%e1r zc9$R2Xd#w2Y*Sv@UGr(R*ci~i=t`Ihj_|`*Ld7SykS5=FmE+4%TlVl05%l?4;oJIB z-T3Cq`v;kOe}JN|4AW(~x3iR&sL&cvSE9X~A*ZqVWo}*retG_RWd2oYwM)V`K6XV1i$7OpRX%>n~ajRN6$v15taiNBZ|Jn$XYoc*V@syb?X)=$qdF8o*eFD zjJYjiG(VyYOvU?tuT{TFYLzVR*paEmSx!)kl!wA9_O*~`IyaQ*rQEkheR>UM>@BC% zj+7g`4^to1s-Q;gh!~bIs&nhOD#&D-mpCxdFmPlarNi(_`g1iXQ>5Si zv!MzI_fUAXJXQuz9p&^yd?T zTj+_~CHrMb%o^UA)YW_-&#Z?aZJy}zDPOA>l1yl7p4|Kb;c}3WmUP_H@`g9uP|=%u za_6YgNbf-D{5h(wS(Q?vkb!I6oEFNoRQ`^$VtMR+34YH#6Juzh zyogoO>LMCCwG5Smdj+$ZozskJtE6-#dQ{>6JOFyW&l86MB(UH^}T*;ASI|OB|e_XsqC% zUU150EjA{|yGUd>ra=?z!0+MiolwOD-a4sjKWM`>6vr5SHc4_FJ%Knbb*(t~#^P68 zX|^@k{Bu>9Up9NYYy1;t8DUJ!WI8s?w-CI+#sxF$F3__}FgfB!Zz*YE*U(VC_>Z7s z>kj^#`Nq>VuIb;ut~`OczQLFRL{D>Fk>sRQOKmaCntyp zQ$({;B;Ge2+Y?gvSw!nIb=^`X*qDj_+Oa-@cOs!U>UTexq`rF3cqnqGfcL6U9VW~Y z3XYD}SbYLP=vED~;}qj>>Z(D7@)cyQak(o$aX|73s;wUg(FkOM?bbitva71Mw_8S? zWu3_4zf0z5m}=v+Az=uW*Q*7G8Bky-@7E@In&y@%igqpFJH6h0Iz$jy#Ve=bWdFT#YU-%*WOwKhU6h{^p_aP@R&Clv8d$BG=rKKSj5$+r|$g z?kf1M9)ckMz#y<*tC9DmOshR12pdsXVR}skV`1_&8I)FYu^IM z%DsrThWg3;uBgW{Lka2<_}sJre=3B)8@rq~3$Mvslj~&ku;@EEB8hT5t1U_fB}TbD za-M6L2VCN<^Xw+rBYHia37hq}am8AhoM%|I;$A1HUUkYfz$Q^`pCam*(Q7-a*nAcD zv?Wel2w9v>P=CIk9R50Q)5zfgWL5pb=P|j=^wq_4FE=f8Yu{!a9MF93p=y4AB@S)M zy0RAH7Tyl`Fb^{7gY0*4(_5iUP5A-^&O$V;WlypR)HQMJ3S^azSr+v`IeC4tcAU7? z9H>0FF}?oNEDuX`kj9t9NiC>s!0!ODNv69whU|Lg=ofhClx!%bd>~eVPln8ddre7c z25nGI-D@*5+Gcn)MuJHPPwY|Vv!Bcd_B6m=ATs%$&U4qvQ=3+eglH~TD}pc-t2Ts7 z<#O?e?~#t0?l~rjH=TqrtySfo>9HaIXWeu!@Jad7m@A{PF}kL zB>&!C1I8A68OH+q^-nS?*3sIUty``M+9Mw-CiIH^!pmIMIp~Qw4;&8?Isq41Bf%&g z9W0D}PRJjX?5JL9tF-rIuU-wk9@%)eL+=C2XjzTsD;;k9gS4?_*ua)jS&CS$$EKO2D5LO)qc(?q^y3#lLg=mnB_;&p7)6jArN&J2*Bxd6D2c+^ezd zlrOh@_`bC673x*UGR}roI&>;QfGe@pBw_3iBR{}ZkMi%I_zt^e=C{{MHh{=e?^-*Nrl==*=i z^{jvdfPa(eS=s-Ac>j?-&jz5zfNXY70BZ(h)C0&dJAmFZ0@yKtLjSW50E1Z=0DPF0 zlNCUZ0Wv!P60`k->9YZ3cvb+N{>#HzIscC5VB+{on*sMT1IRUC^gpuV85sap{(ouy zRlEN`754va+`ruW-=OIKdawZFzn(1cA1IpP-^1bo8{}m8Z_Rf$4pz4R0~GBBsib%| z#|8pI(&-8^X9;xD`LrcsAx?yZLY5bJ|E*I(ELI1skW{2}F2f0&T9O_x@EDUf+w-dR zt9$9GvZAqmJI&N&>nO|ArH+j|(x0(ApR^CSBE+xYIT+0ECy=qWp%gI@5EL3R5J>RN z>Z(jG71pyYH(xvU3MjNlPthl6-Z^lSSf2H_M=BP1OkhYe_dXyY5+GtmYGQk8A|xU> zFv(B&A8z8nO6Q%q(Lmb3ei$GKqI>l;q#NG6xw2DKPFdZyz*{9^rPy5~N^Ka-$fzVNLOL5MdtE_S=*TTlT{z#sV4 zf(wL-5RI^h;PM&P3{jY5=H^l7Q9iX36zAIW>=B4nMA(lveV5QjJQi{RKNw9wNWYr{ z=2J3|&qTSUfT?d19!`w-#`i)F{1g}>Z+cVpTFy~>7s|HfYnuiN?Goxmqf4#1h0F zn6Ts=B%tTByJ~LBhCV!GyVR@h-EPhAB_{g%7R9}9p|{OE zP*6a_0BjuOEA2>^@|yi^TLskfIA`-iOjL#g3^?{Z672Qv zA-fl-%6I&WSRM^ZNH^$nTKJm#;OqB?uKK6y%hyx%0*`*pwog?z&{xd%7Cg+|N1(vj zDr#^xyf&DJ(9Rb;E94jJOq-rq$?tVvPgaG;V{C;W?mXuydM8~Vw=a5bv{Hx%U~U`% z1)`(whI?1$8CE@cjujyPpihs>+ycLzuiHE^#DfT*CZbu|w+oO0%Cj727RuWc z^e@6R!E6G8qzC@okxdq9d%4ub);PC)mo~WGcO+*7 z#Y%XC8t^*NpuiW99hSAp4KEtrtNX+05F@v9cIRW31n&6l-Kzb;de}~Gfid7BHqL>I zY&4(Qv)Y!uRYdXr9lsPirVOi0$CF^zdORyNhXd6}DK^IXx=c#@)j!~%kIXVZ4az1J{9?mraqtNvL@&t^3PiRC+YbcQo95!XAUUw%>tlRyi?DE__(xdLv%Et=sFPX;)MH_GRiT-L-bRb%cR5>tLYND&eNic@JAWuQm<~P`vL-j| zN^X8Ucckosx_j~l<}T$D9)pyVDaq`$r}&S&#ROoy8rXWHBX2&0#ymAuOcKtP2c0(U z{?OdgrR9#YBB!mB&cvs!W02=vYDM0vLAPnwoLBLm5q}!S%zsQPF2Y(nJiojygm()j z>fq^SS~fIc8B>wrrsf^7kjm`kd7FxBii0*(d6Rfx5D!J0A5lLBPtfSRX{Q?116 z415=FqxP{X_mn#T8iW-MW@*)*Y6IDy>g60Wnysy$P7n#%;$p@ zhu*%@CXM5Kl$YD(-$$=Ccb6{whCB;t0~OvDU5vV>oo|OGe}P)SCkUEzWlDb{n4n#q zXspkzyl6ccmBD!{l1-)o$&c?0ymF)ADdtql`Zy1HrVI%XMZZ8yn1_Ly{Op$-dFpu_ zQmaXd#0MeSqdEG?ze0N31q~L_qUupF9SpEv2mgB?xXYxF`hL)`T~W<|CWy z^SIa>%ikvnc7qgbNjg`R0Tuhz%He71R$zC0Q0YUQr!7P}9LKYO#|=_B8B)Rlo7HjG=g~+9}JGZu?3u={Yx^w8l<}rQc((ntowT2kzC*b(^nC7 z9XM}OtjwUm_Tn6l4c7a7{J!!s4{#Tbc$;$L3Ee>dj*wUwY{N1~W4+MZx%&X;TvE2H zrB-WyRBh{{EF-(8Ds8ulHW<%~$M;KuUw2WT#cQ+Q!yKq3E_5Ay#nDTMT@VqeW(MVe zkFZ1v2_jr*@_ZEwJ1XAgYW-$LI^&^@p=Y0a{3J^UOzpk+C8mpjzqe*H6c`qyye&B)|c)eT+X$~53<|@#>!zo$J=H% zB5`9Ip`=9_o9mc!3*Umb(=Jvj8^?a;q={kEtBk#3oUwM9vZVTSZ=UK}${e_z*>5vc z(EH5$+`(SKV{-HrC;Cf^mrR94%EsO65TPn(_apdNsK+d88+;GYijKS`73}%}$wvdY z9H*6KWS)z*+nh@YOEaQ;IKtYsL%3tMyftn4xflubq8xXnm8`L!7V?fS`T~Vc7;W&D zksCOG0#O3LNDFPdT0)LdG6jQwbKmtSOm_KoY`Z{~8SkJ!CU&@7o59VL1zjz2=PY@U z*N4|7Eb~AHRVU%{HFonDfY)InE3F0Z!3)Na^;=f{87kx!Q< z{mM?U(7AgNA=^xucS8uL*`?XpjQ&t@sMz&>e(?LJ2-<<}i0Cah-__-O02Bgpq&jzCtekv)T|N?gTjE3J0ZTKdt0%vrVfaNo%2 zVhj%n73+q-L#YN5>(fcbbnSlMr{#?n-U1XnZpw*vC#n=>vS3CJoT;BaA`ifEO6 z``bmm$w^A=XL|*;?ZI~Fyh2AUPc(x@=(p$NAS4#k)Ye?I0X$E3rFvH^dJIMCk-sSJ z1QoY-td!p=Cizt9j6Jg7&*s=+g+vV8pd?5e@DUBTnxDN;6?QvYjlnn@O58n!e~#XD~UuQ*pCmD;a9;cLVcq z=Cp3mTFl1@uV*ARRx)&p7dE*#)*BQ6QT5c3b0zbSA9mUNzSeu=uhYkH`W+h(_t%<~ zQL6TeV>r&}{1V3}x;ymb=zBTSYWet+h9ma{5TKoDW!QX}LSG!%J0(-b`5M_NeI4HC z>Evl+2&`EiC?u8?!awBDJ&jn1Wwgl5rKO7piMWcONKsOPYmNzsVw4+czp`#X2dawR z*#|Q1*tjJK);H6e;b47D5~3~_Djd}Q{uCLT(>&4%Vrb1ampmE{(Xut0onCkZQ zG`{%tXH&JfbiZ&+AP*G`KHbHoT;}aK^5fUwG&8$31Lp%Nb%Xf#?eN4kA)koC*Nf|U z!!=&cFQ?`l(8oRE4kRGIAgcoxkp=bfvK<-6vM8e>zw`5k1OX#6^KD+$QX9I5NJnL; zT?lKpgU2B>u|@|nN^0)0XF`xBXY$8$JJWWqsh?ZTY5$`t4ffZG+J4r^@X=3_i^jD2 z;b)`lK@OGkwZjei?vyt7?7(NU)(+yMtS_J$bhlT6+BSreW!Gb=;Sem$Z zVX84*gRXE8+);C@r}&bJciJ``jnuGzP77u7Hyu2WYts4IH0M7CISk{RsUj48qvkEG zCemP&Jg!g1kI%=Ay?knt5kJsC%&0ociQS4Kt+MlM>FwXOh;Ba1I2a~tpVi9uPAbtX zLz?Wx`Cb+@q)KMcB;|3P%A~|}H@;Jqh@{SfZ{je!2fow}i?eoT_DHB0HnL)n_MPkX zK!4+A<(h9!czp*Ygq$D83Du5Ky+Voydoxcz3Bt>C^RGrFbNCnn*)J=5#CA7pJDz#O zSQIQrdyVzPXBS2m4aAbEz>oTAKACX@SduB-DbKibvdL?4)$>bHv7K2k3}SMdbm)7K zN$|bUIdZFbugLL%3`*%!$&01%HF8YQM)XY=V3zjHN~AO?#M4w=zIswUJjaH3kXU8G z2Te%%VUS^qxiFFfjfINy$ewhns(7c)T~9}84R}RA5UwP%Wi*C%cqdm}k(U&nRaaYc zcq<67?iB#iL?5s3{W@BbA#g{VVuy=`+5Q8T{XM2Q8vPvBE)noa()sDe^gF0nCVRQU zi>ZrI*Qroq+q(#M1oehMrLoMP~B! za7)J4t0cQw4z04bVyqkL3LQ%}yq`^nlSXkxo7UFawQ|LDDZGl!vI7&lGSbD8|EPr? zrmewA#P|;()iwKJ@|M?QO?~-nCW^_()H*nG2X6rf>tJ511RvZ)fY{1YpccN+a|whD zm0esXUi{WDQccs=bpzg&k;9MXR@!fbx3|Gps4b)m8~NkLdE`RvNihVXv=*x6BAXBj zx{}Q>vIaaEWLnjQ#AF&>INw&Yo2R5>E2%M7kg_%{C)5N(h$ems(F0mA*@hB zk#5&z*CbU}jy`9OUuRG3X7^klA!0l z_8P3ICY?7;Fed$ejgvHx_hXa6o=C_W^Pqgnaph zBSOX(guh`rmkNogmY8a4(1#2#CFAneXpYIjJX^S7UW)e9kq5~lv@1MVt1|W<<3gkB ziG{hM4j@V;EYG8dJTkxey6heJ2!76}_4KHst5-^ts8P)o)mDeeeQzfO5k4pQqMurw zdhm}+*`xx$`RTP9G2?hQ9|F@4IE0n878BASxX@EPa_+osgRP&OAeLfj;JcDx4gYXQ zyOv@mf~OzEs{@cMPvnRQTF3H?w$Bt|Um*u+&Gl$)D%1%{R>P-Q$Y+729yRiq7~#&s z)-o)@eyTn?9}FrG)3Y!Ilins0z81^y%kLUjUoIsBXQd#9vWPZisATJkHZrCI|8X;( zGsa_qbYbr(C~GDr-U$%b5bdX9Ucv>3fp3GL=uk`Ytei(p`DMq{V^2j^emaO%S9%2P z;Wnx&o+Kf;Mrfe^Y_Dyj#t*)CS|6E7f`}g$PdM5xBJ)CQ05xP5cP&abRza@qQ`r(0 zkaC1ZvbSU7g?O@@OoArl;j;Tn?7QL(WE@e1oo1aRIW>+o8U2JOwF}{|qJTqf8>?r|bIg>@YOuWv`?%*o|ECkYIUYt2N?EQBc!A`qd;&nJRFaxF>Sz6;MWP%d#cchX=Gw1Ltl*KqsRQ3L zFXSBDt$0ROL*+Gj4UMxiX9-r%e{}5F#?R4_rE4SY#;? z;UV&Sf?oopHgi#4!ySO1?c|NFV87Q@b~B_gBz%tkZlUpTHXLv@x+Y8euBtdn*Iyh* zUuPLt_1|`Kvqo-Jx(SKesq3QsoMtSlbWnCo-xNPeIP*F&P$4r2RKF0Pwu0>+socvb zFS9p@1Du+7ULE`b(cW33NlP)8s)XfrU|kl;)16dRekv(;q`s?AV%_Vm8zH61Q6rNP z889TD0q<@`rjf!@Q=rJL@0+HgY0_4?n#97m1J!DnJMLhJ9;~@L%e$HUg>r7 zr(w$R3hL&CB1jwNj4#$_xGu6LKEM?;GH8IL?(4OgUudzTz>(8?g#YqLdS+@X1dYoe zHAjshfSQ#HE(DlV?J!xW8yNGT%!4C)W3pScU@v=W|HWob#AtM}WpYl@5< zGIwQLIZ6g~DuoXhMn;pcsZ|WJ>EgkfyV?9UKx(|?JKHiPjYU7B)JvSxhSl$0#Vf~) zG?AmQlml=sT*aL~DGWK|;@Yr6F;;Ff&8Xk0H>hCuO_ChjSwaqOAk77iwoAW)jiWsy zTa?1x(z~3i3!hRSx3QspF!RE`VPGrvfD%26C2XYk9YP(z zzJFuzL{zFV$F4&l1GFJ zJm45|_1)sVB+QLhM{=4$*$ihH-}Q)y^Ov69EZDcc=bJ4NC$ia;8iew@up?tc87QBm zHPcK##6J*oB$(A9mkQGIl87!^iRBRlne8iIcB=d-s*bAch=1~!{s9d75(@g?i7WlT zZZ7}dh^w%ws*NHs*g!kN<6lvam4yWq1G2^!Q)=`u}5k{9iiK zjDJ7(-w;+bKUwR)qSn8!|6kJjZ-Vdtol*YV zo&67|@~;Z@e=?iux-2Ur>;HsNI)XE1UM)A{%z2;& zz;B&)ygBSDE}} zl@>Q%IvzI{dU}g{_;H0p!v+*o@z(BsdfPekmxFJD90O5{)p9Uj( zbpCjpxwfgVKm4S4czB0hQV4;a;O2dL08TQf0674@GOC#}f`7-YZ-M>ve*pF%?0gAE ze?ftn-T^G`(T0M9#y;p%DhfOVRCgER>2)Fxu0_N>03N=#s}Iy1+|O+@#I?T{9%Q$homWQ+>2?tY z=;K%A8>;WGTNeiaPfpLjeOZ^s8$sFC9NpL~?9C+@kcXgtEP!WOREXWO`af{<;A5Zw zeZ4(?c&Ko%UYw)9K%4;Awt>Gju|Z^$7eIZl(Z8o=24Df51l(_3d9}P94!^RFyQjoy zYk@YGegg@(?|ydY5Fi8Ab=-8&-0TcE1^0F7eg9-$=F!%E*?RK+_b!93*`1-Zo=sL$N(ckG=*&b z?7e#UcH#jL^&=sk{`6q~xb^QH0Q=@Si~3Rx0zwVExjcI?41U);8q5!JovYZmqvwd%Vm=XS?_hbz!N0%n26-(9eMZFL>jeqkX96cobS?u7QI1 z9CvYMcW|))Sa9KAb-F#K*4TD@6gjU=o<>01QWkxZ75&%x`g)p1e0W^ofdKD^+Hk+V z#2|KOTxjHJ2Tx|KfnD8nZ4bR5cC$6{dU2wA-?-%H@BwJhqB~XYy8694Y`+P+vPgjJ zZeAMzUYdT`e&*Of_JQjL($f4l!~!{%0$Vaw#^&4|Y@j8iYAw-98XP`m@VMQy5jjPT zYCIn-A??Uh)_24hdx{602{a8D?dYhgky6U2gGi?fxy9nPr?3=hA z;m%rN3|WA!H-RJhv*t2nHx||GH@So$9q&bFx;m6R%{|1A!3ay39a$)Xm~3k#hT9Hc zax?-_yp6`1rqT=b`}yq`3>;#y-r>Eu*s}24IP6DqzvGceY6*}gbG<{3?V?rmd_Ge+jhp@Czs#f*7B>j#Yd=l}yO2nkqscLVp2_0(N3<2u z3oveo;5 z-Tcs69zck?^AS&@_Ap((pDKnsHZf6%zP-DU=ZB@4$JCE~x+`r<{DDw;;7EDE4|3Rt)94vQ)>A7ERwKRY`9--}k*__%{oVct5<8*CXB6 z$`M>B*PS-W5&cy0+6Roz*itiji@W*X6shHVou5hciqWgUu?sLB$Zbi~j&T!ism4I} z4N56rydb8rZQ&Aq`0wDm+m+w7CL`5xqFeVZ7YI1g+wiXl`4~nFxC~;#m~lS*PMDh1 zVyJZe;C(`R$mmn>H(Pz89`W}QOF+gHl^VlS20K_mFxpPXqXS38zJzrd`MnjpGQfs> zC9VD2;1U5m8E5I*U6Q3BDTgq%1__^M{R~rq#+r7D(ceiCPKO|ofp{iy@xi=WTVj?v z=FSxS>URj5lwzBKMY)4|j2?&7V%0vLjZ_z-@jV(hA0=lU10$T%77|fZ{NiCTfvGdi zATJeMC2CIXH8}-yco{7w6RPH@JKM-JAE6$*mW*Lrj2^CLL3V3jds^B_0@tp5wKjErBfI`O0*`Bw z+rnF}3)Ax3k6VH7Mz_jUW)w;3=EZ}RX?$iT#c+w1P9`tYvS~}AFEL1(%!RN`a>!Wb z5@n8itrR)Mii9PU@;ttd;=<*UA)WYh>#@2T(JR%zUWwIFG!whUu3|0-2;c>th&CBF zn`r8fnj;92ctvOrXc8ogAQMhblcl3;dynQPqF^RwfruvI!synp*WdG&XHWw`e7IP6 ziRDVKe4%B}=pq)xdYE6|m(_+#4||G3fhSFxQ|Thl(wSs5FW~AtOah(Zx8HLLKp)9dk=TTc6w zT`*JTXPIjx{P=`VW$xW38;5IT0w3IeALq;9dXwyQ7Z2l(RVv_u_K8{mlu{y3`rEMbQW^mhkFJvig9mw(S>*N@j-kDBgQXPKYEFp2?sG zCn1YZ69Qu9B_;^UZ5-0AWIK>>8bNr@taV9*cRe+&&}2%zD&~2V!jxk}tWgrnYLkMI zOhyCzYLH82I|*)47;MK8fIOD8TFV9B>m%<76!+FQO>9R?fR@X4r!{9R0lr2B9HF^b zvX8$Yw{{^C=4#WfW~Q(Hq_^dD{o1sPMYHx$6Hra2%=kHLdrUMp5>*@7UK--N%cPLB zjHNk<=Qy_{JPGey%_N0{X}a`)^G4l9nHK{=)yNgG=yO@R@p}EU5+1pxS8#b;gp(G{ zsrYW{oZNUF6uVVKRwrmk-hyF5lKD@BL@Kfq5?kH^#!h|O5qmPh!S3@kd=g= zs(GUpwtb&uN`wbMGAdD-T-T~^`s7Ub+LgZ79gUsRJ2>1JBGBlbQuuCcEza;PXXDWT zl-$L*PC>FJ2QDE0NgfY5SuO_;vs0Eku7a0GeVeJMcr}B3T=Ac2@(~7D-k>QUOD`nFA7ske_keF-Y5QoT>A?J+zoUYWSQPAGy}Jrd zFUpOt;d}EGk{v`+tF((Azy-ZDT?9)>LqZ?g2=s?mrw61WMmFvUIUm13%HYqd0=oK;QqFmHN`fbaCb8dsD=}rsNS%)`7V^OnNEOX3 zcGvJ#ruW^uU!fpvYQ?-cf2-~QcZ5XAmQ^e1Zf$>?kj!I&=+_;g+23E4%8mj|Ai7H^ z+8=);JUC;do7=|Y3^^u>=QXw2%AMjQ5{@b=@V7FOt>)R?L`8p%9FT*dZJG%20`oe~ zyBR*VE^*Fu9=u5jws+-$H0@exdP*@jQ70=b$juwMUQMV{h8&ZEg)|bs?sIYz{_4Vq zQS*o}kmR#_;M`cD1o#^9L~P9AxusVo)U`K@nNAVPUf zEo3(9gz%ic8i3g4B`xvRK#s4XtjgiHI8nnlqF$6)1Z1n@*T53LP42{eN zKaN7hG1|=S>l*vGARS5Fqukp@X9qy3Uh`*5bN~-ZETx%mwrW|%ebSLLaT$Ie7sp{i zY9|@8YDB%gCYYosDdeDiLBA{BvEV%mVrLt1A(vQ7*$^_J!Ehrem*K<*wp?aVD&p(j z5eW$w+n*Wdf&LuQR5<76sRlt5S+_v}eFbS}0BT&YsR46O<0NY|NgfyFQFgBukIYo5 zhGnccDB^iIj4aZjxJGh-4M#^Ml>T_iS6wx1A;qF-G^ZKtk_UnU(jj%9(4y#~%LS#g z+FS()N8ujg`j5k?wCm{P9`8(n$foSMrH3*VJlw$$#G!ac@)QwGC#wWlEjiQgw45`qiTBE>T2dz4VScNCKNx+nOtx&iW!JnBDNEf1-E1YK z0zwL$0HW@_$!`(CtpO)X++DJrVK~_^H=9Q#1V7;V%)j#|4g+cSl{-w5#E{jPa$vwz zWw!4hQ;vw-{G3ysSmucYq1C{$h-X(A?+%Zwyz#OgfN{y4tl^hKR0S)}_g-M>$V@K1 zS@6rlp;BM4*>0iNXNjFDova@a8Qp2)astG=1@iSi?N}uqP2|LFO90G(&VSz(o;5AC zq-^dqnXCdWoB`XBB)COuV+cr$@x2}FHOiN6>jlv}7BTV#*i6oXP5|(DFXEaa!H9i` zQX)PcAcG0@)E!L8ZQ+m|c_z}165O;e^it7>i^Ns^r2p*xi9axjksmi{{U8i$J{>zo z*p}K4jOp(<7IIA&RNx8S#br0egt_&eGC(~cA1PcEm1u(h`uyX*3je`M_d(@K7@dSZ zN(;s#!{?s9B6SK2qfLhHZCqGz{-)non|jK3UghZGsIAP_K=WC*=*o`660fN8i2wbf zF2;$1i@Gek&YxL!V4si6cOP9LKQZp)CL#HWB9*Lp(TB8D4*{Wp;1_X^A|g{+Hu@y_ zdC8LDxoOVgg`NyI>q}#YItqa7aLE9rG4@LxfvPNm<$xd&=c}OBJ>8^05XOLb`_n%{ zZ~@^;S9=3DobUKD2^9_tKdynC82ylBlu?}crskuRPD*JiF-YM(h#CK8iU-iSl#%+TeAb*v;DXIik z9&@X&u3sffwCd4}DQB2C?nf1GiJprqHfpj8itVI4@oY`@b@`vUw1(KrG!%e{*T%El zG*T-xxb~(^svom%zccDuXoLICNXLyl z?!&Rh!O@#plZ-;q9PA)UJuwiz3iP4$T3Qqps~*OlHhcxk}1=VgJ|fx7lUvPn{4pC%V>PegI>?|N!WB(9N?pZ91I9asBf zgywaVZ;yeA8NT7O~b${huD1sL#vXdGE^wRdFgU~Q5%WlA!@DSDmQv_L>SPwc&$zt4Z3FS zx0_*bv25|6dOi6S=#%uD1T5mPWO_Q-U0qiiE`s{S+njy|jC*}Y4dn+gwU`W~bS)^> z%HvB4eT(C0O4x63_ju3RRiQeP=Z?Arwc>ep7DOj1;-3Bv@GFr6|KdxAqRkyob0UQs zYAOXo#te(BMcKkD+?EU04Wo_NNrt@lOwpl)rYYL;_Ju&2TycaibmDx~uOTs#_UKVJ zdGd!85t>Ilbf#Cc4#%G`RR1_nk=3Nux|6V>zeH1DnRkvr4J#7-j^c)OVUY{j;` z?_{^MFV{6vV@Zydr;VzJi`H6>o*;F@Tl@8gm%|EOA6d2~=PK#X)9Ulo*l1FL(M%O60_D?8G_ZKf`9~!VF4&P(uQ! z&;mO3SnJIZS88qVl-*L;SX2_~x6U^qlS^rbaVZlJBz+>@j#Z_qJJi94nlf!Te-?6- zS#B&kXzQgW4ZGN9JKoD#*W#_lu!G#2s~rqyz72OS)M=dy8wJF+NL^PoE2o-xfvDVZ z<3xRV4I)D>;jSbW-&CW1ATm~9C2%KK$vn=8^gq2**czNUAuaa##vggDeokWUg~=`Z zCT5+)ADo)_4cNri;5IDMmwB0w?$f)ISC_Cv5i=~QXcwXd%|rB zVlt=$oNwOZ4U#~U{P4m_t~5(>s7SWSjOlhcUopdZy{1v$VbAgrTgkAF>M?=u4o2a7K zrFXkl>6j`*j1A1Pu*nLnRg`yQYXPy(@krQ>RXu&Tov+va^?XeYvk_4xUKiYQ?W(-c zoXF}*VvW)1PFtWtO;-|6MhGl_Lr;&V+4j`5o=wqX;plpT(fGMuJRJG+_B?Lt$cuGc z`qQ4-u9aTB?Z%zW0X^9)%K9?Qa-ecRrfD}ioGYlc2Ri&2XP%gYWBUF20Ma$>G&R+6 zhMa%4l?s@%%>q?F)iRUNv>8l1r85XDVi<0XmqR=|3GE!CV=Ih&k#@qC!|@o2JiHSZ z7ZN2`>`P0yo+`cxSy^sX0$ZV;V*HL{U#SJIuyalLR{-D*rWhK*f{3nXPBPAOMf*s2 znxoRh1yZI+UXG~f?L+yg3SYJ+FQZsy9ibkxkpC>85hbp79_7ImDnb~LTG4_f!!C$F zhB`w0TjNlyxx$N{+5+3tx5lJMl~W(dodZWsvU5*NC*Wqi4qy%klFuu{@6QAYU~Edy zI>`@$>2UH#QoM4AVlKAQI=3J?jQIK?CyN-uP+9?1J`5S zG<93AK2bhx?nYIIi*b|CnSu7!$n+_HAKfX-uBAv5eH;;?V@tgxW=B;1gs0BwhCDt; z@Elp)wX3Bj(z<*O6?+?si#MRWHeZzOyKr!27W?oN$HKyc0Kn|Q<(R?>Fn&fVRUY^h7e`i6{2p)S$dfB#pokO=s7zPzTfs>h;%R>M!46R0@xrS2Df zV=8G?CI>)Ipadv^@6br1fe7T5_8rdcTmG7nw4&XuXY{byX$s+gIZzvhy#q=%!;qVD zw9zI^TJBu%Qp(D*`^Qwhd^nNZmY?!PrEH<8@rLA_C5P$vJSYY*ixP!ZAhKy9-7gEC zXL<~(co8*SZ2cQTeVh(qF-dY(b7IiccX_S6YmU-;E@?y)#dXC6Tm@Id6ceTC6_POW zMFrg1$A`$>hi%W4Wsdp<7ZWRS70kFQJFAT+5&|_E;lRztg`KHeky99qVmQ==F1)7I zp>zE_+#}}fTFyVFGWGZ-gTb~+G7Y$DCqlD)4n)@{NaM1E#pU7#f$^{9} zOCNA3_4h<5&iK`zSb0~w?^02 z{U1GKWdxn066p{G>|($pu$@$=X%ZXYB}`!oJC9%*j*RIB3|PEv5eO*q4jdzIpD1e8 z@?YHwa>DrDI7>L$DQx8vUE1%;Z6)Rbz}51 z7t!0M&>e&8M9$6uld2dtN-z3h)#^&^w?Z;GIr9PjnkfY(t39x8WE(t>!Y(l0`V@Ai|(EYom*3Ddv zAs(hpvWb)}(G6gBxQoirAUEt1aqR8LtHR9e2AbF*8Q@|lJGiwzmloEqd6QQiaztLfAP&Bzg(L!}TA`;64!TKFecsZg1I zbkEYJCD3`F$|j@@T0x`I9qfSxc6nEP9>ES8Br)T}Sr)s+pIaWo-)O} z;PRC-<;UZJU#LNx zFIHXPzi;GG=cK6|YQmIGqNuWkUBdZirX{=qlT90L zVTK3y-dI(gDkWP}iueY4mxM2tYK}b2r&9slvsXl!z3u|ZcO0IP2uvpytIQMQ>L(KV z-fXs|IuS9Am7lc}{g5FPd`WVLlqG!FRcw6d&+jj| zP9Rf_U$+YW8G~VDWcZgD3jOUq7Xv_UY+O9-``gne8ifObgs*MDB;d@{^#O-ijncKg zhCr6z=fQ)rrVSmbl0n$Fi&*5x2RzS~2B^gYpd;M`cT7l6sxv}e*(~$r`O~eF1K}9|K%K96G32wvBg(u?uwXX-~(7lBK z^;Zd>n+uT|a?>MjE4J?8+A0d*_csXh32)-!otTlu$U@VLxu*v=8`3tg*{R#?t5XQL z4sWumv-t|S3K;wh@xns@M%o&}G6)0K>conlOI!G16-_daatzkGg`=BW3^{A(hyMd$ z@eQ~O`sv0FK+E%bWA9`9LmtTcEgj68M{0r!F^}rk2;7SxP3s$7|EDJ;2Al@Kzwrw+ zkhQJA`T<`XJ`ic}80EIZ1%g*i8V;bX=#_-er4+M&Xdr6`d+#xV=vF0d!$FyUojf-) zOHUNe#b4)(j9^oDb|c^g^xLT?S~QVm{>BC=ns>e52choC5s+JuK$A<)Jlx0MS_|ao z^->oHKrc46G`AH1;26sHjrYp0r1z+4dk^gR}4*b+e&&KG79){p45}Q}G8;~Ust{2OZ!%r9BbmitI z>F6qUEk9Pe`={4uhhA1gM@nb=@LMPICwhFMz!SjRQ&$fl$CnlY00kfdK+pyi@Q3>G z1>sZZr$q(T|Fxm(r?fOUumC{cr?!==yC>E4iw#TDM?3`c_6ECAu7v>x*!GJM@K-D? zg!>1;PfpM+$I%bVPfz*h4dUxfaw1n&rZ;fwx8NraKqy21*o(~Qm8^&RCY0bWCkmuP zAAu-6pHX$3Bg2m!IwrW$D#^oG=azzLaFl&;$ge$-RtiE--R5=(xY94&fyWTseeVjg zn4Oi!iQujB;~mhXSlPrY8aGIY2mm~5Yj_?1jf$?OKtS(Z4ea%PPj5IHfYBI1x6NVz zYYjMnUO8)!9&1TOG=Rm|qxS(sP=KcIW@{ZwUXIWPhC^I9RR93TH@F9sz4sO}JTL%v zUQVBlA9KX>vt#Fp{g>2D`qzo?FMi)XPhDC6GaAy<0Nar9+v1y>!_&^UWiZe{h>mCj zncGN}B-2jjNB-YLKAuRP4~F8^PM%+5F+%m&e*GEjB1q)11xx-u??{m4XXk$`Tc@CE zerVGcXRuwQWc-|>l2IB&{6#f5$^+cLaBh&+=&n6Ft3@o3)HKNBv7U}jjGn<;Gn+a- zUFg6La(3k-!XUSYAZ(H+%&Aj+XjquP<)Ws(RGn>a*aGgCV;-lu0r!ro)AY3+2j$tf zo|*F^hQ*efA0wui5!9nZ27KwBmzasqBLu5w6N+!)sWD%?w-V{2rXtHCtaZu{${dBn z&tcwKi#)<}@j|3IbwW!#uZX+nB8xVheRJzPU80A@uIh43CzWLD($8MXdYyi{zq=6W z!e~)#GE>tte%nzi&f<|T7A33SFH$|k8yZ68TQPjkCD(6MV-|{`5e8(^4ZySORM&|Y zjMLvI4$Bvnliwe4Ozi^VOR=QA|e|nTy`gsfS)!PFGf#UOkuSn;%=<-j%Sd0&0<%*|BtWS1q=hpiB&~w~* zED^b=%5c7X-bO$WwqqFO4ejdcYUtGwn$ztya1?0zzO}j9O`m>pt*OnCNikZhxBL4Z zaXXu&mRgv#4OWy*Ryf~PJ+t(`aw8Z7Gu_P%st}FG*HPfdJfx-(G*l8Su79GH)8De` z1sMf;X%JJn3fYa^;(fA#hS=$LG2J74XgbzD zgj$e#z&+r+LpKHQw>KySpHVn}!)LXy=_uAV7AKjvm^_-#l_dy;zEnq7<~bnm^bEIs z%)k%uU%(^NV+T9nittE?Pba3>Il7%g`+<-}fwTcF@V!K9ry|t#xB;?cE?IJ>oZb`< zf35m$)Td#$HdJG0X3}2Ao`!VglG*EQieHYWGr}40;HZ}(QK}@{Lxn+MLo@l$^&Fe< zH;@v9se@aozF_XDwHZX_bYC{v89AP3dlzG=@bFX;8@HDd`M4o2HP@eP&{9g^`=H^| zHPE<-?uR#8pqhCENAb+*kz8~W(3hq8k7t&66SbasFu`xpL@zCH(2h492;bg*vWn{G zt)k|X2qo|&Tzg-bdf9?Gzr6SnkKDuczTO*ZF!iRk2D!K8wQX?S-%KSEWClPX8K-}w zi+mSRQ3$hVFRaHLZjDxTl(qOUde6oE(%ul)PRPmMG5w=mgU)@WvptiBU8CVmOqBLi zoz0!o(xlgXlUg_GZ0dcGYD|^HHW#H$IVwf_6TT1K?>h#pp23prVw7zXd#!l8pHyb1 zYWN+W%gO)ta3HrG-0DJZwXfkMy(PTU$i6hUy(QBxZCkl^w-l(;xVY|tRZWwhsx!NuRxmhix>ot2Z9pZ!LXxryy zrnP=xo7#py)-Rc=fD1;ZQ-vC^0T#oCTuVK~=ny%9f>K(&-E`gV+2a>uRECYo?)y84 zNC(<@G0#~8y$MLad2;~a>(y6XD(ykwP?}`ka?(JD$CdNxYef0luHQ!4z5#knY6!Eq zEQz<=z+Py1*>K#S#^yKT>r+9IRpe^sifJvV4)=-6rCH)ST#Ru)C4tZAvt7zB&jq}7~vO&!TWwh*`1wtQHqmv633 z!hrbba#SlZ6Z64o+(drCK3A=*#tC}n-s87O(66LSJNZ6+)$OV5ANM# z9IS8rj5(e28F9}g%j5T_++Jf?G|*ECR?g+kghHnZu-tcUeq}u|_qcxjPqQC=co-L% z)RNHYDXK-rZrM_Tvv3VA=9ond$^ik)DD+VA$_!FAcU0o3>B*r|62Vk`YzIp6p z@X9Rskw6r;rPV+dJ2SbIea#CHy3aH|TwjS1@CfCP0KJtT$?tqzxW-4GAQ@0C9#wwz@4+YLp&_|qeAXlhWUeFkL8WVl`*-!#51-rrhKs2{I;J%!y<9O%+a~pf7vgTw+(A{M;`z z9hhX@QLg^BJeR5mLRK~43(30Lbbi<-$!->dFo?|yO|@9);r-xJyzwczawp3 zJ|zBEWnTdm$Fi-R1cF0?I}8w92WEyLSa5d;4#C}BLy+JEcS&#$?h@QRNN|D$C&3Aj zzsb4p-h0lu@2>aHTGLa#YwxPs)!l3D+Wk#^g=qq=Vuy_a^2~_Uqk=D9SE>G_KI*6A zEysUuAMYisYX==O;!s;tD`?ulsF+>;qJ|3O;5Ygl-`7=G1 zkg^~m*%5O`3t#Ly3TCc_RVxAMb^djblJ~%;=RGq#c%m=tPaHxv7jokn&t`f#1|b|9 z{bjBZ0_@`t{c7z^I++xmJ>RLd8&FDlze}}8<`}X*8kfb#Np4pYn$<=vI?3|VOI#Q; z_u1umW3KtO(RJ?Vr4nZK{PN-cf~Uq>Hm`t9SFVU5%m5BIc5H3O-{ zd;Tl@mom6qr?`>n*dJiHXwsEA*JayOcF5$rd95pg9ACd0gyGO*T4j}^ z`!p0DNKW_0zS3qxRG_J7R~|ZiaHaP1E@H=%fT-_RSfvc_>$Mh>+4P&UjEnRtA4fu5 zsS!7{b{DKOX2KTsUtzu`Tq6&MzZnelx1AsGm1J!81mRX(b@HPj8hU8gmE%o{JlHdz zk&*7H(Oo=9i9uUdbLeX08)#8@L&RFO&e@}Q9*;bIL}JYmT6!(~X@s5_-W_~9___KR zd6Q<#I3K$dd_;m=%_fKrE-#{>a`D5?Gh1LeSnA+0$IiobAX6yK-^hS~YTP}b$Ay`! zl$1+;TYa1bM@y{hT=csx<~YmIJ`U*U)>=E>gf!eMS*C*Q=4>@O&2bO&R^p3Rqn|5d z{lBGS3CN6VqM}& zC)D~U=ggC7W=QxO@4Zhr^VyN>_!1PDEn(kVj;O{8Ge1tg`1+xu;dFVc;?+^I_!E8h zj17gu$n2pY>(H`;u{;S~cu#;IVQ1RM3a6s{`C4`2=Qv4r`wiQJ>9xxjh_&>~eBcr4 zR1}^Sy62!4D!Gl>+vL3+we9D-HB&=Sku(>@5gyX-^L=@XF>SrseN=I13Wml%#cwuVf!gvjCHku>kdN-fm zG*+GisU|!@)}7B~w!%+M^;)Ki2NOMB zinr*t%0LKT(Q#`;qC!NJTxJfRMwhYHw!yw(dB&99JfX|zIYGzH$s1y-Sbgx`-L;F^ z&T!b5A7kn{{q_nmnui;`9HX81>fyX+Zdb^QQnO4RI||3b5e3itX7JmTHt7l#=n7h6 zvw9Q*szB4$1rNyaGndUe^j+42zY(RyKHNWg{3#1T*K!akc6F)@yveu_P>`TUS8k_Q z(1m&Fw;4gTHh~sT1UaETvNc|8pg_EGci7$J($x{!M zPy9`lhCGI9%deLSt>5xry zSXc;-#iJ^Qgnr*i@fwj-)vL!AItp9GSk&cyw0hKZ4LP$fk?Y=X*G5}>T}vXqiQH}K z>!PWq!4zQ;+`t{EoVHhBVGU)!yazNJug9wv{`aWdFEo;3&%Tx97=y+k-_<{zXvqYxSrNPW&RfN($k*z1(u9* zkZ$FzLz8Y*|7xI?Lh%{1DNFTU!ds@|1bWh^&Apd;g-_gQB2#EL9`aEM$`22NR?WNM z0+N^+<@gdloI9U}9}MTQk;wd{x#d!FHo4`ZZ!|EO4M4OPawqTF5JTUa00$c*8}&QM z>Do~$M|~*A+17eP5$pkf(gwqBmJuTsNs;{O(o%oW7XTYEcysJff%K}*KH?Pzx_HtT zdIPW^PF4TQRWDyQvKO3~?k-Zu6dTM_mfZGfmHaGT1@$-7a++lc^VT4LN-y=Q=$%25 zf)a-g>7WZbfhh|@{-iZC${I;3m!DFJ{ZO=aJUInvD`woQF2*m)-`xugk;LY$WhxGo z8|qGU)OhvOsLk6QZ}*KJqkH!Eo$S?an7K9$TKc(vELxK)?^bkBmt9Pxx+txB%>Y8z?g)Gla%MVRf=4@S)XRgLB*{m+tggfaEWSSBg%YaTO&H3_ zXnI2TnYVPVj6TF)T;&_Br}J>z8yRcun(Frxr;#nuoO~gVt~Q#-8xlpKn z=0wD5eiyi=%gjlds225<=-ilk;r2zYKCx-^_S!c}=Nn1BP2|j#3bbsJlQxwMD$mx@ zbi$|-B8|Qe{Wd>!B#ryO$+?@w{d8CO-1OEYB1Uhc$NZV5UpZf}vNTmgltD`W#|DJ{ z_c6=$MaS7g;~lB5lk2&e?nX<636|2!rWRpzS{j{mG$VMehQ`D(pD^SdD=!=Q-!LG- zmd}fA+Aby|bJz5Io(X1lrqDDIrE6BF>n5ZKl5`e4q?v4~X8C^1kCbCFkzd8qAoX}_ z6(tro&t>=XC>G4(2FZJ0^hLI*)kx&@=6o)KaeRTtIaOw-Y^eo%p=~E#1AaVOJV%7%y5e);uj!I*>+xIVpu2PBz&X~s6c?Xo! zH?MJwo_U5Nmt;6*bo(ZtpLQe)aqq~Q=`(z1(b`dZ8Mv-BanctyM$kp}Zh^P0-Vw_; zA~pG~(ZsX8a%S^oFI>3oNeYr08wgptX$b_w(JWGRu@szW@U3z0Rc_ZOS* zdxT|lF3saI5;UI<@>ID0YHD@$=fPduCwdq0c5e!#m(R7l9|T|z19Dq7Q+x6&s2-6& zi6M>Z**aE)WT|#&sSuxG1aFb-HKV6&B}Lvc#tgP*$sb8-&g$rY+r;K2PR8-*=A*aL z-n_CDBGZ09u6-6(ZT(tsS-ZfAp*`6=TGjU1%SR>O_6?Ks4f=5GA6p}G;=S6wlA$Uaqpr7;p-b*J}d()u!Lf8w;BFM`p0)j zk=TP?n(ts16`L&rV2iCrT;v4URyXB{x-&8`~!boN>cCP22Nv=NSV?BuB0@QbpDy8 z%easwHC-YlZ*t+bv80^SNb%4km^8TaSo3nkTav!$>-dW?WDCoAiQ=^G0OYJV`@C7? z_IN3}Ir-!Wx4IH}Jx2+uSqW(ziK$1Uj0s<5qLD3K7mSrll4(WPQQtI9Umv&4Vkqd< zDj-(vl_U!;n${i|WdHJ8m5KusQxpnn_x-|P*H4bkoG;YMFGv>27PW<6_-RT(SPK#ak2}4>OC09fSuMummNn2xmL5sad zq$>r}J-P}1qersB&NEfddGyF9Eps;{@|{btQ*+jl zTrpfInXKeX8k*_nPk`@FqTmbLes8rkfpIQP$ze)?Ix;F?d!?uHpU_4?mcI%Ech$ zN5XcM7!gsh?9mc=luFzF$wPNDkKU!l)VnwC^48xTCE(st!#sA^5_J_FO|MG_xl6qx z4#RQJa>DMOXiPhAI2T)e$TvR3O%kr3aDlm>x2fx2kKnB{DepP&k@74Z_!g5LVM#%3aKY!%pQGPvSc#(Cas5E zNj7r;iKO%!u$U~_HuDMPv&F=WW&N_K*!y`iB{N!-N(W;A@TiN_!t6D6Jez+PqqCAQ$E93jrDWv9zP5NoTi&}8u?t1Q$b)g?ej#|EDFBboT=Q)tyfu@NNgAvW?njT z0_m(JeV^YHX!fXVY?_UQutQ0l9L74r6Ob0*W7gN@ODg5q(<;Q}13TZy&T)3wnxr_o z^9FeDDtiddcTH%+BPKn;kc}$RHA6)t_Q%!{&iW=#V6U zyZVEp2)C8FH@ji~jr7b7pEJnw*VDFI+RmJ3n+zFI*vw|URa|D&8hfzlc<-@(9VP41 zkEDI3G(2&g9{pM0X((1mnm;608LB;MP5zEMEAbJjx>ZB%lu!_}eLyMCUhy`{L=>fk z?(8B6t&GQo$#FEdJWysJ*c4JcvFYI;M_U!OBS~_zo8E=Huc)5Topt?GX*C$6+6fdw=OfrOmDeTk!F!54*FDfd)NDG ztH@ca^Bw;fG6TQXgLjRO54-vyT*tnSh$PD2gcfH4D%ruCn4g|8jcDR0TNE&Ardb$< z+&*Wc*;>aO_<+pzOz;S6yjaC;3VbZVj-1xb$AKJryd|J7q#?&RC~4h3sAF1^&@cPG z6vXC24qa8y@AReqn0Xwkpb{E+@fb0Seb9O&a2l(_S1;0eLX~{>nCk^!TWAY%CIC|m zM|nN?)Pe@ZFp!bsY?k>%NO=2+^Q#E#gon^d0Yt@pSN z-laVqLCr$~m=nwmyTj<}j+$mAJ{8Jw5i?4(DU~0sPsMz&OcTZ75a7%)Q~V3ct3B{PdUPLC~m2IVz*B)_Zn9yi(pA z?nNo=bA>sAyKMvR)bjiLV;6Y2qsQIOk*>n8G}{h?aus0HJ`Wp7meig*JUmKTh}+jl zSSgbzjE`6zBGh_u8MQr7n%4HIDPNnZ5QV)B^7#CSH4(xS^JDmXIYuOjj!VJoEN{k} zImWe9CC@Po39p4ynoZ>|k?#o;ECkED-iqoY?k;@&pdDee?87k=vrTGrcFw4p)W+b^ z^K5}?@o2{|Y4D42eLyP-jvSa!^9Q z)?-iAA41tMKzEO$v-~ks&ZtU6zuv%+6l0cokptRHp=`G8}Yj0a3f|fHIr1mFUQ; z`cUfNOe+Oh^n~;s-O_lf2q%0aZz)uZoLSO8iP~8l4Z-Y(y!oY!Jn=K7CV`7L@tSmY zANdDkb9l#hJ}i_cuu(j(H}fJEOwZpgGmjmIPZES(moj^`24Z*8qA!^LCPsX*@ zLb%sDi!Am_vyj`cJwrhC7eYP^^FM)1?l~a- zuOJh7WhrH0jo-u;!v7n}1PuKL%7pWNpOyd0Z1G=FCjYk23K$GPF#Z>ui440OyP1KF zjRCtoy92wkfywRg z7BKL=HoyaMU(0!~3FG1bthmAV)EC^~d%6p5=zZJVVD5WcfB*x~0mv|5ARcb$KkOl# zT=zB*ZeToMF!X*4oIf3Y<6}U79HD^K|Ihc|ZQ(o+V9fW{|0=VfRNc z4Dg1B>wfHTFb8mi!Qp@e4u=8M9z1~G0G$WmHz4N%17#k73gmwO87SZb065|Vpgs3| zAaJgGb#A~lpcxn(sDyL>o-!WJdxj987Lah-$T8FAJ|$P=RV_LSFcf73i=xdwIH=(h4iqq&PO~uqTxavT?tL z{=AyqS=vv8|AJm!Z8IkDtgnRn5p4$#@Nx@Z-Wpt++}U2ATQ8;B>&heY$$CYg`3o6i zDH$Jx+N&5@Jjh{k#0>wTVqXLu#h-uI=g|AHyYk_M%2~LR)ii4T3w@e^w>_(24Hkzo z)V{P@m@in2gmH)UX9{&L6E9Uu=^3ZH3^pF!pA&iENy zxGVm0HhEn1X|1^&hs%nuzc@cP^ZZZa)tOQYd;vrZ(@j*)tn!#QDbS!YP27;X-;ym# zq-xGGkg)=i?MPUxUswZ}Splw8lBOnR>`Gdl{Y*@3F*$+Wzi@g)x@Nf4*Y)xVv@<0+ zaeC~6{^#6X-v^O;x0585UpIV7HGX}V&*j(;^A*~UeamI!qPLpsL(*jQsMIfecwhz0aW+-Wuy0az_0Vc$|tFgv~TJWBz(bJr=MeWg6l#g-&} zardOOVt|h~Q z?=lqFp3#pOX*`-@?}6aq9E!@u_AnlG{xHIMQ{2->+99F_~n9_f_ogl|4iw2nLTm zQvLF{u%WbHjyhf+DjaEEhNTsg3@Ve4fpv2n8i8<2-QIE{iPm_$j2Oc(TB?xN&_Ee{ z7wnz6F5m0eTd1=d@Z*~KAwEbtmAbH|7&VNPs@UqB^igzTvX=CdBQp_SLFIB5cQM5S z0YONNTZ55luU%B3JCRamL(!~_PhA;BC+32dTPd4uihi6mu~3at+vXt_xh-+#dfp`g zvOS?|~gl<$RTd&gh>LB;}sp zGH}#q_(t3`OlGjYncUvuayjbi zPG>Jmt@@Qm6z#DdsKQBT-t?0xu9~|g#-i?sKc(mDil?h&-@X4i03X1RGAL1P3mBr# zl`h;@d{j+Tgfif2M^jIOl9I<_cq~he?UE3I^3Gt)aIV-j#@I6|h+CeoOZgj9g56VJ z(u42<^LO~V0Tgs)Pq;tGwq+D9lNK*Ue^hTKL6ygt$YBhsuL)23fth0LD{ds1t<>gN z&N%nuYax5JR$it>r~0FWjE{)LvpMSiz0b5AWfO6D*uE>7%Ep=ghHmFH6lo>56U%G?MLnpyU-#G7a5 zPEmdNRCB>Ae>C^QFJqdRTDSMt#pX>C6S_R#Wyw7ib=z`&_~U;dc-NsVqEa8qZMj6E zWjZ+?Ql-RQQh=M7?;(?f5w+D{uR+w$F5^>8%QaycjsHl0%la6af}y-fK&nZCFvI>+9%8aigEc ze^g?xb&Q|xl%xi8@E=|~%kx!Z*<`V;I238_m+NGAgCcd)w8h?;2|Q6a;A{FZQ@(c4 z{Z7VfQY*0z)xyX`SwdL%K9afb>K`?K z1Ye+gDZ8ABv4w%KojcI~y$b*n9S9EL1R^#OM?3r9a;|%BI&KITaO8w@0O2Yei1h9? zgdCm!yMm&D<2}g!uekWX?+qzs56sm6gkumG`2P@&X)W2UH(9EzeW)IIjp&b<7 zqa6-sSmGb%6At06PV^v(x47f@N$TtgtG(L)ekfC;U7)7k;F)~8sSu$kL}aAeS)Z&a z)f6@pGqe3vx@f)G(e+6e7f}k!*W>RN`hl7i-dM1;1!^AeMmw(;5(EUBR%BYuAXG}z z@b@8!(r({VStc87F@Nyg`ciHTDTtk~SMQGcJ6hqJWD1CIzuH#wFfGf0AJ!SKm0S8f z!k{InjBVzr4LN{E;g@`EVYEB)BMU*oyue4`N;pGgTd7yNT7$%bUbpFsUvXjy;=kx( zI(emDI>m=7tugo2;4P+unw92xDT1iA0VCw$XevF0+w04phUzq4n{fqZ11-cxGg z_GlWrCR0TvZh#_O#J@>_)NTAEY6!GoHV%^_72Y;&kbK=TR702OB=$rwwz-Z-eWMa0 zNKjwg$$BGsIB%#Uhaq!fl67=+Ml5wQAl`aYyc_ggyp=(DM8ySe0@Q$U<@)M5ChD_&;x>TM- zEw;_cm=-<>&Pa8?5#*<2qSGWfSlw?MD3Y>9wNauZ;MUQBcCUU2PZ5u$zS}7UMQqI5Ac!4jKkD}HuNps>2$R5>OPZ*=`0iQ zy3{@XF<*(94huXh5^vrfjo?!!*Ue=29H+*RC+Nvn4&4k3FiL*eIM#kJRX8r!p;MDq zAl`}jk$a0)dcEQ^(j``Ao+Tch*Cqb5$NYjXl*PaOfR48o8wer_Y7$YUKh&7j>>v~1 zg1_ygvlm)QcteNJm`-J2uaNW;;pAHZuICbFd1QbrsrH1>DHB88b&&ovwD~6d*UN=mWZ5BQWaS~^K;fn5 zJx<{dv0W{O$KgKK#CHtHG$$%*&{f}qufF8nw^v!OZ;RI|EI-*?G{H-W72BN^+cDlZ zA@|+u%vfk0PAbRE)i6X`h;BD{bZUi9?zabK6kr{QHH3oH+&hozi_bW!JD1Q%)~and zQQvekC_&_NKaY@uZ5E=_si+i+k6|oUaT3fn*NcOL*%^Y|Lb?7LS$BS9oL7s&d8pE2 zk@)1+}-IlqP|Zt9q(sp*NR*+Cct@ zj*(iLCj8C-hHM%ACOE~BbT>~G}sln)K;m<98f~lX8*I@y(6`@B$={5+6 z!eO^do#ojUb^a#AtA}>_YrTsbI`F?Js6;-pPO4-G!3<=oeT6}_7&quX}_8v`# zU;I*-`GxwgCPA%=l1yp7w?UUARLV2Lcu7`4pAm85={^t73p3m32bvlny!)hy7Oqr@ z5VWcrZT(fdyXgAo1q$I!l|8=F$mEzHrkd6(AAUB4O|4C~D4I~L zj=@geEHe#POl=7q7MfRgtq=&i3}x}(ot}~zYaai^jh@>YAdTj~Io;HYq0kdSN#p)8 zMKv%*HvP<`sUS61=crhE{=nNM;?xaZg7d3md3OP$YRk=Y&vRUT8X)=LBBKgQV3?D6`+O@~v()1q`Joa{>wM$O(-D`nU7ys*ZMX{B$V%iw z6C=2HS8@3GNHxda%4_MOp_Twpux+73AutR-^U{Ss{6^?4>4F zi$&v8h&4o+l^ob!?JW$woS}aoW_Yt(WcbS3zxcf<3RARaXiPbi(bH4}>8NmF3{e?Q zHVmF_Q!M^os`@|Jj}mJ64jq)dE3vd$82Lr+}shJp2)rk9-$>?fR~6qy8;5rPg-Tx&7{GlsPm zcwlb5bG8}CGJBB}%VAybt3Bk5O;xB<90QnQJ-&KB<7M)D1rrNeL6i~SXn4gq)*~(c zC8%1lu>HA)mP#S#vPOUsIBFNqhzp;Je6s}OR@uA4U1LbAMQhsWt4;A}oOq~T(|R*5 z)L`5Us|4XDnl8JnCq1AG9o~2OEDrmNIrR@^Iz8>-%a!Lgt8tb&`f;K9iRG8YMBY-@ z7B4qD!XWfPGIaTNsz0_`+{Aq9jHDgtE+&+i zbiFq;rr)lYF6Kf=#)TTTmh{ev38{!Z0+l0QVQ7#eMA?V6&1$5vW5oQ`Z1<_<#Hp;BLmQ3S&wd$>6G1YG${-kJq zYwZh#srVV64k_+;Pl{;2)b)cKoP~+@&BFS+O2(eZ2LGYrz>8m_RTpRMrMnWdea*if zgjp&0{5?4S_Z_(Z*zEj1Hg>uXj$MHG5MT?Iu`qT5BGBJav@#I={wrh0_4jB|!~poe zrkxoY5YGaw{4Kl$*r)%M;}ZeWcg}W>AO;}B1aY$gM9M%49SFINU5tQi-=CzvRW0mn zMejpw2GQr79AJRKnUfO?By~ApfSH_~@t^9rIDqZexp<&(#(x{HyQ7II8V87r3k_gq z{>KOO`xj&i`a=feC>(ZAmi?#ppl~?!uk#12zy5;^_P4o*fw}*~ zJ;eRDIfX&E|J`3_M*|CM6Gt>)>B+8Q;R!4yf!93Bc6QFd8xr8D0hXsywx)KV-;dD! bt0f@+ZQ$tq`<{kD;M{ODT3Rs$akT#j;MvvF literal 0 HcmV?d00001 diff --git a/paper/figures/ObserverStiff/ObsFeedthroughStiff_compare.pdf b/paper/figures/ObserverStiff/ObsFeedthroughStiff_compare.pdf new file mode 100644 index 0000000000000000000000000000000000000000..b061d29b575037c1b5fc34b3a4a8ae4d82fe809d GIT binary patch literal 43319 zcmV)9K*hf$P((&8F)lO;CCBWKq6#%2Fd%PYY6?6&FHB`_XLM*FHXtw{QZGhnY;kDuP!@s9XLO~V#A|*2eqAilY^cZFa&7O zfORg=gMvn~B|z|QK$Zdd=Qr0Qn3?-XWoy!?0?z%`CYhOh1cMR5760^ceWs5K|MS0p z_x0mH{>}LKhkyR@Pd~1YG(K|8?PIq7@jw3C$N%&3|NclH|G+_(cAhQ=T-a*f8SkL=gNKe z!9V>-?9>nc^LJk#|LKq2vGZen{IUB&f7>0EKI=6;%IBzamXANae*E@7fB)kjcgbCm zMf+z;sgzy(kN^7P&%gco_x4%ys`pZ}Y_f0p|89R0ldXHD-`9YsnRe*aUeqkdlLx6J-JgMk`<+W+7Gmb80&e(Z+1`x43c zqCE#n7qZv){-mBhb83O?nMvdtfviD9U9*whm8iA*C%K(1AvUnZVvXNRKy7Yi&#=0m zy+5nWK>FnS&0Ydog~(X0wLfQnLoc6uz8mO`Ksy7> zz9>d=R+ZT+az6pcngQ%S!WXpVBKsx!^GO>h{M|d_4hbysm$jIQC_ldWqGjG^V-yh{;b8O&65>Db+})PYwIq!uE>({CeKs=Kc*Pvg0F zB8vd`*G8&(;!666Epd~U5JZxZxmYF^$SkpZV_wWXQ#|?8L8j(*A9};tVq)a!GM(#p zBUej-Onqrg<+)#9y-_aL+FjN7rLo92G6{H5&7~5K>6`*t1g0ijzb>xWhN+VSsRY#J{o2a|%W6Mpy3T$=B4Y8} zFRUeSe6M zEq&FlyR=^`YEiu*&?L>ur6OA=piI|3wSRstP2w?KAgR?ot<~i{QI783^UMdZ)WJEs zNcqg#!KZ<$rMZV<&OlZsf&&VX#=*sQmuDcoyOw}X09$X(flO`B@dZ#M1T+_s_JyfG z0+?D0Lpwpw7l#{bE(g%OP$f8kKp3Mhqf&|uJH9Dr)TfxeS|Ckx01&x1>M_rvlm%j%~dZS3h%rHbVo z2&697MRl3ImNX>A)2?{GhSsJsP#LAk#F&&s1qst?xK`FKx<}Ycu~$xrAI{)CO7%h6Rg;#!(UKYzinyJIzlJ8{ zB}ohQy`Ro=ou#UDE(+kp>GV8f}r5SQ}W9 z-etPd(gM#%>~4LwYVI`m-$uGdp|%o;R!80 z$k>f|>MXBTY!TW9rYA+y_T0u@Yin|nCLxoc^$wL;t~Enf?sW!I-jDJQzF)^{1jjQs zqi?`$)pU#D#B^xd+Ij#@Vl`F~6fM25cSs5~ug_?v#E3_)Q@!QPSq5wAVrV%>0+NUdD6k!>qfE!Fp8>YR*`nRN5Nb0 zMuyZLOWUo~TDZoGk|IVbNPt(4f_Ie4mL@uF_5KA&Rg}kigd0SI?UMmYO$s!O#;Xq$7VyM z@$j?7uJJY;|<6lC~As<&WIR z-b`9rr~6PG5BVDKD0kX^r(8tUiR3hCYlVfnIf8&F6)k=gvtG>f%zR?L7# ziZWZ_^}u9qgl+4F+T#H1Keb%qc)11hC%)kd9S^`Bx^^99b8KaEZ*f3;wgocrojCEh zOoI}Gc2+Ba%tT}k^~F{%x4de*`^!2=D?%}8!542 zj6DLolk2W*WeCU?UHjM?%Iw%0-PR;3Mw(OQ=P%fokUc7O&zYEXTc_K?3T3<<>_vzz ztfu?JDo(!}Ij60mB~|x;+3p5pi!UI#4e?7 z_w?hjl|YD187I-OHILDohQEf9a==WM*%>iuI+c1L=amOUGkVa*+R-8E*kLw10O1J3 zChJ;I-Zzqu7#cWAd`J4^w6;NX?4?^XKiwj5P=_br*MX`w)jLv8#z1Fo@qbBa{`npH z5`bFy7G4_(|BSZoF)(nP+p)?=XEW*89)Muf^D)W{sB^pHw+su>J|@>@USSgevIS)= z&{Qvu1Af za3xk+^1RK92ZCBgNMaz|d1n}(CpN*sGB)E(Y;Xd`3ZM%~ml2*5(Tq<n}CY-)lX|x&$*ZK?>&fN00uy5>woO_4B!iL$ZAB2?on zmjVz>oxRV;hwoM4nPTHJkg9p1wJ>wiBuH_x08%yN_HIrHGxg|_@&|+(Pzqn>#9|+u zIzD90Ts00U7R<~v%wg_F??6&bE~>6m%-pLKGPb}c>RLl1Ttf8((xh8i#%|%Oe#c5r zfk2Ofp6F$>SLLPm(TbksqSA!7@|bS~LzC;7|3%yJMy#*S0)HYAuV^4pta1x+GK)6f zJgfxGLiYzNl>j6%?O>XFWT9v6&ff~YkWMuz=hH~XdA{c3&Yqa{l!oW!2IcIolf#qn z4a3qamaFBw&E%}e#}+$_cIREh21y`G+ky|JvueMF)p;06RKWHdMmrE31Z>ft&|S4Z z##*c;cHYZhUQ6t=r&i@W*+}$PrAe2M8Uaum=Q9Pi>N?duNv@7r2h4KZEb>8`VkNxI z?ls8;i&>G}^7_<=mzD$IfR{7-w*rf$mygk5!sV{f^XV4|C&gA$-OfgurdvF!G4_Bv zo~Pv2V7c2~v4PK4xnl90ASe;Lg~{s?y!#SvuEH z^36b2DBVUD%WToyEo5Lbk=kvy9T4i&Gqfv&ph3K1^N<^sL1{~fHd> zrSlc^_3~LZ!_BRrLgnEO*aO*b55)Qi5E=;XiO{ENMfd;!3>T~+!$lU4HrFkchj!u% zCY^%}>%yUHe#5W;N0NSw$)_$Gi35)f&)qs0h=5u?oXtTSEp+IRGaFgzj@Uy-lYZQe zu-r)3@zDp`xmDEOG!NX#`&LmeujG1=;<@ULZ2B})?lMJZpmOHetZ}~a;RVR>M|h{*dML&eo#9n5JC8h2 z5iBI27+llG**R%?#T<+W&p7|I_>I#n%v6@j>*D6P$H3MTAXSUTx+4&(wwGI3j4$B1 z)RGfEbR8(IW&`OuG1-7HmkzVHUbA2=B4Wz~kV;^j5?#RRZnja{Uc;ubxpahqX65}1 zI%{Voi~g;l7PaE7eXFDx#H|X38n&jEa}NK(TsU-diP;VYWD>CaTNiy7mD+0$1e@!H zNn#|$O7)Qx$R1}PJ|?bTe~zJL@Oh_Ik^o&y3U8Ot}hC9P)9=e7T{N^n@m z0y5OB#m%~Ow7ITu%PsURUU`1TcW&ix{~mGNTNgKAAf@@Ebg;Qa6cE}auCQGISwcKg zE78IWJEwPGAXR|-Zwt?&Veolx?M0OMY|mE!Mek>|Y$cv-3Z~$6yA7fkh~s?LUS|!p zj(P`VCYHGr#7LXF!@7^*veDgT!fNZe~L~;W_ z?*x3pSeYx1mC_7kKNLvxa%Q+65KCPk-H4~?R%20XohXD=7==&}P@{OSRgy-lpE1UH zvan3dovpR1lC4~8E3F(**v=0!Utd)a7_@=;sb#;m*4nCibXwp1hJ6Xa5U&&m)&<2C z-P7YJ1*9b*&9A(mGvj@%7XlIB9cYgbWG_C#CvYIO6S2r&Tj9*?E}tg=tf~(5nAf7^ zSiSczc)PiPy&dkeFC;CH7^>R29bz#munY({6YTby{&h&SUPt0o+O4?wq8+$AiP%oN zn)b}=*n)rvh=~kWHbu4+CH$r#cb$)H-a@bN6|6>21*LkFsZ>81Bjk1%u3IJc2y~hD zM(o5uC=%gJ(^$3N-2%FeP6f5FYkxXh{n$ zTAr?B2Vr;-D>*O}2u=!&6Va4_PkO%&{Dk8mIA3g;7~|5p!!efDtG@G$i9pmEFG#Ch zgC67=3U71zKsa#syzUIBYxq!)-OxDz3XC>(AUG?`8fx6ysvZ=}J7i?9Q7V@8ob1-9 zaT>I?4g`kSJy*5JfBu4D?G0J$_7w6#ZbALqJw#7k2?QeuGV6KYLkyfpS>>HG;F+Ei_USl1g*Vd13(wp7Pb)Q zm^ig!O02?TmcGIOj?FVXoC{9LLa)^H&afCNUdM^6Sc_q4@H}4eD$>w#Zm}?2($Ha` zx71(s4`LXt`!8xu8);!`0^)Y$Udq=c7sT#N9bGrV-J>$PVg`b9a}Q(fMi`)mXAM`9 z!0BPmBT@(`NRR+*SU6a9BUMQEL2)DUK=kgo%#Gj(vU}(9o=61C1?y4tEi0Gc`jwJsABC$PyN&bZquGx(&YT5%a zcQufqPFzN^{0k^kHON^O3k0FN9T*)t5l#4wETK zf!U@`$c<($#Oc(7czAWrAwt(~MDlNBa6@@a<17!uM*7tP;qYFT2^*2x4VO{Lfk5rX zptxU(q}mM65H1$cp)l5&k~CMc9o?27Qq*!xfFgIn7@r>hB5%P4q~UKw-U9fiM-4>N zSf=3($XhT%!65=`)ad6MiXjMNhe8aI88N z1^W_$0c`dPZ-8nxc2^y(HzJ<_BKR!Mu+dH;x`DD028g5K(E@-$Iqpa0tI>x51;HQH z82pO|c_ueG4CpM@ShdV~av}wZ%pzp!K}{Y5yq(9q$zy;rm!D0K0pj;8H=A7f(AQc3 z7+>Jkb?`F|I{3-Kg(}&j0Ee={+V3**AM7qIo;C=%TnvV|JSymrB$dOp5IWXb>vAnd zQ*2}$DT)AI0aIVt6A(J}nPqw})Xk zZh9lq)3LO&8@4~8`Yss}`V-2Lj>GPQ73+D}d$4>M+K9ae%QnP~$a{d`XA8F>?*ZH- zUeM!q7Q~~f%**w34pt$9#NBLHm2zg$u(O~#K5QfQ12l(SY-Gxk+#M1?WYHICi_AuB z_Mg&Uetw6r!-^aJQe4r_k&?pBYXqwfkbs}Py`#_aV56{_#N0^xRBS@$X?g=)@iZ%z7m%#k=lv;NLva*M z=YS2!8IT>$V?CS@kSKkltze>y{|j+Ekpnee)2-KC{rY>dz_hoaP{^O%}Li;=oGt} zm)#rt62kb$;p+rMpxeUhRV|>)`JTeENo08Y*0kx` zoDmPBlV9pOrKA!fK{wyAk;yr*k-}k1*QcM{<#|WcPfdYT?S3-C5E%rfMMP(4?CoUQ zNSF5yu`eT#Dlen-xx@oDU5Gv(0hw|$o`$D}HrcjDgmUZqOluMpQE3!ald&CZJ1nvV=^2s2Lq7dX7M<^guzUY{+JdtYdd76(V=Wo5w zblbgX8_svW3%{5LXX(mky*qt@cXZ}=2#8w9@sMe299BI-AQB9#ir1H1}8RcDI!Y#ok zd2vj-C8$_MrLNW8KivycUJ1-|&#kG`4iHbsITf>d*#Jpo_D38_PPj5tY}5|`M~cC z^M0KnIoxa?Co;ah&y-dD*6Y>@e6sLc_FbIAR=(`JIC=^Yhpzf8oiCq&TIe7^ykkqR z+lXw7aQaC-+^2hm9Gm}xfQefa0kaVc=jn-`FS$3Mysj3=l(wiHF<)JZ)j8*FRb6MG zzhGZNniMHZk9GG9I zB8qw%?sP_l3vu^hf=H&vz$AH1p!h|@MN)oRylkW@!Yaq?&&l!3N67$U{i_U@kXvOKK)O0ZZl(>CI0=mrz*Lv| zg|nlTuTZyvG#!M`vvo9vO;<|>NXd?&^V^IVD_byfp0a5qM+*>w`hL=GGA z+32#-e82GJgHiHN1)V3m?>9o_h)6~)tUKzK%bsDg^0n(-Fi>u=2FBq0xy`-h5 z^R%iB`SB4|9+_LW&oyi8N+<{!H@$6b(Cz?)WqNoVGR&@;*fB7*#^4>KMLRw>0&(D? z&y5*(zb$ht0joA-205fahK);?pDw=*g5fRR>M=lh2hLmV&8p<#Y7RSHjs_vp6-8`& ze1;yZhsTGuBW#-mvTlDfpkFQ`AS=CFw#_L*dx=mYw=h)a<`dJ5(-4sU`Ub1QIK{~X zmfN`$QllAP3Ylkpwun1jQACooJECeYSDl!!NHqyb;z47gjZi>vV8Y8-x^-PIh`p<4 zjfzRAHsJdoD{Ls)-Q*=EpCA4nL)|Se!%s?Ns82!?L&fcSRqt(G{u#uxcnWt}pm6;4 zh;+F$;ev^G(YXj^EDXEOMI~Hh0NjjvA6LNhWB&g91^W_Ge0RnlF?1;eaWOgy1Hp7a zG`9>xd7L{S7QDk(K;{vlqsdM@!qS$9u7IRaUh?o2knHVvBfbVw(c_QHGi!5;SPUXnE8dm^AR{8X1<)6RIWpomMhcPd`5@3=aVN!!!1Q&FD|{3{ zJiZ6f8RoH5OokLv_<2@L-POQdQXLZWqMrql#Zw7-rtjuhuHp8!r18=zH?Mporllct zQAv5Pl_ft*jvzcDQ?u45s=VlDc|NI~D_3;|GBo*ZHqBN=A^H3=aTMl+K z=OtGQ)I<0BlB)&6TH{g>TBKV_?)8F8Jz8cGjz!nGSxNgfkmcJ6E+W55iR-l+kz)le z%hChkx@#sJ*a&%d_)){P4FFJX?1)_a?zBd+5zF^n{r+{X(uI(jM{+-Kmx@k2O!O&D!Cmg zpO^>o{*@%J4WgAs4TNjhH%kdn)V5FvOOmbV+y*03wT@azfvov-5EWSZ^;uTj3a`;U zWHkJfM_C?+@()qk(*^e-FWkm+kB@9IMv=KRPKpL6@n7XkR zGc0Q#g@E%c#9-@gmrs~L=$GqZXDnHFDa)``v1A=lcvq$eqWe~M!j`O!wM0|r4&Uzl;a95MF)~{Of*2~xa;AGFNGH==~q0!lBY3VrpTXjE>~?tCZy8N zv*pgIM_DNNI$fsL{yLxaV2EYHuPiyLAQBA|Vw1vJ{jpYQcu<+{N|pOgdPJ-Hs5X{mD5v}5}#O^zDe zzVYZb*%VuNMoN?G2DleO({Tg}s^wpkod>4d?lSbsprm#x0GI$R9f{rKgMqi)?}y7f z`Ubn*N|Vc_9d`u~tjk@rxMA6F@Q;O7lMkjv^eGXA8k|pXltYhGZ0Yj2K%?`f)8%oY zVbf(C{8i#S00c4=%B9Qzr7L71Lgffx4{W!L@AA0xOTT2}AuUe}1VeyG(c)JTRfE-j z#Q!Y?AlesHy8JH)9gxQZ2*$b}*M31Xi{gZ2-3GwWlNrZKAPiD+#BD}2Viik-G*tjy z?Hz2t+++J+BPMfTb|T6<;!EY)k-(QES9n!y2EvgI?%Rxbf5rr* zBe-Xau{_V>WyXFY#{fX?F`~BwG6+~9MC|?(g;u@yB;A`Azy!^%bnH zNnu&DbWgFz^$QXtCq)F=eoTK7_UaKM0b(K zW?$(E>gJnKklfAUnC$U_rYEcBMF{d{e3S`m>k>y&P$z(xIX$Vh$kZ%;w|TgnyQrXo zvbgcmd2hDCipyC%@>}UiUEF1OO}El74Q}<$L>}g(xAEnKrXVs>w%&Bk zU96+=4RGSA8PnHx&xjf~27s&=ksH{XyO<11@HuxeVBH@@lIHg-4-uMOXZFF1hgVK< zgMoa`MI5rtuZ%sJZ*1=2zQicmVl4!Da}TQP;Asx6;^!~ele;+|?qT@sH1$VtDwj{u zeYT)ouHqLww<&>v}gkf<@G~Mu4pO8qL8_ z3GxLkD#7lLGX%v&!eBCn%iOBE6=6v&$g1foK(*sy9#x;^Ti_a`NYw~s_X(av1 zCUZtmXL^x2b4i+nxd&yauX>Wq*<6SIQ26L1OX7{E*akzCi``kPa~!}Fb}_u`(0-c| zE(o5R-GhhUnF2=xwNh|S`sznp;`naEw}Jq)>NidGC6m>ZZl0J z%qE_D`dze6TTnv)@i<1r$an1P$6t>OzqJzB-Yb%(Yr#HkF$kfvgC-abaK5TkG zBr+|MNbRhxB3Myz@pQdt13~R(b>!R35NZODs`QpEIoGEjiW zxp+Rrv#JJi9rDafP6O^X=^&8ro}8NbSy8gl24+Gc{rN8Bzb%^EuUI&#buO3p`FY6;A5_Ol<%yP z$Jx0K=rRBK3ue~lq7U|EujBqHkrNSg5K^;u)wT6o9ZLM=fmGia;O{?z$ zW@t{qSISj+9g$X*Q33oWW~Y^hj{9^8VD;z5jrz%Zo^G&`uvz=!N~erhu2~K74%Ncm zOsP=hC6sT%W(wuQ1uE@d->A1~N~h2c;f(Y{B0;L`P5OK@jxCn{=Bk$mk44{Ulp+;fVB`t~p3#J@M$VdoJXlYrYAJyLaFb6b;mxEN;D$yAMBy5U0yYN8#uX z@9LN!IOi=u$;#keZaOcWEg6VrU3ri->)>;m86B%-g8rsCy!IfbJX0;?NEI7d41fcwJuMe z+K9hvZJ$gJP-&Hm!XIQFXD*@~$S9U@dK2?Dx1gmWZL>DvVAP&XC*O!+7jN@;Xam#d zo^fO#v{$#{o!dmtO!V_2a&9w3-kd?*ZLSD1IqU60YA@wmcu2IRWD2+BG;MP`L@K0h z9=ypNQd@q$hE3ip7gs3OM@c866M38K2QB!~vRDk@6^>fW1cH0y) z_CeGk*9=T;F=fQ<3~x@0C&}~I;)M0{7mPg3y1u#&Ej|gK7q27xX1Cd$D-B*oxH-e1 zVM26rInNJR1cC*Y?5H0&@OWho`TB5}nWk*L7-)#of~VJzU$2>CQ9eEV-7NV-K0W4r z(FR3o=S9RzgWS$&_3S04a&F_W?UTzn6A2b+1jT;fxEK_m@ZhmTaHz_GhhwR?`vC`@ z$^>btshn|TxF2L|-#7vn(`ly0pV2M6obrK#wO2ctof{EzVJ7k=5V%a^3?n99#YP}9 zJx?K~u#`IwNDqqZi7l09@8FPTpd!9HNGwTf#!m{mOtV3cW27J(bSIm3P>*IFi`p^G zZiF5_Af|X2^6=3_WO7?GM7MkfQw}{&tSH0FSg@v<0|i{qAWSHSlr}TMu$80q4|?lB zpx_(p06aQj#Wd<1o*_@{UPld)^kb(m9Jw z$R8*pW102Pck?Lt0nbZtzsq+9#0;FHQCO7`_gsVE8RGx6!^k~&d4kKl^9EBHC)v}G z_pFSY@?PFEl(C{Q=neXSW9slQGjb0|&pcLy@cw&;&!^?H5jA3EQd*36XevOoIn+820xP z_DFItS0);8VmL4^gY@b;c8?){7$QxA_Z$AO$+w9l3zIx!cpaO|NU*G@NAJi(hB96t zlS~+h?1&u;YF6j#g!G)eSi~2!q@J{$6_SOU4tYea*s|y$V+2c3LUZFll*@TP+(s6% z4y!WQt8fFvBPf@v2a6 zR}k-A*j*5A8~nW&?*-*L;#bAr$00Ao%>2mY1abxD$N>`UoEKH*d}mN2({UlvP4<{b zQ;=KaD){*e28znWkh*-Is=#f04Iw6*Ow_D1+51Nz6Q6xJb|&w|sFv9{6Z6>RcJw!s z8{_H0jGB182W76P1=Sk;8Ek@Lw$JUbV$DRsh2Ugw&*VSOM0}hf|1mnzcOwXlbUK|B zsvn5%wr#*{$Os7!icMS{_&`K^Kff1B9LD~s`y06&x+`-b=WSE5dhW~{A|_&Bk*4%ILPT|V)|Vm=mP0~x80F)r8L zGT96=LvdY;N;8lkL#9|`GwvF>qR~t+ZP!af6}d@GYD_?83X>Y+CWJYxNNT*B!EK3P z1g6T&+Z;EmamT}Jjnwh6kP&ZG_lEc&pies%YpQ6ohoNGFBRt(2LMsOaJB?zn6`j|P7fgDO=qBF+Z1ZTDAjPW`_ z1v{v>bMX8+BWYmzSq&p=B_3@Mw8VX?ObK8~nuM?e%aES!Nii5ZOv&aq9z(m^&G|iO z#s}imlcp)=J(Bo_DJgnVrIDt%vt_APKYzi#gkas(dJ-K>?TPiKeiwIfW=fnMNYN&3 zKOGS4iJ*S;T$v0f&I~HiTZ`YAcV@guCe?c&k&0n5Iz872#1p@PVJFs#`13QNPsfIzD!n5wsQ!Ky_e>& zp#$N8q3DZqiL{;IDuzY`_nVm%MW=_JF*PUHQ26>j?VG+h-+5+8U#y+=ib`~`b9XZz zqv(tCxnX1e;(TtWkiWR=v+Z0Uf3d_%P)J_deM^vd|NI35J!RtkM{alSz@(!`Iews( zbo40aPy=MDznqPcG{>HPri~PLETT1vRn`EODhKSdTfrGN_8O_PCfv zHS0ivnIcgKwqlIJo$Q4C#o9oEQWpHhRkKOI$yJOG4?^{d z-g87Xn)ca~bAsH)KJy%4s)hQZHU<(ar)qO9$Hxz9NkMe2dWFjy}G9|HJm==CKI~dIw>!r7ehp$hc1iYBUV3>0-^^-HXzm}vplkweN zT>b2@!R^aL@7kff`g@VcJzA(alerRtdbw$MkN21?%Fq3%>kM++mdT+kT|1bp#i5M( zYKs9GlcnfK4~sFGv(G&Y_K_kDt{e{KJcXE#dq~v|VKo>(8xwkv=>Pdx(IWG_>xoB4 z3fqYOhx?^{=(4lRbeRTnWWgj+a$!5M`pE{(S$__7->@$sJcgVc9H2_Jq>Kyz^NJlT z=+~$B#xuI}YYA}`L<4wUAgca8eH|_CeFMNXqINipK*Eyw=*Nsxm5;} zGw$B-kX}!b=Jj+Pf@Pfj;He4fW)hJCu^I--Wh^noDp|x%vi)cBmI*=FBHAfu=UzFX0e9}or1j1%Ks+`?&k>n@S%jkz|x4a$GKscV)ldrk+NxrIN zy5>wK!Wjt1{JN=^wWTtbR1s3Bv_N-x@-=4~sSQ*fO47O5ZoXz9(TYwW@?aXk_@)Sw z6@T;KqXQTk-h8-UuOWF^4!`L&rKctxQ-aT#pY&pH1`kKlsqP!}B>>wj;s%30nR*;3 zNP_lQ4A1%Iu_2pt=ST&0YLY=Og(FyO&Xu*yP6&jPA|Kk~L>D&SH$&h zgmGwi!=PbII(5KR;c-Yhb)=iA6*F)0D}rU2Tx>+lCqO!9ymLAOOu`zr98b@@-UB3f zy)*Mg^1H6X-`v!4uoPzg3c3~Wn%C6 zPVL1@)gR!m2}(-p)O>c(UsFc${SN){rIDzIA+zWxnvyBQ0H6rW<^FJ}7kZsoXi%7! z8aAD4DH`-}?-9WP0+Xk^R;7A--Q1={d+D_fXL9Kp;(VyUOON4GfRA{d$7_fS@At3^ z%^q50=|wkJf7jx%A|2)$Fg8PBO*d<*IGlk5L2}aAw9}`R=kc5l-v|&rI|yCf=aLLR z-vDWtd2@%9JjqSeXf&G8F(l=ihFQCE%7-r({LYK-<_nbMch=jk_@JTnI?mjxWv!z(2Ffc zGv1f>mpM>8=p2(^uq&dSu31s;SMH(7 z2hXL*s(HvV^P$+P@u9(vcu9B2k*)>Q)Up*@+>pIm2Qw2PCTRtcU{xg4i-1*3F-+4i zbAB&b{DTcOHF;Ab_?gHMV8%*pDOv_@S)}%1UTf(=fR*=$`8m^+?Atx_2 zE7^?s4Z^A`3Za0jK8Uk>3~+oW?gGi=X!XqG)kK0^dxkC3bbn;8b^wQ&sLPb6pa+?; zZvN0{9gNMF=0G?_NLGExXm$gdZ6U{Mmba(|3-JbQiF=rY^hpSY3_=3DcCtd&HoORdKA*)I~^N4hO{76excw^NOA&}Y?K{P(hkf>Ut zV5>k9L0^v4TO_JxgiKsS4Weqrq|893V_i&~jLX)8NO0LU?eoW1A3W4-dE7+QdRCCg zw-GTj!P(8LSF&bCnP~^Z3i9VG0w!W0`gQzx!S$Rair2|vfY56>G{;?LXl9#z7g20W z9T=?5RZfO}`1E_#ShXNiOk&}qbuieU`=_Q(u&4K~l{aD&CyBHkb-1Wk$kB7Q`-Xi9 zaX?cfQ5f>#pyPvX*&z|mg+>n4X$+}0)1tDdP0O+0 zm72EGese;1?UlzK0z?5Wu{AOKDiQB_)9#&l`dF;d_yp^JX)4YF%m((_+SqB6IRv|z9M%TiKG>I6rvM%&?T#ak$klXU~;E}i^T%Y zQfGA)>E}De=ZDvckJ22r{9E$vly!D9TtFY3B4$`bT4MeVUO}j@3V(@2s^2jZG9zme zqgH|+TBoBLRAwNIuE~Pp=9He#*9Wo`0#$<`TH%TH=GwiQ6r-C8^=fhojyS~djH%u< zjinf*IVka2Ivkz2$7~zn9b6>}Y44oA#i(nea24L6IjkK)Hnt;rD+=@8PU zDcvcqu96Enw4fG1l@1w9tNDuXnBc6<3VgsxXw*QuqXVNB^DW&GgrbL*CTANw0~Mv3 zjQBm(!NIeNGm+E<^ZDkkXqcP$R^)q%V_AU|Nv!CbEEDC;m%7b?E4@>rxj>*p`nmyj+mRxo@P2O36( zcM(L(SzCg5daw-M(Tl#!IK~E9-2#D>#j!*? z5LKkA2vrXaf{1naHIZW$Cm;PVJq5xr(iFC9ZfZJP+K_KDXduCaUbSl?OzJv_Pbl$% zL%#QM*u9}x>WCTy!MyCGM+JZN49{Q?v(u1qi-o3`2@G*NNK6AWqc=s!~pgk=ul zv2GsW$=GBBK%aJ9kT*%|EEoYVfa2dn)kI$872DZJzX^7NV&6` zP8Pg#XU=2U53|XzNb1~F=@dy+W^zAV#a%}WH0()1-ZXwgOp0E@H)j(V$(?Nhy~&;F z|G8;=yTbMJgHn3LK%AC!aL9)v5LC{qKkc~SX_oy>M~R=`p)UbdroG@EA2J%ILxe^y zXW4^&tOrtM7qi-yhmD5$Y@I_sy?ne6Ks3K>vmv?je62K*^JQiaaKl}zv7W7Skj*DE zmyg@gc_Uw;~rmO=!PLDvQ7LA?_Vk5N@B+>Jd3;v261oM(?J+{6)6n)xDO=OI6I`v&OuX+hRPEO^r-PsbU~Ln^K4iX5(E zutRt6WYu6(xVS7C z7Lso<4FliL4DzeUIUjew#323Nbe3#|?eiv(E@~xq-gTlcf&+WC21BET;GMSp)%46cOn<>8 zd=-VSrNb@iJ5gxH%(hpR4s^wtk)+ZN_w}=T1h08k6lF=GO(K}66_x`Xz|4o&)R^a+ zn|expJq~CRNZa;jHc6ko%v$n5PX#)e zW|_1W4{VwpTVM>;&fsimpst(!-*&iELl~8^x1)jEp%tx z2CWLaw^`5hS z^R35CRD3n6o~%nnQM|k=pd}2X=$=^(MrL~N5GC0T6|`giWh(vo3-%=>Yiwdx6opp6 z$DI!{bTc42u{6z!ewcEL!YyhfZ6IZ|zCE~;c{e5EmBbYanQlkCu)clmtQ02ee= z<3j@=cIe5Ak3P+T9Xjc{WY9%})(7|hY^^3aG%oJVP)vY8)*ePKu|p5tV+@LB-HU1` zGhC_U@wu;9k`5X}-cFiaGDhR}qkoaZ2hXv-2&BA$MJd`&3`+5}sCHA#R>u6dvonAi z8md+sXT3LV#AJ|ECGr}vOwbPdsub^@>#G|r?a)VqcwYRcxgBp$5u0dkW+D|^bW>Nk zJITAk7fitx-DrPc(5YW=Xeh5kXWq2^BHGr3x4s$GB4Ul~(9oG$P@oXO`fcZYM@nhE z;0Si;OP5lQofHhx$sa2H8VJ^SJE>-iu12*J_(qcH#rYUBsVis#@fCiZu5&H!jrw)E zqQFTjm%Q%Y7}i~v-=(!fy3A|zdYZeV4~=pPPYe*=ZS_q{a!d2t>P^f~4ryJ84I1W4 z7lqA?KS=Gv&Zz;!?P7h?P#hyDsl47t){xgH`}EMH@Khi2u^@}Nd9R0jEEp+oq|6~t zBuIuw*W&F*rVsf~4o{z`rah58bH>o}O-Bd}9dlYbc`1gX{&B_E)ZO#aV!apiBx5Ot z+zwHaO-oE!-pnjPJI@&4o>Wzj%IZz-2T6g$39Um7czJ?aTDJjk12S4}TCrCc3&}^_ z^vWKIsXNFwN%Zs`oHx;#rR|(o{-AHc7lSz7Nt*O%wOM>^_0m0HKxf@*6 zDF!nZ(9%6+a*@_RmIfjAk|kFh8RthJOUpN?+*dhE+%j~@I7os>KV6PD^p!W#)nwU^ z7+Eq{cMYcKoPPd-eF>Rb_9Ojs1iSfX4b#2)Knm5N+d<3M9JLzG_v;)Yn9&GkjhrpEyhcX&ei8&DaPD6%6YXe>G?$V4bE<8! zxi^y0gm&#RxH=e#L;kHYZby{h|L~)4={KNx?zx)sb$uirZ~w=C`|}dP(f5OF0h`m4l>yO|5gG%iuxJlf7g3|LS^ylCHuiyVfZ|`isrQiSdkH7x$pa1yr zUv64+&=TRX;7Q0lI3+})ZaEqVKKbAAIq>=ICG`Kp=Un&aaH=A2&R&j>F99d)-tnJb zlE~fPKEMv6iIKo6wvl<$qqxkhF)STmHl=8RR~9HPTQ`tcdAeMj$=vs8k}gp&z-Wi%7N zPl4hzBT*oJp90N6zfqu_AYc~&-y$^4C=kD2o%wGsrung+Qx7q%VC{hg3$|fQz5jV8 z6^lZzh7a=6Wcu^(a3Ic6fBWa(;m+BI(BJ;{F{|$J{NA(bA^*hdzPs85o_+eSk4<7? zxcR>sn`f!-5AyFTD9L~RGNO+$ew6w*mvsJ^UZ&BpO!wE&ub8pBTmQV*-k%!S!mjjN zW{2&HU44uif7<`YI$jry3o@rJ4#jZTJ1|+KZ|zJ5fIktj ze3OBjQR&4AO70?+66_m-gMuD4jm)T}*YRD#$Lmzxn18mTymOCFM|{_+uXYMg;LkFZ zw*;Tls zO4RCPw0@SEeAQ=}Nv5smM@(L$dDhYm?z@wJ{(|lG)|K%2Q4f}sTA$Of^YY)bh;q$6 zi)1?1A1~CE%luiZ&=vA5Q%L3a=pfiuVvrBg+NMel$FE0r=4lLfhs` z77ayOKHJH(T09XM(w;4gRPJ2{7O-cT%A4@dGL`Ww&oUzQej~lUmJ%G5<24X)OV05s zGw#{!GLz1lXBnm7e17|)S@BtG@gV+qpDBjsM=j9n)Yr3cGG1>a(`x*zmG{x&U8Yb0 zc_U|nxt4e!?)Ulm3-(21jd$BJS3Qx=ss88>csA>645#AXpI@(pHP2d;j*4fkNz3-T z%(oqHu6uuTnMJSdqs&rR*P{%A@Y?GQmjaU>Z@3ge`$&o`GX1?#A_{N4-f-y# z(6fwa5}$~?Y0sA1E$LjQGjiowrqee2{I338Vyk;1~5HaUiXH3 z%8c>+3K*2mM#);VIhFM)lRjS)iZ-Y894@6>dkzJNbnAR-A3#Q%uXYr+@GMj56MvRz z_r`dTqg1(8Biqrl%(xZ7gS6}P&-HB%#tRsijuKCaYm(dIJ!-t$~$oIOt)K9JXp zueiMU(uRP1n_=mpX9>yIt%0i+f(F<3GNa6IWzMdr4$O+6f7Z&pzxb@Bdp%F2+&h}v z5x3W4LS^L`cvPz7Bz*Lj^L9VWDD}&u6(yK^Bju&GN2cs2qJ*iBZYO!lYce51agJ|D z&#zekukd@&%XKUAss*p`?B9_7QudjMI=?1mQM!T$Q0@&b1=8wMp#(B!Xjuf5Is5sf z#vAF+hWj`5=;trk7m?WCbUH#N`?`1ACZ`Iyql%ePb+I64j^l%)+Ug{At4IeejWke|UER%Uz z;8`Z$v(QMncP`he_da!yP@vRbaQD4shr zpk{iywOdVsu2k{QO8MJn^Ya&MuN#mmy)+M|t*x(V+3UR}`Du*~(r2x9AG=)ZyCwvm z&bJK*uIb)iwFWPiJZp_xgE_U{1_I;{&hMTFJyR~<%A8$Ek{BnZ{#qs=Y>?a z`z%wLFyz@zjU;tZsXo+bRq70Xc~9XhKKyEX22hwUkhpRYR$6}c~c%evFdG5lvn{j)O&A%fBe0- ztbT73E;Eh+D4snShw&~m+xr{9Er6CUM_&MuE_~UI-M|p#oSup(0HPs}`%~>w)Iy|n zYE0hYTwsZSE^i`1lPEPB$e&VwpVPqoBsxp(oF-X~@P6tA3%84R_ zCA~TosBS$p90HosSt(4Sk&A{Y+H@rn0QoqY0hhc)OU*P z2f}fv-IszID4Fo-H5i3}P`u&>m--L%TQD&|)1VUo>7}Ui!!FE7nZ~>H`+cAbsg?=3 zkbKZ%l@$kqB!=P!X$Psa#KX81W$j^l8}+^`H2 z0s_7{q>uHp5UAMKhqBvtBaj$Oa>WosWDkeI4*7Yt)|pSdAT?I^y(nZrLeiyqIi{wW z!%Sh)WzhbM(+0};QCYc!=`ILHi&RY|K3vx&+Mh>aKA>5IvNyIY9#{?Av z$+C6Bw>e>0JGn1`K$f?Yt)ev@AMg?it!qpGhcscsp_EAU4atqf?9*iiRRi>-Ka{D5 zcgu&A9|)e>O7RBCJX1&vh7ftp%&uG;n8aSCT{+6Iq_oz%xGJ&ihDu0OV9hH82^qQ} zPg_!(y6xDm=Is**L{hsVoh*75a*}da%ZS-^kR~c}O(D}ZUE|X?ivi5c&=(~%U}CR{ zq-&;#1pu25_G?9vV@wf)L%rn6Mxby*zfo-M&tI^;^bnqdL`!?XwIKk(*`857>fj+W zccb+LrA<)?D9xUuP^ab)xLoa~ATvsxHK+U63J*$ieBN@@z4B&&y zh;0N3q~VBxlSI=L2&OxnExKCRFXbL7M|A)Ky|0{Hz7(qX&K4P&I*DVD4XQeB0+B$l zWy7DRi;X?W%1NK!5Ry1-g*V`v5lkZ>Vq=Do$F2`wt4PMW_~**m`HL%2Ptw2RC=jA-%^85Ecs89XIOXRArt#Iz2?G6yd@ zum@XF@49=9d!>pW1%fdGq7DQn2}5-wb4oWS$w~U#y-)Eff<_z+Bn*HaX0iPF3$|At zRGh5*Pr3=g48y!=(6!AXc`&>5q_OI_7+Qqrawc;HGaf$zp8F6x$$iCwnSqC|Sj<4! z%}tI)Aj&AkP-@LDu!+>-n0EuyA@4dOAQNz&&kGfOD92(x3AdT|*Kz0`o3XgV-+}wc z^eejSV7Ei6Uwq&jfjYwbK2%GQ>$mf&Rowdm0yT}uQmw*h8H6|cvq&C7guiq`i(j3- zKHf6ou?WaqLW&v`6$tZfX^u>h5D=jOzB^s*xqb#39V)%&+8l{*5N8hxRM4E_poF#%w@`6*g zAQNxmUAW->Mc&=sgYYGgWquqjc;wyf{gKT9fco=Bs-(opGlWFEWtf+GxnBsv+*E3 z?^VPC!nF$^n|ep*U?5GbAmZvq!rn202PlxW#1o@q`7og>(?X14WE9crNF*VJ?=t(7 zE|m=OcNnSNNL6-;>}EO-*knc0c*3KXz9TF6dME-0uS=W$Mq{2tCd|}GQ(YmiD9cda zLyF$A#Mq*1U_g3sxM=vY2(NgdluMT>dd+|0?(waD(pPYv0_mo*(HU-JvAUlePykBO zU0P{wK$>sYN+OLc2||vtl#FQjBKbUm;bHgT4P3rW(Y||Ue*u!sjV1kkkom-ENHn=g zYoe>Px-^2ky%b|5Xi!H{dgdph9e|X5HIP1^Ib=rB#qK*x2as+G`FOe#=iIr6MiDhy zF2TnRgc1(yU7G(`K3N&hr0OD7?=^K3TMFQ)x!KpqJd@-A9I&G;%C9B<7x6&c*;$^SyVaqwQKZq{3h;EL5yGrBa0B)+wY(!_J4 zDF;07it|xTUNsR9CL?{$7g9CjbKIx}fft97t0o?SjnWo9lz9Wi)XU@pbfBLAMd7S^!*IFskv?k0id+xuGmG zx_E_2c%%6Z-s0IF1baZ5vwnE)cBLSRbPdSiTc>y#-E5QA6$uIls5YD+P*$KpstsRu zS0my`KdI{h)T&fB{=}hmKt{f1pqk7{hUGD2!lPi4_<)8xe2ZN(0t6YutbKaDArckI zTeZ_^aJ;kDAU*G;G&Z^wH_Ux;vVs5@CZy8Q9;tX+amq?9S8`n>?O#)6l#K8IKfgm? z1gPmEd{^>qX6s;KG8^K_Eu~WgBFSW+#-a zCXzbKKZI^k5sM7h$miQ4nVtka_$|u2OtrEWT;@Q=dM0o|&fiwvWfZOaL^?GJ>TA*? zmKNmA1OTK(8GotrL_CTpqoK%;nFF{;<#U@#2~R+48)00fJ}Mz8@alRu@yReLuoJPe z82~(9q7uau5GjR`T!DFm%ezeR@ZN~bm?U1}U``t>smFG`PPY~wc_e{I&945Xq1CTp z{jiwT2}sYx$(6@*9x@7FN$n`NDUjTCgpj5Kq+Rue$e4QbH~`Ti zuC@~ap+@pRhDScQ-GD3}wc?fw(hld;US$@|GUS8kfk-@rE;dc}R-4axlXTo_SSk}z z4|gu?xQ_}1y02(B*s!^xl_xR~Y5(0f*KvzU%Q#4#fXt?Rld?!5u`n$)HHevkw5i;d z9*QiZED)*s)9HZjQzj59D0NtcLndJ@>`9vtep72lb}-F(bF%O@Hs$Lq#RD3dJ}0x% z>b|y0$Y{%3!J5@YR@-yI7eFPQ!U43C@%){W5e^H^=zbTOadD3KDEPd=lRd>Wa|V}j z-}?tZ{k%nP0U*7UN4{!g2{_xAiy=)PwzSmFeS07{Ul76X zChOnxH$^V2%n}4m7Gxz*A4WJQ9*DSkfeZoKDF{e1_)~a8UoY2e&}b$;pG}11cOx<} zKO3=Cqs5sBDTB+>#edJ(CZqH73uJUQPn-Y>Spbp&O_8mv#N7)ygEijOdfDtULX*NI z1yZUJiqWov4*(q|W|vi(&FCAttkN7M&Dk!iG}MWjCfOofVaSe6>I8M)5Ir)N3sq$#9+oXJ2-|QK zxSIb%<{KbgD@rboIkeZ%awpL;Y}m$>lb{3XMHbaZvflU|`y#@#1(2%8+t`hRl9t`D zxf{sR^J6PrqW3^jVXmmUWH@BLU<2|?0-*`KhIIrPgtg;w2&V1dHIiEZk-9v6s6l36 z?SI4cKq_FFx|-L* zvO&DIc;jV*ICffn^|C=6F&3I8s~&w+1GQujuck_wq*Cio?Flym@~azci;krHLTqL)aZP%W zH%+#%_$=Gm5%f!I22%EN`zyf!v+TyYlb0evuk0klwiKr9ZO=RpNZCtUJZ)i%>+U=D z^#e(JX)i9_1TReEYch1PZ6S>>HA`5`+;+1WD-f zh3ntbw0olcL`q(r$g}4+a`I{@o(PTd$6$sGyz1m+0kVp>rjt_uIe2-{D-l)(g!=vi zQ63GZLZ(asLPLECA-S0SKoo!SUL)-;#T&WTrjcw;L?zW>YTiiS>i4m!J}Y32d3c?n zQcqs$b8r;uyKP^%vtJ{jZZ}u5jHW;+yYlqm57~3OO;Mgo)pmMVMm2WO;% zbHvXuJ#G~xuN+@MnwWh(-sB!L7p$M8;6Cz6`u%Kf$9)Jj+`OaQwVLhiIdUcep~W^g zS&^7QSBY=b<3GPcd*xX#B|EVj7Jqhb*2)27vU*0q3=-yQRH|+ANSI4|dkzf?>2XJJ zrnYQkwedo1Oh=+1&Fp4l`U9~s{Uj4wj)GBW7Jku?o+H2v>2YaJ$=Q>nEC1>Xpke)R zz5=1(!hM*gcB@qR9PU6MG_@nZPjbCGfof7>5Bx4pNVcW{%A=foW*u(n}(oJtRtSz}(^sxmTIA&V}}UTKB|7&gWuh*G08be<)tZ&fYvBr+G*%0{X)i^}v3ga-Qu zV)Hy)F#%B2rJz@43f(LwU^y+3L-%6J*9b@jLd^~q0`>c}B|e#w9sqT21f*yaLYPle zVnUhy*R*M#{w03rv}qoQmi)ABK82F=^A~I{ylH!ViU7Se6-G(KFFidGs*Jt>hKqRm zFBwmnl&u*U&cN6;d2q)Q7Bl2zZ3G>&$+eKJL7o z8_CLBE0YwFljgKX877oZp{i{_3GZay$Iqyt;3OhLNgQ<^Ns-wWQ9X48GL(ByyHa9m zTW1VyMoyAb=hg;Nm2J`K%#qp_`|1^0sS;A#CZ%OnnqmM>a;igWx{`=C(VFr_GqY_~ z8b|#;=}VIzokV#JL}|S*Eej&aPf{j;D?(L>Oe4$Bmen8TMh{dPr&iX7CpiLWplpFm zWujC*Yo@;K1Z25NNOX&dg+#I*@2nj1cO|3^R(je<(*1_W-X*4NAj;3oT)0UM&lw1| z`F9xu%0z!opn6|E?Ej|gYd@W~+|>n>-~U8aa;`-%u_ zBGZ{hm1CW0chkF!XttkalnNE5ZO_1>RH)BdmDH}Nm2x0W&vM%Ct0+0@vmFs_UvVZ$ zOwH?e_M$F2Q?eZaCtd1kc$|i#8PR@j#Ch(oA~x{Dn-P;Fd1_T9XnVe&at}SflSx;vI7<@ntU1ky+xgK{m>Z?Ck}S#Qj|+N120^C?i7!k)FSovE*=fA)W8H zB9-*s*N_66n7h|&Fr`2|k>VSA4@q*~*n7~UVedGPT7#tPZ)Cm)qR;O$X{+JoHEsF| z3GhHXZ@gg-Q9?gjVeIF#Cq@d%5RJ_tG3aGPIxX?B2MfEfVnLI?W7C$$m7RadstLdP>M2+}}%cC@m~&8CfB> zrsdxd`Shb@Uafr9n#!Sc_1N8JIup=~9!COKO6ov{7Jo$%qGJGvr0Dt^X9G7~WnPm;Sz$gNXLdHb&JX!QhoYVU97^~UFT zH#|eeoJuq1ksKrm>6Y`mh_dEBnn94Mw{e{|Q%Prgb7z%w)NaoaCKPQ;*UugGee$33$czlf(?n`Q1(n4ePvNj}7j$(_^kJf9N>-TNJs~ zvg*&8A*oIo=HtC0cS}M_=1{_-($X}!zY6h#xp!XZp#r3do!7Ys|UDre!drDF>SY0_?6z*PhBp)TH$c?pPw^gyu8cc7?< zE}AD~fcCst{UAQDS))P*=q9sL$_JS;ohY_7At$u0NSB)#(rRW<@dIf#(s<1_>rcmQ z17xU{O;4$?z*NHS4 zZ*3Sug6JV@w39I)LA1@rIUgj;*sSRGgapx57HXOJiC|Yrkpm_nWi)0t*B z6fglsUV`fIa^LNUzv5j+ zWN>%O^)YQfM7dq_YoU#P%dUg;*LWWe?)&}5k!CJ3kL-$8)|oXo64K1g;0o1zBgyoG zrxpyK>Ggi3lzUYQcI~@Juxp>5K!|EcD%Yw!9H^ET+BZym+v8hH%KQ3ksh>?vEdgm! zCL1^+?`lTG7JpY7M+myoG(Fs1WSWlj{?c`3f!}6bCLcYu)@44zQ;Uh%-erPG`)((g zw9hLeAhtdQ9GK|Z>l;>eo{GDf>O2*9GwsNwDAP?odcR;0X`gN^d2~Ezk>t}maY36Odt27Gy=SK#q_Gx68o$zjEy!W%4K>O~7PN+0XS$uI%+3rk}rHU*yl8W4#(GCwq?G2fFr1ucnL12v3n}vdQz|seNAW zW_#>8H!!bPBjapBQDi>GHjuY`xw*1W8H9z5=UTm)vCkJ|#cV%or6VY!RyOtI^gUSe zV3+!8Cx5>B7~EDlww)`G7;#S%1pLMVH`2^%dp}B4KhHA#+nxesy&pBsCKIm{^z3&t z^Qg?xOt4B|uOf))Pk|36KEsO5p!1%)6K` zS))*D)NS)6B0SyAw__`xF~7KNCI@?0Qac`tk=M^u_v#mHvmBvNk`a~jWu!ERqANJq z;a5kZY!L1$D$v-=rp!SmGOo)Ru}xbur>T@9Ot)jo z!d^M+^69RO>FzpJxr{sBl^#QnT0*&3FQR-vupVu%&m>qcC9MgSQ>__ul(o&6ohq*} zLO+XAW>*ub>TC;Ci?#4AXX$-lzK-He=4tqdsE}H%`Ul9Q{KH z_tmA>+Z@}ObG_G0$f=U!H7uJnyN$>v&9NkuHEWJk%_!_$NjdM|w6^K5E}QtuxsvC$FPzw#VVld>nC6 ztyjirb^$gC%=OAQpw>$%b3PQcS#E~2sgCNfDr2T~_kIzX*7cAC@}fNYXx?+{9!gOn5H7)e}z z(B;B!;*xg8x?~JLJd#P`^_i%yW@QuIgNC9TCInt{u!)15P_#l57+0aJ20jct;?q14?0m0s3)2B7PPJA;8BzLjqSoopYG;S zn-=^iTy`Zhjd?t}S6XxOjuz?D7!kR98T4s-C;9RIEqT=FnsVHrEl<|lgd%?MBWg|M zwZ>2wat7P2M5sOrAYX}8N>(_RP9r`_z^BuMJqLUm7YhX)Ho%GONfE}A$Tb9J^BI!v zmez@|B8?gy4OYL!jt%y-QJ7{=qrXaz5yMH`8W1)0Mw51kArw-$NS;R9!-X;vth*w! zJkgs5c^b&iy2#UbqfZ>(0cZN%_8#BxCUzPxPY1`vnC57J?^U%m@Tq-^M2&bVILLmh z?5c2>cii}df<6FXGLeXJ*cOjXz?s0)g3wf6nUT%VvL*Lcm~jz=28tUf956IVY_ajM zB~a8tfKTeRgRukMtxlFGYP{pC1ydfIx99>e%NF?^M`iI!uLYHET1>oxq(c<-EkzsN zL{S$3zqM;m6m=)>yPGn7(?LKo z+)}Mn+zV74jVnE<3B*yqYYK$2Iui^c@7GNBMstf2`0?tC$$Y@UINZ^(l9c^^bi%{36*#ACLrRpm1d7IKz&&>xrCgIejjjd1 z1Kl|xjXFtDPm7Jj_ZPuWP#2Yno(7v8cdOO5yKc$h_pe<`qNkB@swP-{{m{OJqkc~& z*xBf-58b*%hvd#+=q6%$^l6Qwes{)2hlot0MjMPzIM2D_@U*f0> z^1VFz6G#1im*sBmGKizbI|V@7)M(vhD!32Ea}mT*XDNCH;i%u$xhCZGdg$;&NsC7f z4E+@_!m2}r5OghuIBE!w_iKYj4JW|FQeSMzxCG|1#Tv=PJ~7|>`i*cKrq(b-{xiYS7WUwqh2C8eZ-* z$<*+a816+dRdcB6r#l~cMeyZawm)H>zfD4?-=h{3v#RA3Ve(^~^+T_SSa^e>qwqN654 zQNNoYhI>=51fY)3RKt;=Y$)otbCmA@@|r}A zWmt2ajXB2Jt&Vll2Y&zh88DGuP>`sJ(bsRY$T`A#vzsX>Iq%1%13L|>|7^=u_pBMfRlkuYX9$WZ!sJfBtAi0q zU1XCpgbgkoQw#2N>M;c&clw<^v6o?WOqs^cojczqX9$W=M8r&2#T2lKe4*50q7{^B zY&H4~Hc>3N`N-Q9!IZ`xrhlSlN<*1HzYpzORA~_C+Y{{nE(ZyUPV0~=4dDv>eV2p8 zz{+AOcU1(Nz86ot5ib4yxQyYfju3R|_isPVa2TXZBUVBUASLP2y)qEO69T&I#7Jwu z7hF2kxCBkQbh)Xh{looh44t5pxB-`jVz~E^cZ41N90ET>y#hXNlyoX_y_G2GL_w|A zAn8;lXw)ESD1l&>Z=#W2rHr=a2>g%k!wz`~@c$CunCp1ugQbZ4R*v|D4N z6WLDWHePaHNe!`S@*t23)bTygaIP*x3*u~~J zrx^`L)MjK;gTngg7YW6WjT^>z<+&OO`sm0V1YO}J#yQDE@7EM(oFURV*{>hkHx>3B zP{g$)*h7l$x{38{MQB!BARg_o(L@`kny_*Er_s)XijMvT+L)$yo4|{51p4A86-9;HL$Kx5$CbfilvmXon0+a>j^Y zEJ2^o@MkK9NW16XYzA+hK{2?P1luA-#TNQv`*cN&Pud7E z?A1zsaMxMU-O|L61>btN(G_Fbhy#z^pvx^gRV$c!F_nn8pbW~y7 z$DgwJrYbqv*@_+rob28Xn=Gd>M;w{pWK-!DIMxODn3?S~xiHAlXqYMTZ`s=*|TB+P2YZ z8Ti`c(#Wovz4+SwL(w4JJo5^^Hjn5I3z)`I&>#e|&MjX>wc#Q~rXUhgu(Y9Q-at+^ zJMtdiUp8(`r>tgc)6wseI9-^_~Z;z?{zP&aITtTHLE9mQs zBSYYCj_a$Sr29_WyGe@uzSTF~p1|!&^W;ne4*=a94_4W}YZ8|W{+!6}UD3&zRl!8$ z1mCA&+vTWjeYt%a-kdZ{Bp>&Yf}invxv9-IB))6vT;8OGaJk8T!S;Zid+}-xvax3{ zt4jE)auKT8mriJ*4k_#BxP2ntF==}(z)-n$X!yJ*~{;?jq^pQ%)xtkiN$w}SUgMLF}fh!=5MD4aCR!wyi?GCXkv zE?f;G#Y0r>F+lMsi6ylv8#@TNP{Qgg8{JD!3lHAB7L)>!jZMf~*%+f;#a@M?HFQJ8 zxiZxvk;b5y^#d4A-x6EO`tda#_oecL4Vp|U5oh-6hxSc~_(LTET@o~&wN|FpNrA>Y zQ|S~8N#kA1X?K9e_0@AY5rB$wXozs8go=9+&T$S}o$GY|-84ZF8I$!1MdL?yIFhEI zsu0}V%^gpZd+%-KO;9-5xgbc$xEBbGDu4Vl&l3lpxVfJcnNorp#T3F138pehe@)!ZNXka;1NLb#-6#R0?Oj|_T@9l!+yaVUOP8NYLA~gZ%aVAe zfJI{)-)pCiivU=8Qb}6$gd!IsqU!=*&d|ONT=l2$vF3yK`puOHes74^|!6+mT%H)qgYq?mM?MAh*^vwG zTHGqfa9*?2_e9AZ_O7UJXbwRYboD)-q7FNbSwhfUqdD%v5KeP9sh%V(lkVSr@BqnM zcQ!7%d#7cx@ZrlhJ%WE{k0Vrye1e%RP~IFvUCk zlW2F%HddOhEzR9TUg0tsT7H@)IXr~<@$&8Y<}|q#=)DA7g*^Ct9|}CQJx%ibA|fY2 z(daNuvS*uZLgmXVp3u2!=Xy&cr2N_(966kY<^wz zqTb)s>4>O5s#u@dGz`J6-Zos7#>pQm+Tb9hz8^KJh4(3To9d}S3#@q6>6^W*=ILLM zenF+b{0nvn4BWW5RhAj_*vI!rjZ{M?7gj2e>(jlbYPX%dWpjHKs|Dg+XEk<{#|~!m z#tq2zEo_`|@(gh)nT|UZc{WX9!?&V}HlwzT71w%CR6YIMmEq>2-k>$l2WM~;+~@9l zL7kocZlUwJI4WSu|In&*X>q3<_~N1L7yN+??A zT-hd1I)gGzJibRJ*RChKv2m0eczpRUODXnRS3bpST!G3ST{{rFjXW#bsD<`6T@gQo zy3Cd6>xU-FzFgatQJ>>ZJbd@!XNw3Y1Y~X%9GB;+^RYz3+-i()NNh*l4t!wucN_1H zA2u3_X7zAX^w#f1XAYofIl}u8B=bk25Y+fqF8Srxr)|c8IY_HVWqeX=E+T*$0g0*BUsdT`8`@P3w-~o4)Ohb%D&M2*Q?&EDDwR8Ef)d)^H#P1|KrRh zX@0wvg!P3pA0YqNQ@#bPdK^WU*VE551YOc3fd119(r(LJAtj17hR_OzdE`TG)RC&a zqJgGq<6qT$hW`4bbNYf7tZ%IdQu8Omw@&=@hg=4D{m>5Mm%5j{qFzeWt>(Q@>+Tgn3KntWAEM zpBTr6&o_Z%!_L_C#i8gk7u;Hr$*=;J!I=$y@v<>#`02C7Jt5d+R(M1<&Ft`JsH<8T zKux&t`()*{6UL9%mxp4$h2Iw7)S0yTtKwaIMHsC2$%d40uqE zr^1DFzlv#MM=jo{f)E^u>Z_b>6mitjdZS;T()X{3OK?0DhN-iH@ZEkdhfk3T#-~!w zkA)cbXDZxTulpCq1@-c2626j6o^Y&JXaYC4nI^s3v%f9OrOtPg%WR`L1iMqyq`vIQ z#Vf|ay>t}aqIa7`_h>ee2>Ze5Q>o|Y3+j6+;9WLZF}yj1p1*z&OP#(6&$gaGgFP|UrZQfoPmC% zs@Ln;XDN&`(2i^{+c`g8P0^b~l?A%|uo-6ytvNpVOjTlJ>Qk`0r|10op?ynt9`Z<95(;3fyZ>_Gh+CfsYbM&c&>Iu`-_AqHWpHl$MBj@(f1>x%Y`AvF{PATF7_5RsHI-@Zi71a5|t%76v zPLa>J<_P1maK*iDslI+_BO^V0KDR#xrbOpk9n&?Mh2`j}B2fvSd76}uVP{N7 zXqrq%C`?-T(6i_^d#-pFpMKC7(_0CX5sr6&Ofe%W`|!&U0Y|^i5CQ$u=2$f%>_2Az zVUuP{SvK`Pl^iX_E&~GsbEn| zh@q$ly8a4J*CzKh6HOsJk4WP=ocX|H-|pq!&z#mlV6!RXOk!7OH}JBMLxQbc2|UzW^hYX9g`_0KiFdK z%sygntMFj`mGp!?*H7iP;mV-RJ1ROBzVh_7X*&|{wsd2cnXaQBIs2`9XWV{MV*GWA z$8Px`74stxl2*w&bwA@@I-dKmAvsYeYvRkZ=7v|r*_)dRee#ap_~Izo8ty87;_la` zs|B$StHLg87WMFtAJ(VI_dm~iR{$RhuM+~>Pjf;3-OIL9K5Zt~%No3Xo8NgLJ$*&i zHE({tn&Pz0;2%EAEn{tLC}93+&TiZF;r))L)NRhOF%=P>#;K6H`^_0=`!j7DZ94DA zSu4p_RFx1GlFNyf;WPhImUah$;=F?l8}XbD2kBy)O|vUZ&y-fe3%{Iw`DytRqepIy z*LMZ3YC9Hx??dt=L!le(b0{&l*6x|wv(%$WXPZ)*5~S-UV&gm(hW6>+%sAXOo%3jY zhjpPbNiO!@DbEv+pD16y(au?xsZ}K)C_Mloa@Ix5an9W8p^gIZL}9nLRE1q+c?-+Se^P z=yB0Wq&72PhS1_zmA{>ob-%3Z66LcV%MOcmr8nvdXr#BfCziPv0frVFQS&AU>^wzI{t1v<;lN3GqWdFOO-YDxB)Ec0g-l}#l&4;)l26Vl3_ zeL4AF!Y8nY8MyqNg}t6qllo`1`^4?5F7)r*C=+b;oX|b9N_=g-U%fw5{8}_!?W>BL zv9iuQ4W&(%o+a*N>-caFIvgXjae8(Cy^7F~)_mUvp(Op!U7NhJiRJfBgz^s5w951w z?YX{e`<>E>AK2!tfnxcceFt0j^$H97*IS>S#k|zt(<1DM>}!0Y-}@r`N@G*1e%~#F zS?zVcE3Zq~^VaRwKOfoK)DhVwywLx(FtVqrFtV%hNnOOb+E;#yK6g$Z-=~iW4=+#| z-&^T;uP&lj#Y0-d2w^k%0vc6cUz71;5=fpalTt%1#WrB`S;Ki_mbW(oa1Vg)h5@WYxO|pBhwc7jV39xv2ObuXjkT4Tsp%pI zRsh2PSvIf;gJTPai2ETN8g*DU1Ofqz{tT>pFohxE01pO#MEn5hG2X+R8>0?w{}1Yk zL?SxV2yO$?Ml5FD%+jV{>REd_j5$y;K5W1a(;a zz}ET=QKH)aKNgG;e*t|Y5=Q9MVI)|uT<+++VsNcvZB=*xwjxaayjMwtA8-Kap~aFY zW{U; zFllJ9!zdpcy%Y+%yuZgVh4lLtcv1g>-+wm>z}JX*2sGjd0sPawfNHgos2i=bMQXx| z9)SEtyBmUY863-+cpM2!BH^(V9LXIr^{4yru|y1Hz-OR`GbjY-DxGVFuzY+6v*@va z)}cKykU2OGSquZVk3Ry~2H6Xc07onpkAW;%d_GX4B8;J%9gG8x3vjHf4=Fv!8xlYv z8X`hXS^fwCi${er;;a(o2bTz12oN4hp#U*PfR0AMY$J8E5oCd|eFVN(3YDOzH)yhi z>@~SpyTU$jPUS~_jZW`PL~+WA*LxAg854Hf)XtD{vE31CuHe0*w8Z~z2|;*(T*{M) z*vG$n=T6P#j2CznS1+t#a)yKa%*P%!v$GPlFb!*8%b(K9yj684jsoqFZJ9RTe5UV~ zPlvs?n!3AuT$}cBiTU~YNzk-tY>P_ala>v}l5!t=zxD-$ESskFJZ5r)D>juW> z%&Rqy(29|rzSzZ7ugdS0du-=gnMwughPGK<&Ban4O+vE^cE`o8#E@}>l@1fqrLSF# zyLMDOam9-xCmw1VuIw|o={qjvu?+0JGjFD{wx*})*OLi8b?F~hN7j?6@7EV7Ph5`( zP0r1>iPI$Nwkv+x2FLc4D{GzF)Z{mB+urL9r7qL@wxl0A@1WYPJb^x^q4bn=mh_h# zg70#^ee#(jEfsCrk4>tVzjbUI7Z4S^U*V9po0v|YcvVqcM%S4gd&T9~dlr_{X}R)D zix!uiXD5Y4$8NLXZBM+cn@a91CzkCww$*ye=S3O9^WtH~8LZGrt(Ew+h2w&`&uZ^3 zVKgi1-?xPB-_-t|`|L{vSrCK&`g(rc zyqiaDDkI_MacKz?)PrNBEs|rSUrpJPxiR#L;N+bHr*#S=PZ5P)WJBw7R`qv!jdHd- z&7R4ftI*87A(3IVAVu};WTotfwbNe8z z@S&tqS5jSGIyS5LB&lLTG&S_ya?_R|xTT59t(VcpyvTa^CtBne6J$t%z(C~@DP$~}N*z)l zFad^fKePy_8L34?*B9cd{6guPud9#8M$TyVhi?AUM8-cj! z1;Zcl77V0#s0xDwYdKID!sComJECLchY5xsVfFuWwFBcQBlQllJ;1`=N4~P-{rE70 zi<90iwtrq;G*#-dxRUK*1&*9VZMfv zM_i+{Jix~$e%1jQo86ufA*vN`uX!ycPRP7m)4xt-VtL8Z7v8=R<1g8KIr@3cU#|A< z3sTI2jBnaT<4BtC_w`5M`8?j{6K&~}lC9Suax*>#=is(uicQV)1m*E(ZAuO2Eip2a ze>^)kO?GE`N|O@fs_J+RHR+r3_^qY^Si4Vl@kh68x&7r{%AItLTVGra4>%?`NP6ru z`XD8)aetBV%6@BE$$0slh&OWN&|x3!^*A$SxwtET6wXUFlb1{MH^?-cxgB>U5r0qO z(PcAcD*Rnh+fdx*e-LOf3M=2Y1wM6qXT`SPb8ZGTu*0+JY5MBNw$l5}JJfSnI+kr) zy%lpVHYR=S$u8|_Y=7pqx6_KgqLjYwMNobFtl5)HzLd+jETtFEYAg0GzADDe{r-Jw z!G=la6@`~(=_{{zHhV&@<>c0VGkn)=y!6FW>(=wdc-CzF+!Z#YO;7OpOFG1?qLPYT zjB8rlEv~M)if8I?n6gWf($V`zhKD+h{#rh6t5uh`ibczV<3z_#f!jVfbgZ=6JXOn{ z0@Vf`v?U2c<;=Ta{D zrDufSeNwVP%t{wwA4to28Lr+FFg5EDE_vk>)tQf6tfD2$V2SqVuB1p6cL^D}YW+?) z*DOc>kLK&h!cfceFK#M#Kcs|AtY5^B*>^^5?Yr9z4<^2;_z>3ib!uKHcv^c>>?IXk z=d|M6F_o%iQCVFv{MYb{2BPBZqnqwcz{i-rnGim`Xv1O2{L9ta)Zha4-fBbOOD#6VzvHDb%^=?2*;QAuf9BYK>0zLy zL46J9Y9qrhmQwrWBvw=xP5UnPcD3gLPROVBLZi20rV^cboo~XcZc6Obt+@2v^&7rw z(fhg~Lb8*(31bn^H7sqYKb`;|c z;vUYoOp|-|EIaZtPkmq1)7g~j*31O=qU$qY+2S(R0g`rD@e=I`27TkdDRiihp_zX+ zw0~#cjd}eU)Xq3y4Uw=Em^`GKe`sY;I8rN%vO`)KsMawJI~WGa`fn^d(G_NtY8AOB zMyOUa|F11NJdrfQqGK>U>0X{p=Ifi9)(O^kHSt8Tj}8%LgudtW-Pn(>!y=7Cp7b3K`!zB%=KoOew7 z%Oe$hn`M1Q`V`931*9YMlcS@fZR4Ylr$ommCtnpVn^;$sU;88yf7_?#>&Y!$adp=E z_tO;jP0uUKFI)1$wJk!w+i$`B>PNNDYOmhcIUZh8V-1x&n_jLa6bMT!ll!wiG{&|H zV8+@{)x551&$Vw$SlZox7EG?;tyiyL_Jwiy@P@G@A{k30;(rAQC>#k8QFaI*nlLz=$Ak!V%u{>V_7~mz zMj=Gxz8HZJH2<#=LLgB`AVl0v{7|2`n52Z5xVZS_0lxrxS4Ok*JC(#c=SXzU8J8H< zS<-1WK5@#p#3_=w!YVnT^fcjQ8KIP{*f?=<)y1$8hZ`!g8nEg{8sKsQ!&pnYz}Jbx z^W!hZnzI={MiwngOiWCiBqkm&CLt~^dA4)2bmya}gTlJk;==Z-l$LSVPRxh{PX;A! zlnTv=*`1r5m7k)#voJQKM5t4@xgjiZdE&;zP4Urj;R#WR8>DPbGA`t2?>n|%`A~8C z)x@n*J7W?zM<>Ls->e*BDsWhxC>0#Ft6+ChR?=RTt*P5~C8j05=~muhzxC+8{KJPc z&z#7~I=MG~)8@#;O;V9N1bO)fa}K4(W&2p!xOjUgFSF&Z^NHM+mVR#g-sJ4`vc&CD zdn0#-fv;fmiBXmgI@qOuu={XY+O7%R^t6e2n1_>zx-RG;i=R@Z6Z6(cj$*u=T;m58gj@q2SUwhxFcS^u`N` zlVbE-y&kum4_|s$CDZtjMX zsH(QXtn4MJ>dAhGS=u~mivAOx5lzL7zw>(%%?=MZN+@!{)-#k(p zqL`GgaCWJ1Ly}KNra^09$y&p=ldjbUK6w19Ksi@($-NzAWkrt!Wm*retYIh3Rip*g z8swWO7@OdiH{6~^@7^r&;_5M1CzY1tH+nOR0J`mYg zY%>{IowDq&QwPFrR#z?jlJS>~1?O~X|sCY#SVy}4u7A-&h^b%L$$0&p-$=};m5sK!i_T{z zrcg-*7b9|4DAk?HblbMVMdn?rzVGfW?CI{V8n;gOEG@mU`DE&e?T3qYOP>TNzsL7ft={eT*CxeImhY##Pmgve zbnZ-BbBGo&<7{XFa-&PPXWpU<5>CAY9jo&D;Z}VI^EG>}30KThN${L_w!H><^8UD^ z*s-*X&zJ3(vMSQ***Ep%E%#Y6>{57!d8ypOCLU1QnEah~()i+)v&qOj1&(|Rai z^uvecY-us%z=DY+5NQ~^r|am4a7CI3>xKBR*t+0zE*I3WET*oS6Uh>1$u&ZJS!Q88 z#6HZ*ff44%pfT0-^)Nd6bP%gUG(+fIO>dFsjE@DHSXb4^&caj`Z4jaz62J`raVu;{ zfIpkB9ipoy>Y@$OXfdRQ6*Up~>8d$f+F%77j=vvEfW>Rkv|vq`uo&yj1K!28;4s9( zT4XgaB#-H>Z3jYj0|SDbu9~kvz}1GJwQJXEttDu2cs>wJqtPH79>U`_K?_ZOC|f`e z(PZ=g0P~3mVL1g0*na&_qKA3yZ_Xq7&1-I6(qkwV)stQ=7=7 zGH6~n1|Som0aL{r*2ICACIbOhE|u)%g(o3H({V?TIch#o0VX5>K7f=qh)FVo7zj^S zZJCV)c9}1SFBmx3uz(#nHE3}8{}ok0He+)E2y~DQI-rfVC5TmdhZ+N)s2;FS$eK93 zCZ6N~lfaj!Y7@wdaIiKGrvv@e5(po3H3BhR;7a`mT}QMW(Urq<0FcmAw={6DFfd$< zb?`+*<`IgB0rN-;>xl69sDP+iBrTj4Orwy&$-YY64$w-XuhP)MT5}N|U4Vw$>_hp$ zcdU)IV6lTjGzMrEO*}Y{4und11b_c)j?=l8mVeLlfBAN9{>dg6f+sx-W*;49qbMebOGLaz;F&50;pEg(*czN z7O-;kM7!6(UoepHXQ8`M+n>(%(Nzo4WFp@5Ab)|H9wZ3hLIN%W2jhV(y*)@wnzsj$ zOr?3ysW_4ciHa~8cm@e!coDTgY;!x% ze>cz%y$pP+x@v1tt^132b;NCVNP(!2r9U))>4|PfAQyB)svB#gyBUYalVB1E&!QVy z4Tn<$&A^8LUs?=q8ueBGhn=}sp`jTK8 zh&_*PN2TI^Suc@B{)HAQo(z0Qqx%wJ(l7H8Vd^hsBpUks#^}Bj_}6)5ai6r2g`l%ghj5$aI;G!7aj) %1.3f\n', ... + T_1, T_2, 100*(dp2 - dp1) / dp1, dp1, dp2 ); +%% Teilbild 2: Externe Kraft +% Speichern der xy-Daten +X = cell(2,1); +Y = cell(2,1); + +% die beiden Versuche durchgehen und die Daten laden +Basenames = {'R11_cartesian_stiffness', 'R13_cartesian_stiffness'}; +for i = 1:2 + Filebasename = Basenames{i}; + figinputpath = fullfile(eval_path, [Filebasename, '.fig']); + uiopen(figinputpath,1); + fig_i = gcf; + ch_f = get(fig_i, 'Children'); + % alle subplots bis auf Fx löschen + delete(ch_f([1:10,12])) + + % Datenreihen speichern + ch = get(gca, 'Children'); + X{i} = get(ch(1), 'XData'); + Y{i} = get(ch(1), 'YData'); +end + +% zusammengesuchte Daten neu plotten +fig_tmp = figure(); +hold on; +for i = 1:2 + plot(X{i}+T_Off(i), Y{i}); +end + +% Speichern +GesFig{1,2} = fullfile(eval_path, 'StiffObs_icra_Fx.fig'); +saveas(fig_tmp, GesFig{1,2}); + +% Textausgabe für Auswertung: +[~,I1_1] = min(abs(X{1}-T_1+T_Off(1))); +[~,I2_1] = min(abs(X{2}-T_1+T_Off(2))); +[~,I1_2] = min(abs(X{1}-T_2+T_Off(1))); +[~,I2_2] = min(abs(X{2}-T_2+T_Off(2))); +f1 = mean(Y{1}(I1_1:I1_2)); +f2 = mean(Y{2}(I2_1:I2_2)); +fprintf('Steigerung der externen Kraft bei t=%1.1f...%1.1f: %1.2f%%. %1.1f -> %1.1f\n', ... + T_1, T_2, 100*(f2 - f1) / f1, f1, f2 ); +%% Teilbild 3: Kartesische Steifigkeit +% Speichern der xy-Daten +X = cell(2,1); +Y = cell(2,1); + +% die beiden Versuche durchgehen und die Daten laden +Basenames = {'R11_cartesian_stiffness', 'R13_cartesian_stiffness'}; +for i = 1:2 + Filebasename = Basenames{i}; + figinputpath = fullfile(eval_path, [Filebasename, '.fig']); + uiopen(figinputpath,1); + fig_i = gcf; + ch_f = get(fig_i, 'Children'); + % alle subplots bis auf Kxx löschen + delete(ch_f([1:9, 11,12])) + + % Datenreihen speichern + ch = get(gca, 'Children'); + X{i} = get(ch(2), 'XData'); % Messwerte + Y{i} = get(ch(2), 'YData'); +end + +% zusammengesuchte Daten neu plotten +fig_tmp = figure(); +hold on; +for i = 1:2 + plot(X{i}+T_Off(i), Y{i}); +end + +% Speichern +% Nicht in Gesamtbild aufnehmen +% GesFig{1,2} = fullfile(eval_path, 'StiffObs_icra_stiffnessx.fig'); +% saveas(fig_tmp, GesFig{1,2}); + +% Textausgabe für Auswertung: +[~,I1_1] = min(abs(X{1}-T_1+T_Off(1))); +[~,I2_1] = min(abs(X{2}-T_1+T_Off(2))); +[~,I1_2] = min(abs(X{1}-T_2+T_Off(1))); +[~,I2_2] = min(abs(X{2}-T_2+T_Off(2))); +k1 = mean(Y{1}(I1_1:I1_2)); +k2 = mean(Y{2}(I2_1:I2_2)); +fprintf('Steigerung der kartesischen Steifigkeit bei t=%1.1f...%1.1f: %1.2f%%. %1.2f -> %1.2f\n', ... + T_1, T_2, 100*(k2 - k1) / k1, k1, k2 ); +%% Teilbild 4: Beobachter-Störmoment +% Speichern der xy-Daten +X = cell(2,1); +Y = cell(2,1); + +% die beiden Versuche durchgehen und die Daten laden +Basenames = {'R11_torque', 'R13_torque'}; +for i = 1:2 + Filebasename = Basenames{i}; + figinputpath = fullfile(eval_path, [Filebasename, '.fig']); + uiopen(figinputpath,1); + fig_i = gcf; + ch_f = get(fig_i, 'Children'); + % alle subplots bis auf shz löschen + delete(ch_f(1:10)) + + % Datenreihen speichern (3=observer) + ch = get(gca, 'Children'); + X{i} = get(ch(3), 'XData'); % obs + Y{i} = get(ch(3), 'YData'); +end + +% zusammengesuchte Daten neu plotten +fig_tmp = figure(); +hold on; +for i = 1:2 + plot(X{i}+T_Off(i), Y{i}); +end + +% Speichern +% Nicht in Gesamtbild aufnehmen +% GesFig{2,2} = fullfile(eval_path, 'StiffObs_icra_observer1.fig'); +% saveas(fig_tmp, GesFig{2,2}); + + + +%% Zwei Einzelbilder in einen großen Kachel-Plot +close all +% Beide Einzelbilder laden +figHandle = figure(1); + +n_cols = 2; +n_rows = 1; + +axhdl = set_fig2subfig(figHandle,GesFig); + +linkxaxes + +change_x_data(figHandle, -4.5); +xlim([0, 3.5]); + +set_y_autoscale(figHandle,0.1) +for i = 1:n_cols*n_rows + % Grenzen automatisch ändern + axes(axhdl(i)) %#ok + grid on;hold on; + ch = get(axhdl(i), 'Children'); + leghdl = line_format_publication(ch, [], {'without obs', 'with obs'}); +end + +% links: +axes(axhdl(1)) +xl1=xlabel('$t$ [s]', 'interpreter', 'latex'); +yl1=ylabel('$\Delta x$ [mm]', 'interpreter', 'latex'); + +% rechts: +axes(axhdl(2)) +xl2=xlabel('$t$ [s]', 'interpreter', 'latex'); +yl2 = ylabel('$f_{x}$ [N]', 'interpreter', 'latex'); + +% Vor-Formatierung +figure_format_publication(axhdl) +set_size_plot_subplot(figHandle, ... + 8.55, 3, ... + axhdl, ... + 0.14, 0.01, 0.18, 0.17, ... % l r u d + 0.14, 0.1) % x y + +% Legende +axes(axhdl(1)); +h = legend(leghdl, {'$\kappa_{\varepsilon}=1$', '$\kappa_{\varepsilon}=0$'}, 'interpreter', 'latex'); +set(h, 'Position', [0.4, 0.90, .25, .05], ... % x y b h +'Orientation', 'Horizontal') + +% a,b,c,d einblenden +annotation('textbox', [ 0.02 0.18 0 0], 'string', '(a)','FontSize',10,'FontName','Times') +annotation('textbox', [ 0.50 0.18 0 0], 'string', '(b)','FontSize',10,'FontName','Times') + +% Position der Achsenbeschriftungen nachjustieren +set(xl1, 'position', get(xl1, 'position').*[0 0 1]+[1,-175,0]); +set(xl2, 'position', get(xl2, 'position').*[0 0 1]+[1,-115,0]); +set(yl1, 'position', get(yl1, 'position').*[0 1 1]+[-0.9,0,0]); +set(yl2, 'position', get(yl2, 'position').*[0 1 1]+[-0.8,0,0]); + +% Speichern +figure(figHandle) + +Filebasename_res = 'ObsFeedthroughStiff_compare'; +saveas(figHandle, fullfile(eval_path, [Filebasename_res, '.fig'])); +export_fig(fullfile(eval_path, [Filebasename_res, '.pdf'])); +export_fig(fullfile(eval_path, [Filebasename_res, '.eps'])); +export_fig(fullfile(eval_path, [Filebasename_res, '.png'])); + +fprintf('Bild nach %s gespeichert.\n', eval_path); \ No newline at end of file diff --git a/paper/figures/ReactionScheme/reaction_scheme.pdf b/paper/figures/ReactionScheme/reaction_scheme.pdf new file mode 100644 index 0000000000000000000000000000000000000000..121778ee6070853f24eb700b5d70d36f0be6c75f GIT binary patch literal 42113 zcmc$_Q*@=>)-@X2MkQHEDz@#UVpMF~ww;P?+qP}nR>gL5^6vfZ|LlX-{;Si@&01s3 zfjRpe&&{)XUnFwEzi1d}nP8Xz^Z*-ua{xCt44s~(t*IUZJw5%m2cQ!Y05AaP4D`M~ zd3j-Yc>zY&hToYm%>PxP=w@pKpp(;cbTqQJhWU^2uT_SBTr+FOe>sdWbc$w{X4WSE z@dO2JTmc&2o#+AI8v>XCS}=5~3XVp$01gfqI< zf5HE6lBo=3oW5ZkdcrmprOqu#L;6Cz7~#Oc)pIGx{f=pTBlb(I$vKstEZi^Z**7~Fcq9c z+It#j$Sbgfe^4VTvN6Yl`}fA}>DGYxW^aS|Jp_Nvf;?C5VDW+BkbHHY|HWcQ3tu+l zuXSY;VumR>zJd=F10iI*MN)I4$07%Y82`8k9U1{;$pMB^$;oAxLyYu)1Abndxt_5;4t&p)4u zP=2p?a6!E@Vg%%rSbp}9ZG;`W{020jc9uxWXiy@ppZ0<7Z@D)&GeG2hxPSd!o;TUi zN(#+k0{3n{f~F9I1)g<320oCsx{>_73ww3yNXL}$B8B^YtMc_!e=;LsvBUYC_2z6F zJP783{%+wjVFMdmyubug@gayIf!RGnTwZ)02dxHq&vyth@SD@6S5-!U3w#6F6`)6) zsXoBy<-OkiHA2VI^+lh7xCVI=90G(W)Y5xH2Q-C<0|cqh@Oe$Y@x}VC0m2X9R{?{A zb@Xc|mh<(g+h4S8=414}#S%ukCdHEFhC+Hjdzl^uo~BV@9^-l@c-rmDuLqEyA~(o$z_N4GQ>6s~0NrnBfQcGvdWX@0>2yC*`G`PZKZFG7Y5w4%YUz+h^H6E*7v?jt#t`YZU&Vk7BZ&_uIK zhmE7NWJ9~i(<15OToV~HV`3_4-%-7zW}#>{C5!e}a`r)LMP;FBFQH0nH{@xXU`1Ni}0w3R|U#dR%?J6>n~LC1&G2;M`rL&)0pB=N`Qv7u*JE&Ry(+Zg@9mXRRr zM}N~{1O!p++Ys88hdE&&Jq;HUNn2-Fl+odR!g^WipYLm{&nxGut)YlmThW^RrIjY9 zwVnfs$rI?&t8dAqV&3LtwlfIXs(CR=P`?Vae5y7iJ)IW4Ziba{jfD6l6uG+GInQqX zwwfvlHzLN~|6Rj=26VIeTSKz-Dvip0`4?ZD*H*mFjzcCV8=??BxK`IuQQ|`x+Ft2h zN&a)gf?CG`yi{zFWLDS~tpj||`_Si|9 z*=tdpfCE$|6DZ4wEO5wb~u#VzIuL&nTvsI&}8*R~D z+ifO2Xl`im1v%d!DEmb`Mm!2pGKe)?JGG8Fzm20h@tI?4ss9%-P&^0|6$T=0AY~uj z-RUi&_A~7U)9hg-I+LLofqFB{ElzOyBB<1#mE{J1GwHQ7FL>zkvQ`mB&so3Zyb zPbs$+t_|gy5mAm^6f~SoBj52>G0g_4r^3o4xXhJCw<8dfTM>r;nK7L`v0MgUnM=@5 z@6<(aa^JH+PfHa$yag!4rrri)b4A?s!X%5wFvLP{`3)(|0~cx=U~$z(wi+mwhC062 z+uZi!`knVJR{Q4I$;#Nsa}>~GwK}krMK{{r#2{dM0%6zZ)dYssoh_~@^1nzQ;zG0s z4wrs$$0V&DCh=%QQMmA^z-5h-Kn=!UvKN5MF`%hRt8|q%fihvQ?Mj^^KGHKDY!#R^ zWgmsrCJG)wl+4<050)C+1v}!*zbR&Q<%Wy^p%_;mVF|?wc9_p2i#t;VhE~QAYCSh9 z4Gy*ZCCtn9*oWZH*-c8BTlLyLfBRd&9jkYsi;eDNvYa#*;B9hvwh z{;qArx-j?I6?o8JquSl^L5711*c#z#f5GkDQ|>nlILdD%n2dw4yrb0ylLyk+h2E6R zSuSXx-g?jv+ua_G$T2?Xr&NOKt83#<>QIu{a>MRgL|5@Vckz>4aeDYdOV1UuVa@`+ zkR_Q*!{`BVeZ8Uhv>e-l30!$_Dp4;R{mWjY@`N3N#b`HX$*Ottc|7zgXP-;=#lo=Fd=+`hV@@P!kbJ6>giJGv>-9{hXxKDl@(v?>=|x8 z$-%5&`=rHFWpAR*Olva8gA%Vho8cNOiJwoc2&Zwld=vz#!SMOAuu5^{UE2k-Sx!)t zmx)OpH#NL)y9yASWLz}tFvo7o5E;gf7ezTP_9M7{CVPLV88i1xHXt}wGa;VlB#f#W z*F$Ts^pjAt5RLIEysGjJliGe&ZB|B5)FLL1QWU$*SOCBfJr%~%9!u}K(x8l`XwaKj z<5d7|?ZiMa@tw90hp2A!Q`wV1wuSYkst+)$5hhquDsyYUBXb0IW-E3$h|8^@1*#!o zxb-%TnzHn}N~CtCZKdcpMVw?B60MdewG^_kv;D<{IyLcqirE+E=(T1XbWEA>RF0pd z?C{J8oTw=4C$qQKf3NqKBzwdu9y&S*#4vF!MstQ1oC+V=zoH#Gpd_RAw`hRC_34b9 zfrnB_wi_uY@KsypttrB4@7v#*KWvm9e2BhgycP52VJ??QGvQsn^KzUPvcOFXn;iWt|n}pZrJq8w{;j-B#yHwGo7+tI~={BY=keTCk zv5n|DVB4{tzfN6l^h3W{h87gzaG6~zqTa;X8$EA()@@CSwa8qExw3UNVb0Czg!tC<4R9dy@;_w!wSk85qGaN`?yKVb!^%W04Rz`2#5~6E#pjuAd$G%T-`b_#SD{}uBOgvBn>Y#lG`no<+7SK&|Yft30OGQ zb7bC4z1UL7==?nIg2<}HrsZX;KLVgNU-^Ft+a9SK74_S~R^I%kc$3N@ea}K{T|9l7 zm)ohIVbX%+S|+n--D%@=JS!_t#Lt#+I=RfGqN$}8Pw3MbTh(yz2YpJJK0PVDzcUM| z@}|Nm23D!Ik-$fOgNQKr@jDtU-LS?T4`#n1U=~7XmFUhcZ7gn@A`_vAJVRnZR+}Qil}2ZDF=Z0@Frgu zJc1BhC7nI&RJ=d;#(IS0uKplnpqgE|AEXK(6nj2ubOcpt_p9*=Q$4%lxZg{cHyWMY z%AfF8 zo1=S5Xz5}!t2w4hXV*H{519=D-F`r2Qh-MR*G&wAtZsoqI3nk@n;J&n5U68Jji+RA z3gwYVJAjv#ENVk$XmOl}6YOBrawMB~Bakc3^RFTh#&fg1WC@RU(vY4o54(qyV4ONK z@xfrM&pkXeC+DG!qq>2OeKn8ox$|E(3S*5~0ZN7>4qg1i>@LAyb0SU~bH`fR!)!+l z|MnVlr|Q3-Kgdk!DeBoyiGwx2G#!hre!AclWEbtk+qhf29J8ZP3HuYM(Nl~4Dq=o~ z|29Q*BNN~$G^c5GJG$t1ZUgG=u$)dI43TVNP+HH3{DfP?%513f#9)!Zf~VqhtmWoR zKOeQk&B6>E?e9e?mw0t$y0-l{t&A5v^&oE2{aAR_@HK$@=UN4opL-~JuAg#yaygc| zobMiSl5MNyV(Ps4WM{X=uwm12_tT8sS!2JX8uZpmv6Y>NERaB*6jk*EOKN(7#UG}~ zJJJvrn(a}l{Onix#W}V0`A<)mmopfbE*qlX6tLl=+`U{CeZ5AAeTQvqJfPvmdBD?# zS2N~qNWxCltZU*-6mvPS0@Fj8?Praib5Mh_ARWXQN!tc?`J=TfaeaFf>9t zn-9D8llUqU?mW)&!x5@LYVFka617kZfEDa*L$uQ7JX>biM5fmGoAdJsU!LrCT?vH{CTyF_n31ko6EEbXMHEmbzZa0WTV_GxY4JDliw z8orp%|7@8}49%5by&_x4gx=&-iX^r5Q|ebhI^I5xQ^;jc)>bi3C7`X9dxQTDl_csE zXnAh&_oE(arM7;9;4fTK_iFkIQSlF~oC4AMRmQqqw57P*tLollml@YJLSrt2T$y^c zm+=0Y-4ssCt1de~CuK9Cwyu>ob{}GwHiw=Wl}^HxSX8CP9el9J12IK;p}&-m=up>$ z8gFe1uQQuP{zhrLHAeE4*PgfXaEnndy@5oj*!nA$*INa|n(i5&x`S~&W{ zpG`bezmUCtaqmr=35>zImc0PNi+&b|dTW>uL3v=Ks>6*^2P-`F0&#^^4G*^FC-ux? zAlSHl;0sZ4wmdsEjUN@e+=#5m27E=j4(Xs3oZ6S+Pu)}G{;!xUC9|~bAYB&TQGGI_ z!)J{-T=-0n^%L!$)FT$o_`jM*tYa3J?z$8glYT2y9baAoGidhURWoW)k?^i#irbd0 z;EWZe%3Beh&rn>f)Q0AKKop$Kl{tN4ET*VkfMz`E6|~x`T%s$ZsRO4|z>=nSB(r=L zn65F|V%s{4WPCcB^SdYB@;KK*anN@jZgwBps3G(-k~shIYkONP_#o#X5vhmBw&*8S z8D^iE%v3dQT5&L2Lz%IUz58 zP?AyFtG-KOQxcX`|Eo@jTTONAkffc!j4m*%K=Ub#vJ+brwPltbK&?7B?|7%4=o9Oi zO@Bi?A@qe;3;aiT@a@ov8_S6$A^VMeSZ_l6()aCT7U{2uNTKmaga3GVFD3cm(@soj z3kd>pFy`|YJ0_t}^pG*Xy8LPB8CUI}YNM>2>|{Q@7w31^jH0x0E6W}Vo<-++P|JLU zUOFXWefE5z2>1{_&h1HsY?uZs7g^Rc!Z>BdODTA zRKNYtY6@k>7y71#j1F$+CKI58HQW%B`{x9smCqy6s6D)Y+GrnU7PEfL2$pNdCl;?m zxZ-vFIeHd=hMOc7*W8;Aq0e&{3^=gI-EST~#HWk%>KBlfKhvbGJ*oHIIEf`LsL0zv zJ7i+x$hJRtP-I9&;vDbQR(8pwb9@?HZqN!}GP@MEuP^^wsdbc`CzpbaK=*{7sp}Yb zvOQH(bys0&&%%6Zx&J8@)1uEC5U66?v3qKnTKq$vS`bBftdOj)tNo!ha4Sk7t5|)s z0&>MZHLk2d6qV!PM~5L(>@_*CSHo5WO5F<%{d|%&>?c8@jr(Cx=Bx%>keU??WjFIg z1qnK%Xc2~BXWNbMpcy;c>3)ABn}vQu{z2Lxq;^)hPQRrpnt%Z}`*exrspynWd_*h%9s0ZfRD%W`qXAUk{F|At1k8mLeZ2-Z6+$v$?E% zu*ow7RA52a?2|@P?KUUeG=8pfAgKFViAhTA1)F$;v+=%D=z>A1XHiH`;9dU5M{8W`O)v zYi2+$lAusVY52-ZMf0-zSk+lpC70U-om>3s`Rf1VfD{lF6$;@a@2l0)c%x-RWj|^y zu1_pcxt`x_e;5os3IoLER^poWmwtrodgJ+g^6jH#v^F~qV&lAy!s4?r}AtPUrplMgsMn9xA-6%*_j3_0H%OSv&mBq4K-(@~qRRQzWAenmBd+Ld`TpQ8X@YjNCMsE% zZKe=Qw`5pjh3K#1&U{k&3CtRCt*XT&3IurJ3Nu1^L9oY9>K)8?R92-e0{&>=l_CtHV1re%0@?92F7{@C+ zOHD)Cg%$S$H|e@{BqKsReRy)HtgWAWw%Fl6J(I!3!=_4%zB)Rm-Y)th)C7JFhzCVK zPfl|sO}p{*yO|{lH2L2SAfWEw&3Te#qqx4gaOQY2iqbDV>hsmU5o?gmMF`Ohp>C35 zlWv_Nq_QOlw`@{0|4CR4mu3oT#ilYhp!bqoW~(rtTVyrZpkv`m8w!VA}<<*6|7NMn}I zZQYYmQyHzPFvc|aVzNy2W6?1~zb`czLUYnv@sh8g%YI|_AwtE9l@M*h*i4mZX~=6` z(CLRZB^KMyOlWxi?X4OQaa38({ zzP0K|Rw=p>65A8khir>E;z~f!=7+&mZ9}KF>=_gbgc`?44;cN zUt#uO5;yDPatgbZ9mA6Y0IJPK)_BP$P8At~E|lS>K2%8JCT6TovqTSN)~UEq9&YH5 z_9KGQEA?3|%R0oJIICvWQto=x6k~!kKE6I%u3e< zi4tQwL3feLBzGJ)iI>MZvzcSl|9nPsr{1la_NDw|u4Dkh;uR*x}|0I*y z|BEO6H<|p)#@bQX$icwg%+}Gy9)|88Uq;XBn_O2^Racgfpc0an|0YhqDQpu5z&A1e zPyF8;It?QmfQFIfn@4A0WCXCW{6l^VI2agNI|5iazB7gNY{iVsOiaIBb|x6Qe>V9i zM#Jz=P~1_^(#$}>+Qic6A2RlvcDGUnuzfS|s{d2N%=FFU3z_QKD;PNf$mxve9O+ys z{=NM-t!@PPhw=Sy2AJdj71?)ZCw<3%X$Ag)``uDd&%x*)4F7k0X7&z_|7`cI3i!^F z()*9c_6^`dz`y!br;s__zH}pMS^L8Cd?Q`lrwLeg0pk1Ndir{|%bq9~r}c z!~y?{_hzGK`47F#2>6~2^FM(8rAqj3;+uhq>3h@vtwtfT8C)*I0)-Y1%*6$JW7EIA zy`8B?H=teeS{J&icauiUc6mqU8Z2bTnWL`VI;^MNoE0OOamE)oiV(2(>XAn=Q_ zsSNPl#)Gv2(QHL+rax3qt#SDC;CX#PC<8<#%lZD)IJ)RB+JkYlgC73;D(VPB`Xa7} zXajCpU0HE`VF%_n0h$@_3w}U+O52j@;Y&RC3Eif=esTig0O)HSLpdUkYr2{ZqE->czfaZ=qEOYnZI=JOP-i9m_5E1R*x&dmOh@J zABOj=+DW>i9#>y8U*~k?6+*Ga6CKR#N+|n#@J9fZ__8Z zb$0b?9bUCxd~`k8q+dP`Um?j~>nC3}f^(OTk3MCmp9^0;3&sclkE?EIoBZ?3$0iJk zo#sQ^cbzhX>uM!s5Ox0zyiXOXW8=preEq1U$1mPrG3Cr7u%@Lj_VqO{7Qvs3L2OTt z0MQ)E74-XIBT!v$i?1CY9n&up*6 z1j^$+{LVmB*V{42hzIANOSNA}>_8RDU%nYY%4a_Ov_R#Pd;m6I^n1kTq|i;i9S@*0 zKAvupqicd^)`yCyFJGHd-!J&qtrnZ+YrX{=Kdn#TZIJd)&|4tY&2RJ8_6yR};pl~6 zRb0 zc_ZH|PwLOI>GMWnTIqcR8Fc(G7PuGy5|hQB%QqgbH#5lfPK$tdQrXPo^G|%G2iT=d zlkNzWe*Txg&mloPjUPDp;049ER}*&XwZXk44ht_wt9Q?6HP#b9ui;XTwM`wC+3HhT z6{-zy!y-aIhwU;%x?VMY5L_L5Em5&>XtqO_K;7SnZ)q7sP0u|4At)Nzr+H1nsD!6= zYlOy#JT_6y&iAzI3NXLxLDJjzX_15}>dxZ1!Dn(UDVU#Q6ae%>?q@TagVB zm-o+S388SINE#k>Ok%58!qt_xCUFIQ3GLGSPG>-eHM6P8+`QdB{tU2~_wcPqJ^;gQ zT0?_*AH;b`4jIp}%ww0E+3vDa%~lHw1cTWv)OqrImITq4#dnRrFK&c>@WlycOOS2v zQl(iX?~$(REPn2~^O~j{XD`a=wBd%SY^nNltWR@;NJ_}b8B*I@`VV3adZEo1JUYPR zrOt`U9w07$I4_rWaCZZG3fDERrmlS3k%zmF(jq}E3{$c-j~{M{CI!zU!vtv^dN04V z{tC2iR#BcZ>NCgS~s!tj9; zzb8c|{S1GFG7k{8%dgV#XaCEkba?`Zsh?TqlQ+4j?#gFA{b4rSoZ^iQ_Ov4--#1qXrDc5`q-=8%8ds>W3u>Wt zutsWe@vs7&NbYZ|% zBQc&Y1r)3$poJ~G2GMtZ4cu`&wI@q;rR~ds|Nh0?OIs4`zN>)nvImz(1PP{{DIfze zbd{OM?|!RVZo7%(8ZH!p!yCb`}&*!>qM<2Q|ft3Z~Vy#ryfz6Y{sDI)_{YN za`@>E{UQ$K)@%=z#;c>f0+z)oJf?eb+I4!F{{p`1mUmE&wN&?8@l?b@7RKyS_9hDx zCsxs$rMg#_rFS%7RPkp4_Pnogucf?m6C>aAy-M$6HiAhc&6A`WE-~vduA5%E5?{bh zdYZWflgKY9DUm8yg(%xtsi8YvI9?a6&L?^F1O05WRuud6w)h}b0U_iaaT|*Vm*2J~ zU!yN6xg@~ApkqB&2~Oo@*{KiRH$!AvuFy4rLe>pOURcKWSEp>rpz(kW!2E&ommSB@~+#gAj7mq?so~E%IS45pG>33P!U>7eS@?_29SU4CNklb~b>^he2 zGm4rDik&Z<+$+7lcxmhglb%;eEi;h!Wo+J!=q$~hl1!?}H|<(cY}#KjUKMqkf& zxpj#g*f!%ixL>9S>P)a?DvH(^MZ)2Z>>VQr+g$Nf>fY5`gdhaq=XDnKLkQupVM`z0 z?1Uzgf4{XiZyO4k8?xI7;J=?#ywb6IZ{BNf0{Wpex0<0#SluvU>#>C#_$Dx2*b{>X z_igk=gLEWn1L<%dk6PhRwO4^+#PSn@cd0n-Ei~Qd5*P?3mzEAjo;MP2Kl(6nilo;H zaeXdhJnDXXn`&NfD)oZp6xDVs+}EVI^!Nd@pu5b&DUjoR*`Huq&8B|I1?i|B))>o7 zHf2EcU+bpXfh}ieccf03J8dRgZHre@4#rN)meKsGCafB1qf?FY7>iV*jU`sDaZ9(N zle^$riWC-oaT3QI`i;XH2Eq$L1W$C{S^bK_4xL}DgBoqUEPVW9O!J&Xt{1T)(9pk; zKD{iU_C+vbC2X&=-0^t~RWVk@WW&wkC`kx{uB^{HVLA<-&`aR4G<7~bfzfLiL|WX; zPTiRQ%WZQfQ|RzaCA(DhlwTE0>h1Oo=8v}9t~ua7uF16{ioN#BkJSt0K5gilGSrvi zi`q5+Knf4F8NIorUW?QEM9Zz%oON8UnCMFg2}j`v z@pHeBa!Pjc108_!#0??+Yp9*}r9Yb1eIfUPkXjwpFY(~yXbBnQd%<|>CPV4_{@JWy zTt-2BLT&ZJQ+YXHy(=-NJh{XC6s*sZ;gEx#$g4*kQ-rk3`$r61vt%+tN9Cd?L9@2* z8gMEgZ75qtRRO4+!>ezZ7)M|yO6XO{tJi>G_>lt#A#$f0E&OfATGR68%HT%%Sbc2f zK#?k33k-7-`veakgF4X07>sP9U*I$AK-~VrnHVVA=|KT-J32^2hfHu#mNr<5`#NLj z(AkFkBC18mD0|94E2)JQ1*3E`-;@u;Z0sMx^=944jJouyP8X9_dlT+WwIbIR6byC~ zn0suqjND&f&C8ZYZk@Qsk`C~_s#v5w3wp_qX`Go{Qk!6^-RwVySlrA!bl56&Ckz#^ ze!qh46eqE}X+Gu{#(RoMb*tf!8`&Wrhv)U#SuVzx#OeB+xKK5t6?V{gAu?DM|6st( zmxE1ZqmrBXu%KP#RekkCz%ZjwexYo`lGi;GjXjh!y4r^}lt+J^ClwNH*wMB7JkA8J zps%=fsoEU$^p|G5AxDuf+Fj%8Ua@qFx>wjQA(559^i$$`Yc`=51T7sy<)koX=istd zdck;!df3-|Ap)35yOfFjj?z+gynIRIL&rmGpVCJ3GABe0YJ?G)VkDhaLoD9ixgDUc ze-cR^%oH;d!8Dds9p<#WXjaDib3jOh7Sn}AK zES8q*311NAf$U;h0oPK?Od-bzPxGE5P`R4(uH?to1(Efe$7^?`r;z;4O!dkg=uCJT z`(*ofvv7nannQa5X71}XuAMxNyyV~Un?=dslb>lDw@J88 zy_Xge%FO~4JT`pN%L-YO1qQ74c)hYbYpqK4TgH=Ju^zakGf$l3Ep78q3YoNYL*hcBLl|G)W`#a^~4gCzP2z zs13WDd?$vULJ+BmKPV<6l;eeXw+iud4f&-04tkY|65I2=A0geOocV?Xy*e%0bz;pH z!XkPv4Cu^Ii&tTK>mz!k;M^^UC`(!-y!10r0o2=g-_jeUC)T^M@_OG zka6)@L!$nw0CoF%)Nhu$P?RcQ7`m8QhN%)`>53nBSKyE;u%Z9DT9o5uVH?Ooq*13@QL z){-r6zF6vg&KaBu*&>-ilYszf)R&zdEonq^qR>aI7qfMbd>=YGbN756WwF$y4JZrm z%7#2{FJz$bAt`%8XB1w2&SZFPD>{zikO377@P}J&I8Sz;LD1-!P`$#gm*){G{)v({ zR@A+vnkq|US{Sa&m32;QusY^A0pak6o)V6dY`^Tae*A-SKHByHbP3(3D11CH=zV-8 z(o59NFwc9Af)lYh0A6A--(Jv-V*U?YB7 zV61og^dfQU2!&jZKpjndu>n7x*BB;@E_xgr8QiR=ZX1NW+PGVPB_|5E#7nM$V%cB| z7JA0k?S^$9g1q$aXu_l{Y|O2|Ffy({^5o8`z|K%$xIH9ErOng~GSQY12@J8(Q&3Zc z*x1@HPl0W_LAze)8+A#64UL-g7&>rsPX zn2)k)#9aX^ED3#BcDmP)pH+QPMp2y2lK?5+c&eh#@z!zNQ^|STIaK_9rna~>Yp^Y= zqg!Y`Hx)>lIe`!v>z`~HrFg!TYTTS*e96Aa15oL7dD70eZA6qKuy5em=LLOUko9{ zLIhzuat}}BwYe;3ThS%Q4%=wb-ajnG+DlQqem2)O6uF~vuRrWzab;6IypT;JycWYi z)~$4Fv93bWg0_bR1Ee>vgma-ja;Tz5Z84UJ5OJ9xB2`>NWz-xxOz@>Ar|uZSLw@JM zo0I0xN_V?NN*QAv}IN51>V#?7OD_uoAUE{3T2PoA>k%3DP<9IPI9G zw=?(jgIJTVsFs5<=QVF>CHy4$MRU*-e=q{sn#a{g@MxfdU5H8Z`uS3-R}o8hO;uvk zBJK9j@nb#IqIEAOfo6?e-;~6`_9zg&!M`?ukfXG< zeHO3$8YrIB8b;)>1;W6@=zy4*BphUQ3hrbn<&wxr6r_XM9nk^t4rHBaDmga&R_Ogv z7JkI1K(vd(6Tw!(LCxwJY8dndm#7?bFTSV)M4G1GB(!UsWY74UsTy4A^|ANb_xfeY zmG%V>dY9{`pJSkPx6WT6@%~RFG_@y=ER{yT<5T7}OO`1;2VlCfrD($p6+@i;_rsr^($9;m|Wp6zoQ2eNIb>#lDVJ%Cpa-#B^I&$KJ>6E$I15 z^L9G09cSQe!y~6BZ^&qC-+SAp5ABOXrWm?E3K2HDoJDtJ5MyvRoN2{aaIMwn$G5+reuLeCWw)I;Rp-vurHSQT z*`~%RL6?a1f=_cGUQT}28{hT1fkWjEH|!SWGd`D8S5j#VPc{cJScVG<1)7RkT`M8Ea?#{$EKWlsr2+q&VE1x_ zUEx+QY0ZH2t9~t0Sx`ewHw2MwK_BIShuov-s0S^BJH||4*A=BUcL+-U3Np*XO+p?S zN6TB87KSFqR!ODoEZJDySx6l2WJO>GNe*Ztg{2W)A7Nt+pr6svyD1+eYtIgjNg$Yn z{lYaMOuc(;GO7`LPO8>sa>nvaiua%!TOSoq+*)f7d{=yr)FEOTjpVjARg}!V3NriZ{Tb3^+O$o#&XHOf8Xj4yctKIjB*;kc{pnNlW*6p zKM75+QY061gsTj-!0VujbnnY(IsS2C#R^Rb_XK+hLC^;S0U09-*?wkbNxJ;Z!9KuE zm;%7nTU7XZ%e*Xzgm>Hq7f`Gc=vUv6kq}f!Vhl38Jv8#Zh!}aj;5BZNVqw#TM@3w%gk*_o}If>964(1GN@3loC{} zf@tRu&AE9Q@g028RPqu>(aZ7LOBbvvNA8^+S5aJ*@4~)!qDLhnyJPm+YMw<5G#;^& zMmTf{eLtohCE^WKw|Bdx(3}S3232cIt+lSL0sSN+0+F6x+9YThG*!?vhBAa?7o2S; zWT`MVz)G~0Ha_z#-kz2SllddyDz7cQ&OgZy0NsOcal)7it49`GNlu?5@Yb=Y8H8O2_DD7O3>-(mXIS$+cH$bLzk`-ILP>iF zs;#YQr}?~Wn#k1*C0a|UjJtOwp5leGRCz*f8g_3|Uq)>Lzd{&uUqkEDia zt3H_U#QK59VtllPe66e|Uy!IWmKV#;Ii!ZouFC6Y7>!MVOIuH*h9(9?qoaV^$reyj zl)VmifQ)2*J4y=WC9H~0%@e6O6Qib`#52`dXHl0n+36b)c>v!!8BH1$_8~5tdR3K# zqHas|_F!Q&Xl^_|PPQc#o}%k<+#p|abaEyy<%-Q1MshUoiD~9UH#1%G(^vj^_!+IJ zAt=M?Z129qzog|%0>)&J!|g=e{U+fx=8rSS$T<~fNc{<6#QQhip{lp@KcM{^6fr&QV zG9?ySmedWCX4vN%qHhZzH>tpUuEb9e#S`5K?#{RT1|CcV`l|B@I<<-8TB|Z;>eCWgV;Ow6s;>eOt^5bFmyFL32@-~Vq-MSDbs8_5&b@D|idH{fYH9?{g4ma=Pl zJ^(b&R@P#ep}*cR|JhhmDaFaRbJ)RH%5xNOIW9rC9VQ+zIZbR6y{&cS^tTo{aX>%d zM1F#-n=|ZrH9D)FiA2;=xr>b$2^K5NGGDE5wz+qRvZ9ox2T+sTe?XUDd=W81dvYlY$)u_70@48_|T7@Dl)ATi}fOOyEZLcJWLJGjTX$_7;!API; zETUS}34#1q_CoKfBWSS%Rx$OfX^MU|2=@U)Vc%-N*toc2bmu4mSjgH>35=CzIjFZW zI&I#+C`jd-_OqZij_;i)1`Up`>-NQ)WMf@agOVRn!rl76#_OPCvW#g5l4e7Wo)NTy z-d2UtxLkt<9R7hSZ#AZUjzx}SF~cT(c(q`C`*cZr_hKo_w~TqRqa^Fn8i&SH=ju>r zcBt??tTkd3u@lAm{*H9^o)~wbC179CU_7opKQT;g`*BVfgD=^7Ca7VS7}^W;B>BGR zT!b|hmY8Y~HLitreg+r3c^Me1JS1nguLQ}?FiT)r58wV}J`BA=m znv2LZX-(7cn_2j0yiH1*Fl&e*sU5h9vr@aa3g+QRv6nSj7>cD&)tH(czg?9YuSdiI zbZrb&yH|{M7Pdp5Cj_VR>!9|B58rwH-qs5GP@o{|t10ql9nMgeGZQe?MPvz=J#(ez zoMDW>C|0oBJs=8TKVjtik3}JvKztdEyBw#q#)!u4xfyKDSKW5Flm|C`aqJEi*B~8| z51$op?J7z;Q%wY)pi$;F`mGEvg8jJqJr09HS#V*_6-(?3nR7)SsRmE23NS8$p8nWU z{Al^6oH~Y@2Z<76Z}gCeg#roGtabc?=AVu&QtVGSkR{SwR*_KN;;@u9^S^el{F5-@ zOC=wrg`z^$JBb+&=s#v;JJ``fZ;4wl5)Sta9SnJiMRoH*eT%cy7OwB5YCpRgUA*G_ z;zo?}S42oMbzPx+DRO986*#ZLd;E;2^`OG@^G984iP3!@h0t|H!G>wT4o+g`KlJf; zXIj8d4~JBz-}8{z8Vv*X77`^nD^i{G3EG@t>iNI&$Nf)9875k?pN|P1J97jEH46e# zyD$22l~3`4aND6MNdhbKll+xoN?~yjJ|(vR4h+BED{@n{{9oGY-qc-^71ROA#n(l3 z%x*5-e5_FA0N65J*)+R#1>=fF%xPrwBYo9OvRFyLjKAg9pf2*&NRkAif^MUl6N~mz z#^mVtbkHuB4>u*fNYR3om`aJkIemeEj#P$Q9YU?63IY5vKld&<_|ro3WF^`-vK*P; zB(MWsgSK}#xF+$}lwV=^D|7IqF9xXdQP^gsfQ?dUS8;sCM81#3CA`>^R}SK&puO4S zul%+8t$N3ym8yJmKwiQ@$-JPZ8sQ+#rGQLhBjT;8RCO2fM;J^d6nTH>3*?52WBV79 z)|)X$SRy|bo-JIso+n$w3v(=F*U#@V52#*bW_ZO_V4Pl$%vb>ia4y+A4+HLU0B$wW z`0_$aXXp6OoQGlG&&RGURNLN?>qRrJ7uldCIK45~#HsnxuMWEuOk3sRs|?j16ol|J z4)S3_`c@f%oSf8IDpi#+bqXr5`#Q3j7l}?uE*MW!kgB$|D>Y_kH4uGc7Vb@+%nl9Ej`*>JhBE%s5Y=Ixc ztC(NO>jp00D11HTJIG2jO_^czSmO_K&xnhS~WN})H1{(E=jmj1=Lk$tKY6bX|yF3092BMrf615 zfc)CtLAR3~9THQIfnL6Fmi$7*SHN!61we!<5v&{lC}fuG*^8P_z%?~n;y$xym1!;I zEjUTPX7h6gS*u_`)_+t{e+1)3h2jIzm4ono9~qPBqq3!U=Z|<>up8o%`d+s7Z=e3j_F`6l}dlM|j>oLsEnnGDIu@X_*XAIE94fr8R;?y(SozI1@J<>Ul=Dn<>|`te7;RB+ecLLTCiFG?k=>WOs}0%OAborR&- zNL?1#(qc&pb!uq0xQ@wMbdH$H-H1h{ZI-(!^?ZKh_BDu$os-R5T1uK)bqXB!29}u_cG|%%N0)@((#7lljVJm+9M6$awi4ePv8q* zG!GFciE`dgSERu721avaMzL?N%Kp`QW*uyE)oq?XB3udG-^F%p z-x`73)DjtK*-db{~Y= z%mx)}vrCj3s>?Oxgq(yCqyCH&(Mdhd#~I)~H5LKgL;tcGA+<2PqA-+G02)$!kRRt``%B_k&ev2Fu_aac#&%L66J{yc38L zW8xsy|0nsOp7Fv8`SPOk-FvpGB{a|rnz^vGr)ZsUi=?U#8J6xA@e2x;t{|7blupY9 zfaiNihLewS>{?!gYAwqs)!k__9M0*+Bv+4Bqv;ryFmY!G@}T2EACh9))M%7_4>uoD1b!BcT~@kEw}bk)j!Ew*35eY z2Xir%t8%^RQpZ2Q6a4cTxks(3t&O189?2t7nKse&3Cx99e`lr|J@v;&hdJ`K++Dw)c0o9&+b;!L~ ze$vz$V<>1#=^l>h3sb8b(aq53Prtyrkk+fo+j#d>Wt>_LDQ<4bjuFnS7nDW%J5h7R zg?I>7h(7!_gC5}lcRwEGv>MjZ#o)O)I9*#iXnY8K7TFIkyj^*HyK8|xQ)h9PBaTk> zb@xP_%dsd4xTm%hY_3%USD!>z|8=@}uG5z~Nn77tjG5sJ?kggydYF_CCo>l$4;{S{ zL;K~f#N5cbpR=2ph@k&*zB zad%y(b`ozWX4Y$I&5`E`9rKasIt3rK0LKVJcZ39sQnbbIF22n4^Ue^F5%|*3r!?&i zwQZ5KT3?M?#Z4{g98RABS9)c_8Gi`Z*LHw>a5nX_;e13i*ZXq;*ZmlT21AQtJ;2>a zu;}+hkR1V0ip@2o6?Z{iD1-CIIbX1l*PveB5_2Odvg4jlYO>>Wp!iw-Bi{A4?{Z9! z)_h{0N6ovm5dhf07a+E90eSf=i5C`ZC=X73U)JQ9RkoR8z(e3lkwrr5`Yod)gU9cB z>rW9!Xp1x@4Xd}`!B@wUbq=k%Sv0Rcd04e!0w-nlQnrZkMjCmmG{2|I;*Ei_(mN?4 zbUw78*~Xy;(%0shk909x^{7rh+U-+{$MCJvmaxf%mlxl|3TxkdY}d~DUX=3E9E)$f z-v%}WNIe?hTpf=TU0_$5yq)=JW#0LsZvCgPPtq5~#OV&QEY}b?k%F8TlDNzLH>XD6 zE8$zhC1DTPu-^t7SyPf)BEnO|EiT6^2>H+*bQ2l;#8x`y?%jEtiS+ z^s50eak105^vmVp9~HT$Q3Cnv9t$QzNNr)&6luS8^xK2Q1jUK;7#NNlfS*HKb)%^d zR~$cyl%XR`FSDTlcVe2|^?xGz8Cc}uOGoG;khoJj26lmxf%Vk)W6g@&fP+(9PmnxM zNN1ipXQF8iB`%M|fY2rQMOH6nCSN|*&>azL-3Iff)f-7?Yw+ea*Ig2CYx4KUaqcfF zn2LIX8G)W@@S3R1vii%RSR<~;F!C;hkRP#21B3Ns%rN9R4V7eKE4l4Os^WBpI)iVrLpQgVYdoHE7C8)%@*8&^{JBc zF6~P|t>a4HAvW8UV8~&3(lvha&(X_cb{i_gKI`lBHLVAS`{I~@vixeuKdYMA#i$jE z>}jBoVh@&F?VJ77E`DZ#03~Gov9C1J(UtvC#<%eX;`Rjh7=#t*Q!i_|hgv>PCrC}F zKNIh88Jjm6%S|DOes!ddD^+=ne#DEi|Es zU42O&HwGT%U?hNgdO!y?to(wI=8&k-EgtJ%LK{r=OJ?=1Q()#;?wXQ#c~MQf_(Otw;$2{x1hq~uWy@+4Zv$8q$Ct9a6GprV^xS)r~g{X)2J6 z!(7Ogt0Ol2Gb29)t?@|zxFL)x@{3&{Ww{U4)`cZ3G{mqRx|3+k)$bU28EvRtJ(Ipy z>D`I4Z13_G2)DV?YvDF!iaQ9wv@{ ztg^Nwpu8WKC%%r1yx1wbvdVuweXZd7%3&N*p7)Y^-c?+?Kl24ViHD`=W&CU$XqHfC zkpBV>oF@Ne8-*CCorL`$HYc{76S;==tgMNY0!QgH&+}2R@HnlEX&oN4%LH7W&%!r5*;6o_BI9OpR33CIx1Vp zux8t5Vvh@)NGJ6|u~K8@o@b^hbg~9g&F-*6alVmcF$@y)yrs0ARbm*P&`dC}3P{aX z5;0c1H2Ywo*}==H8IXKUoOcArqZ;e7LTSBM1zLwi7>v}8Fpe)y!&R220T`M|)%HIa z@unRsBDmwF>q!Bz>a9VV4JB3^m81o-r^;ALpBRPbc=)}tHM7>DNcZ_IeI9Y#_OXy|k1T&?|_<2`KN zLKPy2fS*_bdLE?y5s2)x`Q=ns|9mkR?IWFOMudGbICP|?3c=c;Z|OTUU_jo`g6PqN zgYO*s+k)IzrRWpXY0(8-(sTV|bJIxi2UFn|Q#o-QaUpnID&f{)%cY zJEb7|J%KmuKGI6UwT{(klq?$&xkcFtV5iq&cxm)TYrb$!Q%BNew6h--3jFUy6B!BD z1fN^;58Bsh4R!WpkW(+Fef?ltYQR6|nY&4d>h<1lek5lk)Qv*LRI$%n?_L(cD8*3wsqupN@- zR%MCQL9gXyn!?CzJAFwR_rgY>^r26DeM#WJ{|c2cGX4vN^natu#MFQMP?r6RDr5X6 ztNuHzjD_K!SQ!HY=l?HQ8QcGimFd$P(i?rlWybc-`d0KN^rrM?^yc)I^j7rN^fvUi z^tLv}^bYin-|(3;y(_&Ny@#=b?Y~lJ{{XQ56OqOA-|of#i9`F}cI4kdG?u^IOaBKB zje&sm+r0Mw_F`gZr{f^_*CYEsYFOBrzA3f8kAK&E(|ZK$3>)|oD z(x=jHqwD#h4S+s^W8xDc=xqZ$J?|}vuI6bWD$p+Dmd zn6>vI_{Ot-l3W9PwqXOL!oTOZ_$q%{fQY`+g$U${p{qjlp-0z%FZX8Y16Uiw@+HDY zfCC6Fe@X;#coNJ!AkagsV;Tg?JbODp2&l`T0|)}YLuZ4}<6cJGZr}NFe+3MGmBYR! zCm}RJiJ_xo038TEpLs>txniJrUv$0uvYiD9co4sTF`aKiXtwJTSn+DVz#`hQ%chp? z>Qb7a@9^_^Vn7kVAR(ioAOrNQ12Ev10Do0Kf^}8ZYzbb|vttS7c2m!y>V<*okc4)nDW6~(3HmbR(qGx)==jbA?9q?d0e$icL5CkQ!Svj~ zKTHVr5m3AWetx0#T*ZH3U->$}_{x8E!xx^PoWFCA-*A8W1`*QPnQnC>O)EYA$TQ9h z{}Bm%vsL=1hF@VZXr+%=`;)sYA|UsGFtkQgF%z9;037LcFVvHw-&?PV%MN9J2R`m| z6VxMw83%Aq(4)uK+kRS^VA^+Zx-5_@ubT?*IO+pZkY^g{$A``(J$4A%O7~P=kROq? zZ>jt@Yye>I8v2Zs59!|&1o)}fU}de(*Zl&weI!gEe~bixU#gYRVWbix%Nrxg)t5eMw*%SLx@xu*HTDRrhFfx!(COh(9Ts+ zRvN@j^p@sEo>yW|MHl&@p2>7UGSRfHcQiTrLgUuvcQslu+=r?~+L>2yw0l}o_ZssW ziPR>Jp$y4O4nv((Je$Ej2Km@l5{1)M@3ekI>s_|MpT#awd@-yZojKO5{fVFIg*0W~ zV%oxER~dz3V7mOenWsAZg3+954VBlAvFy%sq_6um=DQM&j%28$6(;u> zwmTpqN^mU|gH`Tbapy2D>r}1diEl_6LnK0{>E@N(_xcZ_)(<-g?v2EU8Gst+DVX@jImA6kq9-7V<31rk_D`e5U{sK*q3Nj}jCai= zKMq}2T%;~nx)`Y4apsJ3?u#tmY52JYea>bY{b{45vjrQ+ROf5w)zHEp)RF0mxOg1(i_jC=`~B{yr-rIS;gTZwXnwyjdc9MxN?`ByLqPWC2@YA_1hB*?5zXP(^^3JIT|jN8m-{8IPQeDV1qYHHT0a;zdqD>= zTfI-8169M>o$9v6NA}KX0ojRvNeG2vzz>=)fy|mRqF;@8r}I_?mXaBUVHtQpb2Gp> zU~5>?&g!CEk&A6O-{t7M*r9pJVLTay@^i+=WkQh?Cf*jk4lX3CHDC1{vW%UB_h(uH zUH;lksYg1f%oA)iNo2xEF-imcpo>?COnqQ+*fM#IMFcXQV3>x5!{x28-EhVlhpJCD+!oM9DT-N`rgq z?p~59>s|Vpe~)UCRDNAHh3io=$}~oGev0FhQ)pa79I)_Q7s+LCc4}7kn`kL4GJtO` z{wXdZP^51~xzHr#f~U$c+$ zKE=%A>75ft^kx1*D(AzhyU^eP=If@e^lmLO03~R1_-F(@ZUd{PnNRZ~XQ{sWM%eKZ zgPFMj%FKB)+tw+s3-FnqpB2?^3&%lu(O1`8RV>Ikp1W62K~0^+iWr5AavI0YHzzKn zDd87_rvGSE`si%}>mO6C0xo>&%@>5sK@`=y?3MS7<(9je7*7`>@0=_wdog}WU6L>ka{ke3;s`TPIy}0qw!CkMh}PdGB|HDMNc&{D z+L{jzv3q*UG9b!VXE1SyCiR|@^t3mBKNo@AfaB1uqk`mHlXW6JB*A&fEWaJT+bxSY zHQsUbV@-mEs)~kZ7SU1<&F(os1wE=;F2hY6l-hFvalIt24zgbmC> zr_HahDV41e@U%wxQOM0*Z=9|ZD=*Qjm;LjVE<~xLczJQtXx+AXuW(cgNJ#lv)_}ZOC*bM1V!c7O1Y%i=>`f?DWFqD z;;Tg{?`1&#k$6_T(Ru>>j5~wewVj!e7+iw@8fnQZ#Y8O7+g<7SW52s57X7(;^wTdk zK4}3R{PQ#41G2mkytCOENr}2Ce(!IUeAD!WYjvDp9cPP8xPe|13%2 zivn5$Vw~R&6%M)fnW{2V_B6_hxWH4(42Is9@r@YS_&z$^bx30pEHNzXFRhn17ORO+ zN)76Xt2^2ARIH)|JX|}!zS30WpmmqqoRm5{94MVqSTBMT^bQioywrb=a0`;k0R;UaznOuc?=LmWm{_a-_GCATVoEa{3D+Oj{DG?5Tv zoE2H`6JdCw+%e;2_vla4pUjrq)eZRNF_)jZyE3<{L45c45P(tvtH@;>mi(8FdnK(l1PItR?6azpM;!aM!3S9V=%TTU)D}dZvIX<|WHOb}7O< zzf@#}v}m7{|T#)m5m6|a%h_g?N%-XdYQ5p7w{0@|d791!rbn=GG1V=RPQV(m=O=FaD0 z3OD?*@aQ8*vueLG;sPC1Cd!ZmMG16om673Ro^|D;$STiHA@UBIO54?uKIu=^>0NT2L&o=ZqZ4n@>qF(p-RK@% zw8AIIT*-A6N?-Y(GOg;|CQA;x<$FI_&6`M*DPCf|fi%3$UX|_7@o2=JOq$YoRkB`CH23Fgj$S$sQnI1 z40}v|Ig+v^enmYk&jJ*cMBsqSK;|xSW^d#(&Y&A%g1Wv0Dav{!b z*gx<)!GcP#BrQUpK_xr4ev)8ps44XKL;}A?*Ov)Kl#JZZU8Z90OKaoW{L7H$Ls$VB4k($Hxe(rlyoyl(K zc-%mob+-CS-z5`Om%DT;t*bezEvNJ}#GL+O_inQa`Qc9O?LFW89G=c6`Fhyt<@jy( zTJWT}DE0u_#i8L_T$h-P*&ypa}BjVEJo{3xULRyY> z6SXte?fheLs#b~WIpTvrQ5Re$+TVG^n|WkEf4;b^b_}x4Sr@OU=%c=9>L)rc{@Z*& zzF3H?2i(o1YJ>Yx>yFiAvz+Tr$@AMBEAf&(2uuU#JTgz5zvUaNg5;4&0riu2nn%59 zWUC25YL46hzpUk(p5MiSRb_EkK3)bCKPZ=}DC5!u&9Y9+fh@m3oYU2@R6G+Q1{j>n= z7ngqM4oaS;Op|fV@;lKXToXP#4k@L*igl8O_kjpQ{C>9~<}D`+X{*Ot!NUo+q`IhXp$I-fhywLSYjd@rM{ z)ML7!y;9<+NYth(*5&6&hZ+6*fqA72n-Ffl zS7p?@`nWttkv#a5)5F_68?wfMqmsPVv|`|nfS3X zP`5O73#rY4hmr;f*~$vi%G-9vSpzj&yX(uR*h0!YwwpHJfc)6RDy#6Qj+^VSe|N9p z;^cr583hrlvM!xliHQB4x Y&K1SXzq#wc91ZB_WWGH_{v7S z|BJtP7InE9Z(r;F)g;<)EFoCMad=0HB+2xk&W|ucq0p32S9NvfQY@z8n!HnR2tMi| zE4xoUo+|><*9#u$5U)aL$PFesx^Z`wB)u7^CrVpR76O06(bA~0TLl8{h!NLnYA$>C z!u9l-#Qo7Y{ri_dUZ%oG9^#YHTgw38kvlUFWl&*9-;sh_(r2E}<&|!g=1hn~%>$<% zm?wOoeNory*u>W{?Ntu4r>QYXy3$WxfW1{C-c|mY6-V0U9cA%4kH>){y_%|vbOjm` zhnP^-{`YPD!D$w?R0ad*Pe5w=5f2eD^xr+>{Wj}SKMfo~)NW2P67(s{Ir(43%mRlT zyavYZEoG7`Y6C39#mg29BMJd}&ycd@_=dLI8j)+hVk8$-0qXWRR8{_vD3q{hnaW@f zDG{fQ&o+Xo#HqSiYHyl$$SkIant=o+MV5;UDf#6ZaZ*?2)4T02yRP`G3bfrH-+z{> zyEC zirLFnGLD6;tjdb%YferfLu!U+_Rq--)P3xB#J0+8#asKizb;N>v}|Q*6^bLa(&VZc zZPUInR6uNPW%5=8!fnj0nReN}QlEcaH&z8nT*xlb@)(t*;! z9B565_k2hM<(aqOfaZlize2N%jW#;9#&s^W zW*2Rd8kP9DSzGFHB-5jT9!8xqgF*!ux{01`Dk8FMM0!D3~R*VY$|5u*mNUu(gNMiu%y0VC{b=bcStMh0UJ zSXW;6Y}J(;9W`H?$>(79t(+5`2<@$xsz*GTb~+&SJL1hC!4F14XVLh6p8^?)yerr>OjGtx_|0-fjdoi~cTQr*kc#3bfX!*Axw2uMNICPlK4iQB zzWSaym=)a&6HM)Ep#HhM)l?|5~s)QpiY&U&gokAkfM9hR&^L=pM!K zi@%dqBw@yyno4^WephsE@gSXig436|H~%*}^?ywu`k(zZzxC*UcRy875mr+Z`_`$Y z#s3HUQ^tRDKV@h9OThg9>V8Vg_-%*!xBn@}w^8T+ z{`VxD-zhm6+5TJMlbw;7{r^GubOlwK^IqehC5$H$lLjeVp*Xor1RLoE`?dUsjjIs5 zs67!S&W4f{6a-Q*HZfLC@WkhL^V1#A)7@9jU6<*RRd;#y)YGfh)*bdx7I?@z6haWL z5-Q-(bs&geJOC*!E-V590050OS{`Z2t zI9UwKT)zB3E$6L(1d!oxUfunGP&RTX<9IOO$9{}5a_m+jo;B1x2>S4W240_W0g|hb zfr1iHP#*5?kbWD}KoE%qH0=02&>{9f7y>hLiR36i&!CvO&@O?W{$v89fD8@+d0$Kz zL^upOdMGG<$}N58d3G#p1Hf?p`2fqO0K%}=et1YwUt{WT^x%9wIsJfsAOc?!Pvozv zL>TX`49lB%J0T$7s+ygsAMiLT)U@IPT92FIGk_k)ehTq2YE;jkK;B*k)f(Kz9oI8G zzp?;6fL|id;P|U}puz^zKxV0D^uGeSXZ2##LE+?uT3Q8nFj!8iKNIySN_ZdFy+OWU zmO!Jg1KvJpIeWGdLUkDk@WccSImS1D%ktibz{`m~nkNw>0Ki6 z0oMd_^=%h^O-3sV<9^21-ih{h0HO)dd&Iu&izuTfJPOp> zgl)1O_lxGIH?~0Drkv+&8f8$YQmUi1+M0bMPyzbaY8Xqe%%9pcgfFo;R>opg<8>3x z5e9Zsm2xfTV(>zXi}lj-W1q}shR&mAjUkOIVu#_WvbLRJixdWDXE$r6m8-CD>xg{J zqf+y9qDUjkGV~)rM;c@FaGZhKrP#o}FCFWrAtQR3Ri=fv^d0LqTK?u6xuGiSBg0X z{JUPW859YR%ut!-K!eX1V`bgrD%_+$>PAG(5-z1uUo(PJa?-R}i2ED8Ovu}Zk|%i^ zW?5-|zV)>{JH;E(QLA)=vDh^Xd2;>OZrUuDDbP^fDH_|^gtCM1UL3ki=XM=NIOnxO`odQ?mR%J*B#TyP_i+N_14=sZ7I@%{A#- zYBR}SetdEQCw6V!>1`sN8DE{UcAMv$^i-GR(v6+Zv0Y@Fk#XEyWL`F84a?)pbVQK@^m@)~*Fy?VsGJ|6E$yD9N?PB%o0LD22z=K>m&$l~36^v`P)plc%|``ZN4^AXu@ z9+d`t95+o-m?1dPef=P{%+tacr1J{!fnT8Zu54>~=V2-PYS+S&Unagv2v_n3!8yo^ zbHlz_a^QzGcjm6-1)hEPBNO~aZSyt=*YESi^quu5P8X7*5jz70D=6PT;@1>@SnebI zT?Y)tumCyIE3uDEZ4uAuR+rX2u#d@HY1X@Wx5~~uEnT1H;ibh4{$%0$mqQS(B33Ans!e7PB}bF5KV<~DI}GcUke4XB(%I&r zV2KbpM@>2D^KZC1jKOh>7tUm8)hd4}!Rd0FV!{l7K;34?RaVVf1J*H79BB`#dQTk2 z$2PvbthAoGN<|+A5JtIT1r`zzO+iIPP@4Q8eNmC&HNRT5AcA0%hP)~d+yQF zqhEjZ$3`TLvbJvvS);~f477sx{`hfSJY?n=ICkqzFMX}yI^cK+|5nNL1yb4{aiA&>V$@U(=Zo9wg;y@jVIf*1& zgK?P)d>82lvz zECL-w9)j_pBxjG<7~#Y+%A;QVqpQ!QSuo0O23oA-xU7a|Qtia#&V4Izrpo3rBusjTSM1Vm?BS|G} zl#lAe{nt)QZ3HIR>w%E22eP3-&4Pit*HV?{qBs1{K5Y3Tu)xL z7pcvAtt4OT+uXgJ@w=MIow=n2rpu`KJ=rvya4&GHz;w}#y@9!ZDQSO2Ngw4OW^19> zDQkxa$E6?#5s|08MLIjGPD1glG)3>ly&kYOl4z0Y7KQ|rKa51F_b0}>U|;PQMYku} zk>qA%mZ53Y7EVp}%Oc50?EgI8ljmUEVp`R(ex&XXFZqLeA0~~yxmT5Vkm8;Ra1?{I zrwx)o#aaFXzN#CSp4jE!r<_*>$Je|| z{n7?P8y2Z^$$n^S*F=Zz-6v?5NjfaFx<|qHy?GZn9y~c+^=b4!!thAufZ06Lwl4A{ zL?KN41WQI1(pd!jiEiiS51MtgUL*Wd8o~LsArNe;BN#XkrV5TV>l%bzbS>s6DRJcT zASud23nVM~9sX*7v1Z@e(j}qHkvZ=k9vLh3K?EKeA9H5S92{aaI;>63w}?M}=EjK;%9QGry*(r%?3Dy~ozsH3yc51YEGxrpmH$tPm>rpt> zboHgm+_ma9`S~Z!+Z5zij=O8Rk|7#+s9`$2t?i@*x#S8DQSk9^bBh}Grefy|csuXH z-;T_7Te+N6^9{MOP)@1&0}0!bo`fn-FUhdS4R%D+&;pMZZ=4B)`2IM@;aU`oE1QXZ zMpyYU)T+Y~kB!Ol{YEh8~^(^;e#GZG|T3g*4EYzvP2Ino&( zxT5lvUEx~4y8%_mjr56|?rGcHgef`rdXb8Et%SBypd&VcVMDPN3e(MWe?`8gTD-i0 zMO{@EUcFAS8H7b-q7r88kTE57G56JL|5Qx(w?0E_#Dz`453;7`fu@VIQ!2S}#zmgH zJs0+;XE}UNjT-+oahlR7)YXdbLlT0z_aj~cJ3?Oowu<+zsrtNb(a`Qz)1Ia2fQX4 zv)-tv={miw$A(7o5(%J)$|CzmgFy!-YpveYAo}=;2q$pA(qQvR0@gnrH;A#J7}HSJ z*iz{YIj1=b>Ep`6{ zRiTy0+VcZm=U{S3&Em$;9Vs{3H^V)78>1U$OhWaoM#0eb?4Vm|f%Kfuv2fayO$*}! z9(}cib#VIzYx=JfCSatE@z{bRZC7{Y_)j#il7J0iU6JxGlr(tKk87({E*z3j@jIJ+ z?rKjY$EUL`L4ij~zh-XtbP9G~9d51i@3$9M136qsvhT)ntGcACZKOEpE35!j)C<-5 z(w3a~AkEn6E^${yY*U*LxkABth#S2EM^H$Vb##C`ut;tK1wB=&Om~&V z_$v+0m$5ppeTlbIY;5tCm_Dc0a64m7+>hOs5WEa zOGob2y6s+D1}_wnHh_o`n={0Cl0`MQxE@v7k;Hxx6fYMqaYqb$V7zU#T8JbqnpIu! za^iElk>5A<{ytS~5SH-PpAnU8Ch$Z@$PaP-K(yb#ekJmmwoIxNYtK^SE0TEXw3!Tp zW=^+`>O1cmf$>smKluHJozS+LF9%Zqu_;@8tde4wws3uEW@NMsClp?Sm>tqGTedM3 z35ST7>`4nECpa300;NX5VM6Vsf=NnIK2~lPZ<16Eyc_2&H$`KQi~n^~G{n4nd{tG6 zlrFV5<%7v+_;U@&Zg`LZ?4?j!AAPA5C72A_Hl~hr+AGED1Zi!NsiJt7Wu%qRm6-)c zPOM&O#4IDdoroUMlN?x|vN{WfO`@5pC)T^@`l6!EHRI?Zu2u=8dvy7t@!DvBnz()H zE-SxWSvu?JLWmN#j=syny&c*WoxZcNH<77(d{fHpir<850uhu3Cs|!pJh9qB8gUu1 zPDf|~Rr1i0v3yKLfZYTiW@<@VLK)ZlJjVwMZQCThe&nk_&{SQ20NpyW30iD8GNbkQ zC;QmkDoMc_i2dB1ic$erKgE5#(q@O4>jz%@wo$2xrRxR4IFU}`!oXzXwPVk!T59nq zZ@JH{o~f~HxZlNKlBucHo&Oyvs!WI0&(D+fSfINfb8RI8m>PBcWjXQ^+9gaKohp-! z^<9hE$sP|#M}jvqpSTqEJHKgtV2*D@d)ER!!d+$&OGg~h=}ZGGeIkQ03@O9T6*kd`hH5UCluI}H#J zP#PqqyGBwv6ags#kw#Jw>5$TI59i!_?$LX{`~CR#kD0xnch|go=3VQZwVw5q*Oyo` zBzk4Bf5aW?&v0FdJEN|?NYe3Q?IyhKbMMY z4i{TT(9MI~;IvGsv_ciW-35B4=Z@-Mz7p)Um4qjv zWNXXz&~CCBPCVzVb8omlbz?#h3FEV=gWO87xW(GR3d(U9VZ~uvxyV@w!r) z`_14ebo-r8(dN2yK^}#>Bd?m;INb1<2$~@qZOH3e>d+df{5qsOH*yi(U zpunf3bB3Ze;jQA>(w)RI?B|+_aJW)Qh?%XWjP=#LeE+aZrjKzh;$NJ=lnhzO8HZJf$KID?=E# zF5l>{nAH#4Qk$7Y*v#PzBzg1{ex-NW8%eEf(@Ttlw)F)w2Qhv6_H$ohl(iR3HP9Lh zD%sBoskKwe?r|zDZ>##@FkbtpYuuYT1&8ETu!=#@%RJs3>q+sS?xq?mTclXuziabM ze?;}qo}6EReY+m%2CGB1N&`LB0u<$@Fj^B_H7()Rwp%Z=YZyy&HY0Pkiz~h2d87p$ zN?NuH{W5Mp7)`M5Zq3eiZ`h=WjAz&2WG(92G@Bjsg_*rI*z{t?6p&?ol8(4FV;zHY zPvJ|`xfymoU$0Jn5|*)W`56=KmL zA*=2D!D(cUu`Kj7%X)KKKM>IiZhAKIjFPz&vw&3bojuRPW$ia-=vu4HfPv z|W_y>1-|Irf7cJqhf{fY2MCFhm5K$Bko$b!+Hg%0}@xa->B!C zH{IGr(OO7{01)k3Nmu2i?I-H_A7d8|@ukYBs>*y{X-J~$HsnAQ1v+zcJFu69Qmb2igTN-mv#MpiS z5f01KQgBF|9H*q>R_Ai_EfcYEpYG%05!t!-1WC33BE6NgcwguHS#!=xf>LEKrcNTw~%`C*`%gx=HNC{;e zru@F#IZ@Bqj0sb<|pn$o={qn0aubtg33f`eLrsXEag`LaY;v2~2m&h-Q zs^8p;oaUK##3;)YZq5Te%35&H=*DD0-7v?Ytrusp;ijF{c2ZjpnHX1{Z;yw6ga`Pu z-U`ApOR@jiC*k=QPe$yI-hJ;U&)R(PZo7A4Y&51S>5!Mgzfh9b&u~yPQd7Tajoo-o zYlF%WHP0B%(wfU>^n^k!lwza=(XTh{6!uTBpL8Jyj8ySm8i|vce5nDX^Ns4B@tWc!DbA;rN}&=rg^b9-NxVB zx$4hPS;FcvwjJee$j?Xk*@jqk;&yrY-2cR%lKc}3GlLXa4NG)-Y=&@eeJpnS`Glh1 zwe`~zNB8%8#@*%1yU3l@dM!fG@(bxiIJd06g^b(PS+Ln`AG!Be_Xm$xJd!Mx^p};& z7{TNa`W;SA8+?mW?hdEn-q)7feXKMB#4LU#K}$)}*vH+lT!n%2RLT7o$?6xCWTdv5 z)e0nUWA41A=koe?#ORkwk?P;4$}p5jJ!Deho9;KGwL0xNR4rm0p_y5b#{r&CCMm*c zD-Q?1XF+|T^$DyLgArA;cHY;WH670Z`G%*p`%MH!E8FLXdygf|62D6!8#D1gya+7z z{Y)ybN|)WFjVrUbSVKJrD-j=q?dX8H#Cof%=Jq7s^RESQL8!`>^0r?5 zRp6$VhLvpey?eCOOK{v<y|?Gx6OLu0&AQ>Wi*dZSy$rZ}TB+FlRyM_Jto(Iell8C?a1FS{mGy+gmkJ0DpM3z9aA z&-hD`5jFc((z@tx%>_ySG&#_IWdKh5+GC*Uto~x{?NbqbJ5x8_Xek7dxsGPB*#Kr? z%hv4O>$D;q2SxdYV+f0(mrdCWvCZA47Tw+fAEmNie?QrgBa;j)_etaQzk1<#+JE~y zjbpWTr0lAMlu_Guk+O2>SaZ1Lq40EfI(C)q_h1a;qnW0E6TU@DKK?`O@W0WF4eqMz zYRO)PZ~qg|SOoG9p0Vg91NHwQfD42C#{jOSv!kQApuM?^i}~MTxactH-(tA`UZV4V zi{bwIS^pWtMQd07Gl(k&u%Q1D#1#XAxB&4~9L<4+3SG)j!T~`_5f~snDFy?G#lkS) zT^KD=31GmUqC#l4EL;rW>H=h6fE^1JL$^W!F02?x6bij;MI+)6@k??rz@LSpX~WP< zu}onhfXw^L%O5=4e_{0g9|+BtOx=I-f-jH#H=*cXr9p-N(gp>>%0LM)be98b;($2j zpQ`|mTNoWYN5cSzSNKwB6ZBU!8}hr*CR!*|?7xSpzZs}Mr-u=>3{?)h*0-0ivTI*^ zYI3Cp$Bl5qcv^nJ6Xn!w@36^wa>CASi;z@liS*ic#Un~#AP)0eX5)tMcRo0=Z-5P6 z-4DXpN8AL-;}1BFqS$X=Rjnc?TDkuK)pv-2>A>YlK5JDf@${h$Wx3{@ho##%mKxN? z=|tAszK*fW@4KT<@0WJ*9}geWmh~@!jcJ;V=ATtAXE8G>ExfPnstHI$1yG)R+X)am z|4#UTyN)c*s0A^dkQ-f`GJd#o_J*0HYb6VDD7Q)5#NUgoj)da4vy+E7;TIdPzK}-= z$G^BP-6U$5f@*XbZ)Q99&Cgbk2qPnc_e50E)mr5s@P;XMs+o$a{MQb-mq+yUdwF=P zeFm&x(eVCb))4ALZc>zf{WpvxBTl5{O=u*PO%l33cP;p!Hl8GR362r&kV;!f_p|$L z?2m+_7-{EYHz{6722eG9X`9Zvrk9b(*Ywy#EhIpL5HyiF`6_5;heuU?E z9GZ?hHxUwJ6`1g2(PzLnVVAo+#meyFetifPho93e<^y79 z9eMnzvrkuu#mGYJ6snEn{h4(M6VmFLstA2McS1&9nMw2G!(&a5H||9waguG*KV(_} zq}B{!8z_0!(8t78l*X2!xD?QWcgI&g8e`N6#fC9ksNvyaWGJa8a_s8~5c+f@GUO*s z314)%1Bn!=H@TOCiOImusks%=*IcgRQF?_E5HuY!t|~lOxS*B(E>wUMkj_q&C$Rjn zCWbR~>LYF1+AGtX&kqx8WCKwkL#$`wn3)lz?#ClFDpxx`EXAvtI_#<}m)H7i=#Smo zrp-Xi(^b)6)?M{%kyRUd;?7@MxCho)QzVgORuLOzan)mYr(ZRJxtL#H^9cnnXIH@3 zfBYCxGFs*ZM=2To_yUfvm)Lw>N#ZO6UoE`BcW2KtM6q#6`iL*_>m(Zn!<_T;uWDUm zrZW!PbLl;-?8OP6<2fx_=D*d2ef#lDQ-xuc#n_GUT!=r1#^)0h=EfUi0H-B8kQ$C>D zA7VR>Ed0q_9w+|ocjE>5y+($XIno-CI0h1Q09j;r(B%-LLm;SQ?e6U9W@+sXl9VI> zfdsYOoGsBB$i~3xEk!`K*xJVfWQuM<=k|au2R9w`rh<=$lCFojhc)PrydVIQcXn`g z({(Yov<6NF951g6G8WV__W+XOoIrpgvzM)6I*J2;Zkb9We*jO~f5>aSxOg9hvuST-Q#lnqKF;;Jtv9TsGE6~hOP>`~=X&5u-pyP~d@U%s z3C}=6M}onUvIbPp!?(j7B()VZ+e;qF>M8K2c7EC!f*=207==xZ7vT_p_rzp-Dy#b*{c= z8zzY8=F+ga0Xly(tDb=OvPqO!ZRQK4*Hct@)m$mtLy;NrYG6lvDXPyB{ywoa97%O~ zg+Xx&hLmEy`Y7f|T%&B|3vgrw*G9WuZxG+$?fJc>SSmsF`Tm@gWDWl631u#0MBJ$g zwW;=)Z-MHO<74?=S;NF_Fo6>6-iicxaLG*-E9G-D?f(IwVsT&9yY%5jF7$@s%?1 zA)A{y^wQb^ro4%H(~pMBF@HOxq% zR3xucl(x!d(Nj`Eb;D}dkFv^WJ%&!}x!&90T0{Mgr&8NDTd(VNDuM=mOBN6E$U6!0 zDYF7QG81I3teI88G4qwT)LlyMsZVgxDGDwt#mQ4?@I+5L@bt9U zxBH28VHMUc>otwfr$#HKc}}adF;gY+w&rRQ1TEGpvcaE|J=K%v*O{X^*zOzXOOUZS zUnB4o?bf~Z01rNaEXkUyUnCu09t_YmByKP}YcS(@qW^kL8qXt)Hr&+VhcBwt%T+X;pDtBB21#v(A*PnFwI+(*LX|B{TkUh4H2l!j_*-%B(-AH$9SW4Byf@qV{# ziW_}fi$V0$%P>diSIkdr#I*5DQ*4S8PHOV4r5l5$6zMfPRk$3ALIuP=3zJ;9wucys zQWJ^_=LX~-l+J3wRZ@f%9fkr^dx2qh8x{42m2eQ04hs?`aMmYWmD~LyXRO`p{_#&F zV3s~2lin~x7JF))i%LHFq7LHpHAwAnU~@SM=xc)+d9okO88v~rU@EOR_CF!p?4G{J zh&XSjB&+yztSpvTe!W_qYW`4bgIG3OLaVccH3)-b0JnNrsSfu#opz~z@*Tpu#?T3D zlVF+0xKFt8*-C=N<0I?#pV)&?_zKV`hc2rW*nJ{G<_!cP+M*1!`h_OnzS;{&1S;e8 zf+u4WI2W#2N(z04vNL$6`g+$T) z-k&!ik}(c9HCtFZ{Uc5tYRi~)_%>LXSyidUiDH;Xa9r)x;NL$$hq5*q8)EmAv>srI zJ*r9HHM|W^n5{nFQCS$qD+1$brcAC$BoJYptjogp9^vd#jv^JK@@W*v)MOS&tp=$vam`7G?%kKqRq_x zk(y`{gj-wjIbWlDud)r#i~JrFq&kC~Xok;BidN9ghOCu~_D9v{fc_zc2fZ`-TKk;t zCuct>4thNLH}5!z_jw_|f0!g(U~Q#@{D5?tq9oO6y=oe1Ua8^f&hO^*<8`q`=$kcyy-x?8kE);v#?m~gx%fBE24JZFK2b*d8t!Ok!xQZ? z5D2Q-TDb!j{n9JZ0lbO73@_yO0#@?o9_9|tNCLof0M7E8sfPS(i6eP8YjY20HxL(K zu0b#XU`hzgb^#a0%G1*N7xZ#hTW6A0$`5$=K{KX2O&UzU_d1&C~%MH1?2Q622@}|XDI&-LvH|c z!(TD6-!Y(`)NlKVi2**#FUN|(fr;ebF>xU%(8IrA5OKh_`UMjMifa8Gg9yWcRP$dj z2n47S^(zJgJh5LexH#HVL@)pB0}&x1Q6O#m7fe|EHw-2!@;e5F{)UMQ3H{p7BH}{8 z{|Ucb11|hqp90SV_UrQy6&8j33+CZwZtGy}MgX|Qg1WYT*63$0sN?JmIFEmLkAf;r i2xrjc*Ae}X3W2+axtqu3_d`@zObkN6&aR-TNbo\crcr) +% Thanks to Rainer Dorsch for discovering and reporting that \and +% did not work. +% +% 2) Fixed the biography environment so that if a biography's text is shorter +% than the area allocated for the photo, a collision with the next +% biography does not occur. You can now put real graphics (using the +% graphicx package) into the biography photo box with a new optional +% argument of the biography command! For example: +% +% \begin{biography}[{\includegraphics[width=1in,height=1.25in,clip,keepaspectratio]{./tux.eps}}]{Linux Penguin} +% +% will use the specified graphic as the author's photo. The photo area is +% exactly 1in wide by 1.25in high - as is done in IEEE Transactions. Try +% to keep the same 4:5 aspect ratio if scanning/cropping your photos. +% Note the need for the extra set of enclosing braces around the +% \includegraphics. Without it, The LaTeX parser may get confused when it +% sees the \includegraphics's brackets within the biography's optional +% argument. Due to the length of the \includegraphics command, you may wish +% to define your own shorthand form of it. I have not done so with IEEEtran +% to prevent dependence on the graphicx package. If you do not use the +% optional argument, or leave it empty, a standard frame box with the +% words "Place Photo Here" will be used. If you want the space to remain +% completely empty, you can do: +% +% \begin{biography}[\mbox{}]{The Invisible Man} +% +% The interface to biography's optional argument is into a +% 1in X 1.25in minipage in which the argument text is centered both +% horizontally and vertically: +% +% \begin{minipage}[b][1.25in][c]{1in}% +% \centering +% #1% +% \end{minipage} +% +% Within the biography environment, \unitlength is set to 1in. +% With this in mind, you can even design your own custom frameboxes. +% For instance: +% +% \begin{biography}[\framebox(1,1.25){\parbox[][\height][c]{0.9in}{\centering PLACE\\ PHOTO\\ HERE}}]{Author Name} +% +% will yield the same type of result as the default photo box. +% +% Thanks to Herbert Voss for discovering the collision bug, suggesting the ability +% to handle graphics and providing some prototype code. +% +% +% +%******* +% 3/2001 V1.4 (MDS) changes: +% +% +% 1) New "draftcls" and "final" options have been added. +% Thanks to Dragan Cvetkovic for suggesting an option like draftcls. +% +% 2) Documentation changes to reflect the fact that this IEEEtran.cls +% is no longer beta test. +% +% 3) Slightly revised caption sizes. Figure and table captions are now +% in \footnotesize, not \small as before. +% +% 4) Allow user to control figure caption justification. IEEEtran.cls +% normally defaults to left justified as is done in Transactions. +% However, for conferences, you may wish to issue the command: +% \centerfigcaptionstrue +% in the preamble. Short (less than one line long) figure captions +% will then be centered. Multi-line figure captions will always be +% properly left justified. V1.6: This is already done for you when +% using the conference mode. +% +% +% +%******* +% 1/2001 V1.3 +% Michael Shell (MDS) made extensive changes and additions: +% +% +% BUGS FIXED (and many others too numerous to mention!): +% 1) Fixed improper alignment with itemized, enumerated and +% description lists. Added new controls to these three +% environments so that it is easy to get the alignment IEEE +% uses. Furthermore, the itemize, enumerate and description lists +% no longer force a new paragraph to begin at the end the list +% (\par). (Sometimes lists are used within paragraphs.) +% +% 2) JVH's fixes now allow things like $\mathbf{N}(0,P(0))$ +% to work properly without needing the extra braces: +% ${\mathbf{N}}(0,P(0))$. There is no longer any dependence +% on the "rawfonts" and "oldlfont" packages. Thanks Juergen! +% +% 3) Fixed underfull hbox errors and incorrect reference number +% alignment when the number of references in the bibliography +% exceeded 9 entries (which is almost every paper!). +% +% 4) Removed dependence on the LaTeX sizexx.clo files. +% Now, 9pt documents should work correctly even on systems that +% lack a size9.clo file. This is most often used in conjunction +% with the option "technote" for "correspondence" papers like those +% in IEEE Transactions on Information Theory. For virtually all +% other papers, 10pt is used and so it is the default. +% Some improper font sizes have been corrected. \footnotesize is +% now 8pt in 9pt docs, so footnotes in technotes should be the +% correct size now. +% +% 5) Added \interlinepenalty within the bibliography section to discourage +% LaTeX from breaking within a reference. IEEE almost never breaks within +% a reference and when they do it is usually in technotes +% (correspondence papers). You may get an underfull vbox warning in the +% bibliography indicating that the spacing just before the "REFERENCES" +% section is larger than normal, but the final result will be more like +% what IEEE will publish. See the comments in the BIBLIOGRAPHY section +% around line 2034 below if you want to change this behavior. +% +% 6) No longer "blows up" when you use \paragraph and have a table +% of contents. +% +% 7) Theorem environment changed, (but for V1.6, back to the old way, sigh). +% +% 8) Figure captions adjusted: IEEE left (not center) justifies +% figure captions (for journals) and does not indent figure caption text. +% +% 9) Adjusted some spacings in the table of contents(TOC))/list-of-figures/ +% list-of-tables so that section/table numbers will not so easily +% collide with the titles. Section VIII was usually the worst offender. +% Still doesn't right justify the section numbers, but neither does +% article.cls (This must be why LaTeX likes the x.y.z section numbering +% scheme unlike I, II, III, etc. of IEEE. ) +% It may be "normal" as it is (left justified). sigh. +% +%10) Now uses "index terms" now as a heading instead of "keywords". +% Furthermore, the "index terms" and "abstract" headings are in bold +% italic. This is how IEEE does things. +% +%11) \thebibliography and \biography now put entries into +% the table of contents for you. +% +% ******* +% +% +% +% +% +% ******* +% 9/2000 (JVH) changes: (now designated as V1.2) +% +% made some corrections to get closer to LaTeX2e +% 20000906 Juergen v.Hagen +% vonhagen@ihefiji.etec.uni-karlsruhe.de +% +% Permission to redistribute granted as of December 2000. +% ******* +% +% +% +% +% +% ******* +% +% 1996 (JWD) LaTeX2e version: (now designated as V1.1) +% +% In the most recent TeXhax digest, there was a request for a copy of +% IEEEtrans.sty modified to work with LaTeX2e. I have a version I +% modified to make it IEEEtrans.cls, which I have sent to the person +% making the request and am now sending to you to consider posting to +% the archives. +% -- +% Jon Dixon +% dixonj@colorado.edu +% http://spot.colorado.edu/~dixonj/ +% +%******* +% +% +% +% +% +%******* +% +% 30-August-1993 original LaTeX 2.09 version (IEEEtran.sty), +% (now designated as V1.0): +% +% by Gerry Murray and Silvano Balemi +% Automatic Control Lab, ETH Zurich, Switzerland +% balemi@aut.ee.ethz.ch +% +%******* +% +%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%% +% +% +% +% +% +\ProvidesClass{cssconf}[2004/1/15 revision V1.6b by Pradeep Misra] +%\ProvidesClass{IEEEtran}[2002/11/18 revision V1.6b by Michael Shell] +%\typeout{-- See the "IEEEtran_HOWTO" manual for usage information.} +%\typeout{-- The source comments contain changelog notes.} +\NeedsTeXFormat{LaTeX2e} + +% define new needed flags to indicate document options +% and set a few "failsafe" defaults +\newif\if@twocolumnmode \global\@twocolumnmodetrue +\newif\if@draftversion \global\@draftversionfalse +\newif\if@draftclsmode \global\@draftclsmodefalse +\newif\if@draftclsmodefoot \global\@draftclsmodefootfalse +\newif\if@confmode \global\@confmodefalse +\newif\if@peerreviewoption \global\@peerreviewoptionfalse +\newif\if@peerreviewcaoption \global\@peerreviewcaoptionfalse + +% we HAVE to turn off technote as there is no +% "not a tech note" option +\newif\if@technote \global\@technotefalse + +% V1.6 we allow the user to control whether or not the +% font interword spacings are tuned to be more like +% that of IEEE. The default is to tune things. +\newif\if@fonttunesettings \global\@fonttunesettingstrue + +% V1.6b flag to show if using a4paper +\newif\if@IEEEusingAfourpaper \global\@IEEEusingAfourpaperfalse + +% IEEEtran class scratch pad registers +% dimen +\newdimen\@IEEEtrantmpdimenA +\newdimen\@IEEEtrantmpdimenB +% count +\newcount\@IEEEtrantmpcountA +\newcount\@IEEEtrantmpcountB +% token list +\newtoks\@IEEEtrantmptoksA + +% we use \@IEEEptsize so that we can ID the point size (even for 9pt docs) +% as well as LaTeX's \@ptsize to retain some compatability with some +% external packages +\def\@IEEEptsize{10} +\def\@ptsize{0} +% LaTeX does not support 9pt, so we set \@ptsize to 0 - same as that of 10pt +\DeclareOption{9pt}{\def\@IEEEptsize{9}\def\@ptsize{0}} +\DeclareOption{10pt}{\def\@IEEEptsize{10}\def\@ptsize{0}} +\DeclareOption{11pt}{\def\@IEEEptsize{11}\def\@ptsize{1}} +\DeclareOption{12pt}{\def\@IEEEptsize{12}\def\@ptsize{2}} + + +% \@IEEEmarginE is the side margin for equal margins +% \@IEEEmarginW is the wider side margin when the margins are not equal +% NOTE: BOTH of the above margins are as they appear +% on the paper - they are NOT offset by 1 inch +%\DeclareOption{letterpaper}{\setlength{\paperheight}{11in}% +% \setlength{\paperwidth}{8.5in}% +% \def\@IEEEmarginE{0.680in}% +% \def\@IEEEmarginW{0.775in}% +% \@IEEEusingAfourpaperfalse} +% +% +%\DeclareOption{a4paper}{\setlength{\paperheight}{297mm}% +% \setlength{\paperwidth}{210mm}% +% \def\@IEEEmarginE{14.32mm}% +% \def\@IEEEmarginW{17mm} +% \@IEEEusingAfourpapertrue} +% +% [2004/1/15 revision V1.6b by Pradeep Misra] +\DeclareOption{letterpaper}{\setlength{\paperheight}{11in}% + \setlength{\paperwidth}{8.5in}% +% \setlength{\topmargin}{0in}% + \setlength{\topmargin}{-22pt}% HK May 15 2013 + \def\@IEEEmarginE{0.75in}% + \def\@IEEEmarginW{0.75in}} + + +\DeclareOption{a4paper}{\setlength{\paperheight}{297mm}% + \setlength{\paperwidth}{210mm}% +% \setlength{\topmargin}{-0.69in}% HK May 15 2013 + \setlength{\topmargin}{+32pt}% HK May 15 2013 + \def\@IEEEmarginE{13.15mm}% + \def\@IEEEmarginW{0.75in}} + + +\DeclareOption{oneside}{\@twosidefalse \@mparswitchfalse} +\DeclareOption{twoside}{\@twosidetrue \@mparswitchtrue} + +\DeclareOption{onecolumn}{\global\@twocolumnmodefalse} +% the file twocolumn.sty is not read as it changes \textwidth. +\DeclareOption{twocolumn}{\global\@twocolumnmodetrue} + +% If the user selects draft, then this class AND any packages +% will go into draft mode. +\DeclareOption{draft}{\global\@draftversiontrue \global\@draftclsmodetrue +\global\@draftclsmodefoottrue} +% draftcls is for a draft mode which will not affect any packages +% used by the document. +\DeclareOption{draftcls}{\global\@draftversionfalse \global\@draftclsmodetrue +\global\@draftclsmodefoottrue} +% draftclsnofoot is like draftcls, but without the footer. +\DeclareOption{draftclsnofoot}{\global\@draftversionfalse \global\@draftclsmodetrue +\global\@draftclsmodefootfalse} +% we provide a final option just for completeness (article.cls has one) +\DeclareOption{final}{\global\@draftversionfalse \global\@draftclsmodefalse +\global\@draftclsmodefootfalse} + +\DeclareOption{journal}{\global\@peerreviewoptionfalse \global\@peerreviewcaoptionfalse +\global\@confmodefalse \global\@technotefalse} + +\DeclareOption{conference}{\global\@peerreviewoptionfalse \global\@peerreviewcaoptionfalse +\global\@confmodetrue \global\@technotefalse} + +\DeclareOption{technote}{\global\@peerreviewoptionfalse \global\@peerreviewcaoptionfalse +\global\@confmodefalse \global\@technotetrue} + +\DeclareOption{peerreview}{\global\@peerreviewoptiontrue \global\@peerreviewcaoptionfalse +\global\@confmodefalse \global\@technotefalse} + +\DeclareOption{peerreviewca}{\global\@peerreviewoptiontrue \global\@peerreviewcaoptiontrue +\global\@confmodefalse \global\@technotefalse} + +\DeclareOption{nofonttune}{\global\@fonttunesettingsfalse} + + +% IEEE uses Times font, so we'll default to times. +% These three commands make up the entire times.sty package. +\renewcommand{\sfdefault}{phv} +\renewcommand{\rmdefault}{ptm} +\renewcommand{\ttdefault}{pcr} +% enable Times now - so that all class options can see the correct font families +\normalfont\selectfont + + +% default to US letter paper, 10pt, twocolumn, one sided, final, journal +\ExecuteOptions{letterpaper,10pt,twocolumn,oneside,final,journal} +% overrride these defaults per user requests +\ProcessOptions + +% we can send console reminder messages to the user here +\AtEndDocument{\if@confmode% +\typeout{}% +\typeout{** Conference Paper **}% +\typeout{Before submitting the final camera ready copy, remember to:}% +\typeout{}% +\typeout{ 1. Manually equalize the lengths of two columns on the last page}% +\typeout{ of your paper;}% +\typeout{}% +\typeout{ 2. Ensure that any PostScript and/or PDF output post-processing}% +\typeout{ uses only Type 1 fonts and that every step in the generation}% +\typeout{ process uses the US letter (8.5in X 11in) paper size.}% +\typeout{}% +\fi} + + +% warn about the use of single column other than for draft mode +\if@twocolumnmode\else% + \if@draftclsmode\else% + \typeout{** ATTENTION: Single column mode is not normally used with IEEE publications.}% + \fi% +\fi + + +% V1.6, if the user is using pdflatex, go ahead and set the output paper size. +% Otherwise, we declare the papersize via a \special for dvips. +% We keep the tests within braces because otherwise, if not using pdflatex, +% \pdfpageheight and \pdfpagewidth will be set to \relax - possibly affecting +% similar tests of other packages. +{\@ifundefined{pdfpageheight}{% not using pdflatex, setup paper size for dvips +\if@IEEEusingAfourpaper +\special{papersize=210mm,297mm}% +\else +\special{papersize=8.5in,11in}% +\fi}% +{% using pdftex, set paper size for pdftex +\global\pdfpageheight\paperheight\global\pdfpagewidth\paperwidth}} + + + +% The idea hinted here is for LaTeX to generate markleft{} and markright{} +% automatically for you after you enter \author{}, \journal{}, +% \journaldate{}, journalvol{}, \journalnum{}, etc. +% However, there may be some backward compatibility issues here as +% well as some special applications for IEEEtran.cls and special issues +% that may require the flexible \markleft{}, \markright{} and/or \markboth{}. +% We'll leave this as an open future suggestion. +%\newcommand{\journal}[1]{\def\@journal{#1}} +%\def\@journal{} + + + +% pointsize values +% used with ifx to determine the document's normal size +\def\@IEEEptsizenine{9} +\def\@IEEEptsizeten{10} +\def\@IEEEptsizeeleven{11} +\def\@IEEEptsizetwelve{12} + + + +% FONT DEFINITIONS (No sizexx.clo file needed) +% V1.6 revised font sizes, displayskip values and +% revised normalsize baselineskip to reduce underfull vbox problems +% on the 58pc = 696pt = 9.5in text height we want +% normalsize #lines/column baselineskip (aka leading) +% 9pt 63 11.0476pt (truncated down) +% 10pt 58 12pt (exact) +% 11pt 52 13.3846pt (truncated down) +% 12pt 50 13.92pt (exact) +% + +% we need to store the nominal baselineskip for the given font size +% in case baselinestretch ever changes. +\newskip\@IEEEnormalsizefontbaselineskip +\@IEEEnormalsizefontbaselineskip\baselineskip + +\ifx\@IEEEptsize\@IEEEptsizenine +\typeout{-- This is a 9 point document.} +\def\normalsize{\@setfontsize{\normalsize}{9}{11.0476pt}}% +\setlength{\@IEEEnormalsizefontbaselineskip}{11.0476pt}% +\normalsize +\abovedisplayskip 1.5ex plus3pt minus1pt% +\belowdisplayskip \abovedisplayskip% +\abovedisplayshortskip 0pt plus3pt% +\belowdisplayshortskip 1.5ex plus3pt minus1pt +\def\small{\@setfontsize{\small}{8.5}{10pt}} +\def\footnotesize{\@setfontsize{\footnotesize}{8}{9pt}} +\def\scriptsize{\@setfontsize{\scriptsize}{7}{8pt}} +\def\tiny{\@setfontsize{\tiny}{5}{6pt}} +% sublargesize is the same as large - 10pt +\def\sublargesize{\@setfontsize{\sublargesize}{10}{12pt}} +\def\large{\@setfontsize{\large}{10}{12pt}} +\def\Large{\@setfontsize{\Large}{12}{14pt}} +\def\LARGE{\@setfontsize{\LARGE}{14}{17pt}} +\def\huge{\@setfontsize{\huge}{17}{20pt}} +\def\Huge{\@setfontsize{\Huge}{20}{24pt}} +\fi + + +% Check if we have selected 10 points +\ifx\@IEEEptsize\@IEEEptsizeten +\typeout{-- This is a 10 point document.} +\def\normalsize{\@setfontsize{\normalsize}{10}{12.00pt}}% +\setlength{\@IEEEnormalsizefontbaselineskip}{12pt}% +\normalsize +\abovedisplayskip 1.5ex plus4pt minus2pt% +\belowdisplayskip \abovedisplayskip% +\abovedisplayshortskip 0pt plus4pt% +\belowdisplayshortskip 1.5ex plus4pt minus2pt +\def\small{\@setfontsize{\small}{9}{10pt}} +\def\footnotesize{\@setfontsize{\footnotesize}{8}{9pt}} +\def\scriptsize{\@setfontsize{\scriptsize}{7}{8pt}} +\def\tiny{\@setfontsize{\tiny}{5}{6pt}} +% sublargesize is a tad smaller than large - 11pt +\def\sublargesize{\@setfontsize{\sublargesize}{11}{13.4pt}} +\def\large{\@setfontsize{\large}{12}{14pt}} +\def\Large{\@setfontsize{\Large}{14}{17pt}} +\def\LARGE{\@setfontsize{\LARGE}{16}{20pt}} +\def\huge{\@setfontsize{\huge}{20}{24pt}} +\def\Huge{\@setfontsize{\Huge}{24}{28pt}} +\fi + + +% Check if we have selected 11 points +\ifx\@IEEEptsize\@IEEEptsizeeleven +\typeout{-- This is an 11 point document.} +\def\normalsize{\@setfontsize{\normalsize}{11}{13.3846pt}}% +\setlength{\@IEEEnormalsizefontbaselineskip}{13.3846pt}% +\normalsize +\abovedisplayskip 1.5ex plus5pt minus3pt% +\belowdisplayskip \abovedisplayskip% +\abovedisplayshortskip 0pt plus5pt% +\belowdisplayshortskip 1.5ex plus5pt minus3pt +\def\small{\@setfontsize{\small}{10}{12pt}} +\def\footnotesize{\@setfontsize{\footnotesize}{9}{10.5pt}} +\def\scriptsize{\@setfontsize{\scriptsize}{8}{9pt}} +\def\tiny{\@setfontsize{\tiny}{6}{7pt}} +% sublargesize is the same as large - 12pt +\def\sublargesize{\@setfontsize{\sublargesize}{12}{14pt}} +\def\large{\@setfontsize{\large}{12}{14pt}} +\def\Large{\@setfontsize{\Large}{14}{17pt}} +\def\LARGE{\@setfontsize{\LARGE}{17}{20pt}} +\def\huge{\@setfontsize{\huge}{20}{24pt}} +\def\Huge{\@setfontsize{\Huge}{24}{28pt}} +\fi + + +% Check if we have selected 12 points +\ifx\@IEEEptsize\@IEEEptsizetwelve +\typeout{-- This is a 12 point document.} +\def\normalsize{\@setfontsize{\normalsize}{12}{13.92pt}}% +\setlength{\@IEEEnormalsizefontbaselineskip}{13.92pt}% +\normalsize +\abovedisplayskip 1.5ex plus6pt minus4pt% +\belowdisplayskip \abovedisplayskip% +\abovedisplayshortskip 0pt plus6pt% +\belowdisplayshortskip 1.5ex plus6pt minus4pt +\def\small{\@setfontsize{\small}{10}{12pt}} +\def\footnotesize{\@setfontsize{\footnotesize}{9}{10.5pt}} +\def\scriptsize{\@setfontsize{\scriptsize}{8}{9pt}} +\def\tiny{\@setfontsize{\tiny}{6}{7pt}} +% sublargesize is the same as large - 14pt +\def\sublargesize{\@setfontsize{\sublargesize}{14}{17pt}} +\def\large{\@setfontsize{\large}{14}{17pt}} +\def\Large{\@setfontsize{\Large}{17}{20pt}} +\def\LARGE{\@setfontsize{\LARGE}{20}{24pt}} +\def\huge{\@setfontsize{\huge}{22}{26pt}} +\def\Huge{\@setfontsize{\Huge}{24}{28pt}} +\fi + + +% V1.6 The Computer Modern Fonts will issue a substitution warning for +% 24pt titles (24.88pt is used instead) increase the substitution +% tolerance to turn off this warning +\def\fontsubfuzz{.9pt} +% However, the default (and correct) Times font will scale exactly as needed. + + +% warn the user in case they forget to use the 9pt option with +% technote +\if@technote% + \ifx\@IEEEptsize\@IEEEptsizenine\else% + \typeout{** ATTENTION: Technotes are normally 9pt documents.}% + \fi% +\fi + + +% set \baselinestretch +\def\baselinestretch{1} +\if@draftclsmode% draft mode uses larger than normal spacing +\def\baselinestretch{1.5} % controls line spacing for draft version +\fi % some people may like 1.7 or greater + % so that there will be even more space + % for hand written comments + +\normalsize % make \baselinestretch take affect + + +% V1.6 +% store the normalsize baselineskip +\newskip\normalsizebaselineskip +\normalsizebaselineskip=\baselineskip\relax +% store the nominal value of jot +\newskip\normaljot +\normaljot=0.25\normalsizebaselineskip\relax + +% set \jot +\jot=\normaljot\relax + + +% abstract and keywords are in \small, except +% for 9pt docs in which they are in \footnotesize +% Since 9pt docs use an 8pt footnotesize, \small +% becomes a rather awkward 8.5pt +\let\@IEEEabskeysecsize=\small +\ifx\@IEEEptsize\@IEEEptsizenine + \let\@IEEEabskeysecsize=\footnotesize +\fi + + + +% V1.6, we are now going to fine tune the interword spacing +% The default interword glue for Times under TeX appears to use a +% nominal interword spacing of 25% (relative to the font size, i.e., 1em) +% a maximum of 40% and a minimum of 19%. +% For example, 10pt text uses an interword glue of: +% +% 2.5pt plus 1.49998pt minus 0.59998pt +% +% However, IEEE allows for a more generous range which reduces the need +% for hyphenation, especially for two column text. Furthermore, IEEE +% tends to use a little bit more nominal space between the words. +% IEEE's interword spacing percentages appear to be: +% 35% nominal +% 23% minimum +% 50% maximum +% (They may even be using a tad more for the largest fonts such as 24pt.) +% +% for bold text, IEEE increases the spacing a little more: +% 37.5% nominal +% 23% minimum +% 55% maximum + +% here are the interword spacing ratios we'll use +% for medium (normal weight) +\def\@IEEEinterspaceratioM{0.35} +\def\@IEEEinterspaceMINratioM{0.23} +\def\@IEEEinterspaceMAXratioM{0.50} + +% for bold +\def\@IEEEinterspaceratioB{0.375} +\def\@IEEEinterspaceMINratioB{0.23} +\def\@IEEEinterspaceMAXratioB{0.55} + + +% command to revise the interword spacing for the current font under TeX: +% \fontdimen2 = nominal interword space +% \fontdimen3 = interword stretch +% \fontdimen4 = interword shrink +% since all changes to the \fontdimen are global, we can enclose these commands +% in braces to confine any font attribute or length changes +\def\@@@IEEEsetfontdimens#1#2#3{{% +\setlength{\@IEEEtrantmpdimenB}{\f@size pt}% grab the font size in pt, could use 1em instead. +\setlength{\@IEEEtrantmpdimenA}{#1\@IEEEtrantmpdimenB}% +\fontdimen2\font=\@IEEEtrantmpdimenA\relax +\addtolength{\@IEEEtrantmpdimenA}{-#2\@IEEEtrantmpdimenB}% +\fontdimen3\font=-\@IEEEtrantmpdimenA\relax +\setlength{\@IEEEtrantmpdimenA}{#1\@IEEEtrantmpdimenB}% +\addtolength{\@IEEEtrantmpdimenA}{-#3\@IEEEtrantmpdimenB}% +\fontdimen4\font=\@IEEEtrantmpdimenA\relax}} + +% revise the interword spacing for each font weight +\def\@@IEEEsetfontdimens{{% +\mdseries +\@@@IEEEsetfontdimens{\@IEEEinterspaceratioM}{\@IEEEinterspaceMAXratioM}{\@IEEEinterspaceMINratioM}% +\bfseries +\@@@IEEEsetfontdimens{\@IEEEinterspaceratioB}{\@IEEEinterspaceMAXratioB}{\@IEEEinterspaceMINratioB}% +}} + +% revise the interword spacing for each font shape +% \slshape is not often used for IEEE work and is not altered here. The \scshape caps are +% already a tad too large in the free LaTeX fonts (as compared to what IEEE uses) so we +% won't alter these either. +\def\@IEEEsetfontdimens{{% +\normalfont +\@@IEEEsetfontdimens +\normalfont\itshape +\@@IEEEsetfontdimens +}} + +% if the nofonttune class option is not given, revise the interword spacing +% for each font size (and shape and weight). Only the \rmfamily is done here +% as \ttfamily uses a fixed spacing and \sffamily is not used as the main +% text of IEEE papers. +\def\@IEEEtunefonts{% +\if@fonttunesettings +{\selectfont\rmfamily +\tiny\@IEEEsetfontdimens +\scriptsize\@IEEEsetfontdimens +\footnotesize\@IEEEsetfontdimens +\small\@IEEEsetfontdimens +\normalsize\@IEEEsetfontdimens +\sublargesize\@IEEEsetfontdimens +\large\@IEEEsetfontdimens +\LARGE\@IEEEsetfontdimens +\huge\@IEEEsetfontdimens +\Huge\@IEEEsetfontdimens}\fi} + +% if needed, revise the interword spacing now - in case IEEEtran makes any default +% length measurements, and make sure all the default fonts are loaded +\@IEEEtunefonts + +% and again at the start of the document in case the user loaded different fonts +\AtBeginDocument{\@IEEEtunefonts} + + + +% V1.6 +% LaTeX is a little to quick to use hyphenations +% So, we increase the penalty for their use and raise +% the badness level that triggers an underfull hbox +% warning. The author may still have to tweak things, +% but the appearance will be much better "right out +% of the box" than that under V1.5 and prior. +% TeX default is 50 +\hyphenpenalty=750 +% If we didn't adjust the interword spacing, 2200 might be better. +% The TeX default is 1000 +\hbadness=1350 +% IEEE does not use extra spacing after punctuation +\frenchspacing + + +% we want to maintain textheight as an integer multiple of +% \baselineskip. Keep \topsep in with this game plan too. +\topskip=\baselineskip +% set sizes and margins +% Book typesetting is a world where point and pica (12pt) reign supreme. +% IEEE textwidth is 21 pica. They have a colsep of 1 pica. +% V1.6 conference mode margins +\if@confmode + % [2004/10/15 revision V1.6c by Pradeep Misra] + %\topmargin -0.25in % HK May 15 2013 + \textheight 9.5in % The standard for conferences + % However, we will adjust this a tad so that an integer number + % of lines will always fit on each page + % The baselineskip (leading) for each document point size is used + % to determine these values + % rounded up an extra 0.1pt or so to prevent trouble with any rounding errors + \ifx\@IEEEptsize\@IEEEptsizenine\textheight=682.0pt\fi %9.4722in 61 lines/page + \ifx\@IEEEptsize\@IEEEptsizeten\textheight=684.0pt\fi %9.5in 57 lines/page + \ifx\@IEEEptsize\@IEEEptsizeeleven\textheight=673.2pt\fi %9.2611in 51 lines/page + \ifx\@IEEEptsize\@IEEEptsizetwelve\textheight=676.8pt\fi %9.2473in 47 lines/page +\else + \topmargin -49.0pt + \textheight 58pc % = 9.63in or 696pt +\fi + + % [2004/1/15 revision V1.6b by Pradeep Misra] +%\textwidth 43pc % 2 x 21pc + 1pc = 43pc +%\columnsep 1pc + +\textwidth 7.0in % 2 x 21pc + 1pc = 43pc +\columnsep 0.2in + +% IEEE MARGIN INFO and new \overrideIEEEmargins command +% V1.6 revised margins again +% IEEE wants the side margins to be equal under both US letter +% and A4 paper +% +% However, for those of you who need to bind copies of your work +% (for review distribution, etc.) the \overrideIEEEmargins +% command will shift the text a tad away from the binding +% edge. +% +% + + +% the default side margins are equal +\oddsidemargin \@IEEEmarginE +\addtolength{\oddsidemargin}{-1in}% compensate for LaTeX's 1in offset +\evensidemargin \@IEEEmarginE +\addtolength{\evensidemargin}{-1in}% compensate for LaTeX's 1in offset + +% execute \overrideIEEEmargins in the preamble to make the side margin +% near the spine slightly wider so that the paper will be much more +% agreeable to being bound. \overrideIEEEmargins will have no effect +% when in draft or draftcls mode. +\def\overrideIEEEmargins{\if@draftclsmode\relax\else% + \typeout{** ATTENTION: Overriding IEEE standard margins (line \the\inputlineno).}% + \if@twoside + % for double sided, odd pages have the bound side on the left + % make this the wide margin + \oddsidemargin\@IEEEmarginW + % and even pages have the narrow margin on the left + % as they are bound on the right + % evensidemargin is to be the narrow margin + % calculate the narrow margin and set evensidemargin + \setlength{\evensidemargin}{\paperwidth}% + \addtolength{\evensidemargin}{-\@IEEEmarginW}% + \addtolength{\evensidemargin}{-\textwidth}% + \else + % for single sided the bound side is always on the left + % make this the wide margin + \oddsidemargin\@IEEEmarginW + \evensidemargin\@IEEEmarginW + \fi + \addtolength{\oddsidemargin}{-1.0in}% compensate for LaTeX's 1in offset + \addtolength{\evensidemargin}{-1.0in}% +\fi} + + +\parindent 1.0em + +% conference papers do not have headers, other papers need +% to reserve space for them +\if@confmode +\headsep 0in +\headheight 0in +\else +\headsep 0.25in +\headheight 12pt +\fi + +% V1.6, if things get too close, go ahead and let them touch +\lineskip 0pt +\normallineskip 0pt +\lineskiplimit 0pt +\normallineskiplimit 0pt + + +% The distance from the lower edge of the text body to the +% footline +\footskip 0.4in + +% normally zero, should be relative to font height. +% put in a little rubber to help stop some bad breaks (underfull vboxes) +\parskip 0ex plus 0.2ex minus 0.1ex + + + +% draft mode settings override that of all other modes +% provides a nice 1" margin all around the paper and extra +% space between the lines for editor's comments +\if@draftclsmode +\headsep 0.25in +\headheight 12pt +% want 1" from top of paper to text +\setlength{\topmargin}{-\headsep}% +\addtolength{\topmargin}{-\headheight}% + +% we want 1in side margins regardless of paper type +\oddsidemargin 0in +\evensidemargin 0in + +% set the text width - start with the entire page +\setlength{\textwidth}{\paperwidth}% +% subtract for the 1" top/bottom margins +\addtolength{\textwidth}{-2.0in}% +% give them a textheight that won't have underfull +% vbox problems, but can't help them if they later change +% baselinestretch from its default +\setlength{\textheight}{\paperheight}% +\addtolength{\textheight}{-2.0in}% +% subtract of first line taken by \topskip +\addtolength{\textheight}{-1\topskip}% +% now digitize \textheight so that the length after +% the first line is an integer multiple of \baselineskip +% to cut down on underfull vbox errors in draft mode +\divide\textheight by \baselineskip% +\multiply\textheight by \baselineskip% +% add back the first line +\addtolength{\textheight}{\topskip}% +\fi + + + +% margin note stuff +\marginparsep 10pt +\marginparwidth 20pt +\marginparpush 25pt + + +% LIST SPACING CONTROLS + +% Controls the amount of EXTRA spacing +% above and below \trivlist +% Both \list and IED lists override this. +% However, \trivlist will use this as will most +% things built from \trivlist like the \center +% environment. +\topsep 0.5\baselineskip + +% Controls the additional spacing around lists preceded +% or followed by blank lines. IEEE does not increase +% spacing before or after paragraphs so it is set to zero. +% \z@ is the same as zero, but faster. +\partopsep \z@ + +% Controls the spacing between paragraphs in lists. +% IEEE does not increase spacing before or after paragraphs +% so this is also zero. +% With IEEEtran.cls, global changes to +% this value DO affect lists (but not IED lists). +\parsep \z@ + +% Controls the extra spacing between list items. +% IEEE does not put extra spacing between items. +% With IEEEtran.cls, global changes to this value DO affect +% lists (but not IED lists). +\itemsep \z@ + +% \itemindent is the amount to indent the FIRST line of a list +% item. It is auto set to zero within the \list environment. To alter +% it, you have to do so when you call the \list. +% However, IEEE uses this for the theorem environment +% There is an alternative value for this near \leftmargini below +\itemindent -1em + +% \leftmargin, the spacing from the left margin of the main text to +% the left of the main body of a list item is set by \list. +% Hence this statement does nothing for lists. +% But, quote and verse do use it for indention. +\leftmargin 2em + +% we retain this stuff from the older IEEEtran.cls so that \list +% will work the same way as before. However, itemize, enumerate and +% description (IED) could care less about what these are as they +% all are overridden. +\leftmargini 2em +%\itemindent 2em % Alternative values: sometimes used. +%\leftmargini 0em +\leftmarginii 1em +\leftmarginiii 1.5em +\leftmarginiv 1.5em +\leftmarginv 1.0em +\leftmarginvi 1.0em +\labelsep 0.5em +\labelwidth \z@ + + +% The old IEEEtran.cls behavior of \list is retained. +% However, the new V1.3 IED list environments override all the +% @list stuff (\@listX is called within \list for the +% appropriate level just before the user's list_decl is called). +% \topsep is now 2pt as IEEE puts a little extra space around +% lists - used by those non-IED macros that depend on \list. +% Note that \parsep and \itemsep are not redefined as in +% the sizexx.clo \@listX (which article.cls uses) so global changes +% of these values DO affect \list +% +\def\@listi{\leftmargin\leftmargini \topsep 2pt plus 1pt minus 1pt} +\let\@listI\@listi +\def\@listii{\leftmargin\leftmarginii\labelwidth\leftmarginii% + \advance\labelwidth-\labelsep \topsep 2pt} +\def\@listiii{\leftmargin\leftmarginiii\labelwidth\leftmarginiii% + \advance\labelwidth-\labelsep \topsep 2pt} +\def\@listiv{\leftmargin\leftmarginiv\labelwidth\leftmarginiv% + \advance\labelwidth-\labelsep \topsep 2pt} +\def\@listv{\leftmargin\leftmarginv\labelwidth\leftmarginv% + \advance\labelwidth-\labelsep \topsep 2pt} +\def\@listvi{\leftmargin\leftmarginvi\labelwidth\leftmarginvi% + \advance\labelwidth-\labelsep \topsep 2pt} + + +% IEEE uses 5) not 5. +\def\labelenumi{\theenumi)} \def\theenumi{\arabic{enumi}} + +% IEEE uses a) not (a) +\def\labelenumii{\theenumii)} \def\theenumii{\alph{enumii}} + +% IEEE uses iii) not iii. +\def\labelenumiii{\theenumiii)} \def\theenumiii{\roman{enumiii}} + +% IEEE uses A) not A. +\def\labelenumiv{\theenumiv)} \def\theenumiv{\Alph{enumiv}} + +% exactly the same as in article.cls +\def\p@enumii{\theenumi} +\def\p@enumiii{\theenumi(\theenumii)} +\def\p@enumiv{\p@enumiii\theenumiii} + +% itemized list label styles +\def\labelitemi{$\scriptstyle\bullet$} +\def\labelitemii{\textbf{--}} +\def\labelitemiii{$\ast$} +\def\labelitemiv{$\cdot$} + + +% IEEEtran.cls version numbers, provided as of V1.3 +% These values serve as a way a .tex file can +% determine if the new features are provided. +% The version number of this IEEEtrans.cls can be obtained from +% these values. i.e., V1.4 +% KEEP THESE AS INTEGERS! i.e., NO {4a} or anything like that- +% (no need to enumerate "a" minor changes here) +\def\IEEEtransversionmajor{1} +\def\IEEEtransversionminor{6} + + +% **** V1.3 ENHANCEMENTS **** +% Itemize, Enumerate and Description (IED) List Controls +% *************************** +% +% +% IEEE seems to use at least two different values by +% which ITEMIZED list labels are indented to the right +% For The Journal of Lightwave Technology (JLT) and The Journal +% on Selected Areas in Communications (JSAC), they tend to use +% an indention equal to \parindent. For Transactions on Communications +% they tend to indent ITEMIZED lists a little more--- 1.3\parindent. +% We'll provide both values here for you so that you can choose +% which one you like in your document using a command such as: +% setlength{\IEEEilabelindent}{\IEEEilabelindentB} +\newdimen\IEEEilabelindentA +\IEEEilabelindentA \parindent + +\newdimen\IEEEilabelindentB +\IEEEilabelindentB 1.3\parindent +% However, we'll default to using \parindent +% which makes more sense to me +\newdimen\IEEEilabelindent +\IEEEilabelindent \IEEEilabelindentA + + +% This controls the default amount the enumerated list labels +% are indented to the right. +% Normally, this is the same as the paragraph indention +\newdimen\IEEEelabelindent +\IEEEelabelindent \parindent + +% This controls the default amount the description list labels +% are indented to the right. +% Normally, this is the same as the paragraph indention +\newdimen\IEEEdlabelindent +\IEEEdlabelindent \parindent + +% This is the value actually used within the IED lists. +% The IED environments automatically set its value to +% one of the three values above, so global changes do +% not have any effect +\newdimen\labelindent +\labelindent \parindent + +% The actual amount labels will be indented is +% \labelindent multiplied by the factor below +% corresponding to the level of nesting depth +% This provides a means by which the user can +% alter the effective \labelindent for deeper +% levels +% There may not be such a thing as correct "standard IEEE" +% values. What IEEE actually does may depend on the specific +% circumstances. +% The first list level almost always has full indention. +% The second levels I've seen have only 75% of the normal indentation +% Three level or greater nestings are very rare. I am guessing +% that they don't use any indentation. +\def\IEEElabelindentfactori{1.0} % almost always one +\def\IEEElabelindentfactorii{0.75} % 0.0 or 1.0 may be used in some cases +\def\IEEElabelindentfactoriii{0.0} % 0.75? 0.5? 0.0? +\def\IEEElabelindentfactoriv{0.0} +\def\IEEElabelindentfactorv{0.0} +\def\IEEElabelindentfactorvi{0.0} + +% value actually used within IED lists, it is auto +% set to one of the 6 values above +% global changes here have no effect +\def\labelindentfactor{1.0} + +% This controls the default spacing between the end of the IED +% list labels and the list text, when normal text is used for +% the labels. +\newdimen\IEEEiednormlabelsep +\IEEEiednormlabelsep 0.6em + +% This controls the default spacing between the end of the IED +% list labels and the list text, when math symbols are used for +% the labels (nomenclature lists). IEEE usually increases the +% spacing in these cases +\newdimen\IEEEiedmathlabelsep +\IEEEiedmathlabelsep 1.2em + +% This controls the extra vertical separation put above and +% below each IED list. IEEE usually puts a little extra spacing +% around each list. However, this spacing is barely noticeable. +\newskip\IEEEiedtopsep +\IEEEiedtopsep 2pt plus 1pt minus 1pt + + +% This command is executed within each IED list environment +% at the beginning of the list. You can use this to set the +% parameters for some/all your IED list(s) without disturbing +% global parameters that affect things other than lists. +% i.e., renewcommand{\iedlistdecl}{\setlength{\labelsep}{5em}} +% will alter the \labelsep for the next list(s) until +% \iedlistdecl is redefined. +\def\iedlistdecl{\relax} + +% This command provides an easy way to set \leftmargin based +% on the \labelwidth, \labelsep and the argument \labelindent +% Usage: \calcleftmargin{width-to-indent-the-label} +% output is in the \leftmargin variable, i.e., effectively: +% \leftmargin = argument + \labelwidth + \labelsep +% Note controlled spacing here, shield end of lines with % +\def\calcleftmargin#1{\setlength{\leftmargin}{#1}% +\addtolength{\leftmargin}{\labelwidth}% +\addtolength{\leftmargin}{\labelsep}} + +% This command provides an easy way to set \labelwidth to the +% width of the given text. It is the same as +% \settowidth{\labelwidth}{label-text} +% and useful as a shorter alternative. +% Typically used to set \labelwidth to be the width +% of the longest label in the list +\def\setlabelwidth#1{\settowidth{\labelwidth}{#1}} + +% When this command is executed, IED lists will use the +% IEEEiedmathlabelsep label separation rather than the normal +% spacing. To have an effect, this command must be executed via +% the \iedlistdecl or within the option of the IED list +% environments. +\def\usemathlabelsep{\setlength{\labelsep}{\IEEEiedmathlabelsep}} + +% A flag which controls whether the IED lists automatically +% calculate \leftmargin from \labelindent, \labelwidth and \labelsep +% Useful if you want to specify your own \leftmargin +% This flag must be set (\nocalcleftmargintrue or \nocalcleftmarginfalse) +% via the \iedlistdecl or within the option of the IED list +% environments to have an effect. +\newif\ifnocalcleftmargin +\nocalcleftmarginfalse + +% A flag which controls whether \labelindent is multiplied by +% the \labelindentfactor for each list level. +% This flag must be set via the \iedlistdecl or within the option +% of the IED list environments to have an effect. +\newif\ifnolabelindentfactor +\nolabelindentfactorfalse + + +% internal variable to indicate type of IED label +% justification +% 0 - left; 1 - center; 2 - right +\def\@iedjustify{0} + + +% commands to allow the user to control IED +% label justifications. Use these commands within +% the IED environment option or in the \iedlistdecl +% Note that changing the normal list justifications +% is nonstandard and IEEE may not like it if you do so! +% I include these commands as they may be helpful to +% those who are using these enhanced list controls for +% other non-IEEE related LaTeX work. +% itemize and enumerate automatically default to right +% justification, description defaults to left. +\def\iedlabeljustifyl{\def\@iedjustify{0}}%left +\def\iedlabeljustifyc{\def\@iedjustify{1}}%center +\def\iedlabeljustifyr{\def\@iedjustify{2}}%right + + + + +% commands to save to and restore from the list parameter copies +% this allows us to set all the list parameters within +% the list_decl and prevent \list (and its \@list) +% from overriding any of our parameters +% V1.6 use \edefs instead of dimen's to conserve dimen registers +% Note controlled spacing here, shield end of lines with % +\def\@IEEEsavelistparams{\edef\@IEEEiedtopsep{\the\topsep}% +\edef\@IEEEiedlabelwidth{\the\labelwidth}% +\edef\@IEEEiedlabelsep{\the\labelsep}% +\edef\@IEEEiedleftmargin{\the\leftmargin}% +\edef\@IEEEiedpartopsep{\the\partopsep}% +\edef\@IEEEiedparsep{\the\parsep}% +\edef\@IEEEieditemsep{\the\itemsep}% +\edef\@IEEEiedrightmargin{\the\rightmargin}% +\edef\@IEEEiedlistparindent{\the\listparindent}% +\edef\@IEEEieditemindent{\the\itemindent}} + +% Note controlled spacing here +\def\@IEEErestorelistparams{\topsep\@IEEEiedtopsep\relax% +\labelwidth\@IEEEiedlabelwidth\relax% +\labelsep\@IEEEiedlabelsep\relax% +\leftmargin\@IEEEiedleftmargin\relax% +\partopsep\@IEEEiedpartopsep\relax% +\parsep\@IEEEiedparsep\relax% +\itemsep\@IEEEieditemsep\relax% +\rightmargin\@IEEEiedrightmargin\relax% +\listparindent\@IEEEiedlistparindent\relax% +\itemindent\@IEEEieditemindent\relax} + + +% v1.6b provide original LaTeX IED list environments +% note that latex.ltx defines \itemize and \enumerate, but not \description +% which must be created by the base classes +% save original LaTeX itemize and enumerate +\let\LaTeXitemize\itemize +\let\endLaTeXitemize\enditemize +\let\LaTeXenumerate\enumerate +\let\endLaTeXenumerate\endenumerate + +% provide original LaTeX description environment from article.cls +\newenvironment{LaTeXdescription} + {\list{}{\labelwidth\z@ \itemindent-\leftmargin + \let\makelabel\descriptionlabel}} + {\endlist} +\newcommand*\descriptionlabel[1]{\hspace\labelsep + \normalfont\bfseries #1} + + +% override LaTeX's default IED lists +\def\itemize{\@IEEEitemize} +\def\enditemize{\@endIEEEitemize} +\def\enumerate{\@IEEEenumerate} +\def\endenumerate{\@endIEEEenumerate} +\def\description{\@IEEEdescription} +\def\enddescription{\@endIEEEdescription} + +% provide the user with aliases - may help those using packages that +% override itemize, enumerate, or description +\def\IEEEitemize{\@IEEEitemize} +\def\endIEEEitemize{\@endIEEEitemize} +\def\IEEEenumerate{\@IEEEenumerate} +\def\endIEEEenumerate{\@endIEEEenumerate} +\def\IEEEdescription{\@IEEEdescription} +\def\endIEEEdescription{\@endIEEEdescription} + + +% V1.6 we want to keep the IEEEtran IED list definitions as our own internal +% commands so they are protected against redefinition +\def\@IEEEitemize{\@ifnextchar[{\@@IEEEitemize}{\@@IEEEitemize[\relax]}} +\def\@IEEEenumerate{\@ifnextchar[{\@@IEEEenumerate}{\@@IEEEenumerate[\relax]}} +\def\@IEEEdescription{\@ifnextchar[{\@@IEEEdescription}{\@@IEEEdescription[\relax]}} +\def\@endIEEEitemize{\endlist} +\def\@endIEEEenumerate{\endlist} +\def\@endIEEEdescription{\endlist} + + +% DO NOT ALLOW BLANK LINES TO BE IN THESE IED ENVIRONMENTS +% AS THIS WILL FORCE NEW PARAGRAPHS AFTER THE IED LISTS +% IEEEtran itemized list MDS 1/2001 +% Note controlled spacing here, shield end of lines with % +\def\@@IEEEitemize[#1]{% + \ifnum\@itemdepth>3\relax\@toodeep\else% + \ifnum\@listdepth>5\relax\@toodeep\else% + \advance\@itemdepth\@ne% + \edef\@itemitem{labelitem\romannumeral\the\@itemdepth}% + % get the labelindentfactor for this level + \advance\@listdepth\@ne% we need to know what the level WILL be + \edef\labelindentfactor{\csname IEEElabelindentfactor\romannumeral\the\@listdepth\endcsname}% + \advance\@listdepth-\@ne% undo our increment + \def\@iedjustify{2}% right justified labels are default + % set other defaults + \nocalcleftmarginfalse% + \nolabelindentfactorfalse% + \topsep\IEEEiedtopsep% + \labelindent\IEEEilabelindent% + \labelsep\IEEEiednormlabelsep% + \partopsep 0ex% + \parsep 0ex% + \itemsep 0ex% + \rightmargin 0em% + \listparindent 0em% + \itemindent 0em% + % calculate the label width + % the user can override this later if + % they specified a \labelwidth + \settowidth{\labelwidth}{\csname labelitem\romannumeral\the\@itemdepth\endcsname}% + \@IEEEsavelistparams% save our list parameters + \list{\csname\@itemitem\endcsname}{% + \@IEEErestorelistparams% override any list{} changes + % to our globals + \let\makelabel\@IEEEiedmakelabel% v1.6b setup \makelabel + \iedlistdecl% let user alter parameters + #1\relax% + % If the user has requested not to use the + % labelindent factor, don't revise \labelindent + \ifnolabelindentfactor\relax% + \else\labelindent=\labelindentfactor\labelindent% + \fi% + % Unless the user has requested otherwise, + % calculate our left margin based + % on \labelindent, \labelwidth and + % \labelsep + \ifnocalcleftmargin\relax% + \else\calcleftmargin{\labelindent}% + \fi}\fi\fi}% + + +% DO NOT ALLOW BLANK LINES TO BE IN THESE IED ENVIRONMENTS +% AS THIS WILL FORCE NEW PARAGRAPHS AFTER THE IED LISTS +% IEEEtran enumerate list MDS 1/2001 +% Note controlled spacing here, shield end of lines with % +\def\@@IEEEenumerate[#1]{% + \ifnum\@enumdepth>3\relax\@toodeep\else% + \ifnum\@listdepth>5\relax\@toodeep\else% + \advance\@enumdepth\@ne% + \edef\@enumctr{enum\romannumeral\the\@enumdepth}% + % get the labelindentfactor for this level + \advance\@listdepth\@ne% we need to know what the level WILL be + \edef\labelindentfactor{\csname IEEElabelindentfactor\romannumeral\the\@listdepth\endcsname}% + \advance\@listdepth-\@ne% undo our increment + \def\@iedjustify{2}% right justified labels are default + % set other defaults + \nocalcleftmarginfalse% + \nolabelindentfactorfalse% + \topsep\IEEEiedtopsep% + \labelindent\IEEEelabelindent% + \labelsep\IEEEiednormlabelsep% + \partopsep 0ex% + \parsep 0ex% + \itemsep 0ex% + \rightmargin 0em% + \listparindent 0em% + \itemindent 0em% + % calculate the label width + % We'll set it to the width suitable for all labels using + % normalfont 1) to 9) + % The user can override this later + \settowidth{\labelwidth}{9)}% + \@IEEEsavelistparams% save our list parameters + \list{\csname label\@enumctr\endcsname}{\usecounter{\@enumctr}% + \@IEEErestorelistparams% override any list{} changes + % to our globals + \let\makelabel\@IEEEiedmakelabel% v1.6b setup \makelabel + \iedlistdecl% let user alter parameters + #1\relax% + % If the user has requested not to use the + % labelindent factor, don't revise \labelindent + \ifnolabelindentfactor\relax% + \else\labelindent=\labelindentfactor\labelindent% + \fi% + % Unless the user has requested otherwise, + % calculate our left margin based + % on \labelindent, \labelwidth and + % \labelsep + \ifnocalcleftmargin\relax% + \else\calcleftmargin{\labelindent}% + \fi}\fi\fi}% + + +% DO NOT ALLOW BLANK LINES TO BE IN THESE IED ENVIRONMENTS +% AS THIS WILL FORCE NEW PARAGRAPHS AFTER THE IED LISTS +% IEEEtran description list MDS 1/2001 +% Note controlled spacing here, shield end of lines with % +\def\@@IEEEdescription[#1]{% + \ifnum\@listdepth>5\relax\@toodeep\else% + % get the labelindentfactor for this level + \advance\@listdepth\@ne% we need to know what the level WILL be + \edef\labelindentfactor{\csname IEEElabelindentfactor\romannumeral\the\@listdepth\endcsname}% + \advance\@listdepth-\@ne% undo our increment + \def\@iedjustify{0}% left justified labels are default + % set other defaults + \nocalcleftmarginfalse% + \nolabelindentfactorfalse% + \topsep\IEEEiedtopsep% + \labelindent\IEEEdlabelindent% + % assume normal labelsep + \labelsep\IEEEiednormlabelsep% + \partopsep 0ex% + \parsep 0ex% + \itemsep 0ex% + \rightmargin 0em% + \listparindent 0em% + \itemindent 0em% + % Bogus label width in case the user forgets + % to set it. + % TIP: If you want to see what a variable's width is you + % can use the TeX command \showthe\width-variable to + % display it on the screen during compilation + % (This might be helpful to know when you need to find out + % which label is the widest) + \settowidth{\labelwidth}{Hello}% + \@IEEEsavelistparams% save our list parameters + \list{}{\@IEEErestorelistparams% override any list{} changes + % to our globals + \let\makelabel\@IEEEiedmakelabel% v1.6b setup \makelabel + \iedlistdecl% let user alter parameters + #1\relax% + % If the user has requested not to use the + % labelindent factor, don't revise \labelindent + \ifnolabelindentfactor\relax% + \else\labelindent=\labelindentfactor\labelindent% + \fi% + % Unless the user has requested otherwise, + % calculate our left margin based + % on \labelindent, \labelwidth and + % \labelsep + \ifnocalcleftmargin\relax% + \else\calcleftmargin{\labelindent}\relax% + \fi}\fi} + +% v1.6b we use one makelabel that does justification as needed. +\def\@IEEEiedmakelabel#1{\relax\if\@iedjustify 0\relax +\makebox[\labelwidth][l]{\normalfont #1}\else +\if\@iedjustify 1\relax +\makebox[\labelwidth][c]{\normalfont #1}\else +\makebox[\labelwidth][r]{\normalfont #1}\fi\fi} + + +% VERSE and QUOTE +\def\verse{\let\\=\@centercr + \list{}{\itemsep\z@ \itemindent -1.5em \listparindent \itemindent + \rightmargin\leftmargin\advance\leftmargin 1.5em}\item[]} +\let\endverse\endlist +\def\quotation{\list{}{\listparindent 1.5em \itemindent\listparindent + \rightmargin\leftmargin \parsep 0pt plus 1pt}\item[]} +\let\endquotation=\endlist +\def\quote{\list{}{\rightmargin\leftmargin}\item[]} +\let\endquote=\endlist + + +% \titlepage +% provided only for backward compatibility. \maketitle is the correct +% way to create the title page. +\newif\if@restonecol +\def\titlepage{\@restonecolfalse\if@twocolumn\@restonecoltrue\onecolumn + \else \newpage \fi \thispagestyle{empty}\c@page\z@} +\def\endtitlepage{\if@restonecol\twocolumn \else \newpage \fi} + +% standard values from article.cls +\arraycolsep 5pt +\arrayrulewidth .4pt +\doublerulesep 2pt + +\tabcolsep 6pt +\tabbingsep 0.5em + + +%% FOOTNOTES +% +%\skip\footins 10pt plus 4pt minus 2pt +% V1.6 respond to changes in font size +% space added above the footnotes (if present) +\skip\footins 0.9\baselineskip plus 0.4\baselineskip minus 0.2\baselineskip + +% V1.6, we need to make \footnotesep responsive to changes +% in \baselineskip or strange spacings will result when in +% draft mode. Here is a little LaTeX secret - \footnotesep +% determines the height of an invisible strut that is placed +% *above* the baseline of footnotes after the first. Since +% LaTeX considers the space for characters to be 0.7/baselineskip +% above the baseline and 0.3/baselineskip below it, we need to +% use 0.7/baselineskip as a \footnotesep to maintain equal spacing +% between all the lines of the footnotes. IEEE often uses a tad +% more, so use 0.8\baselineskip. This slightly larger value also helps +% the text to clear the footnote marks. Note that \thanks now uses +% its own value of \footnotesep. +{\footnotesize +\global\footnotesep 0.8\baselineskip} + + +\skip\@mpfootins = \skip\footins +\fboxsep = 3pt +\fboxrule = .4pt +% V1.6 use 1em, the use LaTeX2e's \@makefnmark +% Note that IEEE normally *left* aligns the footnote marks, so we don't need +% box resizing tricks here. +\long\def\@makefntext#1{\parindent 1em\indent\hbox{\@makefnmark}#1}% V1.6 use 1em + +\def\footnoterule{} + +% V1.6 do not allow LaTeX to break a footnote across multiple pages +\interfootnotelinepenalty=10000 + +% V1.6 discourage breaks within equations +% Note that amsmath normally sets this to 10000, +% but LaTeX2e normally uses 100. +\interdisplaylinepenalty=2500 + + +\if@technote + \setcounter{secnumdepth}{3} +\else + \setcounter{secnumdepth}{4} +\fi + + +\newcounter{section} +\newcounter{subsection}[section] +\newcounter{subsubsection}[subsection] +\newcounter{paragraph}[subsubsection] + +% used only by IEEEtran's IEEEeqnarray as other packages may +% have their own, different, implementations +\newcounter{IEEEsubequation}[equation] + +% as shown when called by user from \ref, \label and in table of contents +\def\thesection{\Roman{section}} % I +\def\thesubsection{\thesection-\Alph{subsection}} % I-A +\def\thesubsubsection{\thesubsection.\arabic{subsubsection}} % I-A.1 +\def\theparagraph{\thesubsubsection.\alph{paragraph}} % I-A.1.a +\def\theequation{\arabic{equation}} % 1 +\def\theIEEEsubequation{\theequation\alph{IEEEsubequation}} % 1a (used only by IEEEtran's IEEEeqnarray) + +% Main text forms (how shown in main text headings) +% V1.6, using \thesection in \thesectiondis allows changes +% in the former to automatically appear in the latter +\def\thesectiondis{\thesection.} % I. +\def\thesubsectiondis{\Alph{subsection}.} % B. +\def\thesubsubsectiondis{\arabic{subsubsection})} % 3) +\def\theparagraphdis{\alph{paragraph})} % d) +% just like LaTeX2e's \@eqnnum +\def\theequationdis{{\normalfont \normalcolor (\theequation)}}% (1) +% IEEEsubequation used only by IEEEtran's IEEEeqnarray +\def\theIEEEsubequationdis{{\normalfont \normalcolor (\theIEEEsubequation)}}% (1a) +% redirect LaTeX2e's equation number display and all that depend on +% it, through IEEEtran's \theequationdis +\def\@eqnnum{\theequationdis} + +% LIST OF FIGURES AND TABLES AND TABLE OF CONTENTS +% +\def\@pnumwidth{1.55em} +\def\@tocrmarg{2.55em} +\def\@dotsep{4.5} +\setcounter{tocdepth}{3} + +% adjusted some spacings here so that section numbers will not easily +% collide with the section titles. +% VIII; VIII-A; and VIII-A.1 are usually the worst offenders. +% MDS 1/2001 +\def\tableofcontents{\section*{Contents}\@starttoc{toc}} +\def\l@section#1#2{\addpenalty{\@secpenalty}\addvspace{1.0em plus 1pt}% + \@tempdima 2.75em \begingroup \parindent \z@ \rightskip \@pnumwidth% + \parfillskip-\@pnumwidth {\bfseries\leavevmode #1}\hfil\hbox to\@pnumwidth{\hss #2}\par% + \endgroup} +% argument format #1:level, #2:labelindent,#3:labelsep +\def\l@subsection{\@dottedtocline{2}{2.75em}{3.75em}} +\def\l@subsubsection{\@dottedtocline{3}{6.5em}{4.5em}} +% must provide \l@ defs for ALL sublevels EVEN if tocdepth +% is such as they will not appear in the table of contents +% these defs are how TOC knows what level these things are! +\def\l@paragraph{\@dottedtocline{4}{6.5em}{5.5em}} +\def\l@subparagraph{\@dottedtocline{5}{6.5em}{6.5em}} +\def\listoffigures{\section*{List of Figures}\@starttoc{lof}} +\def\l@figure{\@dottedtocline{1}{0em}{2.75em}} +\def\listoftables{\section*{List of Tables}\@starttoc{lot}} +\let\l@table\l@figure + + +%% Definitions for floats +%% +%% Normal Floats +\floatsep 1\baselineskip plus 0.2\baselineskip minus 0.2\baselineskip +\textfloatsep 1.7\baselineskip plus 0.2\baselineskip minus 0.4\baselineskip +\@fptop 0pt plus 1fil +\@fpsep 0.75\baselineskip plus 2fil +\@fpbot 0pt plus 1fil +\def\topfraction{1.0} +\def\bottomfraction{.4} +\def\floatpagefraction{0.8} +\def\textfraction{.2} + +%% Double Column Floats +\dblfloatsep 1\baselineskip plus 0.2\baselineskip minus 0.2\baselineskip + +\dbltextfloatsep 1.7\baselineskip plus 0.2\baselineskip minus 0.4\baselineskip +% Note that it would be nice if the rubber here actually worked in LaTeX2e. +% There is a long standing limitation in LaTeX, first discovered (to the best +% of my knowledge) by Alan Jeffrey in 1992. LaTeX ignores the stretchable +% portion of \dbltextfloatsep, and as a result, double column figures can and +% do result in an non-integer number of lines in the main text columns with +% underfull vbox errors as a consequence. A post to comp.text.tex +% by Donald Arseneau confirms that this had not yet been fixed in 1998. +% IEEEtran V1.6 will fix this problem for you in the titles, but it doesn't +% protect you from other double floats. Happy vspace'ing. + +\@dblfptop 0pt plus 1fil +\@dblfpsep 0.75\baselineskip plus 2fil +\@dblfpbot 0pt plus 1fil +\def\dbltopfraction{1.0} +\def\dblfloatpagefraction{0.8} +\setcounter{dbltopnumber}{4} + +\intextsep 1\baselineskip plus 0.2\baselineskip minus 0.2\baselineskip +\setcounter{topnumber}{2} +\setcounter{bottomnumber}{2} +\setcounter{totalnumber}{4} + + +%% redefine CAPTION +% V1.4 add user control for short figure caption justification +\newif\ifcenterfigcaptions + +% V1.6 set the default according to conference mode +\if@confmode +\centerfigcaptionstrue +\else +\centerfigcaptionsfalse +\fi + +% article class provides these, we should too. +\newlength\abovecaptionskip +\newlength\belowcaptionskip +% but only \abovecaptionskip is used above figure captions and *below* table +% captions +\setlength\abovecaptionskip{0.5\baselineskip} +\setlength\belowcaptionskip{0pt} +% V1.6 create hooks in case the caption spacing ever needs to be +% overridden by a user +\def\@IEEEfigurecaptionsepspace{\vskip\abovecaptionskip\relax}% +\def\@IEEEtablecaptionsepspace{\vskip\abovecaptionskip\relax}% + + +% 1.6b revise caption system so that \@makecaption uses two arguments +% as with LaTeX2e. Otherwise, there will be problems when using hyperref. +\def\@IEEEtablestring{table} + +\long\def\@makecaption#1#2{% +% test if is a for a figure or table +\ifx\@captype\@IEEEtablestring% +% if a table, do table caption +\begin{center}{\footnotesize #1}\\{\footnotesize\scshape #2}\end{center}% +\@IEEEtablecaptionsepspace% V1.6 was a hard coded 8pt +% if not a table, format it as a figure +\else +\@IEEEfigurecaptionsepspace% V1.6 was a hard coded 5pt +% 3/2001 use footnotesize, not small; use two nonbreaking spaces, not one +\setbox\@tempboxa\hbox{\footnotesize #1.~~ #2}% +\ifdim \wd\@tempboxa >\hsize% +% if caption is longer than a line, let it wrap around +\setbox\@tempboxa\hbox{\footnotesize #1.~~ }% +\parbox[t]{\hsize}{\footnotesize \noindent\unhbox\@tempboxa#2}% +% if caption is shorter than a line, +% allow user to control short figure caption justification (left or center) +\else% +\ifcenterfigcaptions \hbox to\hsize{\footnotesize\hfil\box\@tempboxa\hfil}% +\else \hbox to\hsize{\footnotesize\box\@tempboxa\hfil}% +\fi\fi\fi} + + +\newcounter{figure} +\def\thefigure{\@arabic\c@figure} +\def\fps@figure{tbp} +\def\ftype@figure{1} +\def\ext@figure{lof} +\def\fnum@figure{Fig.~\thefigure} +\def\figure{\@float{figure}} +\let\endfigure\end@float +\@namedef{figure*}{\@dblfloat{figure}} +\@namedef{endfigure*}{\end@dblfloat} +\newcounter{table} +\def\thetable{\@Roman\c@table} +\def\fps@table{tbp} +\def\ftype@table{2} +\def\ext@table{lot} +\def\fnum@table{TABLE~\thetable} +% V1.6 IEEE uses 8pt text for tables +% to default to footnotesize, we hack into LaTeX2e's \@floatboxreset and pray +\def\table{\def\@floatboxreset{\reset@font\footnotesize\@setminipage}\@float{table}} +\let\endtable\end@float +% v1.6b double column tables need to default to footnotesize as well. +\@namedef{table*}{\def\@floatboxreset{\reset@font\footnotesize\@setminipage}\@dblfloat{table}} +\@namedef{endtable*}{\end@dblfloat} + + + + +%% +%% START OF IEEEeqnarry DEFINITIONS +%% +%% Inspired by the concepts, examples, and previous works of LaTeX +%% coders and developers such as Donald Arseneau, Fred Bartlett, +%% David Carlisle, Tony Liu, Frank Mittelbach, Piet van Oostrum, +%% Roland Winkler and Mark Wooding. +%% I don't make the claim that my work here is even near their calibre. ;) + + +% hook to allow easy changeover to IEEEtran.cls/tools.sty error reporting +\def\@IEEEclspkgerror{\ClassError{IEEEtran}} + +\newif\if@IEEEeqnarraystarform% flag to indicate if the environment was called as the star form +\@IEEEeqnarraystarformfalse + +\newif\if@advanceIEEEeqncolcnt% tracks if the environment should advance the col counter +% allows a way to make an \IEEEeqnarraybox that can be used within an \IEEEeqnarray +% used by IEEEeqnarraymulticol so that it can work properly in both +\@advanceIEEEeqncolcnttrue + +\newcount\@IEEEeqnnumcols % tracks how many IEEEeqnarray cols are defined +\newcount\@IEEEeqncolcnt % tracks how many IEEEeqnarray cols the user actually used + + +% The default math style used by the columns +\def\IEEEeqnarraymathstyle{\displaystyle} +% The default text style used by the columns +% default to using the current font +\def\IEEEeqnarraytextstyle{\relax} + +% like the iedlistdecl but for \IEEEeqnarray +\def\IEEEeqnarraydecl{\relax} +\def\IEEEeqnarrayboxdecl{\relax} + +% \yesnumber is the opposite of \nonumber +% a novel concept with the same def as the equationarray package +% However, we give IEEE versions too since some LaTeX packages such as +% the MDWtools mathenv.sty redefine \nonumber to something else. +\providecommand{\yesnumber}{\global\@eqnswtrue} +\def\IEEEyesnumber{\global\@eqnswtrue} +\def\IEEEnonumber{\global\@eqnswfalse} + + +\def\IEEEyessubnumber{\global\@IEEEissubequationtrue\global\@eqnswtrue% +\if@IEEEeqnarrayISinner% only do something inside an IEEEeqnarray +\if@IEEElastlinewassubequation\addtocounter{equation}{-1}\else\setcounter{IEEEsubequation}{1}\fi% +\def\@currentlabel{\p@IEEEsubequation\theIEEEsubequation}\fi} + +% flag to indicate that an equation is a sub equation +\newif\if@IEEEissubequation% +\@IEEEissubequationfalse + +% allows users to "push away" equations that get too close to the equation numbers +\def\IEEEeqnarraynumspace{\hphantom{\if@IEEEissubequation\theIEEEsubequationdis\else\theequationdis\fi}} + +% provides a way to span multiple columns within IEEEeqnarray environments +% will consider \if@advanceIEEEeqncolcnt before globally advancing the +% column counter - so as to work within \IEEEeqnarraybox +% usage: \IEEEeqnarraymulticol{number cols. to span}{col type}{cell text} +\long\def\IEEEeqnarraymulticol#1#2#3{\multispan{#1}% +% check if column is defined +\relax\expandafter\ifx\csname @IEEEeqnarraycolDEF#2\endcsname\@IEEEeqnarraycolisdefined% +\csname @IEEEeqnarraycolPRE#2\endcsname#3\relax\relax\relax\relax\relax% +\relax\relax\relax\relax\relax\csname @IEEEeqnarraycolPOST#2\endcsname% +\else% if not, error and use default type +\@IEEEclspkgerror{Invalid column type "#2" in \string\IEEEeqnarraymulticol.\MessageBreak +Using a default centering column instead}% +{You must define IEEEeqnarray column types before use.}% +\csname @IEEEeqnarraycolPRE@IEEEdefault\endcsname#3\relax\relax\relax\relax\relax% +\relax\relax\relax\relax\relax\csname @IEEEeqnarraycolPOST@IEEEdefault\endcsname% +\fi% +% advance column counter only if the IEEEeqnarray environment wants it +\if@advanceIEEEeqncolcnt\global\advance\@IEEEeqncolcnt by #1\relax\fi} + +% like \omit, but maintains track of the column counter for \IEEEeqnarray +\def\IEEEeqnarrayomit{\omit\if@advanceIEEEeqncolcnt\global\advance\@IEEEeqncolcnt by 1\relax\fi} + + +% provides a way to define a letter referenced column type +% usage: \IEEEeqnarraydefcol{col. type letter/name}{pre insertion text}{post insertion text} +\def\IEEEeqnarraydefcol#1#2#3{\expandafter\def\csname @IEEEeqnarraycolPRE#1\endcsname{#2}% +\expandafter\def\csname @IEEEeqnarraycolPOST#1\endcsname{#3}% +\expandafter\def\csname @IEEEeqnarraycolDEF#1\endcsname{1}} + + +% provides a way to define a numerically referenced inter-column glue types +% usage: \IEEEeqnarraydefcolsep{col. glue number}{glue definition} +\def\IEEEeqnarraydefcolsep#1#2{\expandafter\def\csname @IEEEeqnarraycolSEP\romannumeral #1\endcsname{#2}% +\expandafter\def\csname @IEEEeqnarraycolSEPDEF\romannumeral #1\endcsname{1}} + + +\def\@IEEEeqnarraycolisdefined{1}% just a macro for 1, used for checking undefined column types + + +% expands and appends the given argument to the \@IEEEtrantmptoksA token list +% used to build up the \halign preamble +\def\@IEEEappendtoksA#1{\edef\@@IEEEappendtoksA{\@IEEEtrantmptoksA={\the\@IEEEtrantmptoksA #1}}% +\@@IEEEappendtoksA} + +% also appends to \@IEEEtrantmptoksA, but does not expand the argument +% uses \toks8 as a scratchpad register +\def\@IEEEappendNOEXPANDtoksA#1{\toks8={#1}% +\edef\@@IEEEappendNOEXPANDtoksA{\@IEEEtrantmptoksA={\the\@IEEEtrantmptoksA\the\toks8}}% +\@@IEEEappendNOEXPANDtoksA} + +% define some common column types for the user +% math +\IEEEeqnarraydefcol{l}{$\IEEEeqnarraymathstyle}{$\hfil} +\IEEEeqnarraydefcol{c}{\hfil$\IEEEeqnarraymathstyle}{$\hfil} +\IEEEeqnarraydefcol{r}{\hfil$\IEEEeqnarraymathstyle}{$} +\IEEEeqnarraydefcol{L}{$\IEEEeqnarraymathstyle{}}{{}$\hfil} +\IEEEeqnarraydefcol{C}{\hfil$\IEEEeqnarraymathstyle{}}{{}$\hfil} +\IEEEeqnarraydefcol{R}{\hfil$\IEEEeqnarraymathstyle{}}{{}$} +% text +\IEEEeqnarraydefcol{s}{\IEEEeqnarraytextstyle}{\hfil} +\IEEEeqnarraydefcol{t}{\hfil\IEEEeqnarraytextstyle}{\hfil} +\IEEEeqnarraydefcol{u}{\hfil\IEEEeqnarraytextstyle}{} + +% vertical rules +\IEEEeqnarraydefcol{v}{}{\vrule width\arrayrulewidth} +\IEEEeqnarraydefcol{vv}{\vrule width\arrayrulewidth\hfil}{\hfil\vrule width\arrayrulewidth} +\IEEEeqnarraydefcol{V}{}{\vrule width\arrayrulewidth\hskip\doublerulesep\vrule width\arrayrulewidth} +\IEEEeqnarraydefcol{VV}{\vrule width\arrayrulewidth\hskip\doublerulesep\vrule width\arrayrulewidth\hfil}% +{\hfil\vrule width\arrayrulewidth\hskip\doublerulesep\vrule width\arrayrulewidth} + +% horizontal rules +\IEEEeqnarraydefcol{h}{}{\leaders\hrule height\arrayrulewidth\hfil} +\IEEEeqnarraydefcol{H}{}{\leaders\vbox{\hrule width\arrayrulewidth\vskip\doublerulesep\hrule width\arrayrulewidth}\hfil} + +% plain +\IEEEeqnarraydefcol{x}{}{} +\IEEEeqnarraydefcol{X}{$}{$} + +% the default column type to use in the event a column type is not defined +\IEEEeqnarraydefcol{@IEEEdefault}{\hfil$\IEEEeqnarraymathstyle}{$\hfil} + + +% a zero tabskip (used for "-" col types) +\def\@IEEEeqnarraycolSEPzero{0pt plus 0pt minus 0pt} +% a centering tabskip (used for "+" col types) +\def\@IEEEeqnarraycolSEPcenter{1000pt plus 0pt minus 1000pt} + +% top level default tabskip glues for the start, end, and inter-column +% may be reset within environments not always at the top level, e.g., \IEEEeqnarraybox +\edef\@IEEEeqnarraycolSEPdefaultstart{\@IEEEeqnarraycolSEPcenter}% default start glue +\edef\@IEEEeqnarraycolSEPdefaultend{\@IEEEeqnarraycolSEPcenter}% default end glue +\edef\@IEEEeqnarraycolSEPdefaultmid{\@IEEEeqnarraycolSEPzero}% default inter-column glue + + + +% creates a vertical rule that extends from the bottom to the top a a cell +% Provided in case other packages redefine \vline some other way. +% usage: \IEEEeqnarrayvrule[rule thickness] +% If no argument is provided, \arrayrulewidth will be used for the rule thickness. +\newcommand\IEEEeqnarrayvrule[1][\arrayrulewidth]{\vrule\@width#1\relax} + +% creates a blank separator row +% usage: \IEEEeqnarrayseprow[separation length][font size commands] +% default is \IEEEeqnarrayseprow[0.25\normalbaselineskip][\relax] +% blank arguments inherit the default values +% uses \skip5 as a scratch register - calls \@IEEEeqnarraystrutsize which uses more scratch registers +\def\IEEEeqnarrayseprow{\relax\@ifnextchar[{\@IEEEeqnarrayseprow}{\@IEEEeqnarrayseprow[0.25\normalbaselineskip]}} +\def\@IEEEeqnarrayseprow[#1]{\relax\@ifnextchar[{\@@IEEEeqnarrayseprow[#1]}{\@@IEEEeqnarrayseprow[#1][\relax]}} +\def\@@IEEEeqnarrayseprow[#1][#2]{\def\@IEEEeqnarrayseprowARGONE{#1}% +\ifx\@IEEEeqnarrayseprowARGONE\@empty% +% get the skip value, based on the font commands +% use skip5 because \IEEEeqnarraystrutsize uses \skip0, \skip2, \skip3 +% assign within a bogus box to confine the font changes +{\setbox0=\hbox{#2\relax\global\skip5=0.25\normalbaselineskip}}% +\else% +{\setbox0=\hbox{#2\relax\global\skip5=#1}}% +\fi% +\@IEEEeqnarrayhoptolastcolumn\IEEEeqnarraystrutsize{\skip5}{0pt}[\relax]\relax} + +% creates a blank separator row, but omits all the column templates +% usage: \IEEEeqnarrayseprowcut[separation length][font size commands] +% default is \IEEEeqnarrayseprowcut[0.25\normalbaselineskip][\relax] +% blank arguments inherit the default values +% uses \skip5 as a scratch register - calls \@IEEEeqnarraystrutsize which uses more scratch registers +\def\IEEEeqnarrayseprowcut{\multispan{\@IEEEeqnnumcols}\relax% span all the cols +% advance column counter only if the IEEEeqnarray environment wants it +\if@advanceIEEEeqncolcnt\global\advance\@IEEEeqncolcnt by \@IEEEeqnnumcols\relax\fi% +\@ifnextchar[{\@IEEEeqnarrayseprowcut}{\@IEEEeqnarrayseprowcut[0.25\normalbaselineskip]}} +\def\@IEEEeqnarrayseprowcut[#1]{\relax\@ifnextchar[{\@@IEEEeqnarrayseprowcut[#1]}{\@@IEEEeqnarrayseprowcut[#1][\relax]}} +\def\@@IEEEeqnarrayseprowcut[#1][#2]{\def\@IEEEeqnarrayseprowARGONE{#1}% +\ifx\@IEEEeqnarrayseprowARGONE\@empty% +% get the skip value, based on the font commands +% use skip5 because \IEEEeqnarraystrutsize uses \skip0, \skip2, \skip3 +% assign within a bogus box to confine the font changes +{\setbox0=\hbox{#2\relax\global\skip5=0.25\normalbaselineskip}}% +\else% +{\setbox0=\hbox{#2\relax\global\skip5=#1}}% +\fi% +\IEEEeqnarraystrutsize{\skip5}{0pt}[\relax]\relax} + + + +% draws a single rule across all the columns optional +% argument determines the rule width, \arrayrulewidth is the default +% updates column counter as needed and turns off struts +% usage: \IEEEeqnarrayrulerow[rule line thickness] +\def\IEEEeqnarrayrulerow{\multispan{\@IEEEeqnnumcols}\relax% span all the cols +% advance column counter only if the IEEEeqnarray environment wants it +\if@advanceIEEEeqncolcnt\global\advance\@IEEEeqncolcnt by \@IEEEeqnnumcols\relax\fi% +\@ifnextchar[{\@IEEEeqnarrayrulerow}{\@IEEEeqnarrayrulerow[\arrayrulewidth]}} +\def\@IEEEeqnarrayrulerow[#1]{\leaders\hrule height#1\hfil\relax% put in our rule +% turn off any struts +\IEEEeqnarraystrutsize{0pt}{0pt}[\relax]\relax} + + +% draws a double rule by using a single rule row, a separator row, and then +% another single rule row +% first optional argument determines the rule thicknesses, \arrayrulewidth is the default +% second optional argument determines the rule spacing, \doublerulesep is the default +% usage: \IEEEeqnarraydblrulerow[rule line thickness][rule spacing] +\def\IEEEeqnarraydblrulerow{\multispan{\@IEEEeqnnumcols}\relax% span all the cols +% advance column counter only if the IEEEeqnarray environment wants it +\if@advanceIEEEeqncolcnt\global\advance\@IEEEeqncolcnt by \@IEEEeqnnumcols\relax\fi% +\@ifnextchar[{\@IEEEeqnarraydblrulerow}{\@IEEEeqnarraydblrulerow[\arrayrulewidth]}} +\def\@IEEEeqnarraydblrulerow[#1]{\relax\@ifnextchar[{\@@IEEEeqnarraydblrulerow[#1]}% +{\@@IEEEeqnarraydblrulerow[#1][\doublerulesep]}} +\def\@@IEEEeqnarraydblrulerow[#1][#2]{\def\@IEEEeqnarraydblrulerowARG{#1}% +% we allow the user to say \IEEEeqnarraydblrulerow[][] +\ifx\@IEEEeqnarraydblrulerowARG\@empty% +\@IEEEeqnarrayrulerow[\arrayrulewidth]% +\else% +\@IEEEeqnarrayrulerow[#1]\relax% +\fi% +\def\@IEEEeqnarraydblrulerowARG{#2}% +\ifx\@IEEEeqnarraydblrulerowARG\@empty% +\\\IEEEeqnarrayseprow[\doublerulesep][\relax]% +\else% +\\\IEEEeqnarrayseprow[#2][\relax]% +\fi% +\\\multispan{\@IEEEeqnnumcols}% +% advance column counter only if the IEEEeqnarray environment wants it +\if@advanceIEEEeqncolcnt\global\advance\@IEEEeqncolcnt by \@IEEEeqnnumcols\relax\fi% +\def\@IEEEeqnarraydblrulerowARG{#1}% +\ifx\@IEEEeqnarraydblrulerowARG\@empty% +\@IEEEeqnarrayrulerow[\arrayrulewidth]% +\else% +\@IEEEeqnarrayrulerow[#1]% +\fi% +} + +% draws a double rule by using a single rule row, a separator (cutting) row, and then +% another single rule row +% first optional argument determines the rule thicknesses, \arrayrulewidth is the default +% second optional argument determines the rule spacing, \doublerulesep is the default +% usage: \IEEEeqnarraydblrulerow[rule line thickness][rule spacing] +\def\IEEEeqnarraydblrulerowcut{\multispan{\@IEEEeqnnumcols}\relax% span all the cols +% advance column counter only if the IEEEeqnarray environment wants it +\if@advanceIEEEeqncolcnt\global\advance\@IEEEeqncolcnt by \@IEEEeqnnumcols\relax\fi% +\@ifnextchar[{\@IEEEeqnarraydblrulerowcut}{\@IEEEeqnarraydblrulerowcut[\arrayrulewidth]}} +\def\@IEEEeqnarraydblrulerowcut[#1]{\relax\@ifnextchar[{\@@IEEEeqnarraydblrulerowcut[#1]}% +{\@@IEEEeqnarraydblrulerowcut[#1][\doublerulesep]}} +\def\@@IEEEeqnarraydblrulerowcut[#1][#2]{\def\@IEEEeqnarraydblrulerowARG{#1}% +% we allow the user to say \IEEEeqnarraydblrulerow[][] +\ifx\@IEEEeqnarraydblrulerowARG\@empty% +\@IEEEeqnarrayrulerow[\arrayrulewidth]% +\else% +\@IEEEeqnarrayrulerow[#1]% +\fi% +\def\@IEEEeqnarraydblrulerowARG{#2}% +\ifx\@IEEEeqnarraydblrulerowARG\@empty% +\\\IEEEeqnarrayseprowcut[\doublerulesep][\relax]% +\else% +\\\IEEEeqnarrayseprowcut[#2][\relax]% +\fi% +\\\multispan{\@IEEEeqnnumcols}% +% advance column counter only if the IEEEeqnarray environment wants it +\if@advanceIEEEeqncolcnt\global\advance\@IEEEeqncolcnt by \@IEEEeqnnumcols\relax\fi% +\def\@IEEEeqnarraydblrulerowARG{#1}% +\ifx\@IEEEeqnarraydblrulerowARG\@empty% +\@IEEEeqnarrayrulerow[\arrayrulewidth]% +\else% +\@IEEEeqnarrayrulerow[#1]% +\fi% +} + + + +% inserts a full row's worth of &'s +% relies on \@IEEEeqnnumcols to provide the correct number of columns +% uses \@IEEEtrantmptoksA, \count0 as scratch registers +\def\@IEEEeqnarrayhoptolastcolumn{\@IEEEtrantmptoksA={}\count0=1\relax% +\loop% add cols if the user did not use them all +\ifnum\count0<\@IEEEeqnnumcols\relax% +\@IEEEappendtoksA{&}% +\advance\count0 by 1\relax% update the col count +\repeat% +\the\@IEEEtrantmptoksA%execute the &'s +} + + + +\newif\if@IEEEeqnarrayISinner % flag to indicate if we are within the lines +\@IEEEeqnarrayISinnerfalse % of an IEEEeqnarray - after the IEEEeqnarraydecl + +\edef\@IEEEeqnarrayTHEstrutheight{0pt} % height and depth of IEEEeqnarray struts +\edef\@IEEEeqnarrayTHEstrutdepth{0pt} + +\edef\@IEEEeqnarrayTHEmasterstrutheight{0pt} % default height and depth of +\edef\@IEEEeqnarrayTHEmasterstrutdepth{0pt} % struts within an IEEEeqnarray + +\edef\@IEEEeqnarrayTHEmasterstrutHSAVE{0pt} % saved master strut height +\edef\@IEEEeqnarrayTHEmasterstrutDSAVE{0pt} % and depth + +\newif\if@IEEEeqnarrayusemasterstrut % flag to indicate that the master strut value +\@IEEEeqnarrayusemasterstruttrue % is to be used + + + +% saves the strut height and depth of the master strut +\def\@IEEEeqnarraymasterstrutsave{\relax% +\expandafter\skip0=\@IEEEeqnarrayTHEmasterstrutheight\relax% +\expandafter\skip2=\@IEEEeqnarrayTHEmasterstrutdepth\relax% +% remove stretchability +\dimen0\skip0\relax% +\dimen2\skip2\relax% +% save values +\edef\@IEEEeqnarrayTHEmasterstrutHSAVE{\the\dimen0}% +\edef\@IEEEeqnarrayTHEmasterstrutDSAVE{\the\dimen2}} + +% restores the strut height and depth of the master strut +\def\@IEEEeqnarraymasterstrutrestore{\relax% +\expandafter\skip0=\@IEEEeqnarrayTHEmasterstrutHSAVE\relax% +\expandafter\skip2=\@IEEEeqnarrayTHEmasterstrutDSAVE\relax% +% remove stretchability +\dimen0\skip0\relax% +\dimen2\skip2\relax% +% restore values +\edef\@IEEEeqnarrayTHEmasterstrutheight{\the\dimen0}% +\edef\@IEEEeqnarrayTHEmasterstrutdepth{\the\dimen2}} + + +% globally restores the strut height and depth to the +% master values and sets the master strut flag to true +\def\@IEEEeqnarraystrutreset{\relax% +\expandafter\skip0=\@IEEEeqnarrayTHEmasterstrutheight\relax% +\expandafter\skip2=\@IEEEeqnarrayTHEmasterstrutdepth\relax% +% remove stretchability +\dimen0\skip0\relax% +\dimen2\skip2\relax% +% restore values +\xdef\@IEEEeqnarrayTHEstrutheight{\the\dimen0}% +\xdef\@IEEEeqnarrayTHEstrutdepth{\the\dimen2}% +\global\@IEEEeqnarrayusemasterstruttrue} + + +% if the master strut is not to be used, make the current +% values of \@IEEEeqnarrayTHEstrutheight, \@IEEEeqnarrayTHEstrutdepth +% and the use master strut flag, global +% this allows user strut commands issued in the last column to be carried +% into the isolation/strut column +\def\@IEEEeqnarrayglobalizestrutstatus{\relax% +\if@IEEEeqnarrayusemasterstrut\else% +\xdef\@IEEEeqnarrayTHEstrutheight{\@IEEEeqnarrayTHEstrutheight}% +\xdef\@IEEEeqnarrayTHEstrutdepth{\@IEEEeqnarrayTHEstrutdepth}% +\global\@IEEEeqnarrayusemasterstrutfalse% +\fi} + + + +% usage: \IEEEeqnarraystrutsize{height}{depth}[font size commands] +% If called outside the lines of an IEEEeqnarray, sets the height +% and depth of both the master and local struts. If called inside +% an IEEEeqnarray line, sets the height and depth of the local strut +% only and sets the flag to indicate the use of the local strut +% values. If the height or depth is left blank, 0.7\normalbaselineskip +% and 0.3\normalbaselineskip will be used, respectively. +% The optional argument can be used to evaluate the lengths under +% a different font size and styles. If none is specified, the current +% font is used. +% uses scratch registers \skip0, \skip2, \skip3, \dimen0, \dimen2 +\def\IEEEeqnarraystrutsize#1#2{\relax\@ifnextchar[{\@IEEEeqnarraystrutsize{#1}{#2}}{\@IEEEeqnarraystrutsize{#1}{#2}[\relax]}} +\def\@IEEEeqnarraystrutsize#1#2[#3]{\def\@IEEEeqnarraystrutsizeARG{#1}% +\ifx\@IEEEeqnarraystrutsizeARG\@empty% +{\setbox0=\hbox{#3\relax\global\skip3=0.7\normalbaselineskip}}% +\skip0=\skip3\relax% +\else% arg one present +{\setbox0=\hbox{#3\relax\global\skip3=#1\relax}}% +\skip0=\skip3\relax% +\fi% if null arg +\def\@IEEEeqnarraystrutsizeARG{#2}% +\ifx\@IEEEeqnarraystrutsizeARG\@empty% +{\setbox0=\hbox{#3\relax\global\skip3=0.3\normalbaselineskip}}% +\skip2=\skip3\relax% +\else% arg two present +{\setbox0=\hbox{#3\relax\global\skip3=#2\relax}}% +\skip2=\skip3\relax% +\fi% if null arg +% remove stretchability, just to be safe +\dimen0\skip0\relax% +\dimen2\skip2\relax% +% dimen0 = height, dimen2 = depth +\if@IEEEeqnarrayISinner% inner does not touch master strut size +\edef\@IEEEeqnarrayTHEstrutheight{\the\dimen0}% +\edef\@IEEEeqnarrayTHEstrutdepth{\the\dimen2}% +\@IEEEeqnarrayusemasterstrutfalse% do not use master +\else% outer, have to set master strut too +\edef\@IEEEeqnarrayTHEmasterstrutheight{\the\dimen0}% +\edef\@IEEEeqnarrayTHEmasterstrutdepth{\the\dimen2}% +\edef\@IEEEeqnarrayTHEstrutheight{\the\dimen0}% +\edef\@IEEEeqnarrayTHEstrutdepth{\the\dimen2}% +\@IEEEeqnarrayusemasterstruttrue% use master strut +\fi} + + +% usage: \IEEEeqnarraystrutsizeadd{added height}{added depth}[font size commands] +% If called outside the lines of an IEEEeqnarray, adds the given height +% and depth to both the master and local struts. +% If called inside an IEEEeqnarray line, adds the given height and depth +% to the local strut only and sets the flag to indicate the use +% of the local strut values. +% In both cases, if a height or depth is left blank, 0pt is used instead. +% The optional argument can be used to evaluate the lengths under +% a different font size and styles. If none is specified, the current +% font is used. +% uses scratch registers \skip0, \skip2, \skip3, \dimen0, \dimen2 +\def\IEEEeqnarraystrutsizeadd#1#2{\relax\@ifnextchar[{\@IEEEeqnarraystrutsizeadd{#1}{#2}}{\@IEEEeqnarraystrutsizeadd{#1}{#2}[\relax]}} +\def\@IEEEeqnarraystrutsizeadd#1#2[#3]{\def\@IEEEeqnarraystrutsizearg{#1}% +\ifx\@IEEEeqnarraystrutsizearg\@empty% +\skip0=0pt\relax% +\else% arg one present +{\setbox0=\hbox{#3\relax\global\skip3=#1}}% +\skip0=\skip3\relax% +\fi% if null arg +\def\@IEEEeqnarraystrutsizearg{#2}% +\ifx\@IEEEeqnarraystrutsizearg\@empty% +\skip2=0pt\relax% +\else% arg two present +{\setbox0=\hbox{#3\relax\global\skip3=#2}}% +\skip2=\skip3\relax% +\fi% if null arg +% remove stretchability, just to be safe +\dimen0\skip0\relax% +\dimen2\skip2\relax% +% dimen0 = height, dimen2 = depth +\if@IEEEeqnarrayISinner% inner does not touch master strut size +% get local strut size +\expandafter\skip0=\@IEEEeqnarrayTHEstrutheight\relax% +\expandafter\skip2=\@IEEEeqnarrayTHEstrutdepth\relax% +% add it to the user supplied values +\advance\dimen0 by \skip0\relax% +\advance\dimen2 by \skip2\relax% +% update the local strut size +\edef\@IEEEeqnarrayTHEstrutheight{\the\dimen0}% +\edef\@IEEEeqnarrayTHEstrutdepth{\the\dimen2}% +\@IEEEeqnarrayusemasterstrutfalse% do not use master +\else% outer, have to set master strut too +% get master strut size +\expandafter\skip0=\@IEEEeqnarrayTHEmasterstrutheight\relax% +\expandafter\skip2=\@IEEEeqnarrayTHEmasterstrutdepth\relax% +% add it to the user supplied values +\advance\dimen0 by \skip0\relax% +\advance\dimen2 by \skip2\relax% +% update the local and master strut sizes +\edef\@IEEEeqnarrayTHEmasterstrutheight{\the\dimen0}% +\edef\@IEEEeqnarrayTHEmasterstrutdepth{\the\dimen2}% +\edef\@IEEEeqnarrayTHEstrutheight{\the\dimen0}% +\edef\@IEEEeqnarrayTHEstrutdepth{\the\dimen2}% +\@IEEEeqnarrayusemasterstruttrue% use master strut +\fi} + + +% allow user a way to see the struts +\newif\ifIEEEvisiblestruts +\IEEEvisiblestrutsfalse + +% inserts an invisible strut using the master or local strut values +% uses scratch registers \skip0, \skip2, \dimen0, \dimen2 +\def\@IEEEeqnarrayinsertstrut{\relax% +\if@IEEEeqnarrayusemasterstrut +% get master strut size +\expandafter\skip0=\@IEEEeqnarrayTHEmasterstrutheight\relax% +\expandafter\skip2=\@IEEEeqnarrayTHEmasterstrutdepth\relax% +\else% +% get local strut size +\expandafter\skip0=\@IEEEeqnarrayTHEstrutheight\relax% +\expandafter\skip2=\@IEEEeqnarrayTHEstrutdepth\relax% +\fi% +% remove stretchability, probably not needed +\dimen0\skip0\relax% +\dimen2\skip2\relax% +% dimen0 = height, dimen2 = depth +% allow user to see struts if desired +\ifIEEEvisiblestruts% +\vrule width0.2pt height\dimen0 depth\dimen2\relax% +\else% +\vrule width0pt height\dimen0 depth\dimen2\relax\fi} + + +% creates an invisible strut, useable even outside \IEEEeqnarray +% if \IEEEvisiblestrutstrue, the strut will be visible and 0.2pt wide. +% usage: \IEEEstrut[height][depth][font size commands] +% default is \IEEEstrut[0.7\normalbaselineskip][0.3\normalbaselineskip][\relax] +% blank arguments inherit the default values +% uses \dimen0, \dimen2, \skip0, \skip2 +\def\IEEEstrut{\relax\@ifnextchar[{\@IEEEstrut}{\@IEEEstrut[0.7\normalbaselineskip]}} +\def\@IEEEstrut[#1]{\relax\@ifnextchar[{\@@IEEEstrut[#1]}{\@@IEEEstrut[#1][0.3\normalbaselineskip]}} +\def\@@IEEEstrut[#1][#2]{\relax\@ifnextchar[{\@@@IEEEstrut[#1][#2]}{\@@@IEEEstrut[#1][#2][\relax]}} +\def\@@@IEEEstrut[#1][#2][#3]{\mbox{#3\relax% +\def\@IEEEstrutARG{#1}% +\ifx\@IEEEstrutARG\@empty% +\skip0=0.7\normalbaselineskip\relax% +\else% +\skip0=#1\relax% +\fi% +\def\@IEEEstrutARG{#2}% +\ifx\@IEEEstrutARG\@empty% +\skip2=0.3\normalbaselineskip\relax% +\else% +\skip2=#2\relax% +\fi% +% remove stretchability, probably not needed +\dimen0\skip0\relax% +\dimen2\skip2\relax% +\ifIEEEvisiblestruts% +\vrule width0.2pt height\dimen0 depth\dimen2\relax% +\else% +\vrule width0.0pt height\dimen0 depth\dimen2\relax\fi}} + + +% enables strut mode by setting a default strut size and then zeroing the +% \baselineskip, \lineskip, \lineskiplimit and \jot +\def\IEEEeqnarraystrutmode{\IEEEeqnarraystrutsize{0.7\normalbaselineskip}{0.3\normalbaselineskip}[\relax]% +\baselineskip=0pt\lineskip=0pt\lineskiplimit=0pt\jot=0pt} + + + +\def\IEEEeqnarray{\@IEEEeqnarraystarformfalse\@IEEEeqnarray} +\def\endIEEEeqnarray{\end@IEEEeqnarray} + +\@namedef{IEEEeqnarray*}{\@IEEEeqnarraystarformtrue\@IEEEeqnarray} +\@namedef{endIEEEeqnarray*}{\end@IEEEeqnarray} + + +% \IEEEeqnarray is an enhanced \eqnarray. +% The star form defaults to not putting equation numbers at the end of each row. +% usage: \IEEEeqnarray[decl]{cols} +\def\@IEEEeqnarray{\relax\@ifnextchar[{\@@IEEEeqnarray}{\@@IEEEeqnarray[\relax]}} +\def\@@IEEEeqnarray[#1]#2{% + % default to showing the equation number or not based on whether or not + % the star form was involked + \if@IEEEeqnarraystarform\global\@eqnswfalse + \else% not the star form + \global\@eqnswtrue + \fi% if star form + \@IEEEissubequationfalse% default to no subequations + \@IEEElastlinewassubequationfalse% assume last line is not a sub equation + \@IEEEeqnarrayISinnerfalse% not yet within the lines of the halign + \@IEEEeqnarraystrutsize{0pt}{0pt}[\relax]% turn off struts by default + \@IEEEeqnarrayusemasterstruttrue% use master strut till user asks otherwise + \IEEEvisiblestrutsfalse% diagnostic mode defaults to off + % no extra space unless the user specifically requests it + \lineskip=0pt\relax + \lineskiplimit=0pt\relax + \baselineskip=\normalbaselineskip\relax% + \jot=\normaljot\relax% + \mathsurround\z@\relax% no extra spacing around math + \@advanceIEEEeqncolcnttrue% advance the col counter for each col the user uses, + % used in \IEEEeqnarraymulticol and in the preamble build + \stepcounter{equation}% advance equation counter before first line + \setcounter{IEEEsubequation}{0}% no subequation yet + \def\@currentlabel{\p@equation\theequation}% redefine the ref label + \IEEEeqnarraydecl\relax% allow a way for the user to make global overrides + #1\relax% allow user to override defaults + \let\\\@IEEEeqnarraycr% replace newline with one that can put in eqn. numbers + \global\@IEEEeqncolcnt\z@% col. count = 0 for first line + \@IEEEbuildpreamble #2\end\relax% build the preamble and put it into \@IEEEtrantmptoksA + % put in the column for the equation number + \ifnum\@IEEEeqnnumcols>0\relax\@IEEEappendtoksA{&}\fi% col separator for those after the first + \toks0={##}% + % advance the \@IEEEeqncolcnt for the isolation col, this helps with error checking + \@IEEEappendtoksA{\global\advance\@IEEEeqncolcnt by 1\relax}% + % add the isolation column + \@IEEEappendtoksA{\tabskip\z@skip\bgroup\the\toks0\egroup}% + % advance the \@IEEEeqncolcnt for the equation number col, this helps with error checking + \@IEEEappendtoksA{&\global\advance\@IEEEeqncolcnt by 1\relax}% + % add the equation number col to the preamble + \@IEEEappendtoksA{\tabskip\z@skip\hb@xt@\z@\bgroup\hss\the\toks0\egroup}% + % note \@IEEEeqnnumcols does not count the equation col or isolation col + % set the starting tabskip glue as determined by the preamble build + \tabskip=\@IEEEBPstartglue\relax + % begin the display alignment + \@IEEEeqnarrayISinnertrue% commands are now within the lines + $$\everycr{}\halign to\displaywidth\bgroup + % "exspand" the preamble + \span\the\@IEEEtrantmptoksA\cr} + +% enter isolation/strut column (or the next column if the user did not use +% every column), record the strut status, complete the columns, do the strut if needed, +% restore counters to correct values and exit +\def\end@IEEEeqnarray{\@IEEEeqnarrayglobalizestrutstatus&\@@IEEEeqnarraycr\egroup% +\if@IEEElastlinewassubequation\global\advance\c@IEEEsubequation\m@ne\fi% +\global\advance\c@equation\m@ne% +$$\@ignoretrue} + +% need a way to remember if last line is a subequation +\newif\if@IEEElastlinewassubequation% +\@IEEElastlinewassubequationfalse + +% IEEEeqnarray uses a modifed \\ instead of the plain \cr to +% end rows. This allows for things like \\*[vskip amount] +% This "cr" macros are modified versions those for LaTeX2e's eqnarray +% the {\ifnum0=`} braces must be kept away from the last column to avoid +% altering spacing of its math, so we use & to advance to the next column +% as there is an isolation/strut column after the user's columns +\def\@IEEEeqnarraycr{\@IEEEeqnarrayglobalizestrutstatus&% save strut status and advance to next column + {\ifnum0=`}\fi + \@ifstar{% + \global\@eqpen\@M\@IEEEeqnarrayYCR + }{% + \global\@eqpen\interdisplaylinepenalty \@IEEEeqnarrayYCR + }% +} + +\def\@IEEEeqnarrayYCR{\@testopt\@IEEEeqnarrayXCR\z@skip} + +\def\@IEEEeqnarrayXCR[#1]{% + \ifnum0=`{\fi}% + \@@IEEEeqnarraycr + \noalign{\penalty\@eqpen\vskip\jot\vskip #1\relax}}% + +\def\@@IEEEeqnarraycr{\@IEEEtrantmptoksA={}% clear token register + \advance\@IEEEeqncolcnt by -1\relax% adjust col count because of the isolation column + \ifnum\@IEEEeqncolcnt>\@IEEEeqnnumcols\relax + \@IEEEclspkgerror{Too many columns within the IEEEeqnarray\MessageBreak + environment}% + {Use fewer \string &'s or put more columns in the IEEEeqnarry column\MessageBreak + specifications.}\relax% + \else + \loop% add cols if the user did not use them all + \ifnum\@IEEEeqncolcnt<\@IEEEeqnnumcols\relax + \@IEEEappendtoksA{&}% + \advance\@IEEEeqncolcnt by 1\relax% update the col count + \repeat + % this number of &'s will take us the the isolation column + \fi + % execute the &'s + \the\@IEEEtrantmptoksA% + % handle the strut/isolation column + \@IEEEeqnarrayinsertstrut% do the strut if needed + \@IEEEeqnarraystrutreset% reset the strut system for next line or IEEEeqnarray + &% and enter the equation number column + % is this line needs an equation number, display it and advance the + % (sub)equation counters, record what type this line was + \if@eqnsw% + \if@IEEEissubequation\theIEEEsubequationdis\addtocounter{equation}{1}\stepcounter{IEEEsubequation}% + \global\@IEEElastlinewassubequationtrue% + \else% display a standard equation number, initialize the IEEEsubequation counter + \theequationdis\stepcounter{equation}\setcounter{IEEEsubequation}{0}% + \global\@IEEElastlinewassubequationfalse\fi% + \fi% + % reset the eqnsw flag to indicate default preference of the display of equation numbers + \if@IEEEeqnarraystarform\global\@eqnswfalse\else\global\@eqnswtrue\fi + \global\@IEEEissubequationfalse% reset the subequation flag + % reset the number of columns the user actually used + \global\@IEEEeqncolcnt\z@\relax + % the real end of the line + \cr} + + + + + +% \IEEEeqnarraybox is like \IEEEeqnarray except the box form puts everything +% inside a vtop, vbox, or vcenter box depending on the letter in the second +% optional argument (t,b,c). Vbox is the default. Unlike \IEEEeqnarray, +% equation numbers are not displayed and \IEEEeqnarraybox can be nested. +% \IEEEeqnarrayboxm is for math mode (like \array) and does not put the vbox +% within an hbox. +% \IEEEeqnarrayboxt is for text mode (like \tabular) and puts the vbox within +% a \hbox{$ $} construct. +% \IEEEeqnarraybox will auto detect whether to use \IEEEeqnarrayboxm or +% \IEEEeqnarrayboxt depending on the math mode. +% The third optional argument specifies the width this box is to be set to - +% natural width is the default. +% The * forms do not add \jot line spacing +% usage: \IEEEeqnarraybox[decl][pos][width]{cols} +\def\IEEEeqnarrayboxm{\@IEEEeqnarraystarformfalse\@IEEEeqnarrayboxHBOXSWfalse\@IEEEeqnarraybox} +\def\endIEEEeqnarrayboxm{\end@IEEEeqnarraybox} +\@namedef{IEEEeqnarrayboxm*}{\@IEEEeqnarraystarformtrue\@IEEEeqnarrayboxHBOXSWfalse\@IEEEeqnarraybox} +\@namedef{endIEEEeqnarrayboxm*}{\end@IEEEeqnarraybox} + +\def\IEEEeqnarrayboxt{\@IEEEeqnarraystarformfalse\@IEEEeqnarrayboxHBOXSWtrue\@IEEEeqnarraybox} +\def\endIEEEeqnarrayboxt{\end@IEEEeqnarraybox} +\@namedef{IEEEeqnarrayboxt*}{\@IEEEeqnarraystarformtrue\@IEEEeqnarrayboxHBOXSWtrue\@IEEEeqnarraybox} +\@namedef{endIEEEeqnarrayboxt*}{\end@IEEEeqnarraybox} + +\def\IEEEeqnarraybox{\@IEEEeqnarraystarformfalse\ifmmode\@IEEEeqnarrayboxHBOXSWfalse\else\@IEEEeqnarrayboxHBOXSWtrue\fi% +\@IEEEeqnarraybox} +\def\endIEEEeqnarraybox{\end@IEEEeqnarraybox} + +\@namedef{IEEEeqnarraybox*}{\@IEEEeqnarraystarformtrue\ifmmode\@IEEEeqnarrayboxHBOXSWfalse\else\@IEEEeqnarrayboxHBOXSWtrue\fi% +\@IEEEeqnarraybox} +\@namedef{endIEEEeqnarraybox*}{\end@IEEEeqnarraybox} + +% flag to indicate if the \IEEEeqnarraybox needs to put things into an hbox{$ $} +% for \vcenter in non-math mode +\newif\if@IEEEeqnarrayboxHBOXSW% +\@IEEEeqnarrayboxHBOXSWfalse + +\def\@IEEEeqnarraybox{\relax\@ifnextchar[{\@@IEEEeqnarraybox}{\@@IEEEeqnarraybox[\relax]}} +\def\@@IEEEeqnarraybox[#1]{\relax\@ifnextchar[{\@@@IEEEeqnarraybox[#1]}{\@@@IEEEeqnarraybox[#1][b]}} +\def\@@@IEEEeqnarraybox[#1][#2]{\relax\@ifnextchar[{\@@@@IEEEeqnarraybox[#1][#2]}{\@@@@IEEEeqnarraybox[#1][#2][\relax]}} + +% #1 = decl; #2 = t,b,c; #3 = width, #4 = col specs +\def\@@@@IEEEeqnarraybox[#1][#2][#3]#4{\@IEEEeqnarrayISinnerfalse % not yet within the lines of the halign + \@IEEEeqnarraymasterstrutsave% save current master strut values + \@IEEEeqnarraystrutsize{0pt}{0pt}[\relax]% turn off struts by default + \@IEEEeqnarrayusemasterstruttrue% use master strut till user asks otherwise + \IEEEvisiblestrutsfalse% diagnostic mode defaults to off + % no extra space unless the user specifically requests it + \lineskip=0pt\relax% + \lineskiplimit=0pt\relax% + \baselineskip=\normalbaselineskip\relax% + \jot=\normaljot\relax% + \mathsurround\z@\relax% no extra spacing around math + % the default end glues are zero for an \IEEEeqnarraybox + \edef\@IEEEeqnarraycolSEPdefaultstart{\@IEEEeqnarraycolSEPzero}% default start glue + \edef\@IEEEeqnarraycolSEPdefaultend{\@IEEEeqnarraycolSEPzero}% default end glue + \edef\@IEEEeqnarraycolSEPdefaultmid{\@IEEEeqnarraycolSEPzero}% default inter-column glue + \@advanceIEEEeqncolcntfalse% do not advance the col counter for each col the user uses, + % used in \IEEEeqnarraymulticol and in the preamble build + \IEEEeqnarrayboxdecl\relax% allow a way for the user to make global overrides + #1\relax% allow user to override defaults + \let\\\@IEEEeqnarrayboxcr% replace newline with one that allows optional spacing + \@IEEEbuildpreamble #4\end\relax% build the preamble and put it into \@IEEEtrantmptoksA + % add an isolation column to the preamble to stop \\'s {} from getting into the last col + \ifnum\@IEEEeqnnumcols>0\relax\@IEEEappendtoksA{&}\fi% col separator for those after the first + \toks0={##}% + % add the isolation column to the preamble + \@IEEEappendtoksA{\tabskip\z@skip\bgroup\the\toks0\egroup}% + % set the starting tabskip glue as determined by the preamble build + \tabskip=\@IEEEBPstartglue\relax + % begin the alignment + \everycr{}% + % use only the very first token to determine the positioning + % this stops some problems when the user uses more than one letter, + % but is probably not worth the effort + % \noindent is used as a delimiter + \def\@IEEEgrabfirstoken##1##2\noindent{\let\@IEEEgrabbedfirstoken=##1}% + \@IEEEgrabfirstoken#2\relax\relax\noindent + % \@IEEEgrabbedfirstoken has the first token, the rest are discarded + % if we need to put things into and hbox and go into math mode, do so now + \if@IEEEeqnarrayboxHBOXSW \leavevmode \hbox \bgroup $\fi% + % use the appropriate vbox type + \if\@IEEEgrabbedfirstoken t\relax\vtop\else\if\@IEEEgrabbedfirstoken c\relax% + \vcenter\else\vbox\fi\fi\bgroup% + \@IEEEeqnarrayISinnertrue% commands are now within the lines + \ifx#3\relax\halign\else\halign to #3\relax\fi% + \bgroup + % "exspand" the preamble + \span\the\@IEEEtrantmptoksA\cr} + +% carry strut status and enter the isolation/strut column, +% exit from math mode if needed, and exit +\def\end@IEEEeqnarraybox{\@IEEEeqnarrayglobalizestrutstatus% carry strut status +&% enter isolation/strut column +\@IEEEeqnarrayinsertstrut% do strut if needed +\@IEEEeqnarraymasterstrutrestore% restore the previous master strut values +% reset the strut system for next IEEEeqnarray +% (sets local strut values back to previous master strut values) +\@IEEEeqnarraystrutreset% +% ensure last line, exit from halign, close vbox +\crcr\egroup\egroup% +% exit from math mode and close hbox if needed +\if@IEEEeqnarrayboxHBOXSW $\egroup\fi} + + + +% IEEEeqnarraybox uses a modifed \\ instead of the plain \cr to +% end rows. This allows for things like \\[vskip amount] +% This "cr" macros are modified versions those for LaTeX2e's eqnarray +% For IEEEeqnarraybox, \\* is the same as \\ +% the {\ifnum0=`} braces must be kept away from the last column to avoid +% altering spacing of its math, so we use & to advance to the isolation/strut column +% carry strut status into isolation/strut column +\def\@IEEEeqnarrayboxcr{\@IEEEeqnarrayglobalizestrutstatus% carry strut status +&% enter isolation/strut column +\@IEEEeqnarrayinsertstrut% do strut if needed +% reset the strut system for next line or IEEEeqnarray +\@IEEEeqnarraystrutreset% +{\ifnum0=`}\fi% +\@ifstar{\@IEEEeqnarrayboxYCR}{\@IEEEeqnarrayboxYCR}} + +% test and setup the optional argument to \\[] +\def\@IEEEeqnarrayboxYCR{\@testopt\@IEEEeqnarrayboxXCR\z@skip} + +% IEEEeqnarraybox does not automatically increase line spacing by \jot +\def\@IEEEeqnarrayboxXCR[#1]{\ifnum0=`{\fi}% +\cr\noalign{\if@IEEEeqnarraystarform\else\vskip\jot\fi\vskip#1\relax}} + + + +% starts the halign preamble build +\def\@IEEEbuildpreamble{\@IEEEtrantmptoksA={}% clear token register +\let\@IEEEBPcurtype=u%current column type is not yet known +\let\@IEEEBPprevtype=s%the previous column type was the start +\let\@IEEEBPnexttype=u%next column type is not yet known +% ensure these are valid +\def\@IEEEBPcurglue={0pt plus 0pt minus 0pt}% +\def\@IEEEBPcurcolname{@IEEEdefault}% name of current column definition +% currently acquired numerically referenced glue +% use a name that is easier to remember +\let\@IEEEBPcurnum=\@IEEEtrantmpcountA% +\@IEEEBPcurnum=0% +% tracks number of columns in the preamble +\@IEEEeqnnumcols=0% +% record the default end glues +\edef\@IEEEBPstartglue{\@IEEEeqnarraycolSEPdefaultstart}% +\edef\@IEEEBPendglue{\@IEEEeqnarraycolSEPdefaultend}% +% now parse the user's column specifications +\@@IEEEbuildpreamble} + + +% parses and builds the halign preamble +\def\@@IEEEbuildpreamble#1#2{\let\@@nextIEEEbuildpreamble=\@@IEEEbuildpreamble% +% use only the very first token to check the end +% \noindent is used as a delimiter as \end can be present here +\def\@IEEEgrabfirstoken##1##2\noindent{\let\@IEEEgrabbedfirstoken=##1}% +\@IEEEgrabfirstoken#1\relax\relax\noindent +\ifx\@IEEEgrabbedfirstoken\end\let\@@nextIEEEbuildpreamble=\@@IEEEfinishpreamble\else% +% identify current and next token type +\@IEEEgetcoltype{#1}{\@IEEEBPcurtype}{1}% current, error on invalid +\@IEEEgetcoltype{#2}{\@IEEEBPnexttype}{0}% next, no error on invalid next +% if curtype is a glue, get the glue def +\if\@IEEEBPcurtype g\@IEEEgetcurglue{#1}{\@IEEEBPcurglue}\fi% +% if curtype is a column, get the column def and set the current column name +\if\@IEEEBPcurtype c\@IEEEgetcurcol{#1}\fi% +% if curtype is a numeral, acquire the user defined glue +\if\@IEEEBPcurtype n\@IEEEprocessNcol{#1}\fi% +% process the acquired glue +\if\@IEEEBPcurtype g\@IEEEprocessGcol\fi% +% process the acquired col +\if\@IEEEBPcurtype c\@IEEEprocessCcol\fi% +% ready prevtype for next col spec. +\let\@IEEEBPprevtype=\@IEEEBPcurtype% +% be sure and put back the future token(s) as a group +\fi\@@nextIEEEbuildpreamble{#2}} + + +% executed just after preamble build is completed +% warn about zero cols, and if prevtype type = u, put in end tabskip glue +\def\@@IEEEfinishpreamble#1{\ifnum\@IEEEeqnnumcols<1\relax +\@IEEEclspkgerror{No column specifiers declared for IEEEeqnarray}% +{At least one column type must be declared for each IEEEeqnarray.}% +\fi%num cols less than 1 +%if last type undefined, set default end tabskip glue +\if\@IEEEBPprevtype u\@IEEEappendtoksA{\tabskip=\@IEEEBPendglue}\fi} + + +% Identify and return the column specifier's type code +\def\@IEEEgetcoltype#1#2#3{% +% use only the very first token to determine the type +% \noindent is used as a delimiter as \end can be present here +\def\@IEEEgrabfirstoken##1##2\noindent{\let\@IEEEgrabbedfirstoken=##1}% +\@IEEEgrabfirstoken#1\relax\relax\noindent +% \@IEEEgrabfirstoken has the first token, the rest are discarded +% n = number +% g = glue (any other char in catagory 12) +% c = letter +% e = \end +% u = undefined +% third argument: 0 = no error message, 1 = error on invalid char +\let#2=u\relax% assume invalid until know otherwise +\ifx\@IEEEgrabbedfirstoken\end\let#2=e\else +\ifcat\@IEEEgrabbedfirstoken\relax\else% screen out control sequences +\if0\@IEEEgrabbedfirstoken\let#2=n\else +\if1\@IEEEgrabbedfirstoken\let#2=n\else +\if2\@IEEEgrabbedfirstoken\let#2=n\else +\if3\@IEEEgrabbedfirstoken\let#2=n\else +\if4\@IEEEgrabbedfirstoken\let#2=n\else +\if5\@IEEEgrabbedfirstoken\let#2=n\else +\if6\@IEEEgrabbedfirstoken\let#2=n\else +\if7\@IEEEgrabbedfirstoken\let#2=n\else +\if8\@IEEEgrabbedfirstoken\let#2=n\else +\if9\@IEEEgrabbedfirstoken\let#2=n\else +\ifcat,\@IEEEgrabbedfirstoken\let#2=g\relax +\else\ifcat a\@IEEEgrabbedfirstoken\let#2=c\relax\fi\fi\fi\fi\fi\fi\fi\fi\fi\fi\fi\fi\fi\fi +\if#2u\relax +\if0\noexpand#3\relax\else\@IEEEclspkgerror{Invalid character in column specifications}% +{Only letters, numerals and certain other symbols are allowed \MessageBreak +as IEEEeqnarray column specifiers.}\fi\fi} + + +% identify the current letter referenced column +% if invalid, use a default column +\def\@IEEEgetcurcol#1{\expandafter\ifx\csname @IEEEeqnarraycolDEF#1\endcsname\@IEEEeqnarraycolisdefined% +\def\@IEEEBPcurcolname{#1}\else% invalid column name +\@IEEEclspkgerror{Invalid column type "#1" in column specifications.\MessageBreak +Using a default centering column instead}% +{You must define IEEEeqnarray column types before use.}% +\def\@IEEEBPcurcolname{@IEEEdefault}\fi} + + +% identify and return the predefined (punctuation) glue value +\def\@IEEEgetcurglue#1#2{% +% ! = \! (neg small) -0.16667em (-3/18 em) +% , = \, (small) 0.16667em ( 3/18 em) +% : = \: (med) 0.22222em ( 4/18 em) +% ; = \; (large) 0.27778em ( 5/18 em) +% ' = \quad 1em +% " = \qquad 2em +% . = 0.5\arraycolsep +% / = \arraycolsep +% ? = 2\arraycolsep +% * = 1fil +% + = \@IEEEeqnarraycolSEPcenter +% - = \@IEEEeqnarraycolSEPzero +% Note that all em values are referenced to the math font (textfont2) fontdimen6 +% value for 1em. +% +% use only the very first token to determine the type +% this prevents errant tokens from getting in the main text +% \noindent is used as a delimiter here +\def\@IEEEgrabfirstoken##1##2\noindent{\let\@IEEEgrabbedfirstoken=##1}% +\@IEEEgrabfirstoken#1\relax\relax\noindent +% get the math font 1em value +% LaTeX2e's NFSS2 does not preload the fonts, but \IEEEeqnarray needs +% to gain access to the math (\textfont2) font's spacing parameters. +% So we create a bogus box here that uses the math font to ensure +% that \textfont2 is loaded and ready. If this is not done, +% the \textfont2 stuff here may not work. +% Thanks to Bernd Raichle for his 1997 post on this topic. +{\setbox0=\hbox{$\displaystyle\relax$}}% +% fontdimen6 has the width of 1em (a quad). +\@IEEEtrantmpdimenA=\fontdimen6\textfont2\relax% +% identify the glue value based on the first token +% we discard anything after the first +\if!\@IEEEgrabbedfirstoken\@IEEEtrantmpdimenA=-0.16667\@IEEEtrantmpdimenA\edef#2{\the\@IEEEtrantmpdimenA}\else +\if,\@IEEEgrabbedfirstoken\@IEEEtrantmpdimenA=0.16667\@IEEEtrantmpdimenA\edef#2{\the\@IEEEtrantmpdimenA}\else +\if:\@IEEEgrabbedfirstoken\@IEEEtrantmpdimenA=0.22222\@IEEEtrantmpdimenA\edef#2{\the\@IEEEtrantmpdimenA}\else +\if;\@IEEEgrabbedfirstoken\@IEEEtrantmpdimenA=0.27778\@IEEEtrantmpdimenA\edef#2{\the\@IEEEtrantmpdimenA}\else +\if'\@IEEEgrabbedfirstoken\@IEEEtrantmpdimenA=1\@IEEEtrantmpdimenA\edef#2{\the\@IEEEtrantmpdimenA}\else +\if"\@IEEEgrabbedfirstoken\@IEEEtrantmpdimenA=2\@IEEEtrantmpdimenA\edef#2{\the\@IEEEtrantmpdimenA}\else +\if.\@IEEEgrabbedfirstoken\@IEEEtrantmpdimenA=0.5\arraycolsep\edef#2{\the\@IEEEtrantmpdimenA}\else +\if/\@IEEEgrabbedfirstoken\edef#2{\the\arraycolsep}\else +\if?\@IEEEgrabbedfirstoken\@IEEEtrantmpdimenA=2\arraycolsep\edef#2{\the\@IEEEtrantmpdimenA}\else +\if *\@IEEEgrabbedfirstoken\edef#2{0pt plus 1fil minus 0pt}\else +\if+\@IEEEgrabbedfirstoken\edef#2{\@IEEEeqnarraycolSEPcenter}\else +\if-\@IEEEgrabbedfirstoken\edef#2{\@IEEEeqnarraycolSEPzero}\else +\edef#2{\@IEEEeqnarraycolSEPzero}% +\@IEEEclspkgerror{Invalid predefined inter-column glue type "#1" in\MessageBreak +column specifications. Using a default value of\MessageBreak +0pt instead}% +{Only !,:;'"./?*+ and - are valid predefined glue types in the\MessageBreak +IEEEeqnarray column specifications.}\fi\fi\fi\fi\fi\fi\fi\fi\fi\fi\fi\fi} + + + +% process a numerical digit from the column specification +% and look up the corresponding user defined glue value +% can transform current type from n to g or a as the user defined glue is acquired +\def\@IEEEprocessNcol#1{\if\@IEEEBPprevtype g% +\@IEEEclspkgerror{Back-to-back inter-column glue specifiers in column\MessageBreak +specifications. Ignoring consecutive glue specifiers\MessageBreak +after the first}% +{You cannot have two or more glue types next to each other\MessageBreak +in the IEEEeqnarray column specifications.}% +\let\@IEEEBPcurtype=a% abort this glue, future digits will be discarded +\@IEEEBPcurnum=0\relax% +\else% if we previously aborted a glue +\if\@IEEEBPprevtype a\@IEEEBPcurnum=0\let\@IEEEBPcurtype=a%maintain digit abortion +\else%acquire this number +% save the previous type before the numerical digits started +\if\@IEEEBPprevtype n\else\let\@IEEEBPprevsavedtype=\@IEEEBPprevtype\fi% +\multiply\@IEEEBPcurnum by 10\relax% +\advance\@IEEEBPcurnum by #1\relax% add in number, \relax is needed to stop TeX's number scan +\if\@IEEEBPnexttype n\else%close acquisition +\expandafter\ifx\csname @IEEEeqnarraycolSEPDEF\expandafter\romannumeral\number\@IEEEBPcurnum\endcsname\@IEEEeqnarraycolisdefined% +\edef\@IEEEBPcurglue{\csname @IEEEeqnarraycolSEP\expandafter\romannumeral\number\@IEEEBPcurnum\endcsname}% +\else%user glue not defined +\@IEEEclspkgerror{Invalid user defined inter-column glue type "\number\@IEEEBPcurnum" in\MessageBreak +column specifications. Using a default value of\MessageBreak +0pt instead}% +{You must define all IEEEeqnarray numerical inter-column glue types via\MessageBreak +\string\IEEEeqnarraydefcolsep \space before they are used in column specifications.}% +\edef\@IEEEBPcurglue{\@IEEEeqnarraycolSEPzero}% +\fi% glue defined or not +\let\@IEEEBPcurtype=g% change the type to reflect the acquired glue +\let\@IEEEBPprevtype=\@IEEEBPprevsavedtype% restore the prev type before this number glue +\@IEEEBPcurnum=0\relax%ready for next acquisition +\fi%close acquisition, get glue +\fi%discard or acquire number +\fi%prevtype glue or not +} + + +% process an acquired glue +% add any acquired column/glue pair to the preamble +\def\@IEEEprocessGcol{\if\@IEEEBPprevtype a\let\@IEEEBPcurtype=a%maintain previous glue abortions +\else +% if this is the start glue, save it, but do nothing else +% as this is not used in the preamble, but before +\if\@IEEEBPprevtype s\edef\@IEEEBPstartglue{\@IEEEBPcurglue}% +\else%not the start glue +\if\@IEEEBPprevtype g%ignore if back to back glues +\@IEEEclspkgerror{Back-to-back inter-column glue specifiers in column\MessageBreak +specifications. Ignoring consecutive glue specifiers\MessageBreak +after the first}% +{You cannot have two or more glue types next to each other\MessageBreak +in the IEEEeqnarray column specifications.}% +\let\@IEEEBPcurtype=a% abort this glue +\else% not a back to back glue +\if\@IEEEBPprevtype c\relax% if the previoustype was a col, add column/glue pair to preamble +\ifnum\@IEEEeqnnumcols>0\relax\@IEEEappendtoksA{&}\fi +\toks0={##}% +% make preamble advance col counter if this environment needs this +\if@advanceIEEEeqncolcnt\@IEEEappendtoksA{\global\advance\@IEEEeqncolcnt by 1\relax}\fi +% insert the column defintion into the preamble, being careful not to expand +% the column definition +\@IEEEappendtoksA{\tabskip=\@IEEEBPcurglue}% +\@IEEEappendNOEXPANDtoksA{\begingroup\csname @IEEEeqnarraycolPRE}% +\@IEEEappendtoksA{\@IEEEBPcurcolname}% +\@IEEEappendNOEXPANDtoksA{\endcsname}% +\@IEEEappendtoksA{\the\toks0}% +\@IEEEappendNOEXPANDtoksA{\relax\relax\relax\relax\relax% +\relax\relax\relax\relax\relax\csname @IEEEeqnarraycolPOST}% +\@IEEEappendtoksA{\@IEEEBPcurcolname}% +\@IEEEappendNOEXPANDtoksA{\endcsname\relax\relax\relax\relax\relax% +\relax\relax\relax\relax\relax\endgroup}% +\advance\@IEEEeqnnumcols by 1\relax%one more column in the preamble +\else% error: non-start glue with no pending column +\@IEEEclspkgerror{Inter-column glue specifier without a prior column\MessageBreak +type in the column specifications. Ignoring this glue\MessageBreak +specifier}% +{Except for the first and last positions, glue can be placed only\MessageBreak +between column types.}% +\let\@IEEEBPcurtype=a% abort this glue +\fi% previous was a column +\fi% back-to-back glues +\fi% is start column glue +\fi% prev type not a +} + + +% process an acquired letter referenced column and, if necessary, add it to the preamble +\def\@IEEEprocessCcol{\if\@IEEEBPnexttype g\else +\if\@IEEEBPnexttype n\else +% we have a column followed by something other than a glue (or numeral glue) +% so we must add this column to the preamble now +\ifnum\@IEEEeqnnumcols>0\relax\@IEEEappendtoksA{&}\fi%col separator for those after the first +\if\@IEEEBPnexttype e\@IEEEappendtoksA{\tabskip=\@IEEEBPendglue\relax}\else%put in end glue +\@IEEEappendtoksA{\tabskip=\@IEEEeqnarraycolSEPdefaultmid\relax}\fi% or default mid glue +\toks0={##}% +% make preamble advance col counter if this environment needs this +\if@advanceIEEEeqncolcnt\@IEEEappendtoksA{\global\advance\@IEEEeqncolcnt by 1\relax}\fi +% insert the column definition into the preamble, being careful not to expand +% the column definition +\@IEEEappendNOEXPANDtoksA{\begingroup\csname @IEEEeqnarraycolPRE}% +\@IEEEappendtoksA{\@IEEEBPcurcolname}% +\@IEEEappendNOEXPANDtoksA{\endcsname}% +\@IEEEappendtoksA{\the\toks0}% +\@IEEEappendNOEXPANDtoksA{\relax\relax\relax\relax\relax% +\relax\relax\relax\relax\relax\csname @IEEEeqnarraycolPOST}% +\@IEEEappendtoksA{\@IEEEBPcurcolname}% +\@IEEEappendNOEXPANDtoksA{\endcsname\relax\relax\relax\relax\relax% +\relax\relax\relax\relax\relax\endgroup}% +\advance\@IEEEeqnnumcols by 1\relax%one more column in the preamble +\fi%next type not numeral +\fi%next type not glue +} + + +%% +%% END OF IEEEeqnarry DEFINITIONS +%% + + + + +% set up the running headings, this complex because of all the different +% modes IEEEtran supports +\if@twoside + \if@technote + \def\ps@headings{% + \def\@oddhead{\hbox{}\scriptsize\leftmark \hfil \thepage} + \def\@evenhead{\scriptsize\thepage \hfil \leftmark\hbox{}} + \if@draftclsmode + \if@draftclsmodefoot + \def\@oddfoot{\scriptsize\@date\hfil DRAFT} + \def\@evenfoot{\scriptsize DRAFT\hfil\@date} + \else + \def\@oddfoot{}\def\@evenfoot{}% + \fi + \else + \def\@oddfoot{}\def\@evenfoot{} + \fi} + \else % not a technote + \def\ps@headings{% + \if@confmode + \def\@oddhead{} + \def\@evenhead{} + \else + \def\@oddhead{\hbox{}\scriptsize\rightmark \hfil \thepage} + \def\@evenhead{\scriptsize\thepage \hfil \leftmark\hbox{}} + \fi + \if@draftclsmode + \def\@oddhead{\hbox{}\scriptsize\rightmark \hfil \thepage} + \def\@evenhead{\scriptsize\thepage \hfil \leftmark\hbox{}} + \if@draftclsmodefoot + \def\@oddfoot{\scriptsize\@date\hfil DRAFT} + \def\@evenfoot{\scriptsize DRAFT\hfil\@date} + \else + \def\@oddfoot{}\def\@evenfoot{}% + \fi + \else + \def\@oddfoot{}\def\@evenfoot{}% + \fi} + \fi +\else % single side +\def\ps@headings{% + \if@confmode + \def\@oddhead{} + \def\@evenhead{} + \else + \def\@oddhead{\hbox{}\scriptsize\leftmark \hfil \thepage} + \def\@evenhead{} + \fi + \if@draftclsmode + \def\@oddhead{\hbox{}\scriptsize\leftmark \hfil \thepage} + \def\@evenhead{} + \if@draftclsmodefoot + \def\@oddfoot{\scriptsize \@date \hfil DRAFT} + \else + \def\@oddfoot{} + \fi + \else + \def\@oddfoot{} + \fi + \def\@evenfoot{}} +\fi + + +% title page style +\def\ps@titlepagestyle{\def\@oddfoot{}\def\@evenfoot{}% +\if@confmode + \def\@oddhead{}% + \def\@evenhead{}% +\else + \def\@oddhead{\hbox{}\scriptsize\leftmark \hfil \thepage}% + \def\@evenhead{\scriptsize\thepage \hfil \leftmark\hbox{}}% +\fi +\if@draftclsmode + \def\@oddhead{\hbox{}\scriptsize\leftmark \hfil \thepage}% + \def\@evenhead{\scriptsize\thepage \hfil \leftmark\hbox{}}% + \if@draftclsmodefoot + \def\@oddfoot{\scriptsize \@date\hfil DRAFT}% + \def\@evenfoot{\scriptsize DRAFT\hfil \@date}% + \fi +\else + % all non-draft mode footers + \if@IEEEusingpubid + % for title pages that are using a pubid + % do not repeat pubid if using peer review option + \if@peerreviewoption + \else + \footskip 0pt% + \def\@oddfoot{\hss\normalfont\footnotesize\raisebox{1.5ex}[1.5ex]{\@pubid}\hss}% + \def\@evenfoot{\hss\normalfont\footnotesize\raisebox{1.5ex}[1.5ex]{\@pubid}\hss}% + \fi + \fi +\fi} + + +% peer review cover page style +\def\ps@peerreviewcoverpagestyle{% +\def\@oddhead{}\def\@evenhead{}% +\def\@oddfoot{}\def\@evenfoot{}% +\if@draftclsmode + \if@draftclsmodefoot + \def\@oddfoot{\scriptsize \@date\hfil DRAFT}% + \def\@evenfoot{\scriptsize DRAFT\hfil \@date}% + \fi +\else + % non-draft mode footers + \if@IEEEusingpubid + \footskip 0pt% + \def\@oddfoot{\hss\normalfont\footnotesize\raisebox{1.5ex}[1.5ex]{\@pubid}\hss}% + \def\@evenfoot{\hss\normalfont\footnotesize\raisebox{1.5ex}[1.5ex]{\@pubid}\hss}% + \fi +\fi} + + +% start with empty headings +\def\rightmark{}\def\leftmark{} + + +%% Defines the command for putting the header. \footernote{TEXT} is the same +%% as \markboth{TEXT}{TEXT}. +%% Note that all the text is forced into uppercase, if you have some text +%% that needs to be in lower case, for instance et. al., then either manually +%% set \leftmark and \rightmark or use \MakeLowercase{et. al.} within the +%% arguments to \markboth. +\def\markboth#1#2{\def\leftmark{\MakeUppercase{#1}}\def\rightmark{\MakeUppercase{#2}}} +\def\footernote#1{\markboth{#1}{#1}} + +\def\today{\ifcase\month\or + January\or February\or March\or April\or May\or June\or + July\or August\or September\or October\or November\or December\fi + \space\number\day, \number\year} + + + + +%% CITATION AND BIBLIOGRAPHY COMMANDS +%% +%% V1.6 no longer supports the older, nonstandard \shortcite and \citename setup stuff +% +% +% Modify Latex2e \@citex to separate citations with "], [" +\def\@citex[#1]#2{% + \let\@citea\@empty + \@cite{\@for\@citeb:=#2\do + {\@citea\def\@citea{], [}% + \edef\@citeb{\expandafter\@firstofone\@citeb\@empty}% + \if@filesw\immediate\write\@auxout{\string\citation{\@citeb}}\fi + \@ifundefined{b@\@citeb}{\mbox{\reset@font\bfseries ?}% + \G@refundefinedtrue + \@latex@warning + {Citation `\@citeb' on page \thepage \space undefined}}% + {\hbox{\csname b@\@citeb\endcsname}}}}{#1}} + +% V1.6 we create hooks for the optional use of Donald Arseneau's +% cite.sty package. cite.sty is "smart" and will notice that the +% following format controls are already defined and will not +% redefine them. The result will be the proper sorting of the +% citation numbers and auto detection of 3 or more entry "ranges" - +% all in IEEE style: [1], [2], [5]--[7], [12] +% This also allows for an optional note, i.e., \cite[mynote]{..}. +% If the \cite with note has more than one reference, the note will +% be applied to the last of the listed references. It is generally +% desired that if a note is given, only one reference is listed in +% that \cite. +% Thanks to Mr. Arseneau for providing the required format arguments +% to produce the IEEE style. +\def\citepunct{], [} +\def\citedash{]--[} + + +% V1.6b providing this command makes hyperref think the natbib package is +% in use so that it will not interfere with cite.sty. However, as a result, +% citation numbers will not be hyperlinked. +\def\NAT@parse{\typeout{IEEEtran error: Attempt to use fake Natbib command +which is provided to fool Hyperref.}} +% it easy enough to override via: +% \let\NAT@parse\undefined + + +% V1.6 class files should always provide these +\def\newblock{\hskip .11em\@plus.33em\@minus.07em} +\let\@openbib@code\@empty + + + +% Provide support for the control entries of IEEEtran.bst V1.00 and later. +\def\bstctlcite#1{\@bsphack + \@for\@citeb:=#1\do{% + \edef\@citeb{\expandafter\@firstofone\@citeb}% + \if@filesw\immediate\write\@auxout{\string\citation{\@citeb}}\fi}% + \@esphack} + +% V1.6 provide a way for a user to execute a command just before +% a given reference number - used to insert a \newpage to balance +% the columns on the last page +\edef\@IEEEtriggerrefnum{0} % the default of zero means that + % the command is not executed +\def\@IEEEtriggercmd{\newpage} + +% allow the user to alter the triggered command +\long\def\IEEEtriggercmd#1{\long\def\@IEEEtriggercmd{#1}} + +% allow user a way to specify the reference number just before the +% command is executed +\def\IEEEtriggeratref#1{\@IEEEtrantmpcountA=#1% +\edef\@IEEEtriggerrefnum{\the\@IEEEtrantmpcountA}}% + +% trigger command at the given reference +\def\@IEEEbibitemprefix{\@IEEEtrantmpcountA=\@IEEEtriggerrefnum\relax% +\advance\@IEEEtrantmpcountA by -1\relax% +\ifnum\c@enumiv=\@IEEEtrantmpcountA\relax\@IEEEtriggercmd\relax\fi} + +\def\@biblabel#1{[#1]} + +\def\thebibliography#1{\section*{References}% + \addcontentsline{toc}{section}{References}% + % V1.6 add some rubber space here and provide a command trigger + \footnotesize \vskip 0.3\baselineskip plus 0.1\baselineskip minus 0.1\baselineskip% + \list{\@biblabel{\@arabic\c@enumiv}}% + {\settowidth\labelwidth{\@biblabel{#1}}% + \leftmargin\labelwidth + \advance\leftmargin\labelsep\relax + \itemsep 0pt plus .5pt\relax% + \usecounter{enumiv}% + \let\p@enumiv\@empty + \renewcommand\theenumiv{\@arabic\c@enumiv}}% + \let\@IEEElatexbibitem\bibitem% + \def\bibitem{\@IEEEbibitemprefix\@IEEElatexbibitem}% +\def\newblock{\hskip .11em plus .33em minus .07em}% +% originally: +% \sloppy\clubpenalty4000\widowpenalty4000% +% by adding the \interlinepenalty here, we make it more +% difficult, but not impossible, for LaTeX to break within a reference. +% IEEE almost never breaks a reference (but they do it more often with +% technotes). You may get an underfull vbox warning around the bibliography, +% but the final result will be much more like what IEEE will publish. +% MDS 11/2000 +\if@technote\sloppy\clubpenalty4000\widowpenalty4000\interlinepenalty100% +\else\sloppy\clubpenalty4000\widowpenalty4000\interlinepenalty500\fi% + \sfcode`\.=1000\relax} +\let\endthebibliography=\endlist + + + + +% TITLE PAGE COMMANDS +% +% +% \IEEEmembership is used to produce the sublargesize italic font used to indicate author +% IEEE membership. +\def\IEEEmembership#1{{\sublargesize\normalfont\textit{#1}}} + + +% \authorrefmark{} produces a footnote type symbol to indicate author affiliation. +% When given an argument of 1 to 9, \authorrefmark{} follows the standard LaTeX footnote +% symbol sequence convention. However, for arguments 10 and above, \authorrefmark{} +% reverts to using lower case roman numerals, so it cannot overflow. Do note that you +% cannot use \footnotemark[] in place of \authorrefmark{} within \author as the footnote +% symbols will have been turned off to prevent \thanks from creating footnote marks. +% \authorrefmark{} produces a symbol that appears to LaTeX as having zero vertical +% height - this allows for a more compact line packing, but the user must ensure that +% the interline spacing is large enough to prevent \authorrefmark{} from colliding +% with the text above. +\def\authorrefmark#1{\raisebox{0pt}[0pt][0pt]{\textsuperscript{\footnotesize\ensuremath{\ifcase#1\or *\or \dagger\or \ddagger\or% + \mathsection\or \mathparagraph\or \|\or **\or \dagger\dagger% + \or \ddagger\ddagger \else\textsuperscript{\expandafter\romannumeral#1}\fi}}}} + + +% FONT CONTROLS AND SPACINGS FOR CONFERENCE MODE AUTHOR NAME AND AFFILIATION BLOCKS +% +% The default font styles for the author name and affiliation blocks (confmode) +\def\@IEEEauthorblockNstyle{\normalfont\sublargesize} +\def\@IEEEauthorblockAstyle{\normalfont\normalsize} +% The default if the user does not use an author block +\def\@IEEEauthordefaulttextstyle{\normalfont\sublargesize} + +% spacing from title (or special paper notice) to author name blocks (confmode) +% can be negative +\def\@IEEEauthorblockconfadjspace{-0.25em} + +% spacing between name and affiliation blocks (confmode) +% This can be negative. +% IEEE doesn't want any added spacing here, but I will leave these +% controls in place in case they ever change their mind. +% Personally, I like 0.75ex. +%\def\@IEEEauthorblockNtopspace{0.75ex} +%\def\@IEEEauthorblockAtopspace{0.75ex} +\def\@IEEEauthorblockNtopspace{0.0ex} +\def\@IEEEauthorblockAtopspace{0.0ex} +% baseline spacing within name and affiliation blocks (confmode) +% must be positive, spacings below certain values will make +% the position of line of text sensitive to the contents of the +% line above it i.e., whether or not the prior line has descenders, +% subscripts, etc. For this reason it is a good idea to keep +% these above 2.6ex +\def\@IEEEauthorblockNinterlinespace{2.6ex} +\def\@IEEEauthorblockAinterlinespace{2.75ex} + +% This tracks the required strut size. +% See the \@IEEEauthorhalign command for the actual default value used. +\def\@IEEEauthorblockXinterlinespace{2.7ex} + +% variables to retain font size and style across groups +% values given here have no effect as they will be overwritten later +\gdef\@IEEESAVESTATEfontsize{10} +\gdef\@IEEESAVESTATEfontbaselineskip{12} +\gdef\@IEEESAVESTATEfontencoding{OT1} +\gdef\@IEEESAVESTATEfontfamily{ptm} +\gdef\@IEEESAVESTATEfontseries{m} +\gdef\@IEEESAVESTATEfontshape{n} + +% saves the current font attributes +\def\@IEEEcurfontSAVE{\global\let\@IEEESAVESTATEfontsize\f@size% +\global\let\@IEEESAVESTATEfontbaselineskip\f@baselineskip% +\global\let\@IEEESAVESTATEfontencoding\f@encoding% +\global\let\@IEEESAVESTATEfontfamily\f@family% +\global\let\@IEEESAVESTATEfontseries\f@series% +\global\let\@IEEESAVESTATEfontshape\f@shape} + +% restores the saved font attributes +\def\@IEEEcurfontRESTORE{\fontsize{\@IEEESAVESTATEfontsize}{\@IEEESAVESTATEfontbaselineskip}% +\fontencoding{\@IEEESAVESTATEfontencoding}% +\fontfamily{\@IEEESAVESTATEfontfamily}% +\fontseries{\@IEEESAVESTATEfontseries}% +\fontshape{\@IEEESAVESTATEfontshape}% +\selectfont} + + +% variable to indicate if the current block is the first block in the column +\newif\if@IEEEprevauthorblockincol \@IEEEprevauthorblockincolfalse + + +% the command places a strut with height and depth = \@IEEEauthorblockXinterlinespace +% we use this technique to have complete manual control over the spacing of the lines +% within the halign environment. +% We set the below baseline portion at 30%, the above +% baseline portion at 70% of the total length. +% Responds to changes in the document's \baselinestretch +\def\@IEEEauthorstrutrule{\@IEEEtrantmpdimenA\@IEEEauthorblockXinterlinespace% +\@IEEEtrantmpdimenA=\baselinestretch\@IEEEtrantmpdimenA% +\rule[-0.3\@IEEEtrantmpdimenA]{0pt}{\@IEEEtrantmpdimenA}} + + +% blocks to hold the authors' names and affilations. +% Makes formatting easy for conferences +% +% use real definitions in conference mode +% name block +\def\authorblockN#1{\relax\@IEEEauthorblockNstyle% set the default text style +\gdef\@IEEEauthorblockXinterlinespace{0pt}% disable strut for spacer row +% the \expandafter hides the \cr in conditional tex, see the array.sty docs +% for details, probably not needed here as the \cr is in a macro +% do a spacer row if needed +\if@IEEEprevauthorblockincol\expandafter\@IEEEauthorblockNtopspaceline\fi +\global\@IEEEprevauthorblockincoltrue% we now have a block in this column +%restore the correct strut value +\gdef\@IEEEauthorblockXinterlinespace{\@IEEEauthorblockNinterlinespace}% +% input the author names +#1% +% end the row if the user did not already +\crcr} +% spacer row for names +\def\@IEEEauthorblockNtopspaceline{\cr\noalign{\vskip\@IEEEauthorblockNtopspace}} +% +% affiliation block +\def\authorblockA#1{\relax\@IEEEauthorblockAstyle% set the default text style +\gdef\@IEEEauthorblockXinterlinespace{0pt}%disable strut for spacer row +% the \expandafter hides the \cr in conditional tex, see the array.sty docs +% for details, probably not needed here as the \cr is in a macro +% do a spacer row if needed +\if@IEEEprevauthorblockincol\expandafter\@IEEEauthorblockAtopspaceline\fi +\global\@IEEEprevauthorblockincoltrue% we now have a block in this column +%restore the correct strut value +\gdef\@IEEEauthorblockXinterlinespace{\@IEEEauthorblockAinterlinespace}% +% input the author affiliations +#1% +% end the row if the user did not already +\crcr} +% spacer row for affiliations +\def\@IEEEauthorblockAtopspaceline{\cr\noalign{\vskip\@IEEEauthorblockAtopspace}} + + +% allow papers to compile even if author blocks are used in modes other +% than conference or peerreviewca. For such cases, we provide dummy blocks. +\if@confmode +\else + \if@peerreviewcaoption\else + % not conference or peerreviewca mode + \def\authorblockN#1{#1}% + \def\authorblockA#1{#1}% + \fi +\fi + + + +% we provide our own halign so as not to have to depend on tabular +\def\@IEEEauthorhalign{\@IEEEauthordefaulttextstyle% default text style + \lineskip=0pt\relax% disable line spacing + \lineskiplimit=0pt\relax% + \baselineskip=0pt\relax% + \@IEEEcurfontSAVE% save the current font + \mathsurround\z@\relax% no extra spacing around math + \let\\\@IEEEauthorhaligncr% replace newline with halign friendly one + \tabskip=0pt\relax% no column spacing + \everycr{}% ensure no problems here + \@IEEEprevauthorblockincolfalse% no author blocks yet + \def\@IEEEauthorblockXinterlinespace{2.7ex}% default interline space + \vtop\bgroup%vtop box + \halign\bgroup&\relax\hfil\@IEEEcurfontRESTORE\relax ##\relax + \hfil\@IEEEcurfontSAVE\@IEEEauthorstrutrule\cr} + +% ensure last line, exit from halign, close vbox +\def\end@IEEEauthorhalign{\crcr\egroup\egroup} + +% handle bogus star form +\def\@IEEEauthorhaligncr{{\ifnum0=`}\fi\@ifstar{\@@IEEEauthorhaligncr}{\@@IEEEauthorhaligncr}} + +% test and setup the optional argument to \\[] +\def\@@IEEEauthorhaligncr{\@testopt\@@@IEEEauthorhaligncr\z@skip} + +% end the line and do the optional spacer +\def\@@@IEEEauthorhaligncr[#1]{\ifnum0=`{\fi}\cr\noalign{\vskip#1\relax}} + + + +% flag to prevent multiple \and warning messages +\newif\if@IEEEWARNand +\@IEEEWARNandtrue + +% if in conference or peerreviewca modes, we support the use of \and as \author is a +% tabular environment, otherwise we warn the user that \and is invalid +% outside of conference or peerreviewca modes. +\def\and{\relax} % provide a bogus \and that we will then override + +\renewcommand{\and}[1][\relax]{\if@IEEEWARNand\typeout{** WARNING: \noexpand\and is valid only + when in conference or peerreviewca}\typeout{modes (line \the\inputlineno).}\fi\global\@IEEEWARNandfalse} + +\if@confmode% +\renewcommand{\and}[1][\hfill]{\end{@IEEEauthorhalign}#1\begin{@IEEEauthorhalign}}% +\fi +\if@peerreviewcaoption +\renewcommand{\and}[1][\hfill]{\end{@IEEEauthorhalign}#1\begin{@IEEEauthorhalign}}% +\fi + + +% page clearing command +% based on LaTeX2e's \cleardoublepage, but allows different page styles +% for the inserted blank pages +\def\@IEEEcleardoublepage#1{\clearpage\if@twoside\ifodd\c@page\else +\hbox{}\thispagestyle{#1}\newpage\if@twocolumn\hbox{}\thispagestyle{#1}\newpage\fi\fi\fi} + + +% user command to invoke the title page +\def\maketitle{\par% + \begingroup% + \normalfont% + \def\thefootnote{}% the \thanks{} mark type is empty + \def\footnotemark{}% and kill space from \thanks within author + \footnotesize% equal spacing between thanks lines + \footnotesep 0.7\baselineskip%see global setting of \footnotesep for more info + \normalsize% + \if@peerreviewoption + \newpage\global\@topnum\z@ \@maketitle\@IEEEstatictitlevskip\@IEEEaftertitletext% + \thispagestyle{peerreviewcoverpagestyle}\@thanks% + \else + \if@twocolumn% + \if@technote% + \newpage\global\@topnum\z@ \@maketitle\@IEEEstatictitlevskip\@IEEEaftertitletext% + \else + \twocolumn[\@maketitle\@IEEEdynamictitlevspace\@IEEEaftertitletext]% + \fi + \else + \newpage\global\@topnum\z@ \@maketitle\@IEEEstatictitlevskip\@IEEEaftertitletext% + \fi + \thispagestyle{titlepagestyle}\@thanks% + \fi + % pullup page for pubid if used. + \if@IEEEusingpubid + \enlargethispage{-\@pubidpullup}% + \fi + \endgroup + \setcounter{footnote}{0}\let\maketitle\relax\let\@maketitle\relax + \gdef\@thanks{} + % v1.6b do not clear these as we will need the title again for peer review papers + % \gdef\@author{}\gdef\@title{}% + \let\thanks\relax} + + +% formats the Title, authors names, affiliations and special paper notice +% THIS IS A CONTROLLED SPACING COMMAND! Do not allow blank lines or unintentional +% spaces to enter the definition - use % at the end of each line +% Changed Title font to \LARGE from \Huge +\def\@maketitle{\newpage +\begin{center}% +\if@technote% + {\bfseries\large\@title\par}\vskip 1.3em{\lineskip .5em\@author\@specialpapernotice\par}% +\else% not a technote + \vskip0.25in{\LARGE\@title\par}\vskip1.0em\par% + % V1.6 handle \author differently if in conference mode + \if@confmode% + {\@specialpapernotice\mbox{}\vskip\@IEEEauthorblockconfadjspace% + \mbox{}\hfill\begin{@IEEEauthorhalign}\@author\end{@IEEEauthorhalign}\hfill\mbox{}\par}% + \else% peerreviewca, peerreview or journal + \if@peerreviewcaoption + % peerreviewca handles author names just like conference mode + {\@specialpapernotice\mbox{}\vskip\@IEEEauthorblockconfadjspace% + \mbox{}\hfill\begin{@IEEEauthorhalign}\@author\end{@IEEEauthorhalign}\hfill\mbox{}\par}% + \else % journal or peerreview + {\lineskip.5em\sublargesize\@author\@specialpapernotice\par}% + \fi + \fi +\fi\end{center}} + + + +% V1.6b define the \IEEEpeerreviewmaketitle as needed +\if@peerreviewoption +\def\IEEEpeerreviewmaketitle{\@IEEEcleardoublepage{empty}% +\if@twocolumnmode +\twocolumn[\@IEEEpeerreviewmaketitle\@IEEEdynamictitlevspace] +\else +\newpage\@IEEEpeerreviewmaketitle\@IEEEstatictitlevskip +\fi +\thispagestyle{titlepagestyle}} +\else +% \IEEEpeerreviewmaketitle does nothing if peer review option has not been selected +\def\IEEEpeerreviewmaketitle{\relax} +\fi + +% peerreview formats the repeated title like the title in journal papers. +\def\@IEEEpeerreviewmaketitle{\begin{center}% +\normalfont\normalsize\vskip0.2em{\Huge\@title\par}\vskip1.0em\par +\end{center}} + + + +% V1.6 +% this is a static rubber spacer between the title/authors and the main text +% used for single column text, or when the title appears in the first column +% of two column text (technotes). +\def\@IEEEstatictitlevskip{{\normalfont\normalsize +% adjust spacing to next text +% v1.6b handle peer review papers +\if@peerreviewoption +% for peer review papers, the same value is used for both title pages +% regardless of the other paper modes + \vskip 1\baselineskip plus 0.375\baselineskip minus 0.1875\baselineskip +\else + \if@confmode% conference + \vskip 1\baselineskip plus 0.375\baselineskip minus 0.1875\baselineskip% + \else% + \if@technote% technote + \vskip 1\baselineskip plus 0.375\baselineskip minus 0.1875\baselineskip% + \else% journal uses more space + \vskip 2.5\baselineskip plus 0.75\baselineskip minus 0.375\baselineskip% + \fi + \fi +\fi}} + + +% V1.6 +% This is a dynamically determined rigid spacer between the title/authors +% and the main text. This is used only for single column titles over two +% column text (most common) +% This is bit tricky because we have to ensure that the textheight of the +% main text is an integer multiple of \baselineskip +% otherwise underfull vbox problems may develop in the second column of the +% text on the titlepage +% The possible use of \pubid must also be taken into account. +\def\@IEEEdynamictitlevspace{{% + % we run within a group so that all the macros can be forgotten when we are done + \def\thanks##1{\relax}%don't allow \thanks to run when we evaluate the vbox height + \normalfont\normalsize% we declare more descriptive variable names + \let\@maintextheight=\@IEEEtrantmpdimenA%height of the main text columns + \let\@INTmaintextheight=\@IEEEtrantmpdimenB%height of the main text columns with integer # lines + % set the nominal and minimum values for the title spacer + % the dynamic algorithm will not allow the spacer size to + % become less than \@MINtitlevspace - instead it will be + % lengthened + % default to journal values + \def\@NORMtitlevspace{2.5\baselineskip}% + \def\@MINtitlevspace{2\baselineskip}% + % conferences and technotes need tighter spacing + \if@confmode%conference + \def\@NORMtitlevspace{1\baselineskip}% + \def\@MINtitlevspace{0.75\baselineskip}% + \fi + \if@technote%technote + \def\@NORMtitlevspace{1\baselineskip}% + \def\@MINtitlevspace{0.75\baselineskip}% + \fi% + % get the height that the title will take up + \if@peerreviewoption + \settoheight{\@maintextheight}{\vbox{\hsize\textwidth \@IEEEpeerreviewmaketitle}}% + \else + \settoheight{\@maintextheight}{\vbox{\hsize\textwidth \@maketitle}}% + \fi + \@maintextheight=-\@maintextheight% title takes away from maintext, so reverse sign + % add the height of the page textheight + \advance\@maintextheight by \textheight% + % correct for title pages using pubid + \if@peerreviewoption\else + % peerreview papers use the pubid on the cover page only. + % And the cover page uses a static spacer. + \if@IEEEusingpubid\advance\@maintextheight by -\@pubidpullup\fi + \fi% + % subtract off the nominal value of the title bottom spacer + \advance\@maintextheight by -\@NORMtitlevspace% + % \topskip takes away some too + \advance\@maintextheight by -\topskip% + % calculate the column height of the main text for lines + % now we calculate the main text height as if holding + % an integer number of \normalsize lines after the first + % and discard any excess fractional remainder + % we subtracted the first line, because the first line + % is placed \topskip into the maintext, not \baselineskip like the + % rest of the lines. + \@INTmaintextheight=\@maintextheight% + \divide\@INTmaintextheight by \baselineskip% + \multiply\@INTmaintextheight by \baselineskip% + % now we calculate how much the title spacer height will + % have to be reduced from nominal (\@REDUCEmaintextheight is always + % a positive value) so that the maintext area will contain an integer + % number of normal size lines + % we change variable names here (to avoid confusion) as we no longer + % need \@INTmaintextheight and can reuse its dimen register + \let\@REDUCEmaintextheight=\@INTmaintextheight% + \advance\@REDUCEmaintextheight by -\@maintextheight% + \advance\@REDUCEmaintextheight by \baselineskip% + % this is the calculated height of the spacer + % we change variable names here (to avoid confusion) as we no longer + % need \@maintextheight and can reuse its dimen register + \let\@COMPENSATElen=\@maintextheight% + \@COMPENSATElen=\@NORMtitlevspace% set the nominal value + % we go with the reduced length if it is smaller than an increase + \ifdim\@REDUCEmaintextheight < 0.5\baselineskip\relax% + \advance\@COMPENSATElen by -\@REDUCEmaintextheight% + % if the resulting spacer is too small back out and go with an increase instead + \ifdim\@COMPENSATElen<\@MINtitlevspace\relax% + \advance\@COMPENSATElen by \baselineskip% + \fi% + \else% + % go with an increase because it is closer to the nominal than a decrease + \advance\@COMPENSATElen by -\@REDUCEmaintextheight% + \advance\@COMPENSATElen by \baselineskip% + \fi% + % set the calculated rigid spacer + \vspace{\@COMPENSATElen}}} + + + +% V1.6 +% we allow the user access to the last part of the title area +% useful in emergencies such as when a different spacing is needed +% This text is NOT compensated for in the dynamic sizer. +\let\@IEEEaftertitletext=\relax +\def\IEEEaftertitletext#1{\def\@IEEEaftertitletext{#1}} + + +% V1.6 have abstract and keywords strip leading spaces, pars and newlines +% so that spacing is more tightly controlled. +\def\abstract{\normalfont% + \if@twocolumn% + \@IEEEabskeysecsize\bfseries\textit{Abstract}---\,% + \else% + \begin{center}\vspace{-1.78ex}\@IEEEabskeysecsize\textbf{Abstract}\end{center}\quotation\@IEEEabskeysecsize% + \fi\@IEEEgobbleleadPARNLSP} +% V1.6 IEEE wants only 1 pica from end of abstract to introduction heading when in +% conference mode (the heading already has this much above it) +\def\endabstract{\relax\if@confmode\vspace{0ex}\else\vspace{1.34ex}\fi\par\if@twocolumn\else\endquotation\fi% + \normalfont\normalsize} + + +\def\keywords{\normalfont% + % IEEE uses the term (in bold italics) "Index Terms" now. + \if@twocolumn% + \@IEEEabskeysecsize\bfseries\textit{Index Terms}---\,\relax% + \else% + \begin{center}\@IEEEabskeysecsize\bfseries Index Terms\end{center}\quotation\@IEEEabskeysecsize% + \fi\@IEEEgobbleleadPARNLSP} +\def\endkeywords{\relax\if@technote\vspace{1.34ex}\else\vspace{0.67ex}\fi% + \par\if@twocolumn\else\endquotation\fi% + \normalsize\normalfont} + + +% gobbles all leading \, \\ and \par, upon finding first token that +% is not a \ , \\ or a \par, it ceases and returns that token +% +% used to strip leading \, \\ and \par from the input +% so that such things in the beginning of an environment will not +% affect the formatting of the text +\long\def\@IEEEgobbleleadPARNLSP#1{\let\@IEEEswallowthistoken=0% +\let\@IEEEgobbleleadPARNLSPtoken#1% +\let\@IEEEgobbleleadPARtoken=\par% +\let\@IEEEgobbleleadNLtoken=\\% +\let\@IEEEgobbleleadSPtoken=\ % +\def\@IEEEgobbleleadSPMACRO{\ }% +\ifx\@IEEEgobbleleadPARNLSPtoken\@IEEEgobbleleadPARtoken% +\let\@IEEEswallowthistoken=1% +\fi% +\ifx\@IEEEgobbleleadPARNLSPtoken\@IEEEgobbleleadNLtoken% +\let\@IEEEswallowthistoken=1% +\fi% +\ifx\@IEEEgobbleleadPARNLSPtoken\@IEEEgobbleleadSPtoken% +\let\@IEEEswallowthistoken=1% +\fi% +% a control space will come in as a macro +% when it is the last one on a line +\ifx\@IEEEgobbleleadPARNLSPtoken\@IEEEgobbleleadSPMACRO% +\let\@IEEEswallowthistoken=1% +\fi% +% if we have to swallow this token, do so and taste the next one +% else spit it out and stop gobbling +\ifx\@IEEEswallowthistoken 1\let\@IEEEnextgobbleleadPARNLSP=\@IEEEgobbleleadPARNLSP\else% +\let\@IEEEnextgobbleleadPARNLSP=#1\fi% +\@IEEEnextgobbleleadPARNLSP}% + + + + +% TITLING OF SECTIONS +\def\@IEEEsectpunct{:\ \,} % Punctuation after run-in section heading (headings which are + % part of the paragraphs), need little bit more than a space + +\def\@seccntformat#1{\csname the#1dis\endcsname\hskip 0.5em\relax} + +\def\@sect#1#2#3#4#5#6[#7]#8{% + \ifnum #2>\c@secnumdepth% + \def\@svsec{}% + \else% + \refstepcounter{#1} + % load section label and spacer into \@svsec + \protected@edef\@svsec{\@seccntformat{#1}\relax}% + \fi% + \@tempskipa #5\relax% + \ifdim \@tempskipa>\z@% tempskipa determines whether is treated as a high + \begingroup #6\relax% or low level heading + \noindent % subsections are NOT indented + % print top level headings. \@svsec is label, #8 is heading title + %\@hangfrom{\hskip #3\relax\@svsec}{\interlinepenalty \@M #8\par} + % IEEE does not block indent the section title text, it flows like normal + \relax{\hskip #3\relax\@svsec}{\interlinepenalty \@M #8\par}% + \endgroup% + % got rid of sectionmark stuff + % \csname #1mark\endcsname{#7} + \addcontentsline{toc}{#1}{\ifnum #2>\c@secnumdepth\relax\else% + \protect\numberline{\csname the#1\endcsname}\fi#7}% + \else % printout low level headings + % svsechd seems to swallow the trailing space, protect it with \mbox{} + % got rid of sectionmark stuff + \def\@svsechd{#6\hskip #3\@svsec #8\@IEEEsectpunct\mbox{}%\csname #1mark\endcsname{#7} + \addcontentsline{toc}{#1}{\ifnum #2>\c@secnumdepth\relax\else% + \protect\numberline{\csname the#1\endcsname}\fi#7}} + \fi%skip down + \@xsect{#5}} + +% section* handler +\def\@ssect#1#2#3#4#5{\@tempskipa #3\relax% + \ifdim \@tempskipa>\z@% + %\begingroup #4\@hangfrom{\hskip #1}{\interlinepenalty \@M #5\par}\endgroup + % IEEE does not block indent the section title text, it flows like normal + \begingroup \noindent #4\relax{\hskip #1}{\interlinepenalty \@M #5\par}\endgroup% + % svsechd swallows the trailing space, protect it with \mbox{} + \else \def\@svsechd{#4\hskip #1\relax #5\@IEEEsectpunct\mbox{}}\fi% + \@xsect{#3}} + + +%% SECTION heading spacing and font +%% +% arguments are: #1 - sectiontype name +% (for \@sect) #2 - section level +% #3 - section heading indent +% #4 - top separation (absolute value used, neg indicates not to indent main text) +% If negative, make stretch parts negative too! +% #5 - (absolute value used) positive: bottom separation after heading, +% negative: amount to indent main text after heading +% Both #4 and #5 negative means to indent main text and use negative top separation +% #6 - font control +% You've got to have \normalfont\normalsize in the font specs below to prevent +% trouble when you do something like: +% \section{Note}{\ttfamily TT-TEXT} is known to ... +% IEEE sometimes REALLY stretches the area before a section +% heading by up to about 0.5in. However, it may not be a good +% idea to let LaTeX have quite this much rubber. +\if@confmode% +% IEEE wants section heading spacing to decrease for conference mode +\def\section{\@startsection{section}{1}{\z@}{1.5ex plus 1.5ex minus 0.5ex}% +{0.7ex plus 1ex minus 0ex}{\normalfont\normalsize\centering\scshape}}% +\def\subsection{\@startsection{subsection}{2}{\z@}{1.5ex plus 1.5ex minus 0.5ex}% +{0.7ex plus .5ex minus 0ex}{\normalfont\normalsize\itshape}}% +\else % for journals +\def\section{\@startsection{section}{1}{\z@}{3.0ex plus 1.5ex minus 1.5ex}% V1.6 3.0ex from 3.5ex +{0.7ex plus 1ex minus 0ex}{\normalfont\normalsize\centering\scshape}}% +\def\subsection{\@startsection{subsection}{2}{\z@}{3.5ex plus 1.5ex minus 1.5ex}% +{0.7ex plus .5ex minus 0ex}{\normalfont\normalsize\itshape}}% +\fi +% decided to put in a little rubber above the section, might help somebody +\def\subsubsection{\@startsection{subsubsection}{3}{\parindent}{0ex plus 0.1ex minus 0.1ex}% +{0ex}{\normalfont\normalsize\itshape}}% +\def\paragraph{\@startsection{paragraph}{4}{2\parindent}{0ex plus 0.1ex minus 0.1ex}% +{0ex}{\normalfont\normalsize\itshape}}% + + + +%% ENVIRONMENTS +% "box" symbols at end of proofs +\def\QEDclosed{\mbox{\rule[0pt]{1.3ex}{1.3ex}}} % for a filled box +% V1.6 some journals use an open box instead that will just fit around a closed one +\def\QEDopen{{\setlength{\fboxsep}{0pt}\setlength{\fboxrule}{0.2pt}\fbox{\rule[0pt]{0pt}{1.3ex}\rule[0pt]{1.3ex}{0pt}}}} +\def\QED{\QEDclosed} % default to closed + +\def\proof{\noindent\hspace{2em}{\itshape Proof: }} +\def\endproof{\hspace*{\fill}~\QED\par\endtrivlist\unskip} +%\itemindent is set to \z@ by list, so define new temporary variable +\newdimen\@IEEEtmpitemindent +\def\@begintheorem#1#2{\@IEEEtmpitemindent\itemindent\topsep 0pt\rmfamily\trivlist% + \item[\hskip \labelsep{\indent\itshape #1\ #2:}]\itemindent\@IEEEtmpitemindent} +\def\@opargbegintheorem#1#2#3{\@IEEEtmpitemindent\itemindent\topsep 0pt\rmfamily \trivlist% +% V1.6 IEEE is back to using () around theorem names which are also in italics +% Thanks to Christian Peel for reporting this. + \item[\hskip\labelsep{\indent\itshape #1\ #2\ (#3):}]\itemindent\@IEEEtmpitemindent} +\def\@endtheorem{\endtrivlist\unskip} + +% V1.6 +% display command for the section the theorem is in - so that \thesection +% is not used as this will be in Roman numerals when we want arabic. +% LaTeX2e uses \def\@thmcounter#1{\noexpand\arabic{#1}} for the theorem number +% (second part) display and \def\@thmcountersep{.} as a separator. +\def\@IEEEthmcounterin#1{\arabic{#1}} +% redefine the #1#2[#3] form of newtheorem to use a hook to \@IEEEthmcounterin +\def\@xnthm#1#2[#3]{% + \expandafter\@ifdefinable\csname #1\endcsname + {\@definecounter{#1}\@newctr{#1}[#3]% + \expandafter\xdef\csname the#1\endcsname{% + \noexpand\@IEEEthmcounterin{#3}\@thmcountersep\@thmcounter{#1}}% + \global\@namedef{#1}{\@thm{#1}{#2}}% + \global\@namedef{end#1}{\@endtheorem}}} + + + +%% SET UP THE DEFAULT PAGESTYLE +\ps@headings +\pagenumbering{arabic} + +% normally the page counter starts at 1 +\setcounter{page}{1} +% however, for peerreview the cover sheet is page 0 or page -1 +% (for duplex printing) +\if@peerreviewoption + \if@twoside + \setcounter{page}{-1} + \else + \setcounter{page}{0} + \fi +\fi + +% standard book class behavior - let bottom line float up and down as +% needed when single sided +\if@twoside\else\raggedbottom\fi +% if two column - turn on twocolumn, allow word spacings to stretch more and +% enforce a rigid position for the last lines +\if@twocolumnmode +% the peer review option delays invoking twocolumn + \if@peerreviewoption\else + \twocolumn + \fi +\sloppy +\flushbottom +\fi + + + + +% \APPENDIX and \APPENDICES definitions + +% This is the \@ifmtarg command from the LaTeX ifmtarg package +% by Peter Wilson (CUA) and Donald Arseneau +% \@ifmtarg is used to determine if an argument to a command +% is present or not. +% For instance: +% \@ifmtarg{#1}{\typeout{empty}}{\typeout{has something}} +% \@ifmtarg is used with our redefined \section command if +% \appendices is invoked. +% The command \section will behave slightly differently depending +% on whether the user specifies a title: +% \section{My appendix title} +% or not: +% \section{} +% This way, we can eliminate the blank lines where the title +% would be, and the unneeded : after Appendix in the table of +% contents +\begingroup +\catcode`\Q=3 +\long\gdef\@ifmtarg#1{\@xifmtarg#1QQ\@secondoftwo\@firstoftwo\@nil} +\long\gdef\@xifmtarg#1#2Q#3#4#5\@nil{#4} +\endgroup +% end of \@ifmtarg defs + +% save the "original" meaning of \section so we can redefine +% \section after a call to \appendix or \appendices +\let\@IEEEappendixsavesection\section + +% neat trick to grab and process the argument from \section{argument} +% we process differently if the user invoked \section{} with no +% argument (title) +% note we reroute the call to the old \section* +\def\@IEEEprocessthesectionargument#1{% +\@ifmtarg{#1}{% +\@IEEEappendixsavesection*{Appendix \thesectiondis}% +\addcontentsline{toc}{section}{Appendix \thesection}}{% +\@IEEEappendixsavesection*{Appendix \thesectiondis \\* #1}% +\addcontentsline{toc}{section}{Appendix \thesection: #1}}} + +% we use this if the user calls \section{} after +% \appendix-- which has no meaning. So, we ignore the +% command and its argument. Then, warn the user. +\def\@IEEEdestroythesectionargument#1{\typeout{** WARNING: Ignoring useless +\protect\section\space in Appendix (line \the\inputlineno).}} + + +% remember \thesection forms will be displayed in \ref calls +% and in the Table of Contents. +% The \sectiondis form is used in the actual heading itself + +% appendix command for one single appendix +% normally has no heading. However, if you want a +% heading, you can do so via the optional argument: +% \appendix[Optional Heading] +\def\appendix{\relax} +\renewcommand{\appendix}[1][]{\par% + % v1.6 keep hyperref's identifiers unique + \def\theHsection{Appendix.A}% + % v1.6 adjust hyperref's string name for the section + \xdef\Hy@chapapp{appendix}% + \setcounter{section}{0}% + \setcounter{subsection}{0}% + \setcounter{subsubsection}{0}% + \setcounter{paragraph}{0}% + \def\thesection{}% + \def\thesectiondis{}% + \def\thesubsection{\Alph{subsection}}% + \refstepcounter{section}% update the \ref counter + \@ifmtarg{#1}{\@IEEEappendixsavesection*{Appendix}% + \addcontentsline{toc}{section}{Appendix}}{% + \@IEEEappendixsavesection*{Appendix \\* #1}% + \addcontentsline{toc}{section}{Appendix: #1}}% + % redefine \section command for appendix + % leave \section* as is + \def\section{\@ifstar{\@IEEEappendixsavesection*}{% + \@IEEEdestroythesectionargument}}% throw out the argument + % of the normal form +} + + +% provides the user a way to choose between +% Appendix A +% and +% Appendix I +% notation +% defaults to Roman. +\newif\ifuseRomanappendices +\useRomanappendicestrue + + +% appendices command for multiple appendices +% user then calls \section with an argument (possibly empty) to +% declare the individual appendices +\def\appendices{\par% + % v1.6 keep hyperref's identifiers unique + \def\theHsection{Appendix.\Alph{section}}% + % v1.6 adjust hyperref's string name for the section + \xdef\Hy@chapapp{appendix}% + \setcounter{section}{-1}% we want \refstepcounter to use section 0 + \setcounter{subsection}{0}% + \setcounter{subsubsection}{0}% + \setcounter{paragraph}{0}% + \ifuseRomanappendices% + \def\thesection{\Roman{section}}% + \def\thesectiondis{\Roman{section}}% + \else% + \def\thesection{\Alph{section}}% + \def\thesectiondis{\Alph{section}}% + \fi% + \refstepcounter{section}% update the \ref counter + \setcounter{section}{0}% NEXT \section will be the FIRST appendix + % redefine \section command for appendices + % leave \section* as is + \def\section{\@ifstar{\@IEEEappendixsavesection*}{% process the *-form + \refstepcounter{section}% or is a new section so, + \@IEEEprocessthesectionargument}}% process the argument + % of the normal form +} + + + +% \PARstart +% Definition for the big two line drop cap letter at the beginning of the +% first paragraph of journal papers. The first argument is the first letter +% of the first word, the second argument is the remaining letters of the +% first word which will be rendered in upper case. +% In V1.6 this has been completely rewritten to: +% +% 1. no longer have problems when the user begins an environment +% within the paragraph that uses \PARstart. +% 2. auto-detect and use the current font family +% 3. revise handling of the space at the end of the first word so that +% interword glue will now work as normal. +% 4. produce correctly aligned edges for the (two) indented lines. +% +% We generalize things via control macros - playing with these is fun too. +% +% the number of lines that are indented to clear it +\def\@IEEEPARstartDROPLINES{2} +% minimum number of lines left on a page to allow a \@PARstart +% Does not take into consideration rubber shrink, so it tends to +% be overly cautious +\def\@IEEEPARstartMINPAGELINES{2} +% the depth the letter is lowered below the baseline +% the height (and size) of the letter is determined by the sum +% of this value and the height of a capital "T" in the current +% font. It is a good idea to set this value in terms of the baselineskip +% so that it can respond to changes therein. +\def\@IEEEPARstartDROPDEPTH{1.1\baselineskip} +% This is the separation distance from the drop letter to the main text. +% Lengths that depend on the font (i.e., ex, em, etc.) will be referenced +% to the font that is active when PARstart is called. +\def\@IEEEPARstartSEP{0.15em} + + +% definition of \PARstart +% THIS IS A CONTROLLED SPACING AREA, DO NOT ALLOW SPACES WITHIN THESE LINES +% +% The token \@IEEEPARstartfont will be globally defined after the first use +% of \PARstart and will be a font command which creates the big letter +% The first argument is the first letter of the first word and the second +% argument is the rest of the first word(s). +\def\PARstart#1#2{\par{% +% if this page does not have enough space, break it and lets start +% on a new one +\@IEEEtranneedspace{\@IEEEPARstartMINPAGELINES\baselineskip}{\relax}% +% calculate the desired height of the big letter +% it extends from the top of a capital "T" in the current font +% down to \@IEEEPARstartDROPDEPTH below the current baseline +\settoheight{\@IEEEtrantmpdimenA}{T}% +\addtolength{\@IEEEtrantmpdimenA}{\@IEEEPARstartDROPDEPTH}% +% extract the name of the current font in bold +% and place it in \@IEEEPARstartFONTNAME +\def\@IEEEPARstartGETFIRSTWORD##1 ##2\relax{##1}% +{\bfseries% +\edef\@IEEEPARstartFONTNAMESPACE{\fontname\font\space}% +\xdef\@IEEEPARstartFONTNAME{\expandafter\@IEEEPARstartGETFIRSTWORD\@IEEEPARstartFONTNAMESPACE\relax}}% +% define a font based on this name with a point size equal to the desired +% height of the drop letter +\font\@IEEEPARstartsubfont\@IEEEPARstartFONTNAME\space at \@IEEEtrantmpdimenA\relax% +% save this value as a counter (integer) value (sp points) +\@IEEEtrantmpcountA=\@IEEEtrantmpdimenA% +% now get the height of the actual letter produced by this font size +\settoheight{\@IEEEtrantmpdimenB}{\@IEEEPARstartsubfont\MakeUppercase{#1}}% +% If something bogus happens like the first argument is empty or the +% current font is strange, do not allow a zero height. +\ifdim\@IEEEtrantmpdimenB=0pt\relax% +\typeout{** WARNING: PARstart drop letter has zero height! (line \the\inputlineno)}% +\typeout{ Forcing the drop letter font size to 10pt.}% +\@IEEEtrantmpdimenB=10pt% +\fi% +% and store it as a counter +\@IEEEtrantmpcountB=\@IEEEtrantmpdimenB% +% Since a font size doesn't exactly correspond to the height of the capital +% letters in that font, the actual height of the letter, \@IEEEtrantmpcountB, +% will be less than that desired, \@IEEEtrantmpcountA +% we need to raise the font size, \@IEEEtrantmpdimenA +% by \@IEEEtrantmpcountA / \@IEEEtrantmpcountB +% But, TeX doesn't have floating point division, so we have to use integer +% division. Hence the use of the counters. +% We need to reduce the denominator so that the loss of the remainder will +% have minimal affect on the accuracy of the result +\divide\@IEEEtrantmpcountB by 200% +\divide\@IEEEtrantmpcountA by \@IEEEtrantmpcountB% +% Then reequalize things when we use TeX's ability to multiply by +% floating point values +\@IEEEtrantmpdimenB=0.005\@IEEEtrantmpdimenA% +\multiply\@IEEEtrantmpdimenB by \@IEEEtrantmpcountA% +% \@IEEEPARstartfont is globaly set to the calculated font of the big letter +% We need to carry this out of the local calculation area to to create the +% big letter. +\global\font\@IEEEPARstartfont\@IEEEPARstartFONTNAME\space at \@IEEEtrantmpdimenB% +% Now set \@IEEEtrantmpdimenA to the width of the big letter +% We need to carry this out of the local calculation area to set the +% hanging indent +\settowidth{\global\@IEEEtrantmpdimenA}{\@IEEEPARstartfont\MakeUppercase{#1}}}% +% end of the isolated calculation environment +% add in the extra clearance we want +\advance\@IEEEtrantmpdimenA by \@IEEEPARstartSEP% +% \@IEEEtrantmpdimenA has the width of the big letter plus the +% separation space and \@IEEEPARstartfont is the font we need to use +% Now, we make the letter and issue the hanging indent command +% The letter is placed in a box of zero width and height so that other +% text won't be displaced by it. +\noindent\hangindent\@IEEEtrantmpdimenA\hangafter=-\@IEEEPARstartDROPLINES% +\makebox[0pt][l]{\hspace{-\@IEEEtrantmpdimenA}\raisebox{-\@IEEEPARstartDROPDEPTH}[0pt][0pt]{\@IEEEPARstartfont\MakeUppercase{#1}}}\MakeUppercase{#2}} + + +% V1.6 \CMPARstart is no longer needed as \PARstart now uses whatever +% the current font family is. +% \CMPARstart is provided here for backward compatability. +\let\CMPARstart=\PARstart + + + +% determines if the space remaining on a given page is equal to or greater +% than the specified space of argument one +% if not, execute argument two (only if the remaining space is greater than zero) +% and issue a \newpage +% +% example: \@IEEEtranneedspace{2in}{\vfill} +% +% Does not take into consideration rubber shrinkage, so it tends to +% be overly cautious +% Based on an example posted by Donald Arseneau +% Note this macro uses \@IEEEtrantmpdimenB internally for calculations, +% so DO NOT PASS \@IEEEtrantmpdimenB to this routine +% if you need a dimen register, import with \@IEEEtrantmpdimenA instead +\def\@IEEEtranneedspace#1#2{\penalty-100\begingroup%shield temp variable +\@IEEEtrantmpdimenB\pagegoal\advance\@IEEEtrantmpdimenB-\pagetotal% space left +\ifdim #1>\@IEEEtrantmpdimenB\relax% not enough space left +\ifdim\@IEEEtrantmpdimenB>\z@\relax #2\fi% +\newpage% +\fi\endgroup} + + + +% BIOGRAPHY ENVIRONMENT +% Allows user to enter BIOGRAPHY leaving place for picture (adapts to font size) +% As of V1.5, a new optional argument allows you to have a real graphic! +% V1.5 and later also fixes the "colliding biographies" which could happen when a +% biography's text was shorter than the space for the photo. +% MDS 7/2001 +% V1.6 prevent multiple biographies from making multiple TOC entries +\newif\if@biographyTOCentrynotmade +\global\@biographyTOCentrynotmadetrue + +% biography counter so hyperref can jump directly to the biographies +% and not just the previous section +\newcounter{biography} +\setcounter{biography}{0} + +% photo area size +\def\@IEEEBIOphotowidth{1.0in} % width of the biography photo area +\def\@IEEEBIOphotodepth{1.25in} % depth (height) of the biography photo area +% area cleared for photo +\def\@IEEEBIOhangwidth{1.14in} % width cleared for the biography photo area +\def\@IEEEBIOhangdepth{1.25in} % depth cleared for the biography photo area + % actual depth will be a multiple of + % \baselineskip, rounded up +\def\@IEEEBIOskipN{4\baselineskip}% nominal value of the vskip above the biography + +\newenvironment{biography}[2][]{\normalfont\footnotesize% +\unitlength 1in\parskip=0pt\par\parindent 1em\interlinepenalty500% +% we need enough space to support the hanging indent +% the nominal value of the spacer +% and one extra line for good measure +\@IEEEtrantmpdimenA=\@IEEEBIOhangdepth% +\advance\@IEEEtrantmpdimenA by \@IEEEBIOskipN% +\advance\@IEEEtrantmpdimenA by 1\baselineskip% +% if this page does not have enough space, break it and lets start +% with a new one +\@IEEEtranneedspace{\@IEEEtrantmpdimenA}{\relax}% +% nominal spacer can strech, not shrink use 1fil so user can out stretch with \vfill +\vskip \@IEEEBIOskipN plus 1fil minus 0\baselineskip% +% the default box for where the photo goes +\def\@IEEEtempbiographybox{{\setlength{\fboxsep}{0pt}\framebox{\begin{minipage}[b][\@IEEEBIOphotodepth][c]{\@IEEEBIOphotowidth}\centering PLACE\\ PHOTO\\ HERE \end{minipage}}}}% +% +% detect if the optional argument was supplied, this requires the +% \@ifmtarg command as defined in the appendix section above +% and if so, override the default box with what they want +\@ifmtarg{#1}{\relax}{\def\@IEEEtempbiographybox{\mbox{\begin{minipage}[b][\@IEEEBIOphotodepth][c]{\@IEEEBIOphotowidth}% +\centering% +#1% +\end{minipage}}}}% end if optional argument supplied +% Make an entry into the table of contents only if we have not done so before +\if@biographyTOCentrynotmade% +% link labels to the biography counter so hyperref will jump +% to the biography, not the previous section +\setcounter{biography}{-1}% +\refstepcounter{biography}% +\addcontentsline{toc}{section}{Biographies}% +\global\@biographyTOCentrynotmadefalse% +\fi% +% one more biography +\refstepcounter{biography}% +% Make an entry for this name into the table of contents +\addcontentsline{toc}{subsection}{#2}% +% V1.6 properly handle if a new paragraph should occur while the +% hanging indent is still active. Do this by redefining \par so +% that it will not start a new paragraph. (But it will appear to the +% user as if it did.) Also, strip any leading pars, newlines, or spaces. +\let\@IEEEBIOORGparCMD=\par% save the original \par command +\edef\par{\hfil\break\indent}% the new \par will not be a "real" \par +\settoheight{\@IEEEtrantmpdimenA}{\@IEEEtempbiographybox}% get height of biography box +\@IEEEtrantmpdimenB=\@IEEEBIOhangdepth% +\@IEEEtrantmpcountA=\@IEEEtrantmpdimenB% countA has the hang depth +\divide\@IEEEtrantmpcountA by \baselineskip% calculates lines needed to produce the hang depth +\advance\@IEEEtrantmpcountA by 1% ensure we overestimate +% set the hanging indent +\hangindent\@IEEEBIOhangwidth% +\hangafter-\@IEEEtrantmpcountA% +% reference the top of the photo area to the top of a capital T +\settoheight{\@IEEEtrantmpdimenB}{\mbox{T}}% +% set the photo box, give it zero width and height so as not to disturb anything +\noindent\makebox[0pt][l]{\hspace{-\@IEEEBIOhangwidth}\raisebox{\@IEEEtrantmpdimenB}[0pt][0pt]{\raisebox{-\@IEEEBIOphotodepth}[0pt][0pt]{\@IEEEtempbiographybox}}}% +% now place the author name and begin the bio text +\noindent\textbf{#2\ }\@IEEEgobbleleadPARNLSP}{\relax\let\par=\@IEEEBIOORGparCMD\par% +% 7/2001 V1.5 detect when the biography text is shorter than the photo area +% and pad the unused area - preventing a collision from the next biography entry +% MDS +\ifnum \prevgraf <\@IEEEtrantmpcountA\relax% detect when the biography text is shorter than the photo + \advance\@IEEEtrantmpcountA by -\prevgraf% calculate how many lines we need to pad + \advance\@IEEEtrantmpcountA by -1\relax% we compensate for the fact that we indented an extra line + \@IEEEtrantmpdimenA=\baselineskip% calculate the length of the padding + \multiply\@IEEEtrantmpdimenA by \@IEEEtrantmpcountA% + \noindent\rule{0pt}{\@IEEEtrantmpdimenA}% insert an invisible support strut +\fi% +\par\normalfont} + + + +% V1.6 +% added biography without a photo environment +\newenvironment{biographynophoto}[1]{% +% Make an entry into the table of contents only if we have not done so before +\if@biographyTOCentrynotmade% +% link labels to the biography counter so hyperref will jump +% to the biography, not the previous section +\setcounter{biography}{-1}% +\refstepcounter{biography}% +\addcontentsline{toc}{section}{Biographies}% +\global\@biographyTOCentrynotmadefalse% +\fi% +% one more biography +\refstepcounter{biography}% +% Make an entry for this name into the table of contents +\addcontentsline{toc}{subsection}{#1}% +\normalfont\footnotesize\interlinepenalty500% +\vskip 4\baselineskip plus 1fil minus 0\baselineskip% +\parskip=0pt\par% +\noindent\textbf{#1\ }\@IEEEgobbleleadPARNLSP}{\relax\par\normalfont} + + +% provide the user with some old font commands +% got this from article.cls +\DeclareOldFontCommand{\rm}{\normalfont\rmfamily}{\mathrm} +\DeclareOldFontCommand{\sf}{\normalfont\sffamily}{\mathsf} +\DeclareOldFontCommand{\tt}{\normalfont\ttfamily}{\mathtt} +\DeclareOldFontCommand{\bf}{\normalfont\bfseries}{\mathbf} +\DeclareOldFontCommand{\it}{\normalfont\itshape}{\mathit} +\DeclareOldFontCommand{\sl}{\normalfont\slshape}{\@nomath\sl} +\DeclareOldFontCommand{\sc}{\normalfont\scshape}{\@nomath\sc} +\DeclareRobustCommand*\cal{\@fontswitch\relax\mathcal} +\DeclareRobustCommand*\mit{\@fontswitch\relax\mathnormal} + + +% SPECIAL PAPER NOTICE COMMANDS +% +% holds the special notice text +\def\@specialpapernotice{\relax} + +% for special papers, like invited papers, the user can do: +% \specialpapernotice{(Invited Paper)} before \maketitle +\def\specialpapernotice#1{\if@confmode% +\def\@specialpapernotice{{\sublargesize\textit{#1}\vspace*{1em}}}% +\else% +\def\@specialpapernotice{{\\*[1.5ex]\sublargesize\textit{#1}}\vspace*{-2ex}}% +\fi} + + + + +% PUBLISHER ID COMMANDS +% to insert a publisher's ID footer +% V1.6 \pubid has been changed so that the change in page size and style +% occurs in \maketitle. \pubid must now be issued prior to \maketitle +% use \pubidadjcol as before - in the second column of the title page +% These changes allow \maketitle to take the reduced page height into +% consideration when dynamically setting the space between the author +% names and the maintext. +% +% the amount the main text is pulled up to make room for the +% publisher's ID footer +% IEEE uses about 1.3\baselineskip for journals, +% dynamic title spacing will clean up the fraction +\def\@pubidpullup{1.3\baselineskip} +\if@technote +% for technotes it must be an integer of baselineskip as there can be no +% dynamic title spacing for two column mode technotes (the title is in the +% in first column) and we should maintain an integer number of lines in the +% second column +% There are some examples (such as older issues of "Transactions on +% Information Theory") in which IEEE really pulls the text off the ID for +% technotes - about 0.55in (or 4\baselineskip). We'll use 2\baselineskip +% and call it even. +\def\@pubidpullup{2\baselineskip} +\fi + +% holds the ID text +\def\@pubid{\relax} + +% flag so \maketitle can tell if \pubid was called +\newif\if@IEEEusingpubid +\global\@IEEEusingpubidfalse +% issue this command in the page to have the ID at the bottom +% V1.6 use before \maketitle +\def\pubid#1{\def\@pubid{#1} \global\@IEEEusingpubidtrue} + + +% command which will pull up (shorten) the column it is executed in +% to make room for the publisher ID. Place in the second column of +% the title page when using \pubid +% Is smart enough not to do anything when in single column text or +% if the user hasn't called \pubid +% currently needed in for the second column of a page with the +% publisher ID. If not needed in future releases, please provide this +% command and define it as \relax for backward compatibility +% v1.6b do not allow command to operate if the peer review option has been +% selected because \pubidadjcol will not be on the cover page. +\def\pubidadjcol{\if@peerreviewoption\else\if@twocolumn\if@IEEEusingpubid\enlargethispage{-\@pubidpullup}\fi\fi\fi} + +% Special thanks to Peter Wilson, Daniel Luecking, and the other +% gurus at comp.text.tex, for helping me to understand how best to +% implement the pubid command in LaTeX. + + + +%% Lockout some commands under various conditions + +% general purpose bit bucket +\newsavebox{\@IEEEtranrubishbin} + +% flags to prevent multiple warning messages +\newif\if@IEEEWARNthanks +\newif\if@IEEEWARNPARstart +\newif\if@IEEEWARNCMPARstart +\newif\if@IEEEWARNkeywords +\newif\if@IEEEWARNbiography +\newif\if@IEEEWARNbiographynophoto +\newif\if@IEEEWARNpubid +\newif\if@IEEEWARNpubidadjcol +\newif\if@IEEEWARNIEEEmembership +\newif\if@IEEEWARNIEEEaftertitletext +\@IEEEWARNthankstrue +\@IEEEWARNPARstarttrue +\@IEEEWARNCMPARstarttrue +\@IEEEWARNkeywordstrue +\@IEEEWARNbiographytrue +\@IEEEWARNbiographynophototrue +\@IEEEWARNpubidtrue +\@IEEEWARNpubidadjcoltrue +\@IEEEWARNIEEEmembershiptrue +\@IEEEWARNIEEEaftertitletexttrue + + +%% Lockout some commands when in various modes, but allow them to be restored if needed +%% +% save commands which might be locked out +% so that the user can later restore them if needed +\let\@IEEESAVECMDthanks\thanks +\let\@IEEESAVECMDPARstart\PARstart +\let\@IEEESAVECMDCMPARstart\CMPARstart +\let\@IEEESAVECMDkeywords\keywords +\let\@IEEESAVECMDendkeywords\endkeywords +\let\@IEEESAVECMDbiography\biography +\let\@IEEESAVECMDendbiography\endbiography +\let\@IEEESAVECMDbiographynophoto\biographynophoto +\let\@IEEESAVECMDendbiographynophoto\endbiographynophoto +\let\@IEEESAVECMDpubid\pubid +\let\@IEEESAVECMDpubidadjcol\pubidadjcol +\let\@IEEESAVECMDIEEEmembership\IEEEmembership +\let\@IEEESAVECMDIEEEaftertitletext\IEEEaftertitletext + + +% disable \PARstart when in draft mode +% This may have originally been done because the pre-V1.6 drop letter +% algorithm had problems with a non-unity baselinestretch +% At any rate, it seems too formal to have a drop letter in a draft +% paper. +\if@draftclsmode +\def\PARstart#1#2{#1#2\if@IEEEWARNPARstart\typeout{** ATTENTION: \noexpand\PARstart is disabled in draft mode (line \the\inputlineno).}\fi\global\@IEEEWARNPARstartfalse} +\def\CMPARstart#1#2{#1#2\if@IEEEWARNPARstart\typeout{** ATTENTION: \noexpand\CMPARstart is disabled in draft mode (line \the\inputlineno).}\fi\global\@IEEEWARNCMPARstartfalse} +\fi +% and for technotes +\if@technote +\def\PARstart#1#2{#1#2\if@IEEEWARNPARstart\typeout{** WARNING: \noexpand\PARstart is locked out for technotes (line \the\inputlineno).}\fi\global\@IEEEWARNPARstartfalse} +\def\CMPARstart#1#2{#1#2\if@IEEEWARNPARstart\typeout{** WARNING: \noexpand\CMPARstart is locked out for technotes (line \the\inputlineno).}\fi\global\@IEEEWARNCMPARstartfalse} +\fi + + +% lockout unneeded commands when in conference mode +\if@confmode +% when locked out, \thanks, \keywords, \biography, \biographynophoto, \pubid, +% \IEEEmembership and \IEEEaftertitletext will all swallow their given text. +% \PARstart and \CMPARstart will output a normal character instead +% warn the user about these commands only once to prevent the console screen +% from filling up with redundant messages +\def\thanks#1{\if@IEEEWARNthanks\typeout{** WARNING: \noexpand\thanks is locked out when in conference mode (line \the\inputlineno).}\fi\global\@IEEEWARNthanksfalse} +\def\PARstart#1#2{#1#2\if@IEEEWARNPARstart\typeout{** WARNING: \noexpand\PARstart is locked out when in conference mode (line \the\inputlineno).}\fi\global\@IEEEWARNPARstartfalse} +\def\CMPARstart#1#2{#1#2\if@IEEEWARNPARstart\typeout{** WARNING: \noexpand\CMPARstart is locked out when in conference mode (line \the\inputlineno).}\fi\global\@IEEEWARNCMPARstartfalse} + +\renewenvironment{keywords}[1]{\if@IEEEWARNkeywords\typeout{** WARNING: \noexpand\keywords is locked out when in conference mode (line \the\inputlineno).}\fi\global\@IEEEWARNkeywordsfalse% +\setbox\@IEEEtranrubishbin\vbox\bgroup}{\egroup\relax} + +% LaTeX treats environments and commands with optional arguments differently. +% the actual ("internal") command is stored as \\commandname +% (accessed via \csname\string\commandname\endcsname ) +% the "external" command \commandname is a macro with code to determine +% whether or not the optional argument is presented and to provide the +% default if it is absent. So, in order to save and restore such a command +% we would have to save and restore \\commandname as well. But, if LaTeX +% ever changes the way it names the internal names, the trick would break. +% Instead let us just define a new environment so that the internal +% name can be left undisturbed. +\newenvironment{@IEEEbogusbiography}[2][]{\if@IEEEWARNbiography\typeout{** WARNING: \noexpand\biography is locked out when in conference mode (line \the\inputlineno).}\fi\global\@IEEEWARNbiographyfalse% +\setbox\@IEEEtranrubishbin\vbox\bgroup}{\egroup\relax} +% and make biography point to our bogus biography +\let\biography=\@IEEEbogusbiography +\let\endbiography=\end@IEEEbogusbiography + +\renewenvironment{biographynophoto}[1]{\if@IEEEWARNbiographynophoto\typeout{** WARNING: \noexpand\biographynophoto is locked out when in conference mode (line \the\inputlineno).}\fi\global\@IEEEWARNbiographynophotofalse% +\setbox\@IEEEtranrubishbin\vbox\bgroup}{\egroup\relax} + +\def\pubid#1{\if@IEEEWARNpubid\typeout{** WARNING: \noexpand\pubid is locked out when in conference mode (line \the\inputlineno).}\fi\global\@IEEEWARNpubidfalse} +\def\pubidadjcol{\if@IEEEWARNpubidadjcol\typeout{** WARNING: \noexpand\pubidadjcol is locked out when in conference mode (line \the\inputlineno).}\fi\global\@IEEEWARNpubidadjcolfalse} +\def\IEEEmembership#1{\if@IEEEWARNIEEEmembership\typeout{** WARNING: \noexpand\IEEEmembership is locked out when in conference mode (line \the\inputlineno).}\fi\global\@IEEEWARNIEEEmembershipfalse} +\def\IEEEaftertitletext#1{\if@IEEEWARNIEEEaftertitletext\typeout{** WARNING: \noexpand\IEEEaftertitletext is locked out when in conference mode (line \the\inputlineno).}\fi\global\@IEEEWARNIEEEaftertitletextfalse} +\fi + + +% provide a way to restore the commands that are locked out +\def\IEEEoverridecommandlockouts{% +\typeout{** ATTENTION: Overriding command lockouts (line \the\inputlineno).}% +\let\thanks\@IEEESAVECMDthanks% +\let\PARstart\@IEEESAVECMDPARstart% +\let\CMPARstart\@IEEESAVECMDCMPARstart% +\let\keywords\@IEEESAVECMDkeywords% +\let\endkeywords\@IEEESAVECMDendkeywords% +\let\biography\@IEEESAVECMDbiography% +\let\endbiography\@IEEESAVECMDendbiography% +\let\biographynophoto\@IEEESAVECMDbiographynophoto% +\let\endbiographynophoto\@IEEESAVECMDendbiographynophoto% +\let\pubid\@IEEESAVECMDpubid% +\let\pubidadjcol\@IEEESAVECMDpubidadjcol% +\let\IEEEmembership\@IEEESAVECMDIEEEmembership% +\let\IEEEaftertitletext\@IEEESAVECMDIEEEaftertitletext} + + +\endinput + +%%%%%%%%%%%%%%%%%%%%%%%%%%%%% End of IEEEtran.cls %%%%%%%%%%%%%%%%%%%%%%%%%%%% +% That's all folks! + diff --git a/paper/iros_references.bib b/paper/iros_references.bib new file mode 100644 index 0000000..926e34a --- /dev/null +++ b/paper/iros_references.bib @@ -0,0 +1,354 @@ +% This file was created with JabRef 2.10. +% Encoding: Cp1252 + + +@Article{ajoudanidual, + title = {Dual Arm Impedance Control with a Compliant Humanoid: Application to a Valve Turning Task}, + author = {Ajoudani, Arash and Lee, Jinoh and Rocchi, Alessio and Ferrati, Mirko and Hoffman, Enrico Mingo and Settimi, Aelssandro and Tsagarakis, Nikos G and Caldwell, Darwin G and Bicchi, Antonio} +} + +@Article{Albu-SchaefferOttHir2007, + title = {A Unified Passivity-based Control Framework for Position, Torque and Impedance Control of Flexible Joint Robots}, + author = {Albu-Schäffer, Alin and Ott, Christian and Hirzinger, Gerd}, + journal = {IJRR}, + year = {2007}, + number = {1}, + pages = {23-39}, + volume = {26}, + + doi = {10.1177/0278364907073776} +} + +@Article{BicchiTon2004, + title = {Dealing with the Safety-Performance Tradeoff in Robot Arm Design and Control: Fast and "Soft-Arm" Tactics}, + author = {A. Bicchi and G. Tonietti}, + journal = {IEEE Robotics and Automation Magazine}, + year = {2004}, + + month = {June}, + pages = {22-33}, + + timestamp = {2015.09.14} +} + +@Article{BicchiTon2002, + title = {{D}esign, {R}ealization and {C}ontrol of {S}oft {R}obot {A}rms for {I}ntrinsically {S}afe {I}nteraction with {H}umans}, + author = {A. Bicchi and G. Tonietti}, + journal = {In Proc. IARP/RAS Workshop on Technical Challenges for Dependable Robots in Human Environments}, + year = {2002}, + pages = {79-87}, + + timestamp = {2015.09.14} +} + +@Article{BidardLibArhMea2005, + title = {Dynamic identification of the hydraulic Maestro manipulator{\textemdash}Relevance for monitoring}, + author = {C. Bidard and C. Libersa and D. Arhur and Y. Measson and J.-P. Friconneau and J.-D. Palmer}, + journal = {Fusion Eng. and Design}, + year = {2005}, + + doi = {10.1016/j.fusengdes.2005.06.177}, + publisher = {Elsevier {BV}} +} + +@TechReport{ConnerKohRomStu2015, + title = {Team {ViGIR} ({DARPA} Final Report, Accession Number {ADA623035})}, + author = {Conner, David and others}, + institution = {Defense Technical Information Center Document}, + year = {2015}, + + url = {http://oai.dtic.mil/oai/oai?verb=getRecord&metadataPrefix=html&identifier=ADA623035} +} + +@InProceedings{DeLucaAlbHadHir2006, + title = {Collision detection and safe reaction with the {DLR-III} lightweight manipulator arm}, + author = {De Luca, Alessandro and Albu-Schäffer, Alin and Haddadin, Sami and Hirzinger, Gerd}, + booktitle = {IROS}, + year = {2006}, + + doi = {10.1109/IROS.2006.282053}, + file = {:irt/2006/DeLucaAlbHadHir2006.pdf:PDF}, + timestamp = {2015.09.08} +} + +@InProceedings{DeLucaFla2012a, + title = {Integrated control for {pHRI}: Collision avoidance, detection, reaction and collaboration}, + author = {De Luca, A. and Flacco, F.}, + booktitle = {BioRob}, + year = {2012}, + + abstract = {We present an integrated control framework for safe physical Human-Robot Interaction (pHRI) based on a hierarchy of consistent behaviors. Safe human robot coexistence is achieved with a layered approach for coping with undesired collisions and intended contacts. A collision avoidance algorithm based on depth information of the HRI scene is used in the first place. Since collision avoidance cannot be guaranteed, it is supported by a physical collision detection/reaction method based on a residual signal which needs only joint position measures. On top of this layer, safe human-robot collaboration tasks can be realized. Collaboration phases are activated and ended by human gestures or voice commands. Intentional physical interaction is enabled and exchanged forces are estimated by integrating the residual with an estimation of the contact point obtained from depth sensing. During the collaboration, only the human parts that are designated as collaborative are allowed to touch the robot while, consistently to the lower layers, all other contacts are considered undesired collisions. Preliminary experimental results with a KUKA LWR-IV and a Kinect sensor are presented. © 2012 IEEE.}, + art_number = {6290917}, + document_type = {Conference Paper}, + doi = {10.1109/BioRob.2012.6290917}, + file = {:robotics/2012/DeLucaFla2012.pdf:PDF}, + keywords = {Collision detection; Contact points; Depth information; Depth sensing; Human gestures; Human robots; Human-robot collaboration; Physical interactions; Residual signals; Voice command, Human computer interaction; Integrated control, Collision avoidance}, + owner = {Vorndamme}, + source = {Scopus}, + timestamp = {2015.09.14} +} + +@InProceedings{DeLucaMat2004, + title = {An adapt-and-detect actuator {FDI} scheme for robot manipulators}, + author = {De Luca, A. and Mattone, R.}, + booktitle = {ICRA}, + year = {2004}, + + doi = {10.1109/ROBOT.2004.1302506}, + file = {:robotics/2004/DeLucaMat2004.pdf:PDF}, + issn = {1050-4729} +} + +@InProceedings{DeLucaMat2003, + title = {Actuator failure detection and isolation using generalized momenta}, + author = {De Luca, A. and Mattone, R.}, + booktitle = {ICRA}, + year = {2003}, + + doi = {10.1109/ROBOT.2003.1241665}, + file = {:robotics/2003/DeLucaMat2003.pdf:PDF}, + issn = {1050-4729} +} + +@Article{GolzOseHad2015, + title = {Using tactile sensation for learning contact knowledge: Discriminate collision from physical interaction}, + author = {Golz, Saskia and Osendorfer, Christian and Haddadin, Sami}, + journal = {ICRA}, + year = {2015}, + + doi = {10.1109/icra.2015.7139726}, + isbn = {http://id.crossref.org/isbn/978-1-4799-6923-4}, + url = {http://dx.doi.org/10.1109/ICRA.2015.7139726} +} + +@InBook{Haddadin2014, + title = {Towards Safe Robots}, + author = {Haddadin, Sami}, + pages = {34--37}, + publisher = {Springer Berlin Heidelberg}, + year = {2014}, + number = {90}, + series = {Springer Tracts in Advanced Robotics}, + + doi = {10.1007/978-3-642-40308-8}, + url = {http://link.springer.com/book/10.1007%2F978-3-642-40308-8} +} + +@InProceedings{HaddadinSupFucBod2009, + title = {Towards the Robotic Co-Worker}, + author = {Haddadin, Sami and Suppa, Michael and Fuchs, Stefan and Bodenmüller, Tim and Albu-Schäffer, Alin and Hirzinger, Gerd}, + booktitle = {International Symposium on Robotics Research (ISRR)}, + year = {2009}, + month = {Aug 31 - Sep 1}, + + file = {:irt/2009/HaddadinSupFucBod2009.pdf:PDF}, + url = {http://www.isrr2009.ethz.ch/proceedings.html} +} + +@InProceedings{HerzogRigGriPas2014, + title = {Balancing experiments on a torque-controlled humanoid with hierarchical inverse dynamics}, + author = {Alexander Herzog and Ludovic Righetti and Felix Grimminger and Peter Pastor and Stefan Schaal}, + booktitle = {ICRA}, + year = {2014}, + + doi = {10.1109/iros.2014.6942678}, + url = {http://dx.doi.org/10.1109/IROS.2014.6942678} +} + +@Article{Hog1985, + title = {Impedance Control: An approach to manipulation, Part {I} - Theory}, + author = {N. Hogan}, + journal = {ASME Journal of Dynamic Systems, Measurement, and Control}, + year = {1985}, + pages = {1-7}, + volume = {107}, + + file = {:robotics/1985/Hogan1985.pdf:PDF}, + url = {http://summerschool.stiff-project.org/fileadmin/pdf/Hog1985.pdf} +} + +@Article{Hogan1985, + title = {Impedance Control: An approach to manipulation, Part {I} - Theory}, + author = {N. Hogan}, + journal = {ASME Journal of Dynamic Systems, Measurement, and Control}, + year = {1985}, + pages = {1-7}, + volume = {107}, + + file = {:robotics/1985/Hogan1985.pdf:PDF}, + url = {http://summerschool.stiff-project.org/fileadmin/pdf/Hog1985.pdf} +} + +@Article{Hyon2007SARCOScompliance, + title = {Full-Body Compliant Human-Humanoid Interaction: Balancing in the Presence of Unknown External Forces}, + author = {Sang-Ho Hyon and Hale, J.G. and Cheng, G.}, + journal = {IEEE Trans. Robot.}, + year = {2007}, + + month = {Oct}, + number = {5}, + pages = {884-898}, + volume = {23}, + + doi = {10.1109/tro.2007.904896}, + issn = {1941-0468}, + publisher = {Institute of Electrical \& Electronics Engineers (IEEE)}, + url = {http://dx.doi.org/10.1109/TRO.2007.904896} +} + +@InProceedings{jung2012collision, + title = {Collision detection using band designed Disturbance Observer}, + author = {Jung, Byung-Jin and Choi, Hyouk Ryeol and Koo, Ja Choon and Moon, Hyungpil}, + booktitle = {IEEE CASE}, + year = {2012} +} + +@InProceedings{JungChoKooMoo2012, + title = {Collision detection using band designed Disturbance Observer}, + author = {Jung, Byung-Jin and Choi, Hyouk Ryeol and Koo, Ja Choon and Moon, Hyungpil}, + booktitle = {Automation Science and Engineering (CASE), 2012 IEEE International Conference on}, + year = {2012}, + organization = {IEEE}, + pages = {1080--1085} +} + +@Article{2014:JFR-ViGIR-DRC-Trials, + title = {Human-Robot Teaming for Rescue Missions: Team {ViGIR}'s Approach to the 2013 {DARPA} Robotics Challenge Trials}, + author = {S. Kohlbrecher and others}, + journal = {Journal of Field Robotics}, + year = {2015}, + number = {3}, + pages = {352-377}, + volume = {32}, + + url = {http://onlinelibrary.wiley.com/doi/10.1002/rob.21558/full} +} + +@InProceedings{LeTienAlbDeHir2008, + title = {Friction observer and compensation for control of robots with joint torque measurement}, + author = {Le Tien, L. and Albu-Schäffer, A. and De Luca, A. and Hirzinger, G.}, + booktitle = {IROS}, + year = {2008}, + + art_number = {4651049}, + document_type = {Conference Paper}, + doi = {10.1109/IROS.2008.4651049}, + file = {:robotics/2008/LeTienAlbDeHir2008.pdf:PDF} +} + +@InProceedings{Lee2014atlasadmittance, + title = {Natural admittance control of an electro-hydraulic humanoid robot}, + author = {Kit-Hang Lee and Newman, W.S.}, + booktitle = {ROBIO}, + year = {2014}, + + doi = {10.1109/ROBIO.2014.7090479} +} + +@Article{LucaMat2005, + title = {Sensorless Robot Collision Detection and Hybrid Force/Motion Control}, + author = {de Luca, A. and Mattone, R.}, + journal = {ICRA}, + year = {2005}, + + doi = {10.1109/robot.2005.1570247}, + isbn = {http://id.crossref.org/isbn/0-7803-8914-X}, + url = {http://dx.doi.org/10.1109/ROBOT.2005.1570247} +} + +@InProceedings{MasonRigSch2014, + title = {Full dynamics {LQR} control of a humanoid robot: An experimental study on balancing and squatting}, + author = {Sean Mason and Ludovic Righetti and Stefan Schaal}, + booktitle = {Humanoids}, + year = {2014}, + + doi = {10.1109/humanoids.2014.7041387}, + url = {http://dx.doi.org/10.1109/HUMANOIDS.2014.7041387} +} + +@Article{NikoobinHag2008, + title = {{Lyapunov}-Based Nonlinear Disturbance Observer for Serial n-Link Robot Manipulators}, + author = {Nikoobin, Amin and Haghighi, Reza}, + journal = {Journal of Intelligent and Robotic Systems}, + year = {2008}, + + month = {Dec}, + number = {2-3}, + pages = {135--153}, + volume = {55}, + + doi = {10.1007/s10846-008-9298-2}, + issn = {1573-0409}, + publisher = {Springer Science + Business Media}, + url = {http://dx.doi.org/10.1007/s10846-008-9298-2} +} + +@Article{Oh1999, + title = {Disturbance observer based robust impedance control of redundant manipulators}, + author = {Yonghwan Oh and Wan Kyun Chung and Il Hong Suh}, + journal = {IROS}, + year = {1999}, + + doi = {10.1109/iros.1999.812753}, + isbn = {http://id.crossref.org/isbn/0-7803-5184-3}, + publisher = {Institute of Electrical \& Electronics Engineers (IEEE)}, + url = {http://dx.doi.org/10.1109/IROS.1999.812753} +} + +@Article{Ott2008, + title = {Cartesian Impedance Control of Redundant and Flexible-Joint Robots}, + author = {Christian Ott}, + journal = {Springer Tracts in Advanced Robotics}, + year = {2008}, + + doi = {10.1007/978-3-540-69255-3}, + isbn = {http://id.crossref.org/isbn/978-3-540-69255-3}, + issn = {1610-742X}, + publisher = {Springer Berlin Heidelberg}, + timestamp = {2014.06.26}, + url = {http://dx.doi.org/10.1007/978-3-540-69255-3} +} + +@InProceedings{OttHenLee2013, + title = {Kinesthetic teaching of humanoid motion based on whole-body compliance control with interaction-aware balancing}, + author = {Christian Ott and Bernd Henze and Dongheui Lee}, + booktitle = {IROS}, + year = {2013}, + + doi = {10.1109/iros.2013.6697020}, + url = {http://dx.doi.org/10.1109/IROS.2013.6697020} +} + +@Article{park2006fourier, + title = {Fourier-based optimal excitation trajectories for the dynamic identification of robots}, + author = {Park, Kyung-Jo}, + journal = {Robotica}, + year = {2006}, + + publisher = {Cambridge Univ Press} +} + +@Article{PrattWil1995, + title = {Series Elastic Actuators}, + author = {Pratt,G. and Williamson,M.}, + journal = {IROS}, + year = {1995} +} + +@InProceedings{SpVdTh14, + title = {Modeling, Identification and Impedance Control of the {A}tlas Arms}, + author = {Schappler, Moritz and Vorndamme, Jonathan and T\"odtheide, Alexander and Conner, David and von Stryk, Oskar and Haddadin, Sami}, + booktitle = {Humanoids}, + year = {2015} +} + +@InProceedings{SotoudehnejadKer2014, + title = {Velocity-based variable thresholds for improving collision detection in manipulators}, + author = {Vahid Sotoudehnejad and Mehrdad R. Kermani}, + booktitle = {ICRA}, + year = {2014}, + + doi = {10.1109/icra.2014.6907343}, + url = {http://dx.doi.org/10.1109/ICRA.2014.6907343} +} + diff --git a/paper/sec_abstract_intro.tex b/paper/sec_abstract_intro.tex new file mode 100644 index 0000000..51ac68f --- /dev/null +++ b/paper/sec_abstract_intro.tex @@ -0,0 +1,101 @@ +% !TEX root = atlas_iros_16.tex + + +%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%% +\begin{abstract} +% motivation +Soft robotics methods such as im\-pe\-dance control and reflexive collision handling have proven to be a valuable tool to robots acting in partially unknown and potentially unstructured environments. +Mainly, the schemes were developed with focus on classical electromechanically driven, torque controlled robots. +There, joint friction, mostly coming from high gearing, is typically decoupled from link-side control via suitable rigid or elastic joint torque feedback. +% problem +Extending and applying these algorithms to stiff hydraulically actuated robots poses problems regarding the strong influence of friction on joint torque estimation from pressure sensing, i.e. link-side friction is typically significantly higher than in electromechanical soft robots. +% contribution +In order to improve the performance of such systems, we apply state-of-the-art fault detection and estimation methods together with observer-based disturbance compensation control to the humanoid robot Atlas. +With this it is possible to achieve higher tracking accuracy despite facing significant modeling errors. +Compliant end-effector behavior can also be ensured by including an additional force/torque sensor into the generalized momentum-based disturbance observer algorithm from \cite{DeLucaAlbHadHir2006}. +\end{abstract} +% +%\begin{keywords} +%generalized momentum based disturbance observer, collision detection, Atlas robot, joint impedance controller, observer feedforward, DARPA Robotics Challenge +%\end{keywords} + + +%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%% +\section{\large Introduction and State of the Art} +\label{sec:intro} +%%-- "General context" +% TODO: Zitate für diesen Absatz benötigt? +% Compliant manipulation und Reflexe als Mittel zur Erreichung eines sicheren Verhaltens +Compliant manipulation and appropriate reflex reactions to collisions have been an active research field over the last decades, opening the door to safer and more autonomous robot applications \cite{Haddadin2014,BicchiTon2004,DeLucaFla2012a}. +Human-friendly robot behavior has to be ensured not only for industrial robotic co-workers, which are typically serial chain manipulators, but also in future healthcare, rescue or even personal robotics applications, where mobility is essential. +At the same time, compliance control and reflexive contact handling are sought to be essential features in damage protection for systems as the Boston Dynamics Atlas hydraulic robot \cite{2014:JFR-ViGIR-DRC-Trials,ConnerKohRomStu2015}. + +% Möglichkeiten zur Umsetzung der Nachgiebigkeit: Inhärent oder aktiv geregelt. +Essentially, softness is either achieved by an inherently compliant structure \cite{PrattWil1995,BicchiTon2002} and/or active compliance control via high-fidelity joint torque feedback. +% Impedanzregelung als eine Möglichkeit, nachgiebiges Verhalten zu erreichen +One of the most prominent control concepts to implement compliance is impedance control. +It was introduced in \cite{Hogan1985} and extended to flexible joint robots e.g. in \cite{Albu-SchaefferOttHir2007,Ott2008}. +% Bezug Elektromechanische Roboter +However, up to now the schemes were mainly applied to electromechanically driven robots. +% Bezug Hydraulische Roboter und andere Regelungsmethoden als Impedanzregelung (Beispiele nur für Ganzkörper- oder Ganzarmkonzepte. Keine einzelnen Gelenke, das ist mehr Fokus des Humanoids-Beitrages) +For hydraulic humanoid robots, basic compliance control schemes were implemented on the SARCOS humanoid, focussing on balancing and contact Jacobians \cite{Hyon2007SARCOScompliance}, on constraint handling via quadratic programming \cite{HerzogRigGriPas2014} or with LQR feedback gain optimization \cite{MasonRigSch2014}. +The concept of admittance control (position-based impedance control) has been implemented on the Atlas robot in \cite{Lee2014atlasadmittance}. +% TODO: Vorteil des Impedanzreglers gegen diese Konzepte. +% Impedance Control can be seen as a generalized low-level concept to ensure compliance and can be combined with other high-level concepts. + +%% Sicheres Verhalten auch durch Reflexe (zusätzlich zur Regelung) +% Voraussetzungen für Reflexverhalten +Activating reflex reactions as a response to potentially unwanted environmental contacts is another main pillar in safe and sensitive robot interaction. +This requires the ability to discriminate internal from external torques based on accurate dynamics models together with proprioceptive position and torque measurements. +% Möglichkeit zur Umsetzung: Beobachter +Disturbance observers are a common technique in robotics to handle either modeling inaccuracies \cite{Oh1999,NikoobinHag2008} or to recognize unexpected events such as collisions. +% Beispiele zur Anwendung +\cite{LucaMat2005} used a momentum-based disturbance observer for \textbf{collision detection}, \textbf{isolation}, and \textbf{estimation}, including validation with a 2-Degree-of-Freedom (DoF) simulation. +These results were extended to the flexible manipulator case and experimentally validated with the DLR lightweight robot arm III~\cite{DeLucaAlbHadHir2006}, using the concepts of \emph{total link energy} and \emph{generalized momentum}. +An analysis of different terms in the error dynamics and an approach for velocity-based variable collision thresholds were presented in \cite{SotoudehnejadKer2014}. +An estimation of the external end-effector wrenches based on observed disturbance torques was used in \cite{OttHenLee2013} to enhance a model predictive balancing controller on the humanoid robot TORO. + +% Erweiterungen zu Kollisionserkennung: Einordnung der Kollisionen +In \cite{GolzOseHad2015} the subsequent \textbf{collision classification} problem was approached by applying state-of-the-art machine learning techniques to learning the collision torque profiles of different collision types, including features based on collision frequencies, amplitudes or other physically motivated aspects. +A summary of collision handling can be found in \cite{Haddadin2014}. +The focus of these works was on electromechanically actuated robots equipped with link-side joint torque sensing. + +% Anwendungsbeispiel Hydraulische Roboter +A collision detection for the 6-DoF hydraulic robot arm \emph{Maestro} with low-pass filtered model error was evaluated in \cite{BidardLibArhMea2005}, focussing on hydraulic friction effects. +In \cite{jung2012collision} the authors applied a disturbance observer for collision detection that contains a bandpass filter, making use of specifically identified collision frequencies, to a 3-DoF hydraulic robot arm with joint torque sensors. + +% Unterschiede elektromechanisch, hydraulisch, Herausforderungen +In contrast to their electromechanical counterpart, and due to the fact that no high gearing with according friction losses is required, commonly used hydraulic actuators do not have link-side torque measurements. +In fact, actuator forces can be estimated via the chamber pressures. +However, link-side friction, e.g. induced by the chamber seals, can be rather high indeed. +This in turn makes direct high-fidelity joint torque control, and thus also any other soft-robotics control concept, difficult to realize. + +%% Unser Beitrag +% Identifikation, Ãœberleitung von Herausforderungen bei Hydraulik zu unserem Ansatz (getrennte Identifikation) +In the present work, we approach this problem by identifying friction and the required dynamic parameters for our model-based control concept with a two-step method. +In the first step, a friction model including Coulomb and viscous friction is identified. +In the second step, the results of the first step are used to reduce the number of parameters for the identification of the dynamics model. + +% Störgrößenbeobachter zur Modellfehlerkompensation: Vorteile, Nachteile, Ausgleich der Nachteile +In order to compensate for model errors when using impedance control, a generalized momentum-based disturbance observer is used \cite{SpVdTh14}. +As a drawback compliance is lost, since external forces cannot be systematically discriminated from the disturbance torques and are thus compensated by the observer as well. +To overcome this problem for end-effector contacts +we use a wrist force/torque sensor to calculate the external joint torques and exclude them from the disturbance torque calculation. +% Störgrößenbeobachter zur Schätzung externer Kräfte: Erweiterungen +Finally, an identified friction model is part of the control scheme to further reduce the observed disturbances. + +% Zusammenfassung unseres Beitrages +The contributions of this paper are +\begin{enumerate} +\item the extension of momentum-based collision handling by considering effects such as friction and wrist force/torque measurements, % methodische Erweiterung der Kollisionserkennung +\item the experimental validation of disturbance observer-enhanced collision detection and reaction schemes to the hydraulic part of the 7-DoF Atlas robot arms, +\item simulative results of a disturbance observer compensation concept based on wrist force/torque measurement increasing the impedance controller precision and keeping the end-effector compliance simultaneously, and +\item a two-step friction and extended rigid body dynamics identification method applied to a serial chain robot with both hydraulic and electromechanic actuators. +\end{enumerate} +% Aufbau des Artikels +The paper is organized as follows. +Section~\ref{sec:advance} adapts our identification and control concepts from \cite{SpVdTh14} and compares the results to the previous approach. +Section~\ref{sec:CollDet} shows experimental results for collision detection and reaction with the Atlas robot. +Furthermore, the concept of regaining compliance when using disturbance compensation from \cite{Oh1999} for our controller implementation is explained. +Section~\ref{sec:conclusion} concludes the paper. + diff --git a/paper/sec_colldet.tex b/paper/sec_colldet.tex new file mode 100644 index 0000000..8d22921 --- /dev/null +++ b/paper/sec_colldet.tex @@ -0,0 +1,92 @@ +% !TEX root = atlas_iros_16.tex +%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%% +\section{\large Collision Detection} +\label{sec:CollDet} +% +In the following experiments (Sec.~\ref{sec:CollDet_EE} and \ref{sec:CollDet_Link}), we used the collision handling (\ref{eqn:CollDet}) and (\ref{eqn:CollReact}) to detect collisions with the Atlas robot with a disturbance joint torque threshold $\bm{\zeta}$ of $11$~Nm for each joint. +A lower threshold frequently leads to false alarms due to remaining modeling errors (see Fig.~\ref{fig:ident_torque_compare}) and the large friction effects (see Fig.~\ref{fig:ident_friction_char}). +Our model is not able to reliably remove the static friction torque from the observer ($\kappa_{\mathrm{f}}=1$ in (\ref{eqn:observer_settings})) due to the indeterminate friction state for low velocities \cite{BidardLibArhMea2005}. +The friction compensation in (\ref{eqn:controller}) currently leads to unwanted oscillations indicating closed-loop stability problems originating in the velocity feedback, as described in \cite{ConnerKohRomStu2015}. +Therefore, this feature is disabled in the experiments with $\kappa_{\mathrm{f}}=0$. +However, it is possible to reliably detect soft collisions at moderate velocity (100~mm/s) in adequate time with the Atlas system. +For the collision detection and reaction experiments, the disturbance compensation in (\ref{eqn:controller}) was disabled ($\kappa_\varepsilon=0$). +The first joint was selected for evaluation of the experiments, since the collision is detected at this joint first. The other axes show qualitatively the same behavior. + +\subsection{End-effector Collision} +\label{sec:CollDet_EE} +% +\begin{figure} +\begin{subfigure}{.24\textwidth} + \centering + \includegraphics[trim=550 250 350 100,clip,width=.98\linewidth]{figures/CollDetCinderblock/ImpCtrlv5_E057_R04_impCtrl_K300_wall_colldet_move_away_021.jpg} + \caption{Enabled (``Coll.Det'' in Fig.~\ref{fig:CinderCollisionSummary})} + \label{fig:CinderColl_zerog} +\end{subfigure}% +\begin{subfigure}{.24\textwidth} + \centering + \includegraphics[trim=550 250 350 100,clip,width=.98\linewidth]{figures/CollDetCinderblock/ImpCtrlv5_E057_R05_impCtrl_K300_wall_nocolldet_collision_022.jpg} + \caption{Disabled (``Stiff'' in Fig.~\ref{fig:CinderCollisionSummary})} + \label{fig:CinderColl_push} +\end{subfigure} +\caption{Result after the end-effector collision with and without detection and reaction (snapshot at $t\approx1.5$~s of Fig.~\ref{fig:CinderCollisionSummary})} +\label{fig:CinderCollPictures} +\SkipBeforeText +\end{figure} +% +\begin{figure} +\centering +\parbox{\columnwidth}{ +\includegraphics{figures/CollDetCinderblock/Collision_Summary_Cinderblock.pdf} +} +\vspace*{-1ex} +\caption{Absolute external force $|\bm{f}_\mathrm{ext,EE}|$, observed disturbance torque $\hat{\tau}_{\varepsilon,1}$ and joint position $q_1$ are depicted for the cinderblock collision experiment (see also Fig.~\ref{fig:CinderCollPictures}). +For the ``Stiff'' and ``Coll.Det'' mode, $k_i=300$~Nm/rad and for the ``Compliant'' mode $k_i=100$~Nm/rad were chosen.} +\label{fig:CinderCollisionSummary} +\SkipBeforeText +\end{figure} +% +The first experiment lets the end-effector collide with a styrofoam-protected cinderblock, see Fig.~\ref{fig:CinderCollPictures}. +The protection aimed to protect the robot from damage and has no major influence on the collision detection. +The measured data during the three runs with different settings is depicted in Fig.~\ref{fig:CinderCollisionSummary}. +Using a rather stiff joint impedance controller with joint-wise $k_i=300$~Nm/rad (``Stiff'') and deactivated collision handling leads to pushing the cinderblock away and tipping it over till reaching the final goal position, see Fig.~\ref{fig:CinderCollPictures}~(b) and Fig.~\ref{fig:CinderCollisionSummary}. +Reducing the joint stiffness to \mbox{$k_i=100$~Nm/rad} (``Compliant'') leads to smaller resulting quasi-static contact forces, while the positioning error increases, see Fig.~\ref{fig:CinderCollisionSummary}. + +Using the collision detection and reaction (``Col. Det.''), the arm drifts away after the collision has been detected and the contact force decays to zero, see Fig.~\ref{fig:CinderCollPictures}~(a) and Fig.~\ref{fig:CinderCollisionSummary}. +The collision in Fig.~\ref{fig:CinderCollisionSummary} is detected at $t=1.1$~s, when the disturbance torque line crosses the detection threshold $\bm{\zeta}$. +At this point in time, the maximum contact force of about 69~N is already reached, which is caused by the relatively slow dynamics of the observer (\mbox{$k_{\mathrm{o},i}=5~\mathrm{s}^{-1}$}). +A larger gain would allow an earlier detection with less reaction force. +Using retract reflexes would allow further reduction of contact forces. +In turn, larger observer gain causes vibrations when being used as disturbance compensation. +To overcome this issue, two observers could be used in parallel: a slower one for compensation and a faster one for collision detection. + +\subsection{Link Collision} +\label{sec:CollDet_Link} +% +\begin{figure} +\centering +\parbox{\columnwidth}{ +% \includegraphics[trim=550 50 350 340,clip,width=\linewidth]{figures/CollDetStick/GOPR2201_ImpCtrlv5_E055_part4_t036.jpg} +\input{./figures/CollDetStick/GOPR2201_ImpCtrlv5_E055_part4_t036_bearb.pdf_tex} +} +\caption{Scene during the collision from Fig.~\ref{fig:StickCollisionSummary} at $t\approx5.5$~s.} +\label{fig:StickCollisionPhoto} +\SkipBeforePicture +\end{figure} +% +\begin{figure} +\centering +\parbox{\columnwidth}{ +\includegraphics{figures/CollDetStick/CollDetStickIROS.pdf} +} +\vspace*{-1ex} +\caption{Joint position $q_1$, model torque $\tau_{\mathrm{mdl},1}$, estimated disturbance torque $\hat{\tau}_{\varepsilon,1}$ and motor-side joint torque $\tau_{\mathrm{m},1}$ during link collision, see Fig.~\ref{fig:StickCollisionPhoto}.} +\label{fig:StickCollisionSummary} +\SkipBeforeText +\end{figure} +% +The second experiment shows that collisions at the proximal links and not only at the end-effector are detected as well. +The arm was pushed at the elbow with a cardboard stick against the moving direction during a joint trajectory, see Fig.~\ref{fig:StickCollisionPhoto} (in the depicted situation, the elbow was moving to the right). +The movement speed was $\approx50~\mathrm{mm/s}$ at the collision location. +Figure~\ref{fig:StickCollisionSummary} depicts the measurement data. The collision at link $4$ starts at $t\approx5.5$~s, which one can see from the high motor torque in joint 1. +The detection threshold is reached at $t\approx5.6$~s, leading to the halt in gravity compensation mode. + diff --git a/paper/sec_compliance_obs.tex b/paper/sec_compliance_obs.tex new file mode 100644 index 0000000..4cc0b47 --- /dev/null +++ b/paper/sec_compliance_obs.tex @@ -0,0 +1,103 @@ +% !TEX root = atlas_iros_16.tex +%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%% +\subsection{Compliance Loss Compensation} +\label{sec:comp_obs} + +\subsubsection{Loss of Compliance with Disturbance Compensation} +\label{sec:comp_obs_loss} +% +\begin{figure} +\centering +\includegraphics[]{./figures/ObserverStiff/ObsFeedthroughStiff_compare.pdf} +\caption{Position error $\Delta x$ and measured Cartesian external force $f_x$ are compared for two experiments with enabled ($\kappa_{\varepsilon}=1$) and disabled ($\kappa_{\varepsilon}=0$) disturbance compensation. +The end-effector was pushed manually and held at a certain displacement.} +\label{fig:stiff_observer_feedthrough} +\SkipBeforePicture +\end{figure} +% +The increased stiffness of the system, when using the disturbance compensation ($\kappa_{\varepsilon}=1$) was experimentally verified. For this, the robot end-effector was pushed with and without activated disturbance compensation, see Fig.~\ref{fig:stiff_observer_feedthrough}. +% Prozentuale Aussagen zu Kraft, Positionsfehler und Steifigkeit stammen aus ObserverFeedthroughStiff_Format.m +With enabled disturbance compensation the applied force was about $93$\% larger than without disturbance compensation (Fig.~\ref{fig:stiff_observer_feedthrough}~a) while the arm was only pushed back $67$\% in position (Fig.~\ref{fig:stiff_observer_feedthrough}~b). +This increased stiffness of about $187$\% is limited by the cutoff value for the estimated disturbance torque of $30$~Nm for safety reasons, as the observer was tuned to be near the (unknown) stability limit to ensure the fastest possible convergence. +However, with $\bm{K}_\mathrm{o}$ as chosen above, instabilities could not be observed during the experiments. + +\subsubsection{Regaining Compliance with Force/Torque Sensing} +\label{sec:comp_obs_regain} +% Bild erstellt mit atlas_joint_impctrl_sqrt_damping_test_extforce_comp.m +\begin{figure} +\centering +\parbox{\columnwidth}{ +\includegraphics[width=\linewidth]{simulations/SimExp_ObsExtForce.pdf} +} +\vspace*{-1ex} +\caption{Simulation results: An external force step of 50~N is applied normal to the end-effector at $t=0.5~\mathrm{s}$ and released at $t=3.5~\mathrm{s}$. +Joint position $q_1$, external joint torque $\tau_{\mathrm{ext,1}}$, and observed disturbance torque $\hat{\tau}_{\varepsilon,1}$ are plotted for disabled disturbance compensation DC ($\kappa_\varepsilon=0$), DC without EFC ($\kappa_\mathrm{ext}=0$) and DC with EFC ($\kappa_\mathrm{ext}=1$).} +\label{fig:DistTorque} +\SkipBeforeText +\end{figure} +% +Since the wrist wrench sensor of the real system was not yet fully operational, the ability to eliminate external forces from the disturbance observer via (\ref{eqn:regainComp}) was validated in simulation. +The continuous time forward dynamics derived from (\ref{eqn:invdyn}) of the arm was implemented with viscous and Coulomb friction and parameters from Table~\ref{tab:errors_tracking_left}. +The observer gain was chosen to be uniformly $k_{\mathrm{o},i}=10~\mathrm{s}^{-1}$, stiffness $k_i=150~\mathrm{Nm/rad}$ and modal damping $d_{\xi,i}=0.3$. +The Controller (\ref{eqn:controller}) was implemented with model errors and sensor noise $\bm{\delta}$. +The model errors were generated with uniformly distributed pseudo random numbers between $\pm 10\%$ as a scaling factor to all masses, inertias, center of mass coordinates and friction coefficients. +The sensor noise was (component-wise) uniformly distributed between \mbox{$\pm 3.4\cdot10^{-4}~\mathrm{rad}$} for joint position, \mbox{$\pm 5.5\cdot10^{-2}~\mathrm{rad/s}$} for velocity, \mbox{$\pm 2\cdot10^{-4}~\mathrm{m/s^2}$} for the gravity vector, \mbox{$\pm 7.3\cdot10^{-2}~\mathrm{Nm}$} for the joint torque and \mbox{$\pm 2.3~\mathrm{N}$} for the external forces, respectively. +These values were obtained from the measurement data of the hydraulic joints during the starting phase of the experiment in Fig.~\ref{fig:stiff_observer_feedthrough}. + +For this setup, a step change of the external force acting on the end-effector was performed with different observer settings. +The results are shown in Fig.~\ref{fig:DistTorque}. +For $\kappa_\varepsilon=0$, i.e. applying no disturbance compensation, compliant behavior is achieved. Using the disturbance compensation without EFC ($\kappa_\mathrm{ext}=0$) leads to a very stiff response according to (\ref{eqn:compLoss}), with $\hat{\tau}_{\varepsilon,1}$ converging to $\tau_{\mathrm{ext,1}}$. +When selecting $\kappa_\mathrm{ext}=1$, the observer torque remains near zero, as it only observes the model errors. +In addition, the compliance is the same as without disturbance compensation, i.e. as expected from (\ref{eqn:regainComp}). +Therefore, the simulation results imply, that this approach allows to compensate for model errors, while correctly reacting compliant to end-effector contacts at the same time. +% +\begin{figure} +\centering +\parbox{\columnwidth}{ +\includegraphics[width=\linewidth]{simulations/SimExp_MdlNoiseExtForce.pdf} +} +\caption{Simulation results: The experiment of Fig.~\ref{fig:DistTorque} was done multiple times with different model errors. +The normalized mean squared integrated error is plotted over the maximum parameter noise level. +The results for $\kappa_\mathrm{ext}=0$ and $\kappa_\mathrm{ext}=1$ are shown in the top and the bottom plot respectively.} +\label{fig:MdlNoise} +\SkipBeforePicture +\vspace*{-1ex} +\end{figure} +% +\begin{figure} +\centering +\parbox{\columnwidth}{ +\includegraphics[width=\linewidth]{simulations/SimExp_MesNoiseExtForce.pdf} +} +\caption{Simulation results: The experiment from Fig.~\ref{fig:DistTorque} was done multiple times with different measurement errors. +The normalized mean squared error is depicted over the scaling factor applied to all measurement noise levels from the simulation of Fig.~\ref{fig:DistTorque}.} +\label{fig:MesNoise} +\SkipBeforeText +\end{figure} +% +\subsubsection{Robustness of Disturbance Compensation with EFC against Model Errors} +Further simulations (as in Fig.~\ref{fig:DistTorque}) were performed to investigate the robustness of the above method. +First, the influence of model errors is investigated. +The model errors were introduced by scaling the masses, the center of gravity positions of the links, the link inertias and the friction parameters by uniformly distributed random factors. +The normalized mean squared integrated error (MSIE) +\begin{equation} +\mathrm{MSIE}=\frac{1}{n_{\mathrm{j}}T_\mathrm{f}}\sum_{i=1}^{n_{\mathrm{j}}}\int_0^{T_\mathrm{f}} \left(q_i(t)-q_i^{\mathrm{ref}}(t)\right)^2\mathrm{d}t +\end{equation} +is depicted over the maximum noise factor for limits from 1\% to 30\% in Fig.~\ref{fig:MdlNoise} for the controller with and without EFC. +The norm $\|\mathrm{MSIE}\|=\mathrm{MSIE}/\max(\mathrm{MSIE})$ is calculated for Fig.~\ref{fig:MdlNoise} and Fig.~\ref{fig:MesNoise} separately. +The compliant behavior of the controller without disturbance compensation and without model errors or measurement noise was selected as reference $\bm{q}^\mathrm{ref}$. +In order to gain comparable results, the model errors were the same in both plots. +It can be seen that the influence of the model errors is similar for both cases and the results with EFC remain close to the reference case. The order of magnitude between the results with and without EFC stays the same for all model error levels. +%Therefore, the deviation from the desired compliant behavior increases slightly +Even with an identification error of up to $30\%$, the controller can cope with the resulting model errors for this quasi-static movement. + +\subsubsection{Robustness of Disturbance Compensation with EFC against Sensor Noise} + +Figure~\ref{fig:MesNoise} depicts the influence of measurement noise on controller performance. +The measurement noise levels from above were scaled by factors of 1 to 30 and the MSIE is compared for the controller with ($\kappa_\mathrm{ext}=1$) and without EFC ($\kappa_\mathrm{ext}=0$). +It can be seen that for noise levels amplified up to 10 times, the deviation from the reference behavior does not change noticeably in either case, i.e. the compliance rendering of the controller remains the same despite increased noise. + +For larger measurement noise the deviation from the desired behavior becomes smaller for $\kappa_\mathrm{ext}=0$ since the limitation of the observer output prevents the compensation of external forces for high measurement noise. +This effect even leads to a behavior closer to the desired one with \mbox{$\kappa_\mathrm{ext}=0$} instead of \mbox{$\kappa_\mathrm{ext}=1$} for very high measurement noise (at least 25 times as high as observed in the experiments). +In term, Fig.~\ref{fig:MesNoise} implies that the controller is able to cope with measurement noise about 10 times higher than found in our experimental setup. +To cope with larger measurement noise, one would have to use filtering or increase the output limit of the observer. \ No newline at end of file diff --git a/paper/sec_ident.tex b/paper/sec_ident.tex new file mode 100644 index 0000000..52aeb4c --- /dev/null +++ b/paper/sec_ident.tex @@ -0,0 +1,148 @@ +% !TEX root = atlas_iros_16.tex +\subsection{Rigid Body and Friction Identification} +\label{sec:advance_ident} +% + +% +In our previous work \cite{SpVdTh14} both, rigid body model and friction were simultaneously identified as the parameter vector $\bm{\beta}_{\mathrm{I}}$. +The results still contained a relevant error regarding model fitting and plausibility of the friction parameters compared to single-joint experiments. +Therefore, in this work a sequential procedure was applied, where pre-identified Coulomb and viscous friction parameters $\bm{d}_\mathrm{v,p}$, $\bm{\mu}_\mathrm{C,p}$ were included into the identification procedure in order to reduce the parameter space from $59$ to $45$ +unknowns\footnote{ +The 70 dynamic parameters (10 per joint) are reduced to $n_\mathrm{b}=45$ in the minimal regressor form. +Additionally, the model has $2n_\mathrm{j}=14$ friction parameters (2 per joint) resulting in $n_\beta=59$ parameters overall, see \cite{SpVdTh14}.}. +\subsubsection{Identification Model and Approach} +% +For identification purposes the robot dynamics (\ref{eqn:invdyn}), including a suitable friction model, can be written in regressor form as +\begin{equation} +\bm{\tau}_{\mathrm{m}} = \bm{\Phi} \bm{\beta} - \bm{\tau}_{\mathrm{ext}}, +\label{regressor} +\end{equation} +where the regressor matrix $\bm{\Phi}$ contains distinct base and friction parameter related columns $\bm{\Phi} = \begin{pmatrix} \bm{\Phi}_\mathrm{b} & \bm{\Phi}_\mathrm{f} \end{pmatrix}$. +The elements of the parameter vector $\bm{\beta} = \begin{pmatrix} \bm{\beta}_\mathrm{b} \ \bm{d}_\mathrm{v} \ \bm{\mu}_\mathrm{c} \end{pmatrix}^{\mathrm{T}}$ denote the base, viscous friction and Coulomb friction parameter vectors. +The regressor matrix of the friction model can be allocated as +\begin{equation} +\bm{\Phi}_\mathrm{f}(\dot{\bm{q}}) = +\begin{pmatrix} +\mathrm{diag}\{\dot{\bm{q}}\}& +\mathrm{diag}\{\mathrm{sgn}(\dot{\bm{q}})\}\\ +\end{pmatrix}. +\label{friction_mdl} +\end{equation} +Assuming $\bm{\tau}_{\mathrm{ext}} = \bm{0}$ during identification procedure, the influence of (\ref{friction_mdl}) can be incorporated by subtracting (\ref{friction_mdl}) from both sides in (\ref{regressor}). +This leads to the friction-corrected motor torque +\begin{align} +\bm{\tau}_{\mathrm{m},\mathrm {f}} &= +\bm{\tau}_{\mathrm{m}} - \bm{\Phi}_{\mathrm{f}} ( \dot{\bm{q}})(\bm{d}_{\mathrm{v}}, \bm{\mu}_{\mathrm{c}})^{\mathrm{T}}\\ +&= +\bm{\Phi} \bm{\beta} - \bm{\Phi}_{\mathrm{f}} ( \dot{\bm{q}})(\bm{d}_{\mathrm{v}}, \bm{\mu}_{\mathrm{c}})^{\mathrm{T}}=\bm{\Phi}_\mathrm{b}\bm{\beta}_\mathrm{b}. +\end{align} +%TODO QUELLE +%The influence of friction to motor torque $\bm{\tau}_{\mathrm{m}}$ can now be corrected by $\bm{\tau}_{\mathrm{m},\mathrm {f}} = \bm{\tau}_{\mathrm{m}} - \bm{\Phi}_{\mathrm{f}} ( \dot{\bm{q}})(\bm{d}_{\mathrm{v}}, \bm{\mu}_{\mathrm{c}})^{\mathrm{T}}$ using prior knowledge of friction parameters $\bm{d}_\mathrm{v,p}$ and $\bm{\mu}_\mathrm{c,p}$. +Identifying the numerical values of $\bm{\beta}_{\mathrm{b}}$ is done using a Moore-Penrose pseudoinverse +% +\begin{equation} +\hat{\bm{\beta}}_{\mathrm{b}} = {\left( \bm{F}^{\mathrm{T}} \bm{\Sigma}^{-1} \bm{F} \right)}^{-1} \bm{F}^{\mathrm{T}} \bm{\Sigma}^{-1}\bm{b} +\label{MoorePenrose} +\end{equation} +% +filled with experimentally gained optimized Fourier-based joint angle trajectories of duration $t_{\mathrm{f}}$ \cite{park2006fourier}. +The information matrix $\bm{F}$ and the measurement vector $\bm{b}$ are defined as +% +\begin{equation} +\bm{F} = \begin{pmatrix} +\bm{\Phi}_{\mathrm{b}}\left( \bm{q}(t_1),\dot{\bm{q}}(t_1),\ddot{\bm{q}}(t_1) \right) \\ +\bm{\Phi}_{\mathrm{b}}\left( \bm{q}(t_2),\dot{\bm{q}}(t_2),\ddot{\bm{q}}(t_2) \right) \\ +\vdots \\ +\bm{\Phi}_{\mathrm{b}}(\bm{q}(t_{\mathrm{f}}),\dot{\bm{q}}(t_{\mathrm{f}}),\ddot{\bm{q}}(t_{\mathrm{f}}))\end{pmatrix},~~ +\bm{b} = \begin{pmatrix} +\bm{\tau}_\mathrm{m,f}(t_1) \\ +\bm{\tau}_\mathrm{m,f}(t_2) \\ +\vdots \\ +\bm{\tau}_\mathrm{m,f}(t_{\mathrm{f}}) +\end{pmatrix}, +\end{equation} +% +where $\bm{\tau}_\mathrm{m,f}(t_i)$ are friction-corrected torque measurements using prior knowledge of friction parameters $\bm{d}_\mathrm{v,p}$ and $\bm{\mu}_\mathrm{c,p}$. +The covariance matrix $\bm{\Sigma}$ is composed of actuator noise variances. +Torque measurements $\bm{\tau}_{\mathrm{m}}$ are determined based on chamber pressures for the hydraulic joints and electric currents for the electromechanic joints. +Gear ratios and motor constants are provided by the manufacturer. +The joint angle $\bm{q}$ is measured by position encoders. +The resulting parameter vector $\bm{\beta}_{\mathrm{II}}$ of the sequential method, which is used to parameterize (\ref{regressor}), consists of the elements $\bm{\beta}_{\mathrm{II}} = \begin{pmatrix} \bm{\beta}_\mathrm{b} \ \bm{d}_\mathrm{v,p} \ \bm{\mu}_\mathrm{c,p} \end{pmatrix}^{\mathrm{T}}$. + +\subsubsection{Single Joint Friction Identification} + +The identification of joint friction parameters $\bm{d}_{\mathrm{v,p}}$ and $\bm{\mu}_{\mathrm{c,p}}$ is done by running a set of different constant velocities $\dot{q}_i$ in positive and negative direction and measuring the resulting torque $\bm{\tau}_{\mathrm{m}}$ for every joint. +Mean velocity and torque are calculated using intervals of constant speed. +Figure~\ref{fig:ident_friction_char} depicts the joint friction characteristics for the hydraulic joints which show significant Coulomb and viscous friction. + +% figure generated with MATLAB in +% drc_paper/Atlas_IROS_16/figures/Identification/FrictionCharacteristics_resultfigures_IROS.m +\begin{figure} +\centering +\includegraphics[]{./figures/Identification/FrictionCharacteristics_left} +\caption{Viscous and Coulomb friction for the hydraulic joints of the left arm. Each marker represents the mean value of one constant velocity single joint experiment, see Fig.~\ref{fig:velocity_tracking_friction}. Dynamics effects from $\bm{\Phi}_{\mathrm{b}}$ were removed and calculated with dynamics parameters $\hat{\bm{\beta}}_{\mathrm{b,I}}$ from the combined identification approach \cite{SpVdTh14} and with assumed fixed and upright upper body orientation.} +\label{fig:ident_friction_char} +\SkipBeforePicture +\end{figure} + +The identification results could be further improved by using the impedance controller to execute the identification trajectory, as it shows significantly improved velocity tracking compared to an extensively tuned PD controller implemented by the manufacturer, see Fig.~\ref{fig:velocity_tracking_friction}. +The identified friction parameters are given in Table~\ref{tab:errors_tracking_left}. + +% +% figure generated with MATLAB in +%./figures/Identification/ConstVel_AssemblyFigure_middle_plot.m +\begin{figure} +\centering +\includegraphics[width=\linewidth]{./figures/Identification/SI_E036_Joint4_ConstVel_Summary_medium_speed} +\caption{Single joint friction experiment exemplified for joint 4 reveals improved velocity tracking of the impedance controller compared to PD position control with controller gains from \cite{2014:JFR-ViGIR-DRC-Trials, ConnerKohRomStu2015}.} +\label{fig:velocity_tracking_friction} +\SkipBeforeText +\end{figure} + +% MSE-Werte werden auch in atlas5_plot_torque_ident_MPV_left_DRC_IROS.m ausgegeben. +% +\setlength\tabcolsep{5pt} +\begin{table} + \caption{Mean square errors (MSE) for arm identification using different base parameter vectors $\hat{\bm{\beta}}_{\mathrm{I}}$, $\hat{\bm{\beta}}_{\mathrm{II}}$ and data from Fig.~\ref{fig:ident_torque_compare} and identified friction parameters from single-joint experiments} + \begin{center} + \begin{tabular}{c|c|c|c|c} +joint & $\mathrm{MSE}(\bm{\tau}_{\mathrm{m}}-\bm{\tau}_{\mathrm{I}})$ & $\mathrm{MSE}(\bm{\tau}_{\mathrm{m}}-\bm{\tau}_{\mathrm{II}})$ & $\hat{{\mu}}_{\mathrm{C,p},i}$ & $\hat{{d}}_{\mathrm{v,p},i}$ \\ + & [(Nm)$^2$] & [(Nm)$^2$] & [Nm] & [Nms/rad] \\ +\hline +1 (shz) & 97.04 & 13.03 & 2.0 & 1.3 \\ +2 (shx) & 52.64 & 20.78 & 6.7 & 0.9 \\ +3 (ely) & 22.58 & 16.62 & 10.3 & 1.6 \\ +4 (elx) & 25.22 & 18.66 & 6.1 & 2.7 \\ +\hline +5 (wry) & 2.82 & 6.50 & 0.1 & 0.5 \\ +6 (wrx) & 8.11 & 3.46 & 0.1 & 0.2 \\ +7 (wry2) & 0.26 & 18.28 & 3.1 & 0.2 \\ + \end{tabular} + \end{center} +\label{tab:errors_tracking_left} +\SkipBeforePicture +\end{table} +\setlength\tabcolsep{6pt} + +\subsubsection{Results of the Sequential Identification} + +A comparison between the base parameter vector $\hat{\bm{\beta}}_{\mathrm{I}} = \begin{pmatrix} \hat{\bm{\beta}}_\mathrm{b,I} \ \hat{\bm{d}}_\mathrm{v} \ \hat{\bm{\mu}}_\mathrm{C} \end{pmatrix}^{\mathrm{T}}$, where friction was identified as part of the combined least squares optimization \cite{SpVdTh14}, and the base parameter vector $\hat{\bm{\beta}}_{\mathrm{II}}$ of the sequential method can be found in Fig.~\ref{fig:ident_torque_compare}. +Good model consistency is indicated by low distance between model and measurement. +To avoid the problem of overfitting, the trajectory of this experiment was different from the one used for identification. +When using the parameter vector $\hat{\bm{\beta}}_{\mathrm{II}}$, significantly improved results could be achieved in the hydraulic joints, indicated by the lower mean square error between measured and modeled torques in Table~\ref{tab:errors_tracking_left}. + +% Bildquelle: atlas5_plot_torque_ident_MPV_left_DRC_IROS.m +\begin{figure} +\centering +\includegraphics{./figures/Identification/atlas5_plot_torque_ident_MPV_left_IROS} +\caption{Measured ($\bm{\tau}_\mathrm{m}$) and simulated torques of the left arm joints comparing the sequential method $\bm{\tau}_{\mathrm{\mathrm{II}}}$ with the combined method $\bm{\tau}_{\mathrm{\mathrm{I}}}$.} +\label{fig:ident_torque_compare} +\SkipBeforeText +\end{figure} + +As already mentioned in \cite{SpVdTh14}, the electromechanic wrist joints (wry, wrx, wry2) do not seem to be identifiable for the Atlas system without working joint torque sensors. +Although friction was identified in single axis experiments, the predicted +torques have essentially no correlation with the measured torques. +Presumably, this is due to the current-based torque measurement on actuator side, which decreases the quality of the measured information significantly. + +In the next section, the results for the experimental collision handling performance with the Atlas system are outlined. \ No newline at end of file diff --git a/paper/sec_model.tex b/paper/sec_model.tex new file mode 100644 index 0000000..71f8ece --- /dev/null +++ b/paper/sec_model.tex @@ -0,0 +1,281 @@ +% !TEX root = atlas_iros_16.tex +%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%% +\section{\large Modeling and Identification} +\label{sec:advance} + +In this section we shortly review the system modeling and enhanced impedance controller approach (\ref{sec:advance_controller}), modifications to the momentum-based disturbance observer to include wrist wrench measurements (\ref{sec:advance_observer}), compensation of modeling errors and collision handling (\ref{sec:friction_comp_and_collDet}), and an identification scheme that iteratively estimates friction characteristics and rigid body parameters (\ref{sec:advance_ident}). + +\subsection{System Model and Joint Impedance Controller} +\label{sec:advance_controller} +This work focuses on the 7R type serial chain arms of the Boston Dynamics humanoid robot Atlas, see Fig.~\ref{fig:StickCollisionPhoto}. +The arms employ a hybrid actuation concept where the first four joints (shz, shx, ely, elx) are hydraulic, and the wrist joints (wry, wrx, wry2) are driven by electromechanical gear drives. +We assume the standard fixed-base rigid joint arm model +\begin{equation} +\bm{M(\bm{q})}\ddot{\bm{q}}+\bm{C}(\bm{q},\dot{\bm{q}})\dot{\bm{q}}+\bm{g}(\bm{q})=\bm{\tau}_\mathrm{m}-\bm{\tau}_\mathrm{f}+\bm{\tau}_\mathrm{ext} +\label{eqn:invdyn} +\end{equation} +with generalized joint position $\bm{q} \in \mathbb{R}^{n_\mathrm{j}}$ ($n_\mathrm{j}$ being the number of joints), positive definite and symmetric inertia matrix $\bm{M}(\bm{q})$, centrifugal and Coriolis matrix $\bm{C}(\bm{q}, \dot{\bm{q}})$, gravity torque vector $\bm{g}(\bm{q})$, actuator torques $\bm{\tau}_\mathrm{m}$, friction torques $\bm{\tau}_\mathrm{f}$ and external torques $\bm{\tau}_\mathrm{ext}$. +The friction torque $\bm{\tau}_\mathrm{f}$ is composed of the motor side friction $\bm{\tau}_{\mathrm{f},\theta}$ and the link side friction $\bm{\tau}_{\mathrm{f},q}$. +Both hydraulic and electromechanic actuators are considered as ideal torque sources, generating a motor torque $\bm{\tau}_\mathrm{m}$, allowing a separation of the actuator dynamics from the rigid body model. + +For soft-robotics control of the system we chose the joint impedance control torque $\bm{\tau}_\mathrm{d}$ to be +\begin{equation} +\begin{gathered} +\bm{\tau}_\mathrm{d}= +\bm{K}(\bm{q}_\mathrm{d}-\bm{q})+\bm{D}(\dot{\bm{q}}_\mathrm{d}-\dot{\bm{q}})+\hat{\bm{g}}(\bm{q}) % tau_I +\\ ++\hat{\bm{C}}(\bm{q},\dot{\bm{q}})\dot{\bm{q}} % tau_c ++\hat{\bm{M}}(\bm{q}_\mathrm{d})\ddot{\bm{q}}_\mathrm{d} % tau_ff ++\kappa_{\mathrm{f}} \hat{\bm{\tau}}_\mathrm{f}(\dot{\bm{q}}) +-\kappa_{\varepsilon} \hat{\bm{\tau}}_\mathrm{\varepsilon}(\bm{q}, \dot{\bm{q}},\bm{\tau}_\mathrm{m})\;, +\label{eqn:controller} +\end{gathered} +\end{equation} +where $\bm{q}_\mathrm{d}, \dot{\bm{q}}_\mathrm{d}, \ddot{\bm{q}}_\mathrm{d}$ are the desired position, velocity, and acceleration, respectively. The matrices $\bm{K}=\mathrm{diag}\{k_i\}$ and $\bm{D}_\xi=\mathrm{diag}\{d_{\xi,i}\}$ denote diagonal positive definite stiffness and modal damping and $\bm{D}$ the resulting positive definite damping matrix. +$\hat{\bm{g}}$ and $\hat{\bm{C}}$ are the gravity and centrifugal/Coriolis estimates. +The inertial feedforward term makes use of the estimated inertia matrix $\hat{\bm{M}}$ as a function of the desired position $\bm{q}_\mathrm{d}$. +The compensation terms $\hat{\bm{\tau}}_\mathrm{f}(\dot{\bm{q}})$ (viscous and Coulomb friction) and $\hat{\bm{\tau}}_\mathrm{\varepsilon}(\bm{q}, \dot{\bm{q}},\bm{\tau}_\mathrm{m})$ (estimated disturbance from Sec.~\ref{sec:advance_observer}) are activated via the scalars $\kappa_{\mathrm{f}}\in \{0,1\}$ and $\kappa_{\varepsilon}\in \{0,1\}$, respectively. + +Combining (\ref{eqn:invdyn}) and (\ref{eqn:controller}) leads to the closed-loop dynamics +\begin{equation} +\begin{gathered} +\bm{M(\bm{q})}\ddot{\bm{q}}-\hat{\bm{M}}(\bm{q}_\mathrm{d})\ddot{\bm{q}}_\mathrm{d} ++\bm{D}(\dot{\bm{q}}-\dot{\bm{q}}_\mathrm{d}) ++\bm{K}(\bm{q}-\bm{q}_\mathrm{d}) + \\ +=\bm{\tau}_\mathrm{ext} ++ \bm{\delta} +-\kappa_{\varepsilon} \hat{\bm{\tau}}_\mathrm{\varepsilon}, +\label{eqn:closedloop_general} +\end{gathered} +\end{equation} +where $\bm{\delta}$ denotes lumped dynamics and friction modeling errors and errors caused by sensor drift, offsets and time delays. +We assume these effects to be additive. + +\subsection{Disturbance Observer} +\label{sec:advance_observer} +% +\begin{figure} +\centering +\input{./figures/MechErsatzBSB/rigid_flexible_joint_struktur.pdf_tex} +\caption{Relevant torques acting along the mechanical structure for the rigid joint model (a) with link inertia $\bm{M}$ and the flexible joint model (b) with motor inertia $\bm{B}$ and motor position $\bm{\theta}$.} +\label{fig:rigid_flexible_joint_structure} +\SkipBeforeText +\end{figure} +% +Before introducing our observer design, let us shortly summarize the underlying problem of collision detection with typical hydraulic robots. +Figure~\ref{fig:rigid_flexible_joint_structure} emphasizes the friction torques that are relevant for rigid joint models in comparison to the flexible joint case. +The latter represents e.g. electromechanically actuated robots with elastic joints and torque sensing \cite{Ott2008}. +In the former case, the total friction $\bm{\tau}_\mathrm{f}$ and external torques $\bm{\tau}_\mathrm{ext}$ act on a single body that represents both motor and link inertia and sum up to a total disturbance torque. +Thus, except under certain modeling assumptions they cannot be separated with standard proprioceptive sensing and according observer techniques. +In the latter case, motor and link-side dynamics are coupled via the joint stiffness $\bm{K}_{\mathrm{J}}$. +Typically, this originates either from rather elastic gears such as Harmonic Drives in combination with joint torque sensors (rather high inherent stiffness $\bm{K}_{\mathrm{J}}$), or from deliberately placed spring elements as e.g. in the Series Elastic Actuation (SEA \cite{PrattWil1995}) case (rather low inherent stiffness $\bm{K}_{\mathrm{J}}$). +Since the link side friction $\bm{\tau}_{\mathrm{f},q}$ is usually low (it is mainly caused by low friction link-side bearings), it may be neglected and the link-side observer essentially estimates the true external joint torques \cite{Haddadin2014}. +Therefore, it is possible to set up two observer schemes, one for the actuator side estimating $\bm{\tau}_{\mathrm{f},\theta}$ \cite{LeTienAlbDeHir2008}, and one for the link side estimating $\bm{\tau}_\mathrm{ext}$. +Note that one can obviously set up an elastic joint model for the hydraulic case as well. +However, this would only have a similar implication if an additional joint torque sensor for decoupling would be inserted after link friction. + +To be able to distinguish between internal and external effects, we extend the momentum-based disturbance observer from \cite{DeLucaMat2003,DeLucaMat2004,Haddadin2014} to include measurements of external wrenches $\medmuskip=1.3mu +\thinmuskip=1.3mu +\thickmuskip=1.3mu +\bm{\mathcal{F}}_\mathrm{ext,EE}=\begin{pmatrix}\bm{f}_{\mathrm{ext,EE}} & \bm{m}_{\mathrm{ext,EE}}\end{pmatrix}^\mathrm{T}$ that act on the end-effector, i.e. ``after'' the sensor \cite{OttHenLee2013}. +The extended residual for end-effector contacts is then defined as +% +\begin{equation} +\medmuskip=0.5mu +\thinmuskip=0.5mu +\thickmuskip=0.5mu +\hat{\bm{\tau}}_\mathrm{\varepsilon}=\bm{K}_\mathrm{o} +\left( +\hat{\bm{M}}(\bm{q})\dot{\bm{q}} +-\int\limits_0^t + [\bm{\tau}_\mathrm{m} + -\bm{\gamma}(\bm{q},\dot{\bm{q}}) + +\hat{\bm{\tau}}_\mathrm{\varepsilon} + -\bm{\alpha}(\bm{q},\dot{\bm{q}}) + ]\mathrm{d}\tilde{t} + \right), +\label{eqn:observer} +\end{equation} +% +where $\bm{K}_\mathrm{o}=\mathrm{diag}\{k_{\mathrm{o},i}\}>\bm{0}$ is the observer gain matrix and +\begin{equation} +\medmuskip=0.05mu +\thinmuskip=0.05mu +\thickmuskip=0.05mu +\bm{\gamma}(\bm{q},\dot{\bm{q}}):= +\hat{\bm{g}}(\bm{q}) ++\hat{\bm{C}}(\bm{q},\dot{\bm{q}})\dot{\bm{q}} +-\dot{\hat{\bm{M}}}(\bm{q})\dot{\bm{q}} += +\hat{\bm{g}}(\bm{q})-\hat{\bm{C}}^\mathrm{T}(\bm{q},\dot{\bm{q}})\dot{\bm{q}}\;. +\label{eqn:gamma} +\end{equation} +Equality (\ref{eqn:gamma}) follows directly from the skew-symmetry of $\dot{\hat{\bm{M}}}(\bm{q})-2\hat{\bm{C}}(\bm{q},\dot{\bm{q}})$ \cite{DeLucaAlbHadHir2006}. +The vector $\bm{\alpha}(\bm{q},\dot{\bm{q}})$ is defined as +\begin{equation} +\begin{split} +\bm{\alpha}(\bm{q},\dot{\bm{q}}) :=& +\kappa_{\mathrm{f}}\hat{\bm{\tau}}_\mathrm{f}(\dot{\bm{q}}) -\kappa_{\mathrm{ext}}\bm{\tau}_{\mathrm{ext,EE}} \\ +=& +\kappa_{\mathrm{f}}\hat{\bm{\tau}}_\mathrm{f}(\dot{\bm{q}}) +-\kappa_{\mathrm{ext}}\bm{J}^{\mathrm{T}}(\bm{q}) \bm{\mathcal{F}}_\mathrm{ext,EE} \; . +\end{split} +\label{eqn:observer_settings} +\end{equation} +The contact wrench $\bm{\mathcal{F}}_\mathrm{ext,EE}$ is typically measured with a load-compensated force/torque sensor in the robot wrist. +The resulting external joint torques $\bm{\tau}_{\mathrm{ext,EE}}$ are obtained by the well known mapping via the end-effector Jacobian $\bm{J}(\bm{q})$. +Its feedback is activated via $\kappa_{\mathrm{ext}} \in \{0,1\}$. +Note that the components of $\bm{\mathcal{F}}_\mathrm{ext,EE}$ that are in the kernel of $\bm{J}^{\mathrm{T}}(\bm{q})$ are absorbed by the structure of the robot and are not reflected in $\bm{\tau}_{\mathrm{ext,EE}}$. + +To distinguish directly measurable joint torques originating from external wrenches at the end-effector $\bm{\tau}_{\mathrm{ext,EE}}$ from joint torques caused by external wrenches at the structure $\bm{\tau}_{\mathrm{ext,links}}$ that cannot be measured by the wrist sensor, we define the total external torque vector $\bm{\tau}_{\mathrm{ext}}$ to be +\begin{equation} +\bm{\tau}_{\mathrm{ext}} := \bm{\tau}_{\mathrm{ext,EE}} + \bm{\tau}_{\mathrm{ext,links}}. +\label{eqn:extjointtorqueseparata} +\end{equation} +The true disturbance joint torque ${\bm{\tau}}_\mathrm{\varepsilon}$ for rigid joint models consists of the joint torques from (\ref{eqn:extjointtorqueseparata}) plus the error term $\bm{\delta}$ in (\ref{eqn:closedloop_general}). +% +As derived in \cite{Haddadin2014} the observed disturbance torque, also for this extended form, converges element-wise with first order dynamics (presented in frequency domain) +\begin{equation} +\hat{\tau}_{\mathrm{\varepsilon},i}= +\frac{k_{\mathrm{o},i}}{s+k_{\mathrm{o},i}} +\left(\tau_{\mathrm{ext,EE},i}(1-\kappa_{\mathrm{ext}}) ++ \tau_{\mathrm{ext,link},i} ++ \delta_{i} +\right) +\label{eqn:disttorqueconvergence} +\end{equation} +where $1/k_{\mathrm{o},i}$ is the time constant. +% +\begin{figure} +\centering +\includegraphics{./figures/ObserverFlowChart/observer_scheme} +\caption{Flowchart of the proposed observer structure.} +\label{fig:observer_flowchart} +\SkipBeforeText +\end{figure} +% +Figure~\ref{fig:observer_flowchart} depicts an overview of the overall observer structure. + +In the next section, we outline how this extended disturbance observer is used to compensate for model errors and detect collisions simultaneously. + +\subsection{Compensation of Model Errors and Collision Detection} +\label{sec:friction_comp_and_collDet} + +Assuming $\bm{\tau}_\mathrm{ext}$ to have slower dynamics than the observer (sufficiently large observer gain $\bm{K}_{\mathrm{o}}$). +One can approximate the disturbance torque as +\mbox{$\hat{\bm{\tau}}_\mathrm{\varepsilon}\approx +\left(\bm{\tau}_\mathrm{ext,EE}(1-\kappa_{\mathrm{ext}}) ++ \bm{\tau}_\mathrm{ext,link} ++ \bm{\delta} +\right)$}. +Therefore, one obtains from equation (\ref{eqn:closedloop_general}) +\begin{equation} +\begin{split} +\bm{M(\bm{q})}\ddot{\bm{q}}-\hat{\bm{M}}(\bm{q}_\mathrm{d})\ddot{\bm{q}}_\mathrm{d} ++\bm{D}(\dot{\bm{q}}-\dot{\bm{q}}_\mathrm{d}) ++\bm{K}(\bm{q}-\bm{q}_\mathrm{d})\\ += \bm{\tau}_\mathrm{ext}+\bm{\delta} +-\kappa_{\varepsilon}\left( + \bm{\tau}_\mathrm{ext,EE}(1-\kappa_{\mathrm{ext}}) ++ \bm{\tau}_\mathrm{ext,link} ++ \bm{\delta} +\right)\;. +\end{split} +\label{eqn:closed_loop_converged} +\end{equation} +The trajectory tracking performance can thus be improved significantly by using the disturbance compensation with $\kappa_{\varepsilon}=1$ in (\ref{eqn:controller}) and $\kappa_\mathrm{ext}=0$ in (\ref{eqn:observer_settings}), as this would eliminate model inaccuracies $\bm{\delta}$. +The obvious drawback would be the loss of compliance w.r.t. external torques, since equation (\ref{eqn:closed_loop_converged}) becomes +\begin{equation} +\bm{M(\bm{q})}\ddot{\bm{q}}-\hat{\bm{M}}(\bm{q}_\mathrm{d})\ddot{\bm{q}}_\mathrm{d} ++\bm{D}(\dot{\bm{q}}-\dot{\bm{q}}_\mathrm{d}) ++\bm{K}(\bm{q}-\bm{q}_\mathrm{d}) += \bm{0}. +\label{eqn:compLoss} +\end{equation} +Thus, the system no longer reacts to external forces in case of precise disturbance estimates. +This unwanted increase in stiffness could be avoided for interaction with the end-effector by exploiting wrist wrench sensing. +Setting $\kappa_{\varepsilon}=1$ in (\ref{eqn:controller}) and $\kappa_{\mathrm{ext}}=1$ in (\ref{eqn:observer_settings}), the closed loop behavior (\ref{eqn:closedloop_general}) becomes +% +\begin{equation} +\medmuskip=3mu +\thinmuskip=3mu +\thickmuskip=3mu +\bm{M(\bm{q})}\ddot{\bm{q}}-\hat{\bm{M}}(\bm{q}_\mathrm{d})\ddot{\bm{q}}_\mathrm{d} ++\bm{D}(\dot{\bm{q}}-\dot{\bm{q}}_\mathrm{d}) ++\bm{K}(\bm{q}-\bm{q}_\mathrm{d})= +\bm{\tau}_\mathrm{ext,EE}\;. +\label{eqn:regainComp} +\end{equation} +This scheme has similarities to the one proposed in \cite{Oh1999} and will be termed disturbance compensation (DC) with external forces compliance (EFC) from now on. A qualitative comparison for the different settings of $\kappa_{\varepsilon}$ and $\kappa_\mathrm{ext}$ is shown in the Table of Fig.~\ref{fig:ReactionScheme}. +% + +In summary, it is possible to +% +\begin{enumerate} +\item detect end-effector contacts with the inertia compensated wrench sensor, +\item detect contacts along the entire robot structure beyond a tolerance band with the extended observer, +\item render end-effector compliance while having stiff behavior for contacts along the robot structure. +\end{enumerate} + +The missing compliance for link collisions can still be encountered by switching to compliance control as soon as a link collision is detected. + +Using the above observer, we implemented a simple collision detection scheme that is based on a constant disturbance joint torque threshold ${\bm{\zeta}}$. +% +\begin{equation} +\text{CollDet}= +\begin{cases} + 1,& \text{if } \hat{\bm{\tau}}_{\varepsilon} > {\bm{\zeta}} \text{ (component wise)}\\ + 0,& \text{otherwise} +\end{cases} +\label{eqn:CollDet} +\end{equation} +For (\ref{eqn:CollDet}) to work properly, one has to solve the trade-off between robustness and convergence speed of the observer. +The first order observer dynamics in (\ref{eqn:disttorqueconvergence}) with time constant $1/k_{\mathrm{o},i}$ makes the collision detection robust against sensor noise and peaks, as long as $\bm{K}_{\mathrm{o}}$ is not chosen too large. +However, large $\bm{K}_{\mathrm{o}}$ leads to faster convergence of $\hat{\bm{\tau}}_\mathrm{\varepsilon}$ to $\bm{\tau}_\mathrm{ext}$. + +\begin{figure} +\centering +\includegraphics[scale=0.999]{./figures/ReactionScheme/reaction_scheme} +\SkipBeforePicture +\begin{center}\footnotesize +\begin{tabular}{|l|c|c|c|} +\hline +Property & $\kappa_{\varepsilon}=0$ & $\medmuskip=0mu +\thinmuskip=0mu \thickmuskip=0mu \kappa_{\varepsilon}=1, \kappa_{\mathrm{ext}}=0$ & $\medmuskip=0mu \thinmuskip=0mu \thickmuskip=0mu \kappa_{\varepsilon}=\kappa_{\mathrm{ext}}=1$ \\ +\hline +Increased accuracy & \no & \ok & \ok \\ +\hline +End-effector compliance & \ok & \no & \ok \\ +\hline +Link compliance & \ok & \no & \no \\ +\hline +Closed-loop behavior & (\ref{eqn:closedloop_general}) & (\ref{eqn:compLoss}) & (\ref{eqn:regainComp}) \\ +\hline +\end{tabular} +\end{center} +\SkipBeforePicture +\caption{Context sensitive control and reaction scheme and comparison between different setups of controller (\ref{eqn:controller}). +Control mode \mbox{$\kappa_\mathrm{ext}=1$} is used for tasks which need end-effector compliance, \mbox{$\kappa_\mathrm{ext}=0$} for tasks which do not. When a collision is detected, the controller switches into compliant mode ($\kappa_\varepsilon=0$).} +\label{fig:ReactionScheme} +\SkipBeforeText +\end{figure} + +For collision reaction, in this work, we switch to gravity compensation mode \cite{Haddadin2014}: +\begin{equation} +\bm{\tau}_\mathrm{d}= +\begin{cases} + \hat{\bm{g}}(\bm{q}),& \text{if CollDet}=1 \\ + \bm{\tau}_\mathrm{d} \text{ from (\ref{eqn:controller})},& \text{otherwise}\;. +\end{cases} +\label{eqn:CollReact} +\end{equation} +% +Another possibility would be to implement the scheme depicted in Fig.~\ref{fig:ReactionScheme}. +It uses the three control modes in the table in a context sensitive manner. +For example, for grasping objects end-effector compliance and high position accuracy is needed, therefore \mbox{$\kappa_\varepsilon=1$} and \mbox{$\kappa_\mathrm{ext}=1$} is used. For moving objects of unknown weight, end-effector compliance is not wanted and therefore \mbox{$\kappa_\mathrm{ext}=1$} is used. +Finally, if the collision threshold is exceeded, the robot switches into full compliant mode (\mbox{$\kappa_\varepsilon=0$}) to avoid damage. + +Next, we outline our system identification and friction modeling approach. + + diff --git a/paper/sec_rest.tex b/paper/sec_rest.tex new file mode 100644 index 0000000..79c0b8b --- /dev/null +++ b/paper/sec_rest.tex @@ -0,0 +1,29 @@ +% !TEX root = atlas_iros_16.tex +%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%% +\section{\large Conclusion} +\label{sec:conclusion} + +%\textbf{Schreibt die Conclusion bitte in der Art: In diesem Paper haben wir folgende Methoden erarbeitet, die es erlaubt haben folgendes Verhalten zu ermoeglichen. Dies erlaubt... Bisherige Limitierungen sind und koennen folgendermassen ind er Zukunft untersucht und geloest werden.} +In this paper we designed and implemented a two-step identification method and an adapted generalized momentum observer for articulated robots. +We applied both methods to the arms of the humanoid robot Atlas. +The two-step identification significantly improves the identification results in the presence of high friction in the examined scenario compared to our previous work. +The adapted observer enables precise and compliant manipulation. +In addition, friction models can be incorporated to further improve the observer performance. +The proposed solution is able to detect collisions along the entire robot structure. +Overall, this provides key features to safely operate in unknown environments and is a first step towards the safe cooperation of (partly) hydraulically driven humanoids with humans. + +%One Limitation of the current approach is the still rather basic friction model. +%Also, more sophisticated reaction strategies beyond switching to gravity compensation are to be developed. + +%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%% +%\section*{APPENDIX} + +%Appendixes should appear before the acknowledgment. + + +%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%% + +% BIBLIOGRAPHY +\renewcommand{\baselinestretch}{\BibBaselineStretch} +\bibliographystyle{ieeetr} +\bibliography{iros_references} diff --git a/paper/simulations/EquivalentConstantError.m b/paper/simulations/EquivalentConstantError.m new file mode 100644 index 0000000..ebf3259 --- /dev/null +++ b/paper/simulations/EquivalentConstantError.m @@ -0,0 +1,5 @@ +figure; +msie=0:1e-5:0.1; +plot(msie,sqrt(msie/10)*180/pi); +xlabel('MSIE') +ylabel('Equivalent constant error [°]') \ No newline at end of file diff --git a/paper/simulations/SimExp_MdlNoiseExtForce.pdf b/paper/simulations/SimExp_MdlNoiseExtForce.pdf new file mode 100644 index 0000000000000000000000000000000000000000..77a708bbb103bd508ec6991d47cb96436027a3a2 GIT binary patch literal 17180 zcmb_^2|Sc-_wX3om@FeHqztmh%vfjayO7;jl4WA-%b2n6JC#r*WlxJO6e47;v@obF zDZ7j;*+L|~TTeYt&-1?T_y2$2@14=ieV_YW*LAM5UDtKanFNeAwZ%~q(oliUh18o+ z88{N|bIu*AsE9a?_jd7fh06jEQ-rpgryrgOM`(NE{P3E1M;|A=vNDw9N5td2pg}n! zXZ0%u>wHIgD(kaBMe#mgXPxEhs2KU_nyQo(Iu5j1&?w}gBTkTejO6D1OP?!Tkzxws zI~C=ZO_`_9E+++*4n>COR&EK5>@7z|uC0uy>`ex3Z6KCbU)3!ULtb>w2js2a_FUZM zzdHE+W6xOAw>qPT{o#=!I*)AZ_1rgC0^H|!Zvx#9b8aq1PS#1fZKaposF+;a`$aUUYjh3e{r zD=nWSJ}G=yR>Ymed=mLS)6R?{L{TYtbhU9w*85ruh;V0jxY{pw$Dg|5NK@|Pn)!RX zpCSS`Rd({n!os$$u?%{s*l)i|oPTQi{*`~scF4vz+Q_e8KY#CO-pwBi->FO;6x-<- zjQlGvObYRELU(2JcN8Axr+zlz8rK}ap5j&5y z9xsRzxEM+0sSOuQj?7|BY8Qb^frqEQCUQm#?}aReQ_n1#gpA73Qr8ZAQysOR4}aiM zzB?DbJ*QJ!yD^-y`E9+$X3=u$TNn@7552UpN1Jj4ZTH5qWq0|_{Eb2J`cSoZFnS%)RDT=B3tNpX(ebz?dmezTfA2~d@60W-&sCtIbO@X6uE^ZS9V?= z+ncxSR8rB8+?yg4n%a?G?AXY!WSQhMr;Z8rsyaL}BrH@~9%?%k8~qf-;f{R30d_QC zbiTc@5n{V%MrDA^XLJX*Uku;#y;7;`KZ0#0k98hs{CsD+(Wi1?&3``l=tww^#C!*K z>`Ay|WT=kN?o*?R(0Zfrp&fTQ2Sg%WeRLZ2g|vLwIl>7C;^SS#?YMD`nAWmsCEM@i zn(GRA3AhMDM{j&I%nIjNUX%ahKG!ozOZ)K^{l$)J^Bdvu;RJNB6w$ zOctdSN{4qBpD8qA0EppLfs^0+9?Dd7emiO+G@4Z5*$LrzA&_cp*=Q#))`8215tCR~ zsnv4=tKODnpg0VJ5OKYAe2^f-;1j{x3YU^W0$MaD_6JsMbg@8NV~a!#n=PyC8fP^B z?1eArqL&XRdM)F+X|>18%WLbe*&FeQm5j76j-(V(Zu)RUy$|wCjtOj}RderTZ8C`) zqrE>i0!Bp-i&uSEjA?$qITsQBEQ?szQEAjP+?&9#G;5mB*b?bpCshA_W%s>Ib9rD& z%-fjyA=g3N%SGgoZS4uISU0_0I!?l{`y}0=>G_4M46GV6#KF{pmV^HM8gGI@PRm;+ z31(*UV9FtKV)Kb7-pP4YOPAIzd04Z5DL8uaB?EZt1~xhuPiR)q=^PhHI=^r0*HRSAO6Wstc27I@x5ZFqraN6*^l@hD zuF~u@Ps~hdtC|F`#-O=HiOMU%%V= zI$RK4E^SK?C<8nBUsxFK)?f#TRf`&194`fpzIF&_qUqWWHD&_-V7gZ9u2r0+4(^F! zewDG;*A+@*!Y`Jprc{Z}=B;~W9h{%K;9E0)GyOg8R-|=lK?u3?DuUnhyCQ7)MC=;x z9X5(W9(R(`EM4aTIf|v@;Q%mEwN)<_#=dnP-4e4>ueI3s_z-u}+|JI-z~BN6H!Du` z0&7a;#r%*1LJl7V(c%vuL7wKMvbw`hs-L$6vAPqQna0^E2!CoacqS|;Gka~M8aYX5 zXj6K1898%+G8h$wIt5AI?%JviC65Wx1X;+bM>yp8C_T%Gq^VS8<^YH0=7Jhu62QGj z9OE#K)X{-24WpC~_yTHBmX;0bkwlMa7ZQ}e$d`b_eUe)*pDZm1BHP2qsDkrNg(NDHuQ#6HYS71ly65f1*PKH&UG`z*2R`6h)F(yUhC0w;UgHb)8 zfl6m}eCN%oz>}>&h(82VkinxSfs=XezG5gAu@ApNKa~!u=-nM}pQ>avDIC6Xxb#s;^8|1*m_Ht;N2V1306I&Fk zjbE%8t;9JBYoU5X>%G@>?E}Hdt*7S*V9!frJF1F4`u2g@)n5`O+deFPAbu^pzxC!S zX#R*dHtKqE+t!SmFC8yE4N`fY?n_N3mRi|pA~Uhpfdf-0O)+mu zz})eZ?6X#al@2diqTCC1R1cJnyQ;CH7g0H&{?PU>)#+IX*o*>fN@93@BMS_-Y(T+lVdw zurQO95Xdn^B!!)0;sH#lo~y{cpc`UlN_{z2wDkh0R4fTYR}OiejzE;Qex%QFX@jht zJjGrx)|+e8os(*~u9{`k4f#?SXf-54X(TOFp`~f^ifCV5TBQ!x9)h^H)$&&sXps?A zsDAzsyf3^&mku|;WF-a>5t<5Hi#D`OxCsfe7+{*E_Kj#IH6M*%5FD~P&Pj9kXpBl{ zj!GH$73J=Dk4Z#p6U}5;c@#&|;Sm~2A{&K&=2UY+D(g6!yV*N4C+d)Sn|Uy(=Vg*~ z8JNUhZXbD<5k5z+0l8nls&O+mBk7I;NnO3+vrxUL|Xe4o?8Wit9qjc*OQEpx-x}4Fc zU*-U6G(NI7NslOrQ7VlQY66e1#ejQZtrYyE?gq46)FFu0imlZy8cWMq+1gKYg0jFy zsmpSVN>*uPAVt8=1GOysx=6rZ1QAA7oGNX=B)YW}wTXmc84%)Jf$)zbER+}7+-r9s6N zb5{w<5==V^jY{i| z`i!U6UMPfmE~e)&OJl2ON0vuw<94}SR^;US`BO@%q?D4@Y%>~JtH6{7@E4^_1;!i~ zU;ftnR*R;yyI0BkJCu}5K4kh!PjXVv+TcFjh1|Vj#U4dO$G++)ZQb@Pj(NdQQ~!KSpC@f-)I~$`w;)gwNJ;S$bTUgjpK%UUr=@ z(zIYy1^Qe-(i-(2TMocMBDU0u!MW;_>@?T{#04x>S35$J9X-(b?V7trxdNd-#^^13 z*zR$f18T8fqT3t9kd9FoaT@Ga8EisuzVU-zXY5rhyj<_llayyF>D$kyPKKQzf%8hl zs*;q@k-Imksuoopo{N1PPM!#aOB$co(SbmXL%%dDuoxnJqN2PO!usv=l4GQaZ>K#3M&}?|vDx zhmP?^dnTjW!#&`^f&xMy(y`>KRmk|Li1r5)fmQ<@yYIdIZdaJ6PB&q0&fgRaGVYwp$Hq;aSpxt-34 z)AI=A6!{od3>F{R4m~Mqk6U! zkQXdIVr6?Kr6_lkaOxFFBb2*m`9sobO(f{QiGFZ!P+!LUUN{9lEtm>)$Ec{b&z!G;j!6Oi5L z3XO3$w_}r|uT+O@a5Ni3kC|U=Wi%G}C(YlFuCjBX*`onE4p7o>$;VfdkTEO_F_8uH zX*rFn?aG(hqpL1=L3SC+HHhy%o}@tR8OUnCdX-od57(QA$wBGcwIzQH%*mfce%%=r zT?SEK%78JDeIHaAb2Yh`#~f#i`y$UTYkYAtxzw7hIuGMkOHM--CwWo|{GZEU*rgIQ z=2+VjY1&kJ{hzPb)_c|QOr`Nk$rbqIqw{go$HGoL!vxf8%};I+3@$P~n$)Aw8YqZ}Jgl}AU5AJ1*=AC~!sht~&%?7Upbae>HiX!%5_k=P}od?UM z0PWNbw(}`FFFcaBHbm2--$#plJKU}hoRMh@`r<(_+oZL!yn?5J&y&o0dM9nnu~iD> zPFJx~)gti{a8hjSn)t8;I`ZC8B@DX>vH|K~Bozbi* zfPNKvzV&{_yp3*K3sxEfxo=RaS`v%q>2HF^DRSJWB@d35=BRw4!yd(Ombcd6t1ek(1^2F~EVEUG)$Q3%_-$+$ULhQT_Z|su-clAHLlb_vtc4Y5^WYo9qu+T}#^ zSdLTUJc9a|3he19E|-S7wvbDlg{(F(*!}Bk{_$El`8eBGN#*my(XH6w@vy1kZZ{1A zoB2gALt8#dwvI-Q&wUO5jtUpd_XWI=>ibO*byju$j0Oe*yD2S(7;&*d?P?}`^~siO zLeg3t1Fqt!>bUTU$^trUR0<6*xd2McHIIIbnGDNfx(W4DXQF8ip9I)DX3?BHgtbKS z8RXbQ@!A^93PLMnXqLWj{EZhT-!n^Yga!?25B-Emgkp60&%06MWgw{ z7PL0KOr(f$#+=lbF->5z!=2N~5Q@i><3NxhoAvO0T{+b!GmPqfK%9bO(47u96V`Eh z|Cmfwsm>Y4Wlp6m&Rf$-V^Sn)Y_HiAGb`vhcPdE~6c~?Dd1w7OI4*^TziW^qiH3r9 zz|k9ms>Z1_OTh?8HnzqS0_ov05s-+y6++>OKB#YNw#Yu zlY&_lJGdZPzMic0XhZ+ zx%SoDkBl12&|90KmzI_kSH7=vjpe5`Uk=erc}-gt`YtLt4@DHFY$o;AR>NmXsk+4_ zDR+;vx?hBWi5H)2JygH811f(l+*vTMs6Eb=n**{HuPCLj`8Frdoaf*HDO&XiA zP@Gb?>NwyE8e)MP$O7~F+$IC_vf@3O~jyt{QYX>HwFi(ON$ z&F?n6pfhew4mih$M6=2>Gu+q0!XC$P|M*i3rM*EdL{8+chfC9wIcdrbAoAH*Dq(ID z+8a}bYGqOs{rqe;038r<6J{N{a56FV@(g=DV~j%Qc`n`Ds4TT&RID)t2u|QPpw4l& zchz6MKu5k2y37bxJb;IN(LE6h>REmImi_t7IBOn@14Xvij^2cNYVnmfWQo4}phy(;2c(Mlx=E=^#j$6edop;#tj!sn@qx9pI3*u2ku+od#Mho_Qh2U6sz z)n5XR$7XiXsKjadC=8^qi#JKK1Z-2wOzwP%*0#cPV~@AKyoMg*2wxR_XMohEK;o0_ zKIC4o1R3euMF(7)r3*SUu>&0KDRL+0S$&ms4WlZOudn%rE5RN%AC{vUc-B(_wpBVn zaWrtOqmGJV{~9q4>v!*vnx&gZ+|$XKgPuGJsD8M*)x%gRNbBs2Pf%ZQN|LcHFU0(? z&PsSlCi2-6gI;ANeGbQI8X#0!K*t3swp{QPzqv)#vxSDz7CK&s6(6-?KXe!R0Yh$0 zj}um7KV1uKq8SRS1F)&jb6B!E=8tG`8?ujMpNpZvl&Rb+mIXbcc2s9S-fsZ+vR~nW zc!Ou5mI>!_d}_H#{jEo@(jOSu({X`mTBeDDuzgLJbW00p2Ym9@CpM>n$fr>gS1A}n zT>}30xHu-clqz!1m`*KZ7P4jd0{(n*67tUQ1?&{005~HS-LgGw`qrB@&MI=Voag=e z!cFL%2hlwn&^!~`{3Uip6ED}M0z0)XlyD~y_V~b8sydi+3+hlSTBra&?WbbFktQ4aZq)v(QxX%1LW) z;;KRgDnZXW$HV4HGdphAV(zWdQu%zo@2*jNdVB(0%W&&xxn$ebLOA8U^~^E4SGLg4 z-1J)sBB#0@ z}$CagzIeWaBmr%I1ekm-YB^Qt;gz897`X6QAU=`UW`_|kgklHq!ixlF;LsU@&0a4_P7)V~Z# zqzXAqjZ1mzeocK-gE+HO>)p!k;+2AlTjQM@oXOIVguvG0*95A0qeUtrd3C6h1bD z7<;e`u*V&vGoG*Dq_Ov^@9s}{2G5v=JVJB!sY<;R>N*j9^68|x8nJ;ldZS<` zDlZztGrvLKKDTkPIx}sp&;q&jwGdLqep)#KMtL7DNtrsXr@o*jH(lT10IZ;hv%v+T z?gLCJjM&~L(Wr<~v1Z|QXr2Xa-g=)0f%a`F^vjO^K;kzb_Uo@@%+&Li{Z!g(B}k#| zXTxD}?H7ls-&q^7w?+Q6!~9RS zzG7+Wv~1_01u9uH9F7AC%5js>yj$ zo@_O|Ny!BnpP3Xa9^irumE8@6`HkF|OrFD8tRAPa+7i50YqN;7S~9i5P(4^n#HwXu z)kvkFjqgn+`m@{&@Mr!?Hwn$|2Z-R;x1gtO(nM8#TC%W=oN-oOR*to}OZ^E6Fl>~} zr4i;R(W+qu%E4Z^8}~)C=2;6%QC&51 z0UTYx?yJ-NTKfdsm2zO!HeL*F7ecDCyN1USl+jdiN#0a-L^kZ6U>7rSIuyA39De z#7A|XegyO~eI9B)(S@b~Xxe)6Z%E;A+2uV83o){~L|M$U=X@ zq<_MI>H_m%0v=(EbHO7F@J?CILV;oh zga&XA^hkpL3HnLa{t$l@JpjD{biscRMuH>s-JD2p8|WYX*}{Py{P(-u@9k$()Spd% zw$#A+;XHj@es%GadIP*4&Ixz|m)xJ@4|0BXAouqU{+b39VPtFoM=2}+8tFIYnaV-; z+nN4G$8UujrYIy7^FpHY}CY)9EolOKOZ6-wLfLkKjgRH0^qY7k>sc0iUXb@+l|8su(YOv39V4{EWbpPp3x_+q1uXc!iD*wE(bn{m8 zCb|82uj%IOj0aQ(&=DJ8{&I+OIHJ=zPut%*-si+WC#-91X>M}r=Y)y>X1+f}`0wW{ zi}`E1Xeq?6*~+5#IlKRslHKRl{u_hZHwYy3k2@I|ncw&UH2nKi{sUw7<@ZnW_0`SQ zG_YdkZeDnjxT%j9&ikJN`-9g%82L|mNlE@iKS~n$YXVS7nLo(f|3pjeGvM#j{IG%FHFTe`f7!?n2^iwM@c+S@)B$e?I6Luu zHcH9L!R2I-w)>S;E`V!-BGgEZ`+g4q0xkbRD}Ir5C)L&yFqLGsvwh;LMki&St{n}`2o883pYcAPDKIt_*L(mHLHW2x7HDnldR~0XaXQD| z*gE5Sp2^LEiSiN$CkNN!@ocLrta6#AxSZc~x_<;!89+w@7`&*5>&NEBQD(RXo0X^b~C5f`j-(1@5-q^}UMr?k#P8{oq zv`!+=*?}@j%CCNN>9Bim%aCD>)K97On=two@7Y2tSmiSl(kkBh^qg{jB5Cd9@#A!K zp!7MDo_$aD_tg;f*BbMeEBSXC^KaeJp9&)hN6TU0a!8q9`XVbMBa8k^XOMvOf76-$ z+rM;1@;|5yN(u#N$$!=hErc$@0Acnw#rWs)^V>4^zgG-d%anC=}wG|j#eE?+K^^^frMjnfc^y^JNVj^t4`ckI9-PD${jjLhuX!8sex?e=?OI?wsy zJg=vT(|0zUZAzmN#S|YhxsN_}cd^}xOIzV`GJNA$xvR%gjm(X%09$XZyozGu%0X=Z zaQBh-p54b1{jT0y-+KfRF|@SE)tCjn)S;af*3&!5Py3+A`lex~K$UwRL^1E9?=)?6 zwdKl3+@s=-oM+m@x4@x~{0?SZ$t+)?;b%O)WB7ggMygcD*YlSYXKJS3ge>s!?~b3i zBy&QUv53N>pG?g1>`1wF$yz__?1q9t*E1M?6|Mh?`Qq|*^C^RIt(Y;cbjQT1JLhTZ z(Ms*<&I6FaLaJm3<|d29x@6;(RttsG*RAeeet71&E1VgD15d*6Yz(7%oYoT0iU&z` zmm5&LJJ^(wb9r~2sx zI5PO2Sw5$ zDhx}!9A(YKoBWs0O;~L=vd(ko<(D0QmwrEPFz)oFn(WGuw@B)x+KW;=7R%?;%){0t z7D=($)E_lwLtl=Iy#>+aN>tW$YGwC4R4fa{(wx!tMn9+vY6!cXJK^2($$G)md56Pa zDe%$=$Ab+ywe;1ux1kyy)??-};m!%UYtNd#*G19d zLR9p^8Bg&uG>hg=cjRj$-c$xOIOlgg^yqH8UOUsdlU++rB@K*vs4RV3pahS0wB_U? znG>fDaw87kZayl^sw31B8Hy6abd?!)iAt!R>m1{53@WSo{%q|cXW;?5v-Pb{A5HW> zm6!V(B;pxKdsw0^2b1GP)#>SzK$Fm1>ph~NARuD>;OkJmbdQ0ZosCkebMS8HQ_?kI z8D-gbB&KgyB=oM_O454aw!1P}v})dSZ8mTB%3|I(MQW}4tG8U=MON-mruUc*bRcmL zPH1J`5Hw09f8gQ2V02K2+it1W_f2Sao#*CDl6FG z7oUaQe>@b?#k1BH;85wHkCIDH74H!C#LT4lBB>sNJ5V=1vXP!m58=r|IdpgHa)`Nk z#7$zP{{VWgJ$*%RStdyOe%z2Dw}APRz-c{GJ^90))&ytX$II*S;upVOjEL5@yaTi1 zoPz@4sCth~n-=b8*2`6kaNt1fbIdP?Vmr{nM3GIBe?*V@dj6+~4MhdMmD_Ta1( z+Nk~Hq}%jRXW|w1h~{?sxPj$hiza!rO#%GnC9FVylxL-J{F~x9P_#SNis}W}eK^a& zD`%s#Y6EqI>$))XkT50d=|AjRnh78mUZ1eUkDz>fI@o8fCBuryd$Fcs~*8I8L_)U)`%VnC=|)tCIz zk_X{u%hq4vOAfknk?wV63f5heo7m6|e39&uiXhu(+CL?;mB4jj*M%9@F3kt$33h1%WuPUcZ(G4D9i`EairtzOY(4a& z{Xc$3R2bNuQusJ#!0)L}RClAk7gK%go`&Tj!_n*^Sq15$WPKqQV&(y{tk}0)rzWva zwR4dgH&4AtyL}t_`j$+;$UFCYhV*^~Rkxm7Y1*k@Tk+Z`URhIm*k{(B)x{6xt&{)r!;8)yjts~_l{YN}# zPhNTX@~aglIYaz-pI%dS?@g-fs%E!DdYjI79WTS(u6S5=*c_@FUi+!$a!mnJpwG~F;k&cE!#&)K{ z#CGjXq1XyLhUd~=iy$Tq27<}h9e2H@^AEOTk+8xmw_Zp-c&e&>C%3EW9as6K+fVUN z1#u>LUs~kld%2gwDK_aEal15UmMWiLJorM&d<7o;xGDVmWjT7XZ1N~<)q^>+-zCTP z9W7Va-OwR{nh9RoD_?GWIeT6227=xx=T=$1gh1=pN8YoNs=Ke2maNfLju=JHwsci( z+t;8obRCMv)vu-B+h`ykjHdN6J-BgG^q6tS(KA$-C1Jn8P_W z2`i+!Z#{Jn?6wQNF>kGwjb5#mwb~w3zuB53OS6{YY33aJ=oS>>dG+08Y14xaceNL7 zR97Pt$jk^)0da#XAB26XYf`^$W~gfvN^rlngCo9E59Ltu``hkT-mQ4NfM`I8QWhCB8Z=P(4o1^wPaozx@pj zG9&vmyTQY@ZK)`3*W@uReiT*A+qu>)k#uKXuzrS6tHHrc){R~AHcr*iqBWJc#s3%@W!EgipUk6|Wnp32QTbDP7`VM8jND&lJ zxY6Y~`k<)fwxmLg_Q$o4qOljO4^q-BtBW37U!%B5aQmOUeZyqIXA1c+_`v0~@JZ># zq0@eE-}*uKs#znD-HYm%AKQk%!OhIGsCKW}#KYgNvcxC94woKXQ+j~am@eiI% zJ6nh9Tbq=q->wcwD1{Fnpn_d>Iv#-7d{DH zpQyEhp4TJ6Q$(J#ka5$4+M#WOX^mCJdfm(q+z;`Z+@fTPUye*fAtPY&-F=8lpRL+& zcJ}yAw12D`iTRe{WEstRWlM!`ENUZY#az?F|M4eH5wU~>JuFzshbJHOmE6#Z^6^#kji2{9`>ZSj@y_-1dwye7R=9^T@0p_bb3KFN2Ed@mbWM-AN zBjiU=49|5Oqu+-y`wTriuiY#hb?sGomQfg1Zf&~ZXw#ai-(c>ZOxO|SThG)qOo{^3 zM~{F4(rsdQlrx>OJUioGtV7ddn2c_VDplAkZ*|w)bBSvvJY1B|qA7Z(aV6!;v(u!v zx>xpQHwbIjUx_up55$KDIR&Vf8|U22xD)9tvOJs3wXg$DvuD=adMY~QWP0Xgrtn_c zb|oy%Lnw=-+?%kxo5DFDar$7_9SbR{%joSnEl>|jK;anMPQJ_dQvQ@{4^4ax`fa;Q z)7Eh^(vpV&mwFMOFF9t4WUQpVO;=Px2~AZr3kbM&xEd{ysa`PU)30dJ&LJuM7oLfiA zqmvHkB*ffE)9(m-S1S7~IO)wg^~vxqJop%oNm3bu>B0rorenKFG_LGJ15LGvCZThu zLk^@7UVKP3hLq%v-K4$Dd8SXffxW^pG8$QbKVGx1_}UGH7B+D$L)32L*nwcE+}U#1 z>NB$m4Jj|ZTZh}e9_*VKo{^P(917KIX3h(s^t47K6ht)mZFAQfD1VS?rt=*go2uP( zTCF@9x3k3Bsi5>O@Ttw_rYd(sSJ>98?_Y5>U(X}wndY*MZB9b?HjiT-Y<5(6km|U| zDXEYxAlYARFnBJpl_S_|eBsIB?y0fX41OxU!e&@h%r(8Z8xhYQU2@zz5O~&5EoIB} zyJZKgag)}M+W1ua=41Hz%p$Gqfr6{g*FS%QH4-a6F9=MS)G%R!ZwB5z!JWtqbz(1G zTNNnb>-SZS;P7RUXz=8$d-z(2%cd(pb=Qq>V71Wpm>I_6-mx2vbMm;e)!h}<4H)8? z4_mA$mplg{kxb&M`YIgEjS9Wk_kBQ+U@n4Y_tfa&_0Q}#4wj6j3_VY)F>++-V=$RK z%?j6Y6Q_8u@1nz^mEF8by}?e>VW*#tx8YD1zK;v1Wt-kR(Nbn|!z{DrAZuk|yz9Hq z`q6c}yO#Ad&F&(l1A}kYhqv1Ukf1ZC!)3qJjX_dbbM_QwpL{5|kn~!kr1_=>gUJdf zAA$SUL#_~AWfu8sBZ;5oEHkMzd>=K-4wifLRHkuCKXrdC)A5qKrrklz+y1NT<;U$$ zKbky#b&m0y5dU-Hy?;G7{zwY^9!~s~F8C{=W@T{tS2zv$4UpWQCmKbSAmBI!oYUav z@GfrNNLlEm2n0X_eTW`#l!UAh&?V8yS>6;#*!gPw0M<4G%SmBm93{`;#PO0yoHz=F zmk~z-FL4=1j4VzPErr6#IQ<%q@Ee(b8xME@3@8Qg0l1O}GEz?dj(DPykdESrD0!cAtNhC^E94RG^M46+c z!R1x$bKO=_Fj&+ff2;fhUso1%#H6kw8kIFmkd$nDnf$DL|_X?yQIe+z1FA;QaP8 zMrOezAiOOP2Qnp2K7k~-oX8(^{}}w|Sc-^!N&m*<|2Efg1OtQrJKw#$_6=hnPhQi< z(ccRQf9Pudzo^}RTT`4I|0I~;PxSm@V@{3;yeEF2HWHvLD1c%oM|o!-q8ARZ5FCL3 zBozRr`*G#Klr`x_o%6sCxU6h1^#GUZYIDbz+A!QAD z1eOE{7GYszYN)9efkLPe2!I~p5T|_{ah^cB){B7fBREUT$VxfMNZLC}$vE0eVANF*A_ z*8B~IM9Ts(=YN4o{|gKwCkG_5{?-gxe^}YDsFyVbCZo87&Ph yEsUgwjEshirlgFvI$BFcT@9oBKV#VLS96g3a74c!%7T)WMan`21hkB_q5lWAXAeFA literal 0 HcmV?d00001 diff --git a/paper/simulations/SimExp_MesNoiseExtForce.pdf b/paper/simulations/SimExp_MesNoiseExtForce.pdf new file mode 100644 index 0000000000000000000000000000000000000000..168b59637f6bcc983f408d86afc4e4128b3f21a7 GIT binary patch literal 11708 zcmb_C2|UzW+Z3fCQA$OOEfoH<8eEoDO^6~{N|6u|B1@5-gceJS zvXn@rC>3R?^!;b3-0FVseZTL{{Ft*m=bYy}`#H~%GSkwLhby2UQf(6n*$^}o2Bo;{ zhp4IoMntkZ-2DL6I(cOroN}P$PhzUS(xx|+ISXkOUI7(fr;+uq^ zyQ_UVE^~02Lu)AgwtX2!%rs$j&CZ1@y=f%uSGoc2jc%rvkEJan&rs_~d6mPG9%Ia6p;$C*~ zjRt;eny1c2^e}jzOt+|AFER4F7OlsRdCnFQvT7nwSv{EX{(aZFbq}MjX69X;bPPRs z%F+JYUdM)mU&rH2ONQ#|1{<(y*VNU z1YTHYI-J-2WZ2~Rv3kp-bwU&S=8OAYjJ9bbb{1!~l+yf!)=lq!$t!eVB74B*%7Lpdyp#Vc3}3jc54K6?3QE#=i{p7AE~;hGs8H0D*k;pqGbHzZ%E*5ZmJBzVgB<$5QFut#QG3 zVvF)D9j)drpmmHq&jcbo71KJmRC*WY^WX6jCL~XkUBB9?)$D2~AFDi+r<*ikKO)dt z^n6aqK0rTt$Y?_k`w@w-zTU(SQJ#py<*U;9w5KY4PNR{2lDuCtkO;Ae?0fHHKnOXK zVq>FiHovbyT8oA-=bcJ6 z8xOWi&6h6Z;71{L;^S$B3@&ZW2RvG6ok~}Q7uDrD5HUWkG#`QZtpTIi8+H;7CF4rR zFEqlbo4yvEKK3k)Zv*N|=Lq#s+v%33OtUNYcx!^1yIJ)5@Jz(HbBVpexNFzPTGp7R zq#YC!8k}t^sd}o-Z|f9!XxF?^3V)Q6Qil7p`~t7>*!mmE(Q6=gN%Z4EcP54>t@+nU z?7N*Ma&s#6)u))f@+#X5toTFM^&h3@@(C~WOC0*7vpUIEQOH~4nnlp5hy4-s++tp- z+G10VEy*`~r5CH(S9>;{-d2N>h>~Ifg|y1X0}tSn)lo?iTdGx^Bk)C^v!`R;V}rt+?-J(BvPUMk}g#@F>nuPEEEsc1F&aNAMkL~D(iXk*uz zm<^L;zpA}HF$dmX71yry%qYyS(5+qrO<-B<-aIs;_8lAdg{zBq~mR9c8b7Qqz)|j|&k=G$7#5^dw zH@qU+#SEQ#w0+CtWXMummdlM3tBX4Aj^~#fB_1r(E$R%)X*p~mY4lZI&tkG!MRCU) z{=$VPV?J z6Nw%uD*D{&MNaJ)M6^Q3YqumGtl8z@2B!vT6@lat45&!mv9L)p@V&zQgJa=p;!Hwv z?>ef1ViLD(XZo?t)j~0e4woN@z1c1DZe)XYSzsgfLx;%wk?>+(!4m@2`8fXb7gyJ2 z?R}e=kLw%rxvcLgd-0AQ)j>9EX=MdH_$qzcW%1JovP@drAMZjxe{(k2gU`Z&=WvzI**mc)jgPExrT

    ~-AF6*@LChKfG8=>fLZPu3>xl*pNk`WDjXGm$p(7$aA+*>Yi^tmb*C z*TBhQicBeLP+w{~DK7EiORKDO+R8OwNB508=K@3hyiOF}nz0>gJ!gv{L#@5V5hY27 ztT%-C&kNZKXI>D#Ri_z(dzygLyvCK5>a-4q7Y z4hD83P)blZ9I1doJ3zpGDv?ZwBAEdI1h62|D1KB|A`J`;%%~JsOCsG40D}i8U`1rm zL2zvbUDuKhh6hkMD`tQIIuvj?9K#w9Mhk!@SO;gML77p81q5tb!i>4ZV$=c72BHRK z;YNc3h9m+FY6oFrZUJ$Cf;0Frr(8A^{$uFUNKHH)??rL{KE)FD#zZ=v0QP`8{AFz> zdW&nbCiuAx2w-Yv429!xOGvVIwFGH_fv~pqa|^6(e(#0DAaEu*EdUE8h|*#Kj)1@s zOGOj}&O&3^a3=WD@ZESCkx4pWua%*OhQ&_r0KAi{H|+o%#-gYek>*Mz`Oqm;kX5V+ zS=?lf07*`w(&(BVc(4zK0gUj=DmEkn-GgQaMZ;iBZjr$ljzo5cA{LRd^mCyzg@QR3 zxaaSjVfFrnJWJyMCYIkP0c=QQ4Kj`Nqpn4Ab0dP%1B#0sND2(#f~OK(yc~W`%%sY% z`!&(BG1ar)X+`oT(&Q~D-gxq_8^-?qevyb}+l6C5lvvw^Aka+G{@s_=3js;OB+HM# z#nKpCSG`Erx6FJ!b0>K&!_M=ct=KuVUL^6dGR6Y!oD2u-su)Ks33p*H;355jL zU_$+sg}+h%Z+OWPzh7ytZLX!MtGgs))IW$AOMw&80``OC-$}{ZFl$T8 zOBf7Ob(RxKQR#a>Qjsaq%rBOuZr`EMXr{^d<98Xs7fJdX)DH-x(jtLD_98ILbl@Ko zkjb}S3216;p|yKANI(}*NxeybpdicI{h5Mj&@145^oS&PkEJSe31%O2Bm~e0jXB9xgY51_1Vsk0q!YdOK+((@{M}j9 zV(J0}Fvc^M*GM!PXxf&wFfAhJuw<6(kSq&(@JvfYLg6g?{L?V8>P!1xJoPR=^nxfX zHe z_F|G(JxR;mze^sNR47dR?B48n&p|OXWM(jpI@A(s8`JsPkuABPDCM(zi{pU9nq*s; zVSEXF*!1&ZuLjQTrIZ(ejq+`+F1XBS+LWA#$f{LrNw3Yjm>%M<+4rDVBWu*7TclH{QjnS%IT zNQ?nI;0h1{H^7bLPXtJS7vK$$0SZ7N69FH+fx*>OaztiIUXnjo~-nw6VD6{;P=IT)IXVNyRVy z)%{oL)uOboaHsUMNc9&(=~G{;h7L?tcYUs%IdJxtc*G&DO>rAfh^NLRQy|0>_N1rk zv5rmIPCVH*Wn!svUn=<8Z1ugao^>$d-p#eSIZCYQtzc%gP!w)o>|j^cyp$F!Ze!he z*vtbfe7|R*O~YmDJr-GfF9q|(AL?p*A02e!pQA}3OwJ3uG?cJ`$61(PF47V|aq-0U z6JPfeM=ht@CHwN)uj^&WI60&j&JNuSHC^~t$`uiF{HB3`L5lKBqrdsts=Z~~_dlL@ zqQpqXY`bpaBA94&p0D6K*@c^5w@7T{NWc+wzJVi>BUl$%ex1k-T^sm0;`ZLSeT-}S z{p*~)n^INADxsR)n*J)E&EGwFYMBm;k3_Z`Kig4->5w9b%&p`*9N)mU*V*>dm|EvDJlyp=ae^ zFQgtTqVui;?5=L*eit{?5YcS*C?^yOk$3vcr*3L}lQCsu^DO1mnU7Ci96IpivW0=a zqY5`ALf!Pv;Ch%le$9zf2kB##r7BZ;U!85M>NpJ3 zenphXi?t5Znf0_6-d~PFRkxMT)Ry~|bgN5pX|Fr=st#z72fM#-m%?h%)8Q`t2Vx6rLLjFh<#e1=cewMil&-F7CMF(3T|m09uM4dx+QOl9+QAp>C$;KO@6Y2qblQA z?>>z*BTI`sGugQv)pdnho<#-4hbv3#3!3`baE*dhJ(^gXuK2(%(T!IA1<(6;phsW6 znkSo$T~8qFT4NKbpxnRFpC;1Ug`DWqh{y*0VCK-=ap*=Z!5c| z7}*kJqMkbUw97*73|j|&FbclP`*vm3;iGCv3w`f5M9+WbeD*ATGeWhl8sGnXQu*PX zb-4kj6}U^fZ`I*X*6WmnY}sWnA9JBc=(aMK75ec80RxF)>{M9&RXVCIh2tJR&oR#; znIvV#Zly+aEE#xCB72d%HlXOJD=muMlT$}C-ki*XoY1S?u5XzlVR7AH=Efs@KEK`M-q*2FqT5?V@n-V7{*nWwkGyuEWu`yuM{{tNCHh`Wi?lJFGjHeM zq6fyk;3kHlYlVQVS$=B!iJ$Per;l|3j;J0U=7!H`| zPTnb!QQej6rayw`X{@bA$Ee}@)nMYAKU`ZCjD$`*#btSlwYTmrTGKyw>dxrPan^ApmurrdGd{vX_NI&Dh4Q5aZ(>-Pt5bZa_^y>+wAya0DG6?)C$_? z^MW@`tVBJl*t`A6A4QE1K{Bs5bY-k!cPx9qu@=Hj_TDv`GhoB-8{3?jgJC$(Bo@Zs zDNo;=Xkh<#dC(A-tkO8IBGI-*Cw>;IlVB4RrK9GbbYE6U@@g6{GK8ia^tCToW&J&a zve9JKLgj|{0nU~^HnXk@gDxnqwWFsVYmm#f);!%7hSSNCl$gE{q7x??9lXGhkm#6P zrwvUy^f|=PPr8&l~wICPFZqA+;mL z=(YJeo&&0f4(&)t4h%$%mrQvDa3GYc*4(*a!r<>-*P(29T89wpzCJ%?Vt*OBQuFEf zeI&o6H2z{eqK9X}u2VAbERwPJT2|PSAu6 z^S7Dr-Q7&cG2aX=pdN4D{ur;c(u^C6dP_SS^|Y*9GOBsbXoro>YY7xrpgZTBhx^#WUwxoB8+pnC8oE-0Vv#3IM zUs9+}tQIRwV(dEU zl$?A`RDGqd%t6v-nsj6vQvJA7wEOU>mdTnBJdb>YhwQFu^D#k2+BwJ0Gnv&hl&--&(_JrpPiVbUfD)= zyVUtO3pl^Rz~t^&sFNt;^izjxGm6~7GhxQJx(ytOhG$F5c5r|2MGLlOS5fNKeFZz; zht9sKbILnkux@ls?DcEn#_0pK2PdLkTgv$c8zhg$KfbCMsCM|-dxiM$5HUVlp!(Ox zl`uNZgzjlOdtuCY8a=s#j$!O4=ePMcc{{sOn^nrn6e(xJeErTu9g)nauW+_k``qU+ zIksj0{AeRuiMz}50-+`MEY;3r9aqD*j#m?)2hM%uXy=;R}M%SAuH0J zoZ~Z=o$MT%P!EVdolbX(n0ZK41)3f-x%5*AMT-3QXw$C0|)OMmc^dhmTS!fh?}1f@d3|Y-pdYQM%O5 zY@+Y4PoumzGc!4N_GPe-oGMR?ud0Q^wfA**_7@{a(;sVL8wFijBKNK^5aDl{;ELG} zRjyT2ba|qM@?H_UCE=ZWDNH!?lZ%eIZ<@bdNVo#oO=tJupkyvW!87O5(>LPY!<~J; zX)21}hBmi|4|NmYcJ`NT*H4SZ1I~Sqlri-q`NE0lq2jM5FWYDc7JB&tbDT4 zf{FE0gQ=8|Puy?z?LQKDtM}^Dm(PlL)K=kQrgDz2u@YA$tnhDxjlb+zVF~dHSJew& z@!7rSo^{CnN4VG~!{=wFWs7vQuM9*F3(%Wk6=%-#IBMpe5@t8q&IlJ2XM8DjmNFB( z=(5i=q$85cO!nRVqQhIwjlLzdb);u>`&>$Xz@3cNUuj{w+(bID) z(mORTU4|IuRSWxTT&jGexW{)(QR>@`>$G%mx<>;89vDn1nB~hf9J@N7#fd`%$>)US zudf;AQfj()*MInoCvx=Tyu@?o$k(r9UAT+0_Z7eN7V(HMF)TbFrzUjM>)NJ$pFCbz znv9(0oCH19stu?1C#<2Lh%ESa1fLx%hB<3({-#&NPN+g7q55mbBgPncBr+^z_l-7u zWlH7U00G|8hoU}ELzoVEt%F$RYd!x*fIg3Zv-a5LXFk%E?Q*^{jDoN`z8N1sxa=rk zFWr3edbU}n{q~|{Et?wiYpW^sM=q}B!b5hrtNQz>x7PzEe6LQ9)$b@EJ z#%C7i^?MDvzkrOSykjpqbf@?l@5c);HunD4ZoJu%q6ekJ7s@r#PfL>mu0*cejy6@D zd^nwB_!Yb0F1onxKGqqUvPz+{?QZ0b2amOdE$Mnx@z85j@Z+il67!D=q%>AN{s; zsNCHjM15pkmltB#c(-(&(Jq^atfL!f1!~Sd_ier7l{Xdn2Mu6D>_Qj3&-GL#4w-Gn zkhns+zTo<_Z*f>2k(QZxnt?I@YP_2vx)u(zKw9|teXZkcQ*4IlJ@hh=v)`8l;l{sb zfBvc>!AWSxn{daf7dYBXOH;oP%qVVdgfD6J&S2uqbnrXwgPdPsWATw;@Xp;{X-B=mxwlUVH@FqIovHK^5s0WDDHJ@g zRo_N6cv4_db~xurHK)Vf>W}wT4kzCo9eYY>+Mw5Sczw;gsV1xzY~?Xnr;bmxe~Y66 zJz=m$$iPsjsbft*tMH4lBt1^S`II8YdhE>($*p%)UGDi-v}nYh;k7(C>MS6%fOcAfR%x_@vg%bra9xQPGLJ=vcx3cq_5@VX6+QUq^>5#PPaPlp0F zE_W!b>JNtk2i?XW9g5N){mBm(!n*HUeouj5B@>qUie;&le|}GaL@#$0>~`$u7ueZ2 zRxxiDQx=MVfy6S#(>-h`R8N{5RG;knb7t1I*x13%bFP)WuJN5mGpAujk1l=!Es08BDoHvMVu~3%qdI~NhvwZxH6+U6f+VSXAl<| z7j+~&Iw&?Q?huz*xobmVZbosY$oa~Xt#QY=QX=AF!egU@V?-D_bSuX=F8{Domrf_- zB&3TTOO8Jkmm2r#v&ad{V?`N-d3o8@W%)Vf=|`esLgS*iLQl{y7G~w2Pma!YH!-ty za}v=tryX<;jZZyUcRW2Y_vE#><6P;XDSCNvV$;xppk8{3fzkc3c?lm_0esu{)DPewicU5%;c%|h@ zq(fbZ?j*9B^khwgG?YY8leR${!;F12i5?`qKq}EP(8S6$(9;!5kXFY*RMqid){!XB z!28I%v0e(%px`yGnz*Kgk&ZYMfT7Ir_VEUja8QP~7n!EaP?Kg2Q3lJ*WIylf5tISz#@C`yAJlnG8e|XQ2gj>(tdsspF zTwDpRt_Z9f9Q%DapJizNWj(M1To4J;0W2wl308uiE0L-ut!rik)%Bpz=!;1|C`b;N zG_bV&e+w&+H-DxA$j~J+sDd!c#$d|O?SK}TlX4cd401ZqfC_}--C4mw^gJNVC z@n$W)w3aHsgNq6M)bA*8?pPhC57Pn17ROO zsuxSg2;g107mP5mW z7Ff#zKT-Mv%UMmJp#ixM{4irU2=rh2{CgAqwB2B8Mol_^X_c}2g!M}sNZDW8V4(H-wG9D-{RRi7Ab*ErrPlwt1`3Y(eO(k1%u4+g z4yg$Hy$y!`ZLFda78I&q#v(DlwJD*Q_b-2iLm2}Z68Q9^Rdfc$712j_d%!P!IUu-d>jo0EJ=YxP!6Dg1%(2>NMc^I zKmmQS8wJYLFbgmy*Mi!qV&O{KN?PE~wY4w^3=)IUP{isWv^7vLMHCtZL*xE4gah-j Y6OE3i(pka>-ZY`X$J$cbraF-S0f^WP(f|Me literal 0 HcmV?d00001 diff --git a/paper/simulations/SimExp_ObsExtForce.pdf b/paper/simulations/SimExp_ObsExtForce.pdf new file mode 100644 index 0000000000000000000000000000000000000000..d74de9b62f599dff7c4c0021c7996ceaae8e4ef2 GIT binary patch literal 111918 zcmV)|KzzR?P((&8F)lO;CCBWKq6#%2Fd%PYY6?6&FHB`_XLM*FHXtw{QZGhnY;7~w8TnuSTwm$Wh5z&a{>Puc z{>Ohe{`}|v`d9k%pZ~i4r0Y+vb$qoyX-w6bTy^~UH_vx|_+OpZ{FlGJ{~DuwmD2rh@z>|yQ!f3h5C41o zwf+0J;==sT&%flDKi7WwpYUG~ZWE7M{ZH{1{`nr@ zI#=%ZsQ#C~5{LYc|K~sc{P|!0=^pm^XZ`u7|MZt$MEaBR{JPTpQ};E-On?6A=dZv0 zKY#zHf4)C?e~};UUnyOy-XH&`|MRbZ|F?ht_x4rus`+pK_3!hmNSylwm^Zu0X6{12Z&IbT!0pKP}L|M8;sPyF{^)$xhf%i90#zyG@S zPwcnN|IYUh)Op-p{QL9w_L)<7HeuR7^O2ztsO?`*A=-p$`^>-g+Ee~BzwX(wz54sj zk9%g-ultej*Z%MScK!VyEv5T)x4)(M&-J(bq2=?Rm2dnbB)H%|?*G64{8}?#_t>qk zTxOv}{U4U7st^C;`l`Lxt4pT-_CM>N=bw&$Enla``Cro<@z4K?_K1Jpf8hUz{7?}7 z+&4+_`P)D8g^|Di1sWM|;vb2mQ_KPqacnVS|Ly+#zr7XqKl`fx?$#RD`WkcnX{&wp z$$_}ZYULsS;(@v^*^>Uc<*AWC-Gkh(dybpj+O0Jc4QBnCsRy~GW+w$A`={NrxAh?7 z!Y|*Vmuir9fO`U!`=>CLS+{fF=5;^79QXWrNb3jbUsu+J^C~8M$Z?Nz)sK(+vC{pS z%hMaAUGqgI?&rScTf9luS84aJkNexDnqaPNBwxG_+;h|L+=O>{4{>cA!koTx!e{RL zsw+sF2ho7zewv2xCTnOk{HpSOXSnh~IPmwkuBPkU;)^Gp_kAUfM!rQd^@H5=bn=aQ z2ycK_u#YNcw`kq)cky zOTMqO_yY02A{dsFP@aZfKS;U7=O(kqtGMTK8ItBXl1a_^AouWOUihlTpx&d4F)f!h z(ThQ&^sk)pVD}X3ncus~C@+E^Y4aYI%y(Mu0nUx@0!Gbb&9==t}o83Zil3_dp4Fz<-PQtK=4c($zMH7m9EK`(8|{}HLpCtH%T=etD|e!Cb`D1_?8JkCoo=O%|-rMzUn^);U)% zCNSlA$fQ{_!tg>-27u^%0Hnb>P-=VF%5LNyMryzw27QDD{g7qZz9qrWV0(EG+NXQw zTU$(9$9qN;jm5NeJjl%Z6uB=b(Z2na#G$wcCG~m`*(D4PY>)^h9mK!sJxm+NgS4zS zmvzhcf6YGlcJbatXfHnw#w}&{qiMi=hj&EhNnA+2f3Y8uk=FJplCB}^n#L3EKUG?l zpR~fL-a16{0R&cLBk7h5&BiKU;U=7oFbJC0%VzfTc5b4F-^rq&wvZ9m0$&|6k|Yj8@u*$;_ydwlAadg^x0k!&!Mq(H)5 zlg;Wzq?RzsV-*t_(GP*sG3CxT{ZyDty2u7|?ckQ2%WqE)dOQ4b{EB^35WJL~+^57_dJRfI*WX%_;c1q;`)H@)++@YzV zk90ey8sHtkhsE7wy@PDSc&piwQV>c`;|PiLBoCw|U1xc6LUkG_{=8^BZc;7@ac=qx z>VZB?<`s&}?nkkL&O|XL%b*3q;8`mao63VwmEa+Yf{Zu2r^4;$XNBI1_W-H`wGSDbWi@W7 ze&WxmAFH;oP@^RP#c=~tI5{MsX1+uE5k;T5=OwJpZTw0fL11z>Qt6M;#z;ykbkE{| zbxoie@#s$AFH=PQt>%}Lsjon6gl`ir^A4h*^+SfU1vim`uJT{-pqV}ji0sf6N}$@{ zZe-Ex=Li;F=MEVPR0rn6FrdNR!Sqzr4>g%k+>CN7ATq8W;)oUU-}J3Y*A7E*%Ylg^ z)(?qbbl4%N&9)SQ+<3?+FEZ(&G%9M4`Akj)cObHyJE5cuypU=_frAz`iD>jT9GW+G z2yvD4A`y)yJ!!uuHbOV}MCl=p-9BUu2}WmLqV}R+N2WqbvD>~r?AJSBpgi3UiQJgl9k-rjDKeT2 zML-m|R!6(__WuzZ(+$=D4O`ufWX(yWMR?(11B=VZunZg6jZ~(g=&tD@M%dF2=})LV znOy-am*2K@6EO3N0nUm$-t3+aj%FFUmk zqLB1MCX=3chN2O?NgHxo5Q~8J!gVZOFau1dg7nnsYNR0AE zh8@V8wGND)_al-nI3bUKh>kw{=4H?r!_xhtUdH?sX577J=bpa>3DR}6*3uRBj3N+&rOCT?1>ve+BhEF zh8EK&50g~NK^&06|7VcXav0H_(A~dPXlEwBWrwK9Q!;=7krDln?A$<;t8x#qMQ%`n zMdUz#NV9--d&eL$k2~SYN8}{i9W{79O2^$A&q>|RM-gddy~vQ<=A_FyMuo}H{Voa~ zQ%1D~S?NW({RQdo?WThctx^NJi`a zY*B9?NU0!__5#eM-7Zk2F>i4HAr-YdOW5jUUiU>{R&crAO(;1%+e2x$``@q(QV}@^ z;fwi@X0yxXkYa)u2I~YGn|9Azteup|(16hBB5q=Q0z#v^k<7`18w}!LHs^TIW}}-U zsv&{V-AGmH4AHVAu-V4m^K1DbnwH`=;?VVqWEBV(-ZpY;a7fdwX*l(o%_ou`d703B zehA!uWVbK)X#7^U`MhGOkfis6c+oFiUSI@S_tdR(IX}?4Eb2}agTiFX2>?N;0axx~ z(xG+P*qw9=EZhTSEJ6D1oxl}VatH*oWhaU+;VNat9xwDmfW!-&uu8v_WR!y_;;dZR z;`j`Odlfl##^@k0vOCejDWZVIG!s^XAS?KcGIb!ZsXHlrlL*_IuOkx*zuTI8$b_Ec z9_v30 z6zntbuJuh;;&qzT+)d!&A=ly?T#7G|gzJn!N#;68=BF{rwj4_VCQ_UV`aobrccSRH z=Hcj;sVB^?+YwW4`ui8V=ML&`ZkNkO^>!?9y`6MDCvuT;)u;z@+Yf7s=NB zzp|XM3E+* zA~#(}MN3#*l|=!8nb^tVG5}WnEh|;V^dyrbHeJ@%t4t>f0UD!55hT7K2DMiX-nkg5z2hMpfYn2yEwveE(wi+^GyVQ8}Sd5|yKvAY9bHrU|Uw zP9~KzR>M^d*I~q4=WxgpfxuRt1VO?r7)~Jc+lV7M77O?wvYv%Dya!q1AerLA$`~1q zChG}#R$$XvMKlj0uLngXN^$pw7rNpJnpFHwI@PplX_5)6XGi$tB)4(eiS83sI`RyA zo2*>JOV?T~2&VA{mShM2%fwUfvXv+#vJ`aL%AIIQ3bj~Onz$z}2eC3nR-?;SqV!6x zJqYr9JK>TjN^-R93xEg#)nilBxXW0c1S>~)PK#jgpWD%7>oScefvSKESbcT{oV+sq zx87wQUj)*1zg17Iu7DFYU3MJq_limiK2{qhkUUnD>9>Y0<~>zyC~ksM0M=bqeMa#m zs?IbczJIYF5xJCs35zVzSTH-sFky-88)vQ8Im8@MvB0^ z?quEqbUz2CGt)+WD56B!;57_rT^}$NPqL&@V>mDWc5&>{rw!?6RJmAJ4w5Y`iOWhL zHj)Ry_~M;R=_eud9Vo{*s?_YCh%}Mt#|=KIHosyJyyt6JJmOpgFn}$)X}% zh4BMrMzBa5NuCjdIUEs4(M}YU;;uESlMaR&hi7_bjO z#UTS#MU8i-6gUAMX(I|qA#keg8cE4CTqaXpkih<`ncN(@2E6~!L_nD`q&{SF^W^{pe@sPgTuAh0YONeme= zI0`uihN%}mxI!@yn$Uw#59O#Y9LORz=ZXuJItI!3DQ`vvh zs(!%WJ5Zh8zrK*=m@Yn}IyjiZ|)r*0U0Mq^+c{yj}mO3Q-PQtJO z8#wfyZk0+&O4Y^DAk))M24fT(&y8eB8wRcDI)!PB!sRRjTGJg+*6ur28P6zO5ygHE zSxT@k)ZB#N!;MijhaH_5z$P?sD8Qj!tSbrD-vtRd371)*4fNWC6OQh+kBVt|*0 zwX6?;SRVwEgx^ZiK*(#~6BxvDTxDNR!XWf&jweU8eZ87}gi&o@Ptqm*h3o&L>h5p# zVE+sR_Vgr-IT3bCPgPq_>^)*Cg@nQrb$6pFsOO#`$#t`}JP4M@3d=IJ0qo808PXJF za)%P*h;jQOke(}fB@2Ki6*&+lT0v-1H&VD|0Nu19}jsYrbYp^rkp8 zFE0&_W(#^{B_s(j7#}eBv zlP^mKVc0fak(woeZ9E9%1kWIccMRD^jE)koW3=QxG^xJ6Q}SGAfZ+LNun9MKP`AID^Q5en_U`%1;3+ zhy?dT3b$J1^>`ptE`GV9V0oZsCI=9txQ;zJr;(u`sUy<$`gg=_WHa$C1)<{}%}VLHoRb2X z+#CKVv?U995t6P#!|qEXIDOe1oLkr&6a88ou^mUi@jK#iXSY9%9|su{WTUzlCmHa1q6%^>q07xNz}Y# zT6dyA^@`%@d1;ve7nbt`Ld&|5!JI29o{FAAb)x%6WLS6Nz?8Xm-f_~h9)?G=9Rx;n zCn}N0Q_1m|DKjIA**+=FAeap&VUh#Zk6F)&s9;uhCXin~?fF6C6~>dy@*+*m5LDzc zlPYa8SDth`ovUUik*HKEN{~VI!Rg<1ok;rbBB7cos5J$c>jYEIgXK0W0L6Te)|*)Y zD5OoHEl98FAl(+JTBA)w2$c1)k@o)Ec31m)zkjiNhOk42oKFScAgf3QR4z3Ua`D9+ zgf{8&Mz?v#4khy~NS)52dK!3|N=%Y8+A-zWXOZR2SYMXl6j|P#gq>~P2{cPP|FRh6 zn9oSiAyB+7JNzJADcgwSPpF=yZ%yBBvJygBQPOm=;woWMAA)6r);KV7Z9tktPp;SW z)`OjB-40?d+c;5F)a6lH3si@s2Vo$A9ehdODv!6LmDE|o#wJ(ifyl;wNb?AH$5|jf zNt-MarGE3XMPRx%XeWwGA)|^FL6)5B05ZBeSsVmBglA9<6Wg8Nm@Q1~PV^?0^Ukx$ z?Z?#g5VkO}AEJ66f;&E~4n*_9*D zPrcjhAFKNzg&|aRhI@APkI3Basq5Ipx`aSP@$61A&1dXJns+FHRT?NKr4c}6bYs)g zMEy}oZ!+rs-n;hPW9lg8oxL-U$7g?lt!G}ZW)etjfvXDN0DKpfseMMw&V!`qF>PVup1!G^4O)RoIX*+yBu*4WHhH(6|jvY)ci*m~Ns$PP%3j`vYOPeK^ zbAD{D38ImuRJw(9$>=iatSPf(bPu3pN^{jY$f8R;?X;}O7AL2lNLqgpWlo-vv29=` zSdQ3={PE*oE-gBr1nwVX$@Y7N{a(%^zNl!m$_!9veqDNz6c{}ZX?B$ zE<`8Oj$ttfb8V0R0hnM&%U|6z5u5lx>*T}SM=i^FVc}>gPN|sYnJ5jm18t^QVra}-beY9-C zwYvL%wPT88^8n7mvcG8xs&%XWO-Iv$9jnIV!qIxN@=+=JIm5H7m;(MoL#9(aJL0_$|LaR6cpB?nA0qdj>7R z%5n{`4ETVhapzyM*zuPlVk8j#PO?n#PNp>BJ<4Sk6J?e^WO=+}Wfo*{ZL~7lx=FE} z%~3WA!o2cBzJIZM3KfUR7+{9LAe6rnW?>au(S!UsxDgoD8Q#rs!c za5bCR97!6I##g||aJ7uhE?j1oI&#?xE}MK2+tiKd;c$C0%^)m#LD{e#ve|+jL?ROX z4OX)Sb%CJ>E$BvuMWncB8ALLYt!BS}v3m+N+u3_^dBB?O>_)s&JDng}U2!t1BxJx> zS79-fmQ+i3vC0P|*OF3ATEd3Z-X_zi4{>mqOp{HKWzT#BPAS6>B7*R=0^o-h@m2YuLmdgky~%;FpHF zlR-cfS%J`^ZltJU4R*K~(0qP?qh4r3IVr=oGIwulC1DA{hbW>&#f+-0*05!?))Jw5 z*vRBQ6EZc{48xcY%CALH(jHV-I|w0I?@(vrbp`qQ38!MQTnZE zv$v6|dLrzj(D+PSxtg`Tc}*L-0N-zP&kH02;5gK%T3&1!Cw*$2J8cj*GF(2?Lg!A2 zG74SP(S!t#Rl_@*ibOer8l7c(Sfg%nt;_X9)%n)79CzMhYTpYBX>cxTv&GGRa&oLNx&?l&iHA zzf#p|maMRlv0oP?#b`W4n&Yt^s0N@LHJlz#7YdWwNz#|+pRzF|>jZ_3OVOB*#+ZaU zJcG7}=-Y=#mS%eL7-J10@eOO)S){*-22io* z4KRBt%4&~BvNTDapTZ8eH=$52*FfC_nJ)fRO#xOq0P0CJV@m*fH8?ehz1#N0@Ko>66q$; zKvYCBEh2-jMjOUS=%`(GEN`;(a;8;fx(Yj$QQ+1JLfhPx-ns$m`Z*Ta^9VIg`6Nsb z;09IwB{EKe-S(Tty$SZj@iWCYh!Uo9l1>3D(c|+bOdQb(^C+XJDWBw)Va?E1V)~uz zN2JW{Q|W@{QZ%7-774BKMqmUeW387Utm;gUc0v(Tc@yfi=z)3@Hg&^iw5#zZFrz2w z)L5-Pdc}JhYQ#|@^CTliQKgGFL0?40O*w#L*#L{9id6x>_r|@}P~FRu9T%)`GF9Q- zEtvNN$?S8B-%QCz?dy_$_MVEo=A?+8CXvJ&b zUJFg)%a3mL-kq`_sS<(93Lo8!q?@|GHPG>xFDCg0QPLz+tdzb;KLlqe)@;d(YB!My zEm1ow(%%HNg!h0QZu<3Q%Qj^XPckL&&$sU2 zkm9`p$Q-)coeAB{gLG{*(e|O6*!qpX&fx#}^&^ z>oImqCbCAY0ST1*Ne~g0DD%FFOeFR_SfH>(P);&wqUw5FO_t*EI$BdFVZP%a6pj3t z07MEh$4Y&sgfaq!y`DNG^G)nLsb=RUB~-Q6Fi28)6K|ri6P8dfBUhxym2E^%GAVU- zF4H9=iqK#q>m>IW^3m1b;0D-?!Wrlx1R3=gQI}NeR6wq@T3yhor4H z>5h6O%?UO1gImIEDpJbNb4pe~s;;9Y2a;CbWXbhb?cGfZrMX23(M{MTldiy391GE(BQn^K3KOegvgD4&n;Z>XmhtA{t4vbC{Goh1DtOAcwRzRsc{#q9Sx&lkU< zcFg!QF1wK;g%Ki&3MZL1^=~IxCr~uoT7;A!U2{)sXe6VZq)PsZgQkSuNn`h)L3%%l z>;}45Xqu;NTfD;5fwc4{LoZ58sR?He4OyEIr7UAyrk9jSyxVFcUD98D&*+wvIf=BS zO_KXb5FC+cb(LgVfdsMXJ;>C~N=tuXYK|i)M=9wDh8M~5+2rXZ=oU?f?1{$16{KF% zLsmM;pj@!aP7dOL)=oz%vc(@YO)}m@?yIbRsb-{T(UMhm_asHHGkez8!EmHx@5#N1t;iGRkqo*V z&PIS(o5gT3c9O$0R**Fh(qyiy>kSF2{AVTPZ;~S3?tWMB`pPe&oM)&mv`ZQ?)|QiwCXN!VyD zFVeALLYb4&gDOA1iK4udaO8(qwr7|GlwG{J1mRfw$D zqGz+Zk;H%`KiUh#xp$Smh|H6eFE8+^T##f)g*YEUGT&rr5|sG$rqodK<{Oe;PSUBT z^KiM{O@^drL=FXnHZ#cgFNR|v(=&)(Rmf?DLbX>xGT+2K7OI~fMKsQ*YNq7upf@(s zh^#kp*-3o>3yA7799gC|_wb%TQhk%`!j3e8$aM=T%(ApkG1X0E15VPc5fl?;Y{pg* zgp*)d4O_V+R35NiVA%omPs^x&5@#d|itW7Qte_aXHhh^Pqw0RJCS4AWz1R%TPpul{ z_hu%CDJY{p;1^lS55`MCMz%?%l^mqL!E}cT-EUE}TXV$GI8QXoQCC4bNjbr!u0m*+ zSCG_BvZR@stGw@6@p}C!vo;>Jq-GXepjW7vtE?kFQ)Un^I6ova^9Dh&2v^0jh-GFA zGPEpwSuItW(1(2gVwhA_@okNrlq5~1MqWP4+*YAt#e!E=$p@B^iN@enez zJ5hA&bLvPO-98!ETpith2sdZT>$ECuiOCdH?fK0#)-D}H(QPfy3~E`EA&QS~A`5yF zmn&%V(oJftklGgJ)?yKEBZ_?-Hsq%8_9@LIv9fn|6=bE8D7?*43_wDIkV6GES=~Is z=97$*Eapn`lYq_Gc&$ZMOA|tk@g_rN*eTPvfES%&#VbU(`)rYi={{gKk%}tfsJz{MSxVb5{zDbdrGHrQv%EYIy49S#rRwbs$ zI*CGOtiUus1>?LF2mBHY-LhA+LFNfq->P@hf>gg_Tds9Q6Ps}GQK{8V!ce-*SfkH6 z_LO~%tQ;5pfCqfP(T_npzvbZiGjEn$14N7?Kz;p<`%UvPKsc>VwHnhhupZCgA%o#i znvb)%d+#&l`g{Omn*%A3mAMIwr$XGISgj&gsyU3&A#FQ zX(w6QvWFq#?kg2z+vVo2kbaVT03B#`e@k{BZDM+VNI%JV7U`vRL0bAn^s=0Lz*ZX; z*pFDG#4d%>-=wCk7f-^b4vC;A7Pp7xUqnj9DujCgq#3=y#@oQq_$tNbQa+lIU#%GO}|OgyOTvUV~KiGS2TU ziPYs4Ed1Lwwk{_m-F5KShm1E_3Wsczs5rHA$U^5jtPN<*lvP1`e+ZRiMQx!;=1F94 zuzPIymu%@*1dzowRwrpH3~>Yk4`^wYI>AfRQ{KdD+|RGCFYSe}QNX}mzJTSRCrJ?`t48*enH$A*URY9@ zh>C0#wUMloWNEBtwT?laHsxq9d{PEzBj3N+kH~NbFJHQ9QpEWRiQOsdn^5TLSA0n! zczOaFR|>KbV|hNq7q}6wRj1e}k<`kRuge)Gr00fe+USPwzyyUW4Fq#Z@n$HAiTBIS&z->xT@1Q9ha|tV2*TV8{D!9w?o}}!1TyByOB&91{ zB7mu1QmsYEib+6LK8XTx z7@*}Rom5~cKPt^NUpsLm9{Wc~rZ%fOXNT_JHh<1>l8lomTbaruWoW6O9SN?BEUp6E zNnxOiG_!5elsUeh6$6ra5>-6Id-9Xc#~eGzCz&TvnEkXWOK7C6z$yM>Lge|YTLan= zo{F4v?CMGAynm_FrPmHXmiiOKyTo?zOu6wuEg9w$Olm;y24HV|dG#}!1W=iz6qNGtWYyJ^LlzeVD@L4vRMZydF%X^ zaJ0ry=2IJ4NY)AFmpAXL(+9~s!BRT#Q3RE38`R1|Dh{N#lO(44t`=q2I8r2gx4Xm= zq@AFAsY6%^U`tryrGr>aZlq~nyKA<1BFf|)yB-rqf8>6WA*CFt`pR=FHzKtlv%sxr``;C4CM*n;!;XsqD z?uj->)x}ghQG^MlpU zBt!kv;?)#Kk8b@fFkYa|PnVB`b9yfM-|BxsvSf7SxK@`<9YAgNtO0RiQIQ8A!&!?= z*A*v>lB|4^5xEM>5pz(yZmSRB6VCA7s%xe;QWZub=@5T6HN)^~ArGo9C(+K6D~_Q^ zm22g)ZSoJQE2ef*=;U8DY!b*&>eXwfJeXQ3H|>cNnI~yq?zro9&tvZvhENga>so>b5Q+0_{8cyba|6-UQ%~mcxMKa`vdQq&RY);Dpp3*Lo z+CX6fhE=gG$XF+7Av<9(n(Wn16gDFEPc_JpdQ*?7RC%a`-m>y7I&14B^Ggj5hOfJn zg1Dj(7^JK>S!q{9{B?cF{ujvl1*&?r%5B1_X;X_g-7nYfI`$g&_Kc9ciS9%k7ABvxvvXd|XbT7A5c>pDGr*4*zho(QqNpuBWubLF zhH)csn64a|{km#sMP~}CYm`pXbsa5);`C^$;44xGAhd<~aZr|R;YJ*^jmRHW7cK3C zAsPo&DOH?u+0?trMVBDGoJ6ao>B)iPuxR!eDp3p2E^S3TNmrjNo4Urt{Spr;Lfm5T9stJNl}dDWgr|o&7OI2Qc}W^(rylIpQ)+* z=}pvo&x>|AcDl*Oup{4G|Fn^0`xyIgaqKkG>sOA60^%;EJJIdfjN#nrsnnAv3J#tg zGFmf!N+xqBTt2;`O?$#A({Ao{^%A7llk_jQ=yv7~=SNqmYinMfC|%#gnI)%iainxn z%Qt5nnrffe(mbwAE4mYCLP-XFByaaUW|-dvWBrBEgJLZN?d^S zXNm;j$uf|PlT>;5(W0Nk4HaF=(Oj2wk}6YXM+{^sH{oV5F9ZQcsZx=%HZ_LLrgbA+ zucXNL8f1)<;8aXLMa*}c2d?a=YqCIkIY|ylh-dFKn+K^%B0O6=*X$=4Yg=N{{Ut=s;6R6@7?+lZFQo+hItON~gqT>wWyU-eDg z=hit-91=a%?KMVY*xYR-Ge3chg`8^~5-|^8$rGx@9ZBNu&58HnyQ!;OeUzuc5J^oZX-o=SPn{shP$=c{ zOdJ`FDDpXZLZqK$Ajhpn{2H9appg!k-^{Yj+{g-P3kAE_vxO>`7sk2LZp-@tUUG2` zlE+GqKcC}uNLD&Y(QoI-6o7Ok?OY?wqo&76suWYSrA|CXI?K#!#&lKqyvVA1cE9t8 zA&!oV?0J;5?%8YnAT4j?`xpBGnetYmi8=}UhF+npaJ+PpY4aQgsrex3`f`JNw*l!) zum92E3iTo5Bw5izoDNSirL4TJj&r9|d6TI$rpqyVs^Nu6oV)6PPLP$gu|waJ&1#OU z4aq#oU=j>VNXg$~#QJHEPBP|6JYLVv=blxmhs3MYPIt}ENrq2fNhVrU{49Zkv~rRn ziF)=x;6&*nvtgar^J9!RVhz>}aE60Ce~VAH<=u$m%pCD*=Yp&jtCX$9@zJTiNmsrv zrWbn4rtQcAlBEXQUXa20(U(06<*s?gwCsqbpfK`eaituuE(YQa~lHr|k!nDZR z$oDUXc~Z3C2)i(RZ3dsu*lsy%K7nus5d#ncGglRQ>_W~(E zeS@KVu6-h$I31?}c+~52z*Q)b%D8g}Eb?S6sw^E2oR*sL4^>;(9Z>DW8PN&nPfvB# zFL9A}{@LS3p06;-#8pEFRTktOL^0*{^uWML(@8DP^C#)X6zatGv!CJ(g8lGF9U9COVEn2Vy6jNnI60IT*tU)O;IpCJRY*?|T0_IylL5 z@-iFFmd>_WwxBNFVU|bN8ClZXo-rKd%V(@@B|OC5yc{OPNl zgf^73X{CqElT6+76=4j>@R?5@)$!QShcH;>nKhQgX&ZV)LZr_p>-&(TV`F+Oz~cmJ zpH~*9Wh#6B-J;GY?y3eKUv>YMn4qmWIg)UM#& znsqts-AI;&%w8VvOrY>~98>o7#K8_BLFNgnbixzy;9zQ}e$?ij#ODV+q*L=hXQAC> z#4>wWqNUzzJMjp%#{*mndS@KRNm6%!Bd4oQ0&)!*4w&|FfX)Mxv^U{lB{@=wJeFFf zQZol9PAkB*G9K3x;BF*)O;cilL#dssa&ZvIazRJ;w^Z+V5*vDr@wimnc;)Ev2I3g# zAyc!Y#x4ht(ceS|i#f&}i~}`A^KnANji*#&QXeJ)lC@8LCy6z5pUT4F3Zk7jsJ&uy$;dXgEkc>$ zO$9q~td$@6_ZEWdskJ8=CwW3x2V^*%y4drbJxI$Zk?EMvP7Rzz?PCWWRDzUw5bUUN zkS(P*ikA?3tf%7SY3ClD?ij`4>Op)eo(Gj%)s!3Z`z*G#$$fVKQaM1C1sG8V12R1E zmp?;Gdyp>8^u!+^o;LOZL1x{^_b>KiGSBY~$zTin2LhWgMpcOo&M>r5Xtuo17HyEF z0kg0)FSxE}beb1jPqL&x6-3}fYo7C#9v#HRZ?8fO zG;mVkuH9S^>+*+qS+>MB)ZxMKu-j58{(c zz2c9Yx{oBb+m)+ zBtDT?>ziY!N%$v~JzS-9k|Fc$ja@hyd%5h@WL~j8^^l|q@T50DRz67%S#kai=U~e> z4YNNVQ~VH?Ve)81J=C-%Zf^QPFb=>Fmp+rq4{!!{)xpOum>#NG`jGEm43h-bDw6O1 zo-FZ6YCfjqdeX$+>p~*M9X=x#dB@>JE}7Yr_~6m!%0=GbvpPOjjfw|vZ5+#qeg;T4q_9l@Ck?O)Z);{vwVJyfxL4NY`veHxg z*yszb5@epBY85{^cYgn3KO)Op9`q2XW?*pcLNbE(CeufH7vCV;;-K0_({-{gTLDde zNIQYH$6rr1BMz}HGH8}yka~c8$x=R7CM2 zu2yrZ2d7vkX$jYLf-F_bdYJ>KSi90?BTZ4aO$^SpuIrd9Sypi;4q03D?*bY9BukR? z^lJeb8jW~U#YXU{l$t6-+J6gssx^naNH@8S_)S{gQ-!lA8in**-q65}qVCOalU?z3 zJAPeJskD(MKek1d9mG+F69YKPI?LXAa}UWl$xt3{g~v46%aJ$e4XQJ0mo~DLhnvn6 ze*a>aBGra5K1EWrJ{pRsI&6IkK;~x?!$Vx2^E9Xf8D)=XW_@hsL#py;%|{I<99|tc zYdKmVt~7P-k_TLulXUqX^+Se)?D7$BB!0~sad6@}itWSvgd1k_eCv6TcF7@mD*A9z zbyjTR5S3)Ui4z`nEpT@AC4=D<$ZXCBAEams#^h#KWTm-mR-)vodzTH4uD;3vx|DmI zPfyY{C7o%SE@s-vkc5?RcyV&|&~NwofVG3p*t0Mv)Pi_Z<3kvGvZO#i)N>?Nz0(iG zvFAp*=DrIaaolu>ttV1fgYT0pEmu}MOecc)_a?zfkqN``(pd>)r+!G*n>b72@Eu1` zXQetFG0docDvxya`IJ+9NLLkXOd9z9(@I2F9@pznDYT~>9M7m$kx&@jp?GzDl=<+c zkQuevAWAs9B_EEcc43KAiy$-axfdK-&FJMhj)%lMspZY#(CV(Oh+blvBaE)i`*>__ zfF9b+c@>;tUA5IN^upkw9Xps|`MmuEWU7|OuV5^t5cBg=#*&WykeQ@6*E0~)M)n}R z>}fI_K7A=xjvt>TGKL#*?!#qjIG}ne77lwbo1MZBaTU%}X#p~{j6B!#8AnME8A`yF z2)l6r^+>x*PclxTby)0Bu%^FXLDd=qfBgH6egt~|e1>4ETG9Z^Ks3Mgr4#*)B*m^A z0PzCdLrN4Nxufq~HmRrzdI(?FMq2EeiibdC;PcPzyROH8K4e5T(n~PYM@L-G_E?hf zCQ>@#?kumv_Sn!im&+A%glQ{En>LanapuidAU-wyAw>`ROssXe)ORB-cKO&}1Yx1* zMifZ0_$-U4qX`^b4F*UnzlZ{84-bx%mOtx-YaAf$#W;It>sqlG7lhVB`c0|{WO|=X z@n^hi|0G)CwCTnX(pip_%R?612kdVhM@V~5+eW;cYRiH{rJLjV_K>Bx&D~3IgtQm= zHd6Jv+^laU$CcHc2EKo>ACt9xD&bgZm!A1JARH?_l%ia5Z8a9%$x<;|j%8|`BHg6d zTnfQ+rRzx?UB(gQBFD}t&~o{xj1y%RmB2edb-N;kO0{mKqfSEw1B8GW@k85$Vd0Gt`E zMSn+p0Q1<|2(nJ#b=4ke44ff-X$9L!R}hs%tk2)=08PCx9yfXww-!5yPp@|PxzN?F zaIdCUAeT>kI7!zrJRb4lrlOCB3=)TMe@IgcC$ALXz-W{fwc!j3PKVAqFUpw@lKv(> za&bj${$iLfXi{|Fp%Yd%SpHiR` zjAWh!1w4P)>_913o)KM0TxYdZpL7uHhxvoO_Ac1N8PT`RMiYWCV4W8BAdHl_kKQj? z)kw8I#r`1ofFFdh6Q0Zd8IFs-#{%nGo;BJF@gd*8*pJCPzK8BY__62w*QL`P(0ai6 zjHQw#v>ph1F=%xUax0iW+U@Qy(V)J_twXq<+!_x1od2L1fD;o-1xwht9@bMQH@ryJ zvwK+%M^WDaDfV!OJPlgYgD@b)#(JNNf`g|At~{f!2gy1KcLP=&*XZ$@sLc6;z1Cj- z2f4M%LAXB~4x}&0hT{XeU9&;!ovTK@9?NA2mvK*ScPRLRn#Nv~$Tg zb9#b2xloXMT*lL|6$ea1NRZTD{u0b!ojGzS1ou_e48MaLiTFV7Q-Q;zArUxV?(w-! z_G8kwPbC~D4Jp9_kf-OuNIl0T<8ItbljZvAd6$i#KxKvI#pk?&vZ2ZUiH zcH^paj%3V}(4*%ja@}HP4Lt|PZ%?H|FEaE#wGes}^j81V=$5u1_gg#2gzD!;^Qrfl zY0&VQ9-pB>dy$IkwC8;mhLPCEE%lHu6$-rx2BUhR@g{tg+6pY$DGVB4mF3Doks z1If?`4hvnO(K`r3$i|pZPgO6y<7j_P((6gE%FSQbk{ZdvXX5D9jANp!ek*i{_A9)| z9K3SzlUFWewi;FEB=rQ$31aKC$`10yqr?7S^Rg1{B;^fm3BeX|HGj-FHu~0s*ek5G zK*lN2X#?MH^kdN8-=YjgK$R~Y%D^4QmM>He>6YUSx9jyMUlkht=plK|vp(YSY_zA? z*R7opB#@+?6lz5r*j!4G+p&KU$S4n-(eNQaX#7k7T2E{N*gLE$Az~E%XH!SC!d-Sl&df38tS;n1k8MCn% zMiM$MJ*6vL2rzsn(7h!)5{Pc^_kvXQ$U!ilvAhzWVHnAs$9V>U+|28_aM3fR$Ic8H z)B7&9OZxj4`w@YGeLj_OM)Z9@Sh>l*ADL71|FkHnw&z9q;9gS%HW=4Vnja% z1e=%tU?+631y(uGP8I`5-JNa^Ybs51YCR;clW>&9fShyP3E8etgvRB`keHTS9?HvlgwXME-T|)=(cnfsos>X*PoQ5 z8TEZ63qM@Lv&5;;n3!16j?c&fuIO-{apH3s{ERAuGERJkJYq#I_aGzvBAxQ6m6(h( zp!?)dX&o=)3}~pJ8U2k!`bjzheSAw%@J(bDxi>KdfmPfI7bEec$zz@rL(a!9;+fCs zAZQFbIO;mcizL5DhWqjnbb!|X^rrzp<{{6}9yumeQVr0HR1C)QPU4){T9*%zU19iU zKOi!u&!;lZdA{`z_oGW!CDr^KgbS3NTfa@F?y-iy#B-iAKcm%fk#UlxfljVD%&D-@ zPF)AqL&lpxP`i^|83#X4sn>YRC2KgM0USxoZ!(%R<)tAjtc1nJd)ZikTi@(}p(i)c zH-D#dl4w%_{?rRT$o=L1tdZr!<2Lx2cvpp%67Rgk1JF_)1ck_a=ly!f;DxnUFXQ;; ztGo$^GrNlZCP}(Bj`0?mCqWAaKDI;dr0So>+Nbr9c@pl@M&khc!%3Ar2kBI;D-ui@ zCpcHnV$bwSLwFEHo;>WP2DzsrJGS{U3`N<;V0_4W6M*K_e8vIJ6EZQsd??lnVS@0` z>d$8cB!0~gh12XCRa~};YgwvkK59?}LN8)r3n^$ky1iTFv>Kvj*BoRmDWPmabNeDI zbGA&|u14d^o(i=;WSwL}lCC%+lwh7<=~ebH{yfW>n#|D}K|4v398IsXkSx7_J2^Pq zxly;otJOAu7nvA|@hEzvay9QPpEyhH^*5Ez`uvUpP*edZ_XLvLNrt5=W>}{kP4$`W zoppIHQVVac*kJc15z4Mi%ZbU}HyI(odZfX438U9-6$fo;fA*DWBY?tr%#yt4AqEZSi$IQYG$sH3#V}n|>I10_wJ=zy_ac(EZZj|# zQ+HPUrXV%F3B&^H;8v_mTXQ02zx8SBx{(YyPUFjCs=A&N42kH{@60L<7020S9Kd|# zlXOly=(U-HOqsUqDK*)d^B_Z#(jq$rGUbdq>x@&HZG3k!-el^2oYP8+Q7G?6K@>=6 z-i-`RdOM$3^Z$eXC!vZ_x77crolgl;=bQL#h8u>^VNnLVg?kl=Y1E8moY7p$FEaT$ zv!xPQeX24?p^3dq{`BYICy{v)^iQQ)?Yrb(R7!D4tonHEUSX( zAYI|a3L}y)DSx!kW6^o$QO`>uN9sZBBR>RzC-uyTzsuS|VoDOPMoX(XvquY+l{UYT z&~hFG(!}g}6Oo-nJC9X@&`utt$cc6u24w2x*k#B`wldAnm1QeWk`Ix~>0>KL39?S0 zvB4@q^-sZ=X@-sf^Yu48K-O9McRYMGLIs@PEQ96&&o-tXkddmuBWkslq`g6}eEr&1 znQ`iJk$;WiBA%8~=hQH*<$$;EDzwjR3ntno?%YGUI$^tg@Y?>Sa0kfWwzBDQ#=|=E!shL!-W|Mw>&`_PJq?)_g|2 zUy&W#2$O8(QR`}*3Tcn)blcqgO!RJ>yOAt^t+~LTgaVgc3z4%biWsI_m^%BD9i%Fx z%uWvH&H$I)A+Lw@dXg^jx*i*cUBgNgB@0uh2|37=t*oDKDW3i00ZG=IRQV|JSlA@2 zWUF0koU@Eq@ghsflK2+m*Uki{gnMXd6+@_G2}n|e6*GM(KE=0^uhW>HYc^@4DPOn| zbPWH4{-7#GBboZ?@qA<*e`^tS#zBi22P*S!qah{9Ji$`l?fUW)qR~-jZr0@!JWjc7 z>F7T<_)TCz6#; zlC_Eu8&5Oap(YNpQx+uSO|Y);RNZIp0>vHX$7@~e@(ICq6qJ{9y&LJgGM6%Zox$mV zRk2!wU|nq|lR2|{E;(S}1}&{dTsc5Z8_;%AEo@0|dPBvF;7jAlDq~wn(OQl67-rPX zCoe{<4;gO)F&NPSB=a00t;6V06A~|&%=ng~*poCZkXd>0aFuEszJUtUqcRZNg9&k70#dT#B@l#mriN$}ZH9QEP$9>T!E$ISB$=eo5+#{eU$Z zwop73wNM4yDPgDfrgd6>NtHDyf$Zxclk0I#N}w^iwbKfsrPKKsP_=G934>NFzd4P= z!%C$X)ys;6i^K(ng;<%vw$D&w8Z}Ad-lEKI3)ThcpNs<#GmqQQe7F1JUbanhY(ujtJd&o?bo4 z)WAQGLTPyc`rfTWesMf)>ZCqort>+gTDFCj2H?y+=}Q`l_8~qPJ&^3vDwd zfY+)()(Low9md9SAP!H)dOkYK$SnrJ9Nx*I;b2=24Mo)uM-dzUZZ9xYZD2PBry{56 z)#wxii%B~v%=x0oSe6bu7K-Xi{8|)woM34jT(5>Bky$GeyDc-$JEjIcNO66Rb+US? za#AUpBk6A_!)tCG{)3 zDs0Pe@qyodV`B7825YA5fMS;j>qMHX@NXikj5?t8fPMh3zcwC@rMHAta~|F1dmECV z;T=gNEx*ZYL7fP?P1%s6n^CpG z48UTT4;T==78|s3(VhmJabXqa@}~_f3099R0**qa2k`{*Agp}ZNa9Nv&k7{Sl!guc zK4hQqtV$t+z&`IpwZr3CA1N$tzps-Y1MOm`lXR8PWUCt2Hlb0kGAJbTO(04wirzCe z3c*f{XAu`iAyf5Tk6Dl6rh}kH029Z0Y{)?O$BV{3Cai6q1Y&_zMP-<9ICA1gv{99S zCZK)U-flV4Jhbq(c6ujrd8{UKPbtmm9C+#k4YQ)}I14lJzFCtKkMMh06USPb+ESA4F#T z`BGvL%6Mw`%Tif#zaHC*XyX@Xhx%eOPZB2pK=|O(#ianN9iXWw)9+xh`97b}yYj9- z|K=|`%u`_+_jj|wA7+xkzx;K(%k)JTACavS81sgA%0q`y@H?ZOE_dlSg<49n#J>HV z6h1D48%`pgw!;KZ@q&rZv)_S)lMV$Ri^mhu5uVRwbYRg=)btD2kweB~IaxXvt=i(K z)%I+827ySO1erVhy7XB|+WZ5%u8GEDXs^DL+k3`4V_e6o5gzi+yxMSX7rt^%E`_99 zL;_8@k<9hH_Vg|USwj({dZo~xZv90#@GG_o^8jtuJZ1McEbQyk4?=&UvEy(6yn>w! zT05ObqMwqp$RGD(O)l*3WOcMDTZ=s;QY?(|)si3bCipQ1U^7!XlsY zB6CRKw08+^Z_1ikst_cBOLY)zU1-snp1v}(22tt&Uzt)dqavT1fE{9f2r?&lF?x)G zJqMKb5jTh;pD0o>VWU+Zki!yVfa&543m0m9vJxnYIZ0+ZNVBj zt}E*d4CeJ1>z69GeNzur-Rf{1Wv<{3m(q7xVn?5%3Nq<098gx3)K>pYIK)FDX;EQ| zA0=Rw%p{rVAeosjjF(nU;r?Dz^Ga(k+{#?jL6it+E4iGmG}T9)grWj7uZKWA&ZQbj zU#2rjvw>m#;R<(d;ieLdjV%RPc-9yXhr1+m?WC(o1TLfH%)*X7=^$B3kXK$Nb>)qG z|6)HRjSB7az2ZTQS^+q-D7B&bVs#QpD71&5+t(-22=|u5jEZy3Em!WqH=uJtfVAg9 z8b!A|-vzRmrh>lbxObgM^{E>qsq;l}JUD(_gyVzC3!<+ z$~cK`GBcc!T%uFlq#P6!gP<;PCs`6W;uIXZ$tx7vw9G3+R$@XtjR(R zV)?EP6M1nTvZUfLduKPH4gC-l^LYD_ivMfU=EKjVs7YY5)&tK?qk-fR1=|b9O!5iu#wyPVFVrtJRu{DJm{SbBI!!0WLT~nCNrWJXDxpuHv zAV&qt30YC(;8DPS^y4b@iOqmDM^h`YIdY-*p_MaPubfq6{`bTHc(Snr%Qo zBARVL4^lat%gecF(LphW#TvRhm%i>`a82TorEKFkv#a$<@Q^T|bD4B*Hi`moHslyu z?XV!{Fpg8*`fItQwI#!arS%Nvn*KSl=Lo$=F5iRD5N;%ULdAZnT2zkp$#+y%X|REfro zJnj+lX7^ku4ob1^GxYR}G5<+M(Rz)x_tY9eX>6dW)pmD9T8V@*x)Uj#IIO)^1sNah z&o(H@%eB&gHB9kN^v04``)ZY4()LA;eT^`6CwVE#(=rN3yfM{&q00!3Ggj9F&^CX- zWT{Vk4k)YDMi)!tnpZW9?uV$*l1t8X18UQPD;EumK^WZ!$Ytx!GSwzqOM6OdRoiA^ zO(JrgDl0)Vli1v572U#|enokCycOfMKmt?ahNYS)vH4j8gi3|21qob&&W{I-4uCpzS^A}pW1EERXNTXl-2`?*r*30Ys61eG@ zbO(w+6C+3v)gQ3Hfy2wTKK%rYHlM5@TFJ=RT&`e5o0#jGFT&*ON0lxcQQVDG^7=%R zBHzE*Js(!Ylf^+in(1nD1bexE}Odw zq`;jzM$R?-v=xLA&l*G3n?&2E4H&kX&>XIFO8d5H-Sq!=tODFpn*s zGvz1x{t#x+u+Hbp6sL%)8;GJSOv!VzbR^!(`61LOT#(c)Hz!*o6UXjF5t4GElSD{r zqKJ$ER4*pY6?RKy8!zMN*B2G1S z9-8GK*^Ww-nxOTM@~_2aw&hPAH%NN~Oj@tyk8%8vl{O9BvN!I>rYtmIp0ko`k z0ViQTHaVS#-ZJ?}GdC9M$eybdjKp^4L%RJ7OM8hRHO{C;$M4}TO zH#_Z2?<3chtIg#`k~04TZ+lKwLxq6C*XXUmnt`O- zv2?cxUq8gb>WWgI)|3s|NvCGza)_)%i(qwmpDv4YQa{LwHU)APTa$g<2;BRnxKzuG zt=m36U4Kb@gF&>m_u1(Ivb+)$pNV+#Ln=cE_5ffa1Vr&W0Tn8& z(i@d{cU#O4Q1sY&08}y=9E+w}UxHCS;QNj43DG~{q{4r?Fy7IpK$?0hw}ZsOXm>gS zQx$T73&&?^}z$3^5h4YKh_^qhCq>twX5luB4G;A~R zbISIeU}<-hoN2l_?42l;?%w2Hps>>1&W@dwST*Q9NSg;4ELZK%ahV`1=WX*@zhnhZQl{icNpvU( zX|l^XNxq|NzDO?GiaG>j^SC*P!5#O4UHu^HPm_zAt#Ai9Ugt)X1nRkZ9fDis-QJ=F z==~(Bp@Ix(#`h#^wiAVfJwFegR11LXXfFmkMWp&7Ffq6t>51=O?B_3Rc&^r(Y7)vV z?P>33K+^k*6t~mRq~aFntWBg;(70I`0d7VeDagn#f~9Qkt)zR48%x}<8c}O!%O6b= z6)bhO{3&nJybUP4ahxzjORv%whtzg#k4+T zMoR!4CHP%qQ3Akto&?4d609=qj*5FWh#2-zdQrHEA6KLX!l&9u(TvQ`cohYgluPPg zl389vil=!QsTT#8J;xzYz1W;SeK$yEI*5Wx_EGYcmHWn1FrCqh?CS;=t8_S|%+dEM zYkCsAM+z0Sc&{>^nBQ8_BbntOiW2dP9sudwfbMJ1R-yJ{7d!Y=h%ZA>5X z{fpfbscP%}6~!tYM}A$};4T~7tE}lxRA=0uKJfi^l|eIn;JA&d$n#0_8~f0uRkYc^rpiFdX57PKt?-&7U~{nq<7m>T!n50 zNu38tkHNBbLrpCjBIVes)VmET)QL=CR~h_Hin>EY9a-<{49*4@zMcBKf)ByHLrDBm zy6tC*y_F`E5X9Cbu+8(AXSE3R?RVNUZsTDC&}S=j$9= z(t$QnfYH6^z7vI+AgXQbNMdERFS1q|Hq0BDEbr$nGu_;WGP4*$dq~5E`9r26PdWpd zBJ=Y7#73V!ZG>|qph-M}K@@qi8Iat985VXY=y?I%Z{sw>o=z|R^cnVaCzPgig_|_JA7wzYTd#h0EVHPzW4NIsjKeUe%J zU$V~R%5|KH()-_vvfv$J1}x}(ryHIAZ(DZ=2w<+N^gX2{l0Zy|;YFJ2&E*h&euCVs z99gA(h0YDXf@G!_scdu+&7gn&uwN3aNH*;7#ZPbL;#}vxteOw9v@&yeSRgW3vlG7u z8w;(AB<+hFZF>gYk8}~av2;j#F`;t4$Si6OqGqrI9>~(pRkUn8p`EkuB8W8cMc7TJ zIh$ZS;n+qs$FO5e>w(uk-1LYYYi2d!BFm9XIUc*VH(6R7@_$B3>W&m;r37nS#Exu^ z;jx2bvGRZ4c8Mf)UZn1ADq9p}xznJ3ad z$X$0{_0J#nOTz5V{VtI1?N5VtWX|hody3=8(zGX0R~Lzbk%#L~rjJ)fcJvmR{aS0; z(c6otMkU$|4>%E1EpF7zXRswue-Szw2xn z-iZv!rXD4tT=LSmFc$~R7n$JLY&xg_a&P`VWKFLfMkxSi%E@(OnJv8%Zjsagp>2J~5 zVl=s}Y-6s%~db&NumzysNF$@^m0Sh}q&}f3lS2N#x2R zo~}fY(WM$0*VUHj&5`vl87w+vmw{ry43jUIzMs_zLE5L5zX_&d8XCV>dqpYE<+eg4m7V+Ta68X%8O9OK#FM(V^r|abJvmNh!TTM zCi+i3YGt6J*!ft2vZ_A^8RbPNby^JFn~!s1dKB#Z{9(TzqQfAz)p+!6R=gLfRR`g6 zUgu*qiy|-XmHAlB9;8REkHSO%FuWTl!!#3W*@F!Awn+AGCkBmGwGU9R6NF0kAo5Fj z%E>sw;zNwu~X4Mk?M{=A5?oT@uf%_K)f-2!-_$r=>{ zZ`vmARq!S3S5Z`mH~1(1L`08@W@ zayr69OUy|0(Ou8hsRv0~Iqh*y5r|gzmni@5n=mx9HE4^bHzc^Ki?Bz~W2a|kd7I6K z35ZoH+M@X9Sfw7MZ-peqHXWg1dcz9Rj@Lgg@~hW1!~_3Cjn>)OM^87)9c9l8?GNM> zwfrVa9W7LmK8vPFu6I)2pYLslUOb4@~)f`Gg3Is640KYWnYDi^_O zs#6fE+=DdV@MswY!djIcDH*dWF3g4xeG@j|`4ao5Z8;VKvSb{|{+M;{49_4M!odq@ z)kONW#7b+{uNUD{=#l*~n`RCnHA$hW*{oj=V%L)cl#%$*A8&xiwL-Ip$~_6QiAKaEW>>m>^MMYC)hnx^vkBGfMRL{_mRUDp zLR4)MZ@+GZ3!{Mk@kE{yRntYHTTkvLi-YeXr*oozj|bLOzo+W~UW7?UXga1Pg(+tg zaE~2=*j>(ofvXf{pAdA%wflOchQ-{dio;N)96|w?LLz0TAo-M!+tKR zHFU#<_4Gm1#t)yP1e7_#&y5Upl9etZn;qNTI&D}BA4DMv>ifD(WNma;Wk2kLFExox#zU|+oRNjWTlHZ zV+Y?Qt&0@PN4HSs>tqX`agpkRmE?-=IhAMA*lf54sq;m+!Vn43Vwv5KBAlH$shQDX zOQy~Y&HN=gCxOhckur6ROIyMuRC7eqN!C0GT$H7zIhN=vbaQpXlo>sJPM|f|L&U>p zsq)SgLY>R{yGMo?N$W2{uen7}$%#_W?q+TNle9QpSd<|d1@|YbW zSdabW?NuxsO2Ah{Ifb>-oBfio3}e4*J>fe?@dk)|=j`6J>*>2m3#Hxz^YN~AU zCf&_2itdN92)_Q~dO~k^dnhY~-j4B!Aht9HPybeOpVw^9a3%Z6J^I-$_sTv=cD+J( z!SG7qfH9;*+O+SRv(Yk@QSI*BaVkxZo6V5h@E8^5VYGtsHhJz zchFEG5rkU!Aj@~WIo%3`l`->c*S*o6%UNXk|! zAgbax$&?(kB&k-x=q|z(b`qA{Ut}rTEp@-pT*;*jGW!;s7MFEc*45#%j(BbF81XT_ zwz^$0K!e0FYQ@JvSUEFe#_wuTP_p8iTZ(!OxiG7#ODiId+N-TNRJ^54i!NthQnjnl zh^hurnM`=|t67s?gsWslYl+pYNpa*RdETr^H~IO)K6?oAKjO!_Uud`Fr6V7IHS62y z_Lv0jVq?JbT-*!UG^@*n{$|oHCR6DML;-J-UN52yTD?vjo#Da!+H z7%5)ex^_n2iZ!fjFQQzMaKhF|PD>4=8H8!62gz<_QR7hzH#UPAte-rrTMuFn86}}w z@58!uM(2EzkuM^Ln1{oQ@xAOFkO3KOjkriqSzW%rz<(ULP8;P zl1Q<#-kWxap&_&bXY@Kd$@CaY|K_P)XC$(yrnKcrbXL$chKgJ1M!y6~*emW%vSxF# z>X&pUj!e%#2VqS&o~FkZgfbZY++Hhc zQBKlh420y|vTwU$j?%&^$x6^s@(oD!C`L;$x5_z*yj`YmXnU>d%E$dmEq?f_d2OxO z=BvBxBYI(y%=IElLFztLUCW;Esy^ypYwkjj;ZL5s5adfD(LnkX!^s|1D#{H{&!Z8+ zC-H2N>SaT+ZovMi-@G@Hu3|=&29V4fw3ss}tD6K9vu?7Kt)M8=hYU9PU&|>#Brh;y z-lt?giCa7BgyusQ$6w(zg)4-_xg0^5Bdwn^wLRYKSA=a^ngdTClKv^jUk6qK{Y{p- z_vm2oL)hq?+3?So^f#G@H2Z-1&&fE&w}C>A-#UmJph|LnNYU8V$oKw`su^O*K|vCx++D=7BKAOTn(LJu6#S6> z&w8zTjb#rTzK9FMvH|BZQye^L6OF4={E?))XW;UsFHYZjqVsWj$`eDCy1xpYn^b$E zddm;-AmIprkodAT(cmQx;2fKbn`oQ~AD6$qX|z^%5P-x5G@EqIk{)gu{vjMKOoh;z zx8TiwMOr@I^&yKhxz5jCnxyq5ACo_+WK61;B+r|$i8=o2vEZnlt2FIPkg!|DMJU-K zn)o3#hG$hTh1z0x)+U`|D@V^<66fZP{w4D!Bkp1V4H;R>8k1zKn=F=c;q-BeG!1`D zb<0fTLDe_$5Z`2h)HFZ@u`FLY(w^!~ss!8Gk_4xV>n2Upp{H$nlGXiP+NVfrS~nS- z1c7sWUsp^z%l}%uPVIg@H1x3PBl@EZ>QektL%c4+)b;Knr4LE$YrocBBxrc_2e|*L z*CT5sj%uS1@yNmHGYye;ld9oI%c&SYe;8JO_YBMx0;5ZfUSRz9ozwOKT?75fe*RrU zf1l`=PtyJXEi8pgKV)iV9?u55aL6oh8I8TD=9EeFgY9qdo={`q;}Le=CnzFlO<861NRTfF-ovm zV@(eNzDSf)#9x(vn);i)wx?8K%;_eG!H*lTR3SP3@*!Q@vbef}B#)a6PDNpwP6@K~ zW0Vy5A<}y%SsM9QzZdQ~z(IcgFzgwP{W||{ab^e}vEm*dk~E7oMo5y(d6TROscYZn z<*|fgFANPwdy%D531#knNYzN+=&kf2)|Y7u(q(;l5j#im0N2p8=k9YEl2&e_>5q;x zn|OStdcb^$XBQ?nxE7gj((>WTkXXwph@TP{&XKPzGT(&8RSb>%kP_=ffh&?!-h`hV zz0W_SYLImDfyIYt;PQ*O?m528MT=1)EV6DgJepo{g%99V5Eg-#8D!KyWN{;Vu_OuP zZ#jQT+T|R%EV+`7AtmO z6AHoGbr18y=c$BGyo_0$2f-S|KS*XJ7TzihBh3M_ZXmB0HCbMQnO-k`-9bE3$;xap#PK zxMn{V1{yV~a7)oY1? zp-@YdCwz!!3%i0rfXxfyl_Ob>2c)_E^eTPqPOMRbYXa(+= zPtr^#Joec5-THfManY^64Szl&f7BqS@O7aSok5ZDb26s*$=VqOcD0YY3t5SlGKkq92u-1&Pcz@e!yt ze@2HW9Z>t|BWL@ykuE2)-h>}q!oSL%$&3WX_+&?uOB`Z=r1~aVhuEr_CDC%yIpqgb z1stOk_(L2~y-1ThwyBd*>a8=nnr0A>44U8fco^Y9mi#sc;&PVmg#G!9P2~G3bN545 z%max9U#L5q^C?Zbw%hX4LUp%V+}a+_g+1GNw6`|+LzW_iI=1_e%F({xqZyF;2JYJ! zLZ#S+UEyiw(!+nZ#|lzzFgeK=M|AOPs0J^x{<;3!k=0zE*UJd|I~V&-z5s07>&Pv8=w#>I?;2THd7Jr2jk9 z1U_J}HfLuWk+gIZyR5@an?A%^bnfL>-Ce7kFGg$K3xKd_U=LCvOd!X1OTi$ z?heQ1M)i1u>4s!F$jPnhT(oU*-&!2K9Yp;H;_f|5tUJE`ro$|I6)t8;xTW^h4_%9H5k>lAELRy%!vr# zG_^12o~$H$BcnV@RovMdxN9mfs%NeFy43EA$h2}+LhdSqM5c!?v-f!52Pu;Ep)&eV z0$j|q`1!-IYv4gBzFy+*G&}f3#C1B; zu9CP#hb6|4WBc^2Y6i76+a=qa7}VAmssD65ZC?|htF66b&Ut7~FfG^_q?eoM9CxRR zk*s+h)#c$++#O5EtQ5Y<)T)f>pCnWER~R8flY=opVy#W)n+&Bwb(2YV7{9PvxFe@Z z4IILBnbhbP$?A;~g}x+Bz0y_C`5{}Qha#C!HdM8enAYQyyvfo77mOx(3)sO4iWbN=f(l0$MrttwBaP?a7kp5%Y_x z|Ee&Qhoew!s*;&L0uFz}V|2ze&|_EXVLM_Ik!ooBx&t%Nz(S-r`v{YthDzev+uWK~5a%))k0|Kg>arJZl$j8KQU zFbiAlI~)|m;A{hCC-jW)=hA>jK8sG05Gi>EHJCo3G&*# z5GvL2jH!PKBeS#QrNho3VfA|>BcY3r#)&ut>QEHRvhie@gB~rRnp6iu!Zm>OYTT

    C&@21K4j_=_Yc)=iGZnSza7Q6klaMdk{L;hsRqu2*YJX zDM&xtSc&wTC;@5I$gnO->f&gOw26nhY%*0|8?9%Ke$ANd=D^n`^CTco3GEGINVXP>PXGzlNh-6~v?-T~)Gy8@CG1GnP2}kIZFSYhiuG|1M3PkB zq^fG#NAQ@EZ6Re{R#|iQCMA2(C6O+X^u#s=SvQz0!{|HtA7tKO$()<}j}V|%#l068 zNN+bu|J?IRRlFaPLqOTc0ckh*tQ~%e?Rt#AE^52tMF3LMn>2NuvT=YB*-K*&RhyP7 zM`GM$ND#*aom4q2<1{Ww`kU|x&v4u-lfn6$?bBc+_LJU(HJs72AYn-M)NOZY1!Sdz z{QP0RAaX#*J}(3r{U(j;5|x|2AIgim$cR;Fy9^|n8U>Mi$r-o;lDij((UyMd@CBy2 zdlmhfB1N^ktcYlOqYHFEC?KLoVZy}fr0$LJ$sprR*ybV1lM|*|Kd$!G`2@&Py}46G zs&b%SL`^VkA!E!n+pd%dCe|Wd)}NEGtI0veKUesV_<=Jn-I}zr5Ziro`X=Kd)$ZnS zV*rvik2Xsrz1&3gCVi*JVSu$8qS;KX)$Zm&3cUjazw0J$_vZi=23TJ$PDSQT+CR6L za9qABFADm_=XxabO=32kmu{54`Qw4 z%;}1*Q<6v43$U=!JxCg>(XvFnUWCpYO3;_ z_&L6*Y?JXOSzTdm-eQO~yM{G~pwxJ5hJ%1%)z2T&)OST*8m3pXhtB}_KnTAKuODQp zf0^TOAnOmPYL(VZ1`m%$jM7WhW<9d3yhXbF%9F^AY&)I34myoGw29aHF*d+3%-Y>t zLjw%?jD06)fT%@CtdYSp+NOqO1eHro2Q&t5(ewpVLTE-Q*o$Gqph>CwS@;eQxthJZ z_q<4dldijE;|~+B-L6Mo0OngK`D6~Bk@TA^$}Y@@_s2}B(3?!R{qZfGQlZBapHi16 zDJ+N_JN6F}(T^ZHlI{EaghQ{Td_sXM&FMv!I##)=2Q#j#{FE8rE|q$csf98kqKqlm zNtU^j5~@?14ubP3wQsb>TGF5gkYBgk+NQd;x;#j6=SXXsrRusvizprGMY=}ThC*NR z^jg{G>XLTE_Vwaf(vByQUpJm@(kesgBJ$$ctBar99%(*SzO^8|+(d_`$SG8mq&+%3 zZ6iDokXGKLy8&kS5-;`(QY2<}-5_RI7p+6}{uG&SQg!cbY+|al9-spg&8=p8wDc00 zZ&KWKI6g-1Ac9N23VDN2K{`BY&y1&Y67`g{=EF?uHtw&IzC1{>zDyC{XdKn0dl>JL zH~1oIm8u1gq1IE2S?j&ANS&YSl|iy@g5y-!kXHE^VBOrg*pDx@aB(;3jB>S@<()8_ znmVmVaWAJ;*Ed-TzBr2nIkHi=b#ivz4_cFq}H8Lz{#2Ams*` zfdtIN)z-pn>U5gvO{EeqQr*wamyi`UY2iuxvQC!5HbqOy5WJwG;*8=mbbAOX6tH41_Ot_xfiu*lMeK%3}O*>tm z>z6yZ%PKL>+Trnoc=m&r0Qxd1{N=z}bDq;lvbwkC$UnpEYOdmL%YbBzn>2-&>wcou zs_-CPdvPD9qotn(U_8%i@A4p1#%+$O8xR=(HG1A8{I9#f9;E7XY{P*}HK7aA>~WTG zpqdkw#^cIfK7qmymKRSjE>LCXM@yxom8XSb0ps+fO@98cUy&;D(c-h|aI!Mjp#Qu2 zq>0R%=FxvN%(a=p|$R;F6FE`1t4xCX)yS3b;{_~`P5Yl~zI5%lw zayWgZbxCOmD_@0ki$1p}c0iZjyGc_QRu>ZTDaeqri{82w-|-8r_%1TFm7L4tzG`xJ z^-v+a>YEJh+E9GMYOZcQJgnvplK;8qwoiZ{K87B7CAp^jcv2B2< zPH1q}e3_G)Z-bvV`ZdsbqtoON2A45!^N^suNmdU?AAT`uLDr9N#jJ{IFPqA3w)>Tg z|7ek%aDG#-&;c`<{(z=!<^{@g|LdVl=dxTxW|$3W4*2%LlR_;#eO8NjCoz-A$qAEq z*>7z7b8ynFXX}F>9f!~b-GDY2;eJh(V0n(xZBb& z%`zQr4n_J+21DN1K-rfiKe5ei&@C&=gREFS#UZduvNgh*W)JjpW6>R?MVYtC6(3&{RNf`V%u*_KGd^%{IT{d zt4kn%{;*#WdYkdCq+D|fH@h8dk|BTC%Ygm2LX6KKHD4s@^brbGJDNo#+P_W+?M@mx zNmklUOvWLxcVOQHx%jEP$&?3bV}f--8u#H;`tB5=n`8+y8`o@D4)Q*=S@a<1+jQh2Cep_amTW9S#H9ZX$}E}Ny14+ zh!ZhD+>%&xE)s@VKh-C%DM-5(X0f~ZgcZ=8GV~(4@!mScN;lFhe*UmulXbi+VTg6o z^Rj`_ogvhA1}{jjH|bhGbw95XEx@f)30`DIAj>rrm}@Pa>Lw`w^$i@f^7mA^n=Rst zm}#9AJa+gWq})L1pDkvnCrr7P=MxuHx4U@|iy6m`G5302K1}D1IbO=UM4L-#1P-`9 zCrOa3bQ3$15zxheYc8X{7jdVl={Hfw{LV-rUi(P0uC~K((Gm3}pB5YLJ%y5NW^ZpCj+K@3gGmt!SUUqPi9Bh?ED+x-QDUbjcb=c!QBxQ)&OvkkAN6|6Y?}0cR97=1n2m)>*wc2`AcXg-voMbAt zx%ML+I`(WU+DVbjo5*(^yXg#OTQll6IVZrxzUwAQ%cpHSZRUv0X}%OmD{nH@ciCqz zm~9qs@yUu_A}!3%c}g8~l#SlAwmLqD8_kDNu~MwESPM(q_ar$|cI+Nv;I+r* z*sbeJ>X_lk0P}iXcSzQoU^S&`BBm(`}h znCm20MnzX7OK0lt5Qd@FPkIx1J2u(I;}pmoM?)Z59GWwfn8jMvohFlMc z9bb2nhufxi`OhErYts2>Y;|B1c2cIi1wKfVz^_^a7>;cX?RH!sP5Dn2)PuF;GCcG^ zlfB*?Mk86#K;v! z8-`_bT1K2SU^F(*?7kpTw$7MuMY7UOloZ;?M}NclM>kPm z$+iOqUE6o{?kv`*CEPcVRBlow)n^DNviax4qPj#rJl@zuonOXfxD!=#`+#gU|!o1}kAP;@ETsP<+@oV|mzdJ~IlF@kM`la>$EK)Ou`4`GlJzFV3n7U7+fk#U596>?{X=v< z9}l(4<7N9$zh{LXX!ilbupbFa=|O;{8)oAi)3K}4f9(Q;xa{F1o){t93d69Sdt$Sn zyOv{jsKVIoE*rq7+$8-?Xy5JpgE8b4j~zlAk+bxb(nCpxCn;QzoEoPeII3h` zimbKaw55|YuE;$fDUBhe%UMTXGTwy7V|GMnaK3~hgDY*)--Jbgk8`HRu#TM(qrn*M zC*LG#*|Z3Xj_DN4gXDjnZ0k@e#%L=*;9}n~cfRE&%C~I0Uod87=XUzYAbs3Kek)cn z9f+Sl4Etfqm+d*+gAqAO2bo+fbLaP9Ms}HRVmBj{#!9bzPZHICgn~j5n&;u!99vea z7fG&5@Qq$YPQ`B7ff?DZ8VLi|nM{30;xHrI^YAw5s)~=KDS(*CIKO1xM7}IN#T3LQ zt&b&0=1mqu58o~x&CQ+!~Ot!1( zLmZHGgB(TZUR)Sz?c#AgsHv$B@%raQe(~DJue<*}$WpcR{&mgywe}zg+MBre$Wn2# zMJqM1KSTv(Oj>P0+6`O{zx!ok#&uB~)n}O?^#b|%@5r0N4D97I58tMobnbC^~87vC&5bI%n@m~Z{0H)&3TmUPC%>#FipJBT1F-Nb(8t~LP~ z{U$3aNnBD3GK!5deOGxRp5zu2(-}l4!SZ*Ntmwpw`~;9X-o(dhHVHA(dYvKx6RnG^ zlekbP6`iDoJ!&}*5(5Bb5@Lq6y-G_%l5vxvipCOUHJDiaC`7Lj<|L`#WT|sTiBmO_ zagd)s3_GMs?Hzvy=Rm1=j`CvE^^kUOAaS}D;Ur40>ANBvWVmY0kH^VJC)w_%EE0gG zQgiE5&bBT$k++FTAH~gP-3Nbm?>O5!jsjPZNY(ukUDfg>EV&O`7FP#!H)!%b=XMM* zv^p#2DlWT8Dc+=M2gJi_I`o4dFaxCW0!1s?mAD{Nez{b=~J#*efekN43#eB0){4Thr*%=4v@+#-f&jIQ6Ch{tG{`RDUDYMHzu;(b|J4i48 z?K#B>lc&9CL!tB$0>TpXes)jW3+$VS#U(Nm-eVYs;)N5?JvDND)UCZrj zRSef>?=(fuv%bOn=MmF!%Td1ASY&SR8k4D=@ZzWjr&p(opzim|b_B_Ph)*SK_hahx zqh2VsBRQ+Oze$~!zGRy$e!JtTm^%HWn<$m$SpK+~(tHl8fOt^$CPR_46>c!*PJ0l% zM~0D%o2;EWB~u)8r`?GqDUotIKj|h@tu>TO^Ye#clc2qdiou*B4?+oikV1EU?lNYK zl`aZxIF3G@qI8m`RzJHX8;H|9tgly(bkG1J92{pZ&gG)&yw&VdSF)SvvD-7BOXsHW zFf7nK*#Y&^(x1x-N+*#c$!D~JcsA=MC1TP()?Q9NI*Cp|@kFGVF)teO0wk{>(d8tF zeZ<{$VyVZf@&ikdR{jum7~8*a{*&90;w}5!$>&$gsYVA$KJQHX=cGrSeNxmgFQ*#4 z$mEl-DTNWzPC0YN1PJ@_tgr_$LYi9jB1!GUY;a(xbYv-y8pN|;r{Cfu(Gyh36`Oh( zBJE>$>td31lOba#CMscu^sv_GJ{WniUz2sbD`AXuSH6_}Wz3OoYBl0RIFMd%l6I#I zWp*z1{Z?C+=FgGtMJ!K&9L|=mHz`q~VwVKOztAC><&358Au`E&6UM<-98zL-bgt*o z4M=$dcU^JT-pa#CMEfo3(AFYRlc2pxbw2IzkCD?lcPtcxq#1Cy$k6SIzrv}44ydGF z0H(gmwQwNo1|`;;q(F=Xe^%NEfZ`ShvMZO)e7cm8$=0$QF$pqNNE9H*gyk zM+q?{y67A(?p9eLZ-dl_8_(H47#dyGD$)z0DkuvpAl@PkdXt#k?fro!MORB0%#4ny z!x7+mv0syZ|D9Y{9HZ(~5X8Rg6W_Ld*G;-?7?Zn`a zOm#*s*Cz62=dQh6O>-P!Mo5vYwxhE?yjZN~qBS4lzR7o;y8wN)?Ylar3u3Rp-GMM* zx+s+BdidoGrJGC#_bl#_v8hHW9`1l)(%BKx_$#Z~gAC=D?STfXNzXD?-ZvR<5v~RIh2AI0vXF8_zcEKT$N(>nQefPOhM z=^F-Fn#b@WSrua~KA5hY0{vQT5{15Gj?!RW%?^E!)KPe>)zDVbe}Xi{CS) zbWfs^K%^1)2~Me4HTyMa^#%MXp(>}mTV%n0NqvK*l6x0hEq6TayOSPBc>|TWh3Uib z?Yw>a=Te*ENY%P&N}HZUE~;hkdXE2%bTfx6FiDyzFx_2!0aVNCpgE>Sm#cRerbeqm z#krFNE-TLdlp3j$w$m{@x+h<&bFyCS*Q6isN*EsvPXedJUYJXcCkkTxOqZ1CO<=sU zP|bg})R$*Q9tDWad6A6q(JDWaJ)Iw?6+vF}4vO@f=;X4-@qWgzXrHHR$&;jh6Nz_J z?eUh8xT`=f{^SUW1MqS4MUF~D0O#}p=YJEm=781cvt?d4O+Rt zqzb66?adh7Tr50u-(wb?b7B`W*StFA%KUL?LHL`t4ptDYrw3Nc(BZ0g5F}&y0!l}}QySjsf1q&B} zfT=MvAY(wZb1mb^RF%UYKoLcZEGv4Pu24Y2p>J{RE=N27e9O;&LLh(Cz~fWCK)XlK0iku&*m%r0aB&51wjHoAft)p!o?IGokhD zRQE=((oKf8V&sozOn|n$)4C8DH(60pr_!N}dCysbV0jq~X~q{BDqQhuA956FQ_dhw zLdRD=YiO7o2W>I^Ha|}6xyf`ng@xXfy9iBVQ97+a z50WWUYWn9psM9(=KHrTg^@)<8(KnelaoS4u#5EGg#rkY%I;B2u;?|w9mYwMH`GL!# zXi9(HWNNqh5hFIr+rB?n`tu-YudL*xSWHWPAD&1mwriMy&b zdj~l^@&Tce^b|m#dN%p_!+t?>G|y8omZY_t6zQWlpU#OhxVb~+P?6L(pk9dy8X0q( zBSVLA){Lpm+Oj$;5@>HC8&AQgj1kT9uoUzaXm65vOVw^5V~BIK@X5M>^t@hb9W}d~ zBu?s5H_(g;&Tjc-YZzp?WzM5-PFekXmTQDE#xrMiYuKM$qU`G=Qeg7vGlnzUSy0|b z#&Bl%j5WG=iu9XwIq)r{WOD8g$o z)uB-LUCqvQKS*|41uJ}jrusikHOd^&?2^g)CH+mRlHL?-%oxzTTvng`$vb~z6CGBf zjf8xYIvyQ- zb8<2e+ceEh=1rRBS7aY}lJGF|AYI7=kq?}cGks=s-5_b@CUPXBM;SrWT#V^o>|sgK zZA@gn$>LayVOiUr-MwE9KjtX&OzS3#M@?a+p@Ds<02!+tD;Hc-ef7a!QmNkUTpxs2{)G?Du<_JhUa5_@Zk=Iko22qsN9}FmN7uN>j(Dn zCH+mfkd}|(a#E(xcTPG<%WtAnV8=o*9hsw)@;{dtzR<5gP2cwrG>!NTWr{>ZZF&bA zFfo}T=pdOxw=fGwKW2Ig@I{73BdT)oL#meX4oqTd@{@1UV~p9fe3{*AG+wRzeKoW~ znonX#oN?ppn>zGaYa1O-__@i{DZKhs=d>P;OK#i1Sx*dfKFRn`O=9%rC>7?!TQy9| zn4iq?p2;J+NI3QEBAy-_5&>Sr;soAUR;$G7+<)ciNH>|B^6CICW-J$uR7#fbt80jL z-r9O~jc`B6fM<<$=2#9UDr1;uiU}7an38)Fik7+8y)%H;Ho!QCxx7i$_+5z~3|*d@ z467qCk$Dq3oE+CGnV-?2$SE8%fF~gZpm)jH;;}Ve>{o=tk!FN&bEFL&q-)@3an=h7 zS6s{p%N*9cc;g)_0fBXV61bdrSjs3NDC;80!{Xy$FJs8^aBvPpY`E-kNF zWf{|xOXIy!DmY1fgQWq3j=*3Ha^^;}XG_rEq-a#VPsef|n#wsmCMIK2GUu<)a4kss zn`8|Ml@S8KVf9f~o-tl|X{fg2N*Jd6q=WqYVZSE2Jv#Qw7`a@vv~A0SP`O@Y=|}re z2s4+9WT%4&AU39A36`yI9o{67zI9+1W0-T62$}vXjTKHYOGc#MWN3Zuz%EG3H<_^? z9bmy6W`sF3tkJ+jguh^Dn0oBS%9fniY9THZe7p!8Q|=ki(*Y-W9Fz4%bDc|Qs zmL83R)0nwzU2l6HWNAjVo#3oegBQVkVwCcDJ*kd>bMC$Ss>|mxSk_$bzJ1?C&{K>Hul{x=0bL|(S=4>AaCWChWu2du1Vl+*zhvEnr=o26 zW);yrCjE&M_N->97wKF~JgxOr48}oLB(aiEr5mzK`_>RkowKx(=PGPCtZwrwU`h@FpNTJs)6)c2CGS+tU<~*?17M=@s>itXjA_M`9~YsTD{*X$`Na_IIfhD~Z#6aiNLL%KAN4jVA`n103jr)rX$ z{NgoTTgV0n63Sx@dy$!sLDCsxkhAuT$mLCJ_}MZom~l`jQdYdjuIxU`E!nQ@L9ztV^pt~) zF~~SP{W@YCjI4l2+%Z)eT%>V*MO$V9sMM3#OYI?qG4r@ukK_QYUSLLWz~@kyc$_tx z+ZjS2)mNGgXo#yDiSzE8B+CE?`tgSgJ1hXsI1$3;TY z%joN5e8Ey|HC7rt3SFj8;4#*iqV^(1u|c20lxk0RpF@)LH<6X!m4 zsK{y6$s5KPbI;#IQSXvA3GF4{4x^6g)y8yflBJttE483JnR~$piU1@3A*xk~rQRyV z9Rj=Y8K4foj7`Q(7M}$|G*%Zw z1E1#F*D%}_x*QHp8A@m$WdJzGH|F1=t-0gywVnU%ys|oJ2Z==%s0V7 z#(MtwQ+hPZ&0jEIVCi%-456VD+7;dRGKL&KXT1{%PiQYvRO%P|ekiy+*$o$9s_)nZ zlG_qm0-~Z>HL41a1F-E_^o15#H_?$T$N&1TN|ZXqLzpFsYBo_WFba5!!_6;-O*0j4 z9$!l~+NvI;E8lx;;ehk*!p#>#ddd@i5m&@oT+F%Kk=kO3_Na49!RgVz7g<3ZJ?AWhkfVrQ<%2A&ZHtAC5u^XsBHYEGfq3zfaI*_JjT0U|DVRM6n zs54Hi^VMRE{NrfN^WXDd`tSe#pZ^uK?3_NyuIK^+f{KG6|L=bVsXGwDT;Q;qIj|8& z!ra)fn{hg%V*6z>n_432Xr9E2H;4{{+5f%<8IO*4^el?I{2V~tT)v|y*j2$zelxqC+U%J zphLC76rFmJ!N4uW^3=~!lLGcmoYQ1@cvO((o80XU&`eHFaiPE`>GdMo5BRIfqRvv3 z)__H>StX^&X1>XA?Y4hmDU7wz;?c)c8aixsrl*BYJ~>~cMRlR#007m+w#l{IZ}!-mRnh00 zr0iY_`W#doJaWV278X_|w2P=y>Wp|F08W4C0#v<4Db|`nlY{X2eM$3zuQtm{RqfG9 zR4>96HuPOXcNqy5{yFNIPXmAIJyR_OH|hDAv6AqU9FlI)hj2*5+HuW0c|VtrtOnPN_ul0qq63Hv9>5`);G+BR(E zlMnLqhy9W?3bpUw72nq4t~;<{OOrLCWL%OpUj$c8kt%VCS}_kRSLQ;A?3|b$L9oV) zwCtaw1%~YYm5*9+n6=5qk#976`OFu=W?<*crJJ~Tx`|z@5C;e~5IRB8LMZ6&bH37w zLr#pA|IqOZ7O4yz8p8H&G=~giJ^dm&0-f;Lak7-szT z&@Zk`K8bP?+ww4C011>0WRuWz(4HAqmlvUaLdzJMk+4s*>;CT)2eK)I0(D zTM}#NU%{;#9R+{>uwN2(0^jc<>8in3I$W9VKQmm7SJqdTdV$y$K8Y+z$_f8f(jMH+ zoyxLyoiW&|Fk7d*$SU2^$4wx`m!;1>{%uhi%hQpKRy?-p?O936`;lDPk{c@;6QNj*hxvfL_2Ms!Uon&&2Q zqSBlFl1QS*yJ}K3Aj?FC!AM>P+~PG^mmZ|k;-`!s!$hj{OB7)L_IRx+6lM5xB#tcy zS-ixrnOd`YB_N(41Gw^Va$ZE;Pa)LlUsa~!d^_s!wHti|DXcYP;3;Jjt4O6P)@-FY zqX>;;%@?V*MI@Ul=7wdNK}~Ow&iuX}+p5*UXU$fJGe+l;RJ9P4Hwe-hysCCEDkcEC zi=?zXh}2;WuCL{h>qQ@+7BxFvamG{GZ^y0pwCRd<-$Ams82V}P)|JAorEpCUTnZyR zEd_BStswR~aRIy!MN`#x<8A=?oEzA|L_k;)0O>brI?T6B+VdvUp#~jF{rq8{oltfM z86`GVrsUKY8Qf$sZ@1R)I%|l9YQ4H`5)ucJzeMsT=400?BmUTR43{f@suf&A({50y zTDa<|J1fKGvIJCXTx)otC&|m@BU)Ou`N^bMTGcuj@hRQr8m{V>3`YoxorGG|c9EJ} zd$(HOA{lm#AnvjhWN~-#4$_jU?O~TP#yBN3n-%UwWTQnkWo6?YH(pIaq+Y+ouIlcq zSDPkmuxGynY5Qu^AmN5~yUw*)ovz|&7Re|tGKadN=)|kGP@Xwc~DOY?zkjvzR0TWh{n{lJCdn2P+gAk?lDOu?z0u7OM;KMu)4w@jUEmla!9{K zDE;j^Y18=1x~y+6qD7c>0MOXb$4yY_RgrMHe@Wg$qj>|{W5s!p z>L6Hh?7ltWlwPFCiIRqCNY`(YSGvjVv7WrhatAjVZtbzJs)=j>YFLDyGqXY5<1ZL8 z%L>~(w8z6Fr~A~kq+U(9!|FXnGV(>#!e$S?X(?3X@BwH`p(0Phz!`2<*T;kh8Um#u z@h0nm7ylglq!$_Xj^tM~g;zS=s)A&cgZ%tqzaJt80-IJw7f5r2$v@h< zc14j`V+K#Th~3f{S<-T-(F4%lhf~GX-*ULA)xpx1LyLY%c6cCyuAf`%_12vf&~n+q z_aM!ytJyAVIrQU6mLh~Quv%7G{)#MymLr(k97bX)e98v|T4NL%@OpkKoEg&?qQ4mtR&(SC`Sswf*_Seo5N#9=?`Mt!NkDV)#NJVS8H7ng3-C+4{DBXi(3R>P16MMAW@707#H-{!9fzmxl zRS2yl<(#tj8}0?XcZPFGpo|V;50(L@YQj^ugQ(L01d`6MIi(Y-2PuYWnoxayNmnvV zdqSRdt4|glmLR=f#7BNl_y8JWU;nFfZ?!IsdJ_4f)bswX%FR*fABsrFo}}~qjrKwb zf>R#Y$4Z+3fkr)v{7e{6-QCgO?3V;84d$D|BQf*kB=S9BpZgaLwPl7u+yX$+9ze&Y z@C4+u!8*ZOsZ4S2CQz#q%lvTdKZM66fB~@^>Hxku7sg}#kC(q4~a2B-3=HC*jmUyuhup%_SrU{&4VDU z@?s(!b&{^@%+bh|XVf2^fH1LKC=xv4gD{m6kwfpZC8c^2O$%aZo5vWDGR|l-znlaQ z^dO06iU_o8h84?F@Z~vD3z$yYa4V8Zc$o=&zEl@!M)gjCr(=WolrZ@{ydLe5``b`G+ z7cN}stE_&3Iyi{jMqH-Kkyyg;S${auQaG$9X}Oyq3c;JhJ&jt8%HNasT&6es{a?>g zhV_Y&EhM(vSc~jRN}M6z&W@z^p(m?^xahJN6=IL4=bq^>XSM23GJ_-G?Ea zt$#qGMMcl*F!dszzb`9luRtIt>Jx?29X`Qmyizp@1mS{uy6gXXmJf=<&iI8=moM^J zP&n;WnE0Xp*YKR*X2t@^4W{dp58(6amLcZfEKL9A+u++O6E;-pvF5d@cY z5=EY?ickQoK%Y32Cz<6UlE&Cv@;Q6akrmHX{T^x1lgPhh664ShR30Nf$M>{YsUBo8 zX9s8GiqrHe6?zkh2JQ=*6TM1f;v8I-9my;gk^9JXIfn@xn3Ghkj6GrsL@Og|{yQdr zee?#OF&#<}=**MQqb$2I{LdSGb`F|hK3HMh>0G@^XP!i5`<0bc`gXPKW*Vw?SCxjm z3H$; z8lP43H#bY8lfY-izV=dXIx8Li-2i#uWU(iHo|C#$Cy$Y>W> zT1+##z4b1Q2_gf7q|S@ze5x=`oJ}wY1;_m|IeM4IWa6_wIWxw05+07?kL0!YuJ|(Z zQ~0|28GK(aO77~$_Pt9zGR;KNtam?wlfdKTW$V|<;baQ7gjt`yn8xErOE{7As zEctU5W0TA-nFi1wWw-z7LkhGEXW9T%ip1%Ta(zgFG6AG0VD)CdB)ar?S0C~?%TCYk zLt!xx<*JilOCLlwLRtDXjfp8tHIV`xp?1HdYhfYKtPM3Z#SD){!HYhmh)*(^B3^dA zKp%29d2?t^_F+Z*B~$Ju)|xlneEfSxtePpM3qhgtKN8;4FOdg|zfugfPkErs`_aRi zQg=5&pao)F#eaQDq2d?n46IKn)SGa5;plzn+gXZGR^+?@K=(6!-(O`7dyv6p^<7L; z1~Wdl_!>gNZm~YCU=OmGB7`lXG(iyfg3J`t6J6G@c(PI<%Nq6~T7f0BFpnxE#JwX{ zXxNhsN`@Z4XUS`2!jtal(zzrqRNgNM)zwKpKLgor%0lQ2p=Vx}T*lblJQ7a-vrCAa5i8isnlS&(F&i8Cv>%&PXS0(p8$^(4=L-r<;&7& zn$?7Q8PzjY@0s+ektivL34}{*4mS-Mk9^q|!F8eyGCLcLqz-Tx z)bdHPcWw2#&_MbTG**vJ0VL2^2dUn*$x$K@XfqaK@qvzH)qD{xm26XDAR`HS0%y}{ z6DZ;jBL*R{0J@BrBS2VhrLu3TMIwi@oPUK*}VI6$IcWzr}k90RRHx-Llz zAY0=G_<5sW0*WSPi|T``?9SE*s5%tHz>;{_z z;o-MfXvGTmAlVBojy4Aziiv9+w);o1!o3I=TAi+$8X8KB)v2)lDAvLs(^W182}H?3 zG#}tdL>S{b*K}H9HrT1ebmgRWzaaMJ2_f zSq;{htTvj};6*4P$Ar1fgF=^}vEy9ieg+;7SDVfVB|$YBiY!Lqg9upYb!*9!74Wi|}! z!4l(x26tAx`ng{J;uVuYu-b;c*4`>69p-96Z?!}#P?9w-qNl;?B447tRs6IR1czfM zS^N&vxLI7x$ICd*dB?P(Jc!1yp;}FOEFfC6Us9N`g~~XufT>bK)=1H*7_)lOM$b(U zJ%lf5)G>uAyv>9wyGCoYF|8R7qEZd~X8E;aS{vR3DxqY%10Zxrp=qax9nuoL3y1qO zV6`d1b1dseME&RvjE`eixp2B|>#?j2b3O>Q;X!l&j;pYKbXG>uFj50-y)S6Ks_bN! zv8?)V7BJ#HRDB2O5+6C+sQ`h^10iT7w$u<9f2FwMV8fsCB9tgOn%xh?Qiq7j}_}dd=GO z1uZeUU?v^=l^k`*Gg*foBrz5X86jOfF-ojeu2kQ_WR-aluDKeS+7re*Pm--c zbvQpUcm%Q&i&u}ZTkodGke*0Tf`+=ukOnB5;J}^NrNx0ZKG0Apa#l(3057s=A4i;U zBK3v>EyhaEu0jv!ABCPstesUFGrQ6ccoljU!#*#>JL7_LSYKa+`WiA#q7j`>mi|h? zu{rGG=H;`kIYM85Nl~m7jXzARoy*pKAkbO|@ri4S61h37j1Qt-GQ4A24M`q1ZxUo)iuXD<|*0RX@_(mlTd=?+gun5_&6GcX~e4UT%p&nA1~oPE!1P zn$vngV2c(PHi`_Y-!IWgEliOmJBalT((CdwN$PwNuBjBqHWTBB`Fn=vFU%?ByBt&J zYb)O%lVL%&JfuefLVu=A`$cnF`63yz_aIn5Ujol$Nz}@voh#JuzNgFT_XO3pi2~su zxCPvBl7=fhUPC2DU9E_g7*=S8fSv<(0xc4g(H^@yCN?ZBb0? zZ2B0x#~f=rgV2Ec5=|E6g$t-9E87L-YQm#Bn8~`K$(sBi_L%GA&?^WR7z&?#-J!|5 z>#9Jc$-jh&GNr~4pM|bUSs|J3A81AXCD{%$j8Tdi5dFaFG@zC3F0=J!4-)rclkRwy zVpS{W?b55+!OB+TWxDJDgb~V%FcV?BGb?L+8G~{?2v3Jg-&bKpevt5&ligYnD(Qm^ zKb&MGwDRFFyBy`seo3|ytp$(t(xDKHTBL#C-}p4R|5pjOdiY>tm2j)S#BQ}y)kL&1 zvxC*ESaFvKaj&9j#3w0M9+9)Wie_$ct*&lD<#CWk<&o{2FNBz?9AqVDkj(WWNJye8 z8zOTn21V0X38j4!1_G&;4Cqy3{G}dy37s8z^Q(r=J_$B3BTM?=YOk6}7kH&erd|~- ze)n1uiJSW+Qzn^~TD4xr!eVldloVw@(i zOqf5DW9IA6ANJWS%}RH_3xrDs@=gM#h0=|zV-P9bFBx7kEktxv15C#FwOQI%4aaZ% zs^K6yyoHe~ecJ6%<6+U{U(Bjf>_{dh3H{11Neb(EQGw)r^5xs=%8HW|WuJULN45mW z;OWnD73=Dum7_*s_0Y;+()@U$TgmEb*~E6aEr`_em&jet;eo7f9efd#)9|vSMEW-- zttB_YTRs5qI_8$@ISe(|!4p=>83+66}!5$8*lOkTl3 ze*Umu5_*?7`jwiR#peVuFcm~<^GmAokr3!F_BD}VYbVrJ=vOLt*!7|hjUfdQb)8>qK(yB_FEw*8FODK=k!UB z&Ne`p1yiEc=vtu=zr>zw-7;@!Itio7S_{hx@gU7HsQpyYX~}EMvTIpMmgw+KGS`cA z+q#Mdu4P~MD~496&6vsv5+`9_B7qY5J_~Kd9~o7RwRhe-DJrGT=7Lvg!11h*GXOg9;$3{clLU-Uy)%O?C~## zzT{QOCMB^i5Cr~%mVvBGk|wK6LB$XGtaRQAHGB~0Z$jg;+3)@kHaq{wxBaT0uO@$~ z?BEYzJ`a}ztwoY$7b@#6AcUCS#Ea4Q5+Nx|ik^b3bQ6wEW>5FE$&x3g!;=rutt^on zC(>`iLCW|XIff)Ym60{}aoUlWNXtWKxgz~0Y~;*>)i}nuW&{QWnj_O7mhl-NawoC?fd;4D$MB;qX%J>=^zUeZoVl| zBxPO%c@{cn%)Uc-RP!cmTTWe*W)MdtWIcWeTfx6b?T3!|5H^nECtHA24t~5ymuMQ! z?I)Q!>r=c>WZq=N9h?3tju&BAz)KwYPU|L%x3I>Hh4eIzdE_{TGJ^E_CR2}D71AHV z(IFIH8~E%tK&3b?_*G!u4lrz(ussok%K zb(1$ze-wjFe)Z1>AzzT3>7#Gx>7Si1S??t406%Z^YoLYSyc}32Aw#!mS@rVI#}~uP zyca3kgVcWx-KbT@hcJ1M?`btiZ*L+g9pbUk-Vmhr}7u zo8{Rzc}REOq$v@xd8Z;VRm*ku09<*|+3G{AKQB_x!>13C0?jQJ%8>p%z@TWU$%n%q zg1kiD8y%pDjEhW;1Yvt-U-*=2_iJ7HNdW88+mJw(ftBD~4eeh&eO`f5pj zKh7yVnAbnc5lue3L0A6L^z)rt=fx73Tjy;uc#Dr4ihfJldCf3|r5hmU>$5cLq13xHAMh-IPO|tB=D5v-k=|R{MYlHCuOP-2?TpxnCIz>#_ zu}eA-y1Z@D%bQH)j%*?wSc>g;l2&fQ5f)r>-shNf=D=b69%;p!G%ZVIppiIMq-2Pc zkmOX(-$OFrq{v3m>Fb9SiRZ|*BT3~=vaZ4+E}`R+bh~_)580aYBvNN;&i^6OoCvu- zb(3|I&pqTLRvq*QFfEnRN*)BrsDFr#`@DD(IxIrAUkYgalW@7C`kU(H+17x1u0fH)-0s zJ+^L2T`|EJh(S``pi87$Q74{~$slPhNcux;F)4oZAxlcL>@}7jIrK7xQhwrN4^ku` zY!)ZvMl~u0TRtG`26ka1HHpMNLh|j)QqCu-T7zxx5-d<@UNw0k>HQ{B9Bh~4Z?`Uv zNvR}0yFSQpmZ*0?wiE0A;2&UJ9O)S(HN8n!TCIgq!c)uAb6TJ`1TEs^b&EI@ayt%X z0gF~mz7uN%ah`mTCVgGHqoyQP9+&bdJ|uFHt>9;v$NJROufF zH9%HA4fuqtDyO=7Np<;!HyJvIo|bbMj>adb>OunMrypc!Wj@~hA0kJweg#dJqQ}0L zdqc8rBBvQSpi^Hywp!OgCrPh2N&g(IP~a*J>F`pw!r=gjHyLLh--ncc&h@L_1Vj3| z6u0;w`2%7V7XM=1QuGl@{@@;&tv$Y63j6|9*^wc;hkS2|d4kXG=W9RkA$@*KBmD4B2R-bGF#f2T=sDS_Yxf zgqHNMB%RXJHCk4act4B${9)KGXaJ?FvT-q2#4*0Wnd0guK;m=G-u2X$eB>NmZAEkj z5^5O@7Ztg)W0)}Vto^5Y9Nn&EuX+5lkX$8F{{vKQ!sPf8z_OjHU$>;T573!EQqo?} z%i-jMOkMz#m7mM9KV0Itfn=N{KlX=H-1N)=60EbePVfrD~ zrp4v_AKO&g^dyPS$@iE7#Al;6VMyjpisZ(K=r+hGJ|Woep>V#4O}yoqLvQvA(sUva z{Xt23xd~@r(!bQnNoF3ltdu!}v~rXA@2ckekR_oR)g~hIO`1Y1mP8pXpxSXN`Tr?< zdtTdhWlb;Nzhc4BIl)~PzsbOf0pkMB-1BCQ4h;7PV4N9r!-0RkN4+1EsJTv~4Qybq z@k~iWLn2?Yip8oANp`$3@d?R#lR{r@MY%eVNk``Bb)mX*9z z-RxsQU5=lSizP^BBjdw~SPKfFCP+EfK-mWeS@jx;-!;l z>DFy~=c0kqMe0Gy3FdFbn#dK9%k;#4lSL_jf3V%xWQI4$K1NrOD>|^XzLc&Pyj(Q5QET=c$tX?=wj~*F0;72Q=5v%>){2N! zILr#Ua@EAT2B4E@{ex4m{4pyO;Wsu|97pBv$q^~V5x^~BXyvxpCFmWbe*BT^Sn1$DWD|jp7ede{%}qJ04ZG2tPF%L6@CTL3%lf7IC|>jesn!NXU-O zLoV&MCpbec?FX4|lv6D(5>9b6%DV8fStOr3$b6H*F+zUlJY^t{twa$}#Q{_S9w6%^ zG=@>SbD3!U)1&v4dF+B$AgR8|q7rFIG)FB8M!?9?o2M+dgUC-KhftmxqPiD#f@l)! zp?S(aeh}HmZBLjdthwwA^8kalyfn3oL|6~-^+wUt=CVI;`NCRvE?&>di?e{ePXNS5 ziU~~Ux`S^r(%*4Zm0&E+1D=EibIb!YuUmD8^=J;cI1f00_H1}a{}?xGJe_KJ@gYCS zfW343E%VyL{)3ETl_1A1bSjEGt3j4_Te9Pquy@j%B<>WDKcQTS9+{~^T_BUzxk4t2 zETAXJ4pC5(E0KR{Jzd&CMn6duCU`dZa%q&$c7}oUlZ@X=YQW%Vkd{uO)#M>3X@I3S z+VoX2lnwIA9uR?NL|F8sncpIV)s>bKCo`d$%7*%O_EU(9rgbgfJwn`}@k(5jva5XSxLh zE@-|gdH0GUs7?Z#z)4~gRya5{)=D;a?7T@$YJj@V`pqFB>HQWB!v`5`U9zC$CxO9D z6R#+w>PfVeTzB6qG_UVPsB#BcDf$Cso@6g3ODVZ?^Vc1645IL$P5KUvs?EgNUTBFG zg;?FrIPMI5lg`O9^C%{6zQNPj*U?}+Ja+(DZ?dR6jD`97!J>~;n&8#xcoUpJR6-4i zAnPQVdgZ*@Nvkjj(^J!|GPn=IPNA`cS(i9LAXhozro@;8? z1<5)ISEZ{b8Mt}HfGi!NIHv8ZLY6Ul8nVE0#Ee!OkW-8T!X)V_a)HqrlUEF&J!id< zg-J$}>|*3f;@BcbP!RrZ`D!BdTj8E+c}s%SH<;`8*QO(6`5$Wm`a6KFPFEBgajU z!J%4VfT*3#35TL?O5Yyq2T|~#*4m<4cGA;PGaek8i}R(Dj5k?a_R!qDjO_Iti>Kne zPEzRV@+4{OLDxNG>_K;vy|%3AY$V>KbX!ouY{@5)b=~$z5-F`Xc~ICyQDE1T@EPvS zc!_x<`Q+7)=H)d9S@Iy`B#OjY4)=@Hvgv%w4)uDF0z>tVsg1mvh0WVdbyhE=Y@&GP z9mi3W@iuG{&A)=olgLc2HXV@nm(D@0r62`sc@u@lxF1hh#d~!=Ql4Hk+v#=*u;_^K z$QIkgxu#&rSR9{Ugkv2;PriPz=uWHHAIRK#sVMv_=H2S2OH0KM(m2f+`xZGsXD99j z>GdR$+UFPdw=9$PgDA#9u9rx2En8Viy)@Ep68Xye(RHFycIJSjX&J~m$u?>A0_(L+ zTE*g`hCqFjDie(z1^Mn7_^)xcqEOzO6j@UGs&4g}H(4i`2r7WnZj*U}g_aV-7=2k$ zD%)#poZtu1lz)@-Tl)lMZ`4G)b8qkiX(uSZ`2*BSqqs!jFs7LTikqZ2Y1}KN#oee= zBA=Z+6j84u_md1p*zJgmiZU1+OlH}nze#3LS5tP_H~S94#o0VP*^ElrS9+7Kcf;l$ z)j=jrKlw0&IM0Piv5M^LXb60e=6DksD%Fuw4??4|Ec+*G9$vTEL^kA(xrpL3av(iO zJ)arONiNyzr527nUf)DF5ho#K`+5T{C7 zBF!N(53-KV7Jp-;4GYqOOj>D*G($=3e3J27305`rsPJ6!%KlmNw>Io++E~lBGfnE{ z9W&LpbvX%lnrwSDN?R+Pfu?S??p4}N3TF6uc+rvdqG*M49)@z)9Htbw z0Wwe0@NOdBN-y1^Qd1krzkaZ9k@+|ZM2RT<2J3J$)L>r~K6Mg}IPxY`hejpkrB1bR zz&nXTkmbRukzR_9Lk;#-flyCU80eO~U=d`jlW0-4s!}^huP5o24cU7^27Py$B2?6; zz&*>X4$|sLrswr~@ok~~#2TEmxb4C0LDo86bJt+ztc4`&O|(cRUuSjrl1n9kr1mB- zHK&&&qDr;w3^$j4M8QUh>gxy5Ql(W zq^ddly)6@@okSMm_5;^JdvH(G0CYDJ%P3u^Zp_unI<`GHw9o5A-vnGeZ}&+{TP3G1 zT)Bcbk&{%UrZ<`ScotE6lPe`|14Cw{_fwPfH|g|6Z34p*d-CJM^kCVuf+bfIFSO^w}!zZC3_n0;+BI!wFw(TXCsF~Sh1q=ln zzt}g4T$_5%QIEPSW`bQb>QPtD4z$7;q?I@6iW8>I6Gf|=?wSUB6s^`)bEbzQnQu~$ zO|MbdlW$O=0`1y^pVnbO=9?5dc665Pza4KBMXI$AM7_T$*y%+$2U8!7s-j5DIvmN= z6z%jN>GC{Z5*C%LD<7EeC&>Uj3D@=HV2e`LlkHhc#8Jw6aP{p;)=98VTJ{dFs9UYI zEzJpo^m>v`7uKFFL`CXK=Y=0?+9T$J$o!L>N0I8HxLmHwHibIf%atI<0%lZ&g#kak z-6qP`<|BYLNI5~K_h5MBh&r~MILFf^@ zdoik5%VViRFK_luvK|MesAHWp7p|KqZdX#>w4(xZ_P$9w$=VY#N^DdQR=9yC^g((* ziR{Ymb@?c5o!R-^bi${fPEzSgNcOBW6_j`q8PwZ@)e7y%?4t6i6^@4|shqU=cOfh9 zbGbeWSEv3a<L zf0D*k+9gjyQ}EFPboRyVG>?kZl@kMoLIr5~0F$%X>D9y_O5mVS;ix`c#+y_I$ZEH5 z5E)}yxrx%!P7R=DqF|&DGY3z;ShVf7H=ir$5oDaCvN7e|)fz|9SP!PtvN;~ReO5zp4K=lReh-3^{RGL;sRz(JbtdnHAC$jB`s5Cuzmgeao>m-$pVrd>6 zW#J2Vc4(zKh!Xif$Yfxytaj9%UUaq7^$^9Ut3=vAf}`G(OsdCFdF2$vr>~(U7p;W6 z*f&Xi90bsm*-RRUvXSUm>a$b1&a#7Rf|MVC{Xr4;QGQy^F7=qX$H51|__`dHf|}L5 zJFcfk$?8Q9zI;?|w%14R7m+0y)v2{YB+pWi^#dqet>}9u+uB|y4>H=D%%`y#m8dgi z)D3-Ij@6T)2BO^|YHVxUjdC?bZR(2=@AAV3(ZLb>YkAYVV&caZ9kbd9$tPp#M&?s@Kx z@j1w<&o>hVs}-E1K8}Lbv^MoFg2>w3MAoKCYy)WBni;WE)T?$}{hTIP=DA6_96Bz& zi}KX@=)c{8Ko62(Ehrbg$UGD-VARwI zWS(Tu=j9x8DGFa#xfcD)r}ryvvh3{CKA@hpZ>@Q<(G~Y|l5swrtd+$*dInLAvrUS} zIGK?>%lLFHM3VU?Re@7Q-`?2do1=Pq)|mSs!&?fpoYj#8lg}sVItocSNN;LSd_G~~ za{eI!3$nDyUsb^0EILZzK#b`ve`|R1Xif3EN^+tQt?l))cYr(zB~2doUNjCjsSm(9 z0GAaXZ%ctcCGTfZWNJQ0x5rdHv@prb&OHY3BGcha3JHl~)rx`AD=!{hA7FTc7@u&Z znVGwTr=wK0ieJeF3Q|s>kk0NMVo|$V_KqY@n-@+}6|P2;qgO6F=DuaHw)126t;oxX zvemq-LKT8&|Jo+Q-f$VgQMX!>GyMy+DSvI1u1tsaBn(EmgASr@b)}nAA^kxVQTZTh zG=42DG3ds@C%x_ARLSCkD38E{3{FP&W#os=o{I-jCdCJ7>p4e_V%CoLlaVyH)lMWKXOG_RtX^_5SOxP`?zUqL1n z&m&FWtCyR|7~NBnC|*63kmm;D0F^$m>IIM9o0DdEbn0|jo@7Xs)Mt99-!*vwCMsH2 zIx#in=!)oh5&B*Cx6_D?Rgs}PTz>AF$p%p_O3fdmf_0&|X@M$gQ!5tJ9aQl<)wM-Z zRIBb>RABXr6t$_9VE#c;dFs;O8t9$gE{HZZdMF%B0`nx@8zAJu=?dR@lF3_k_Fa&1 z?CAuVC!v9QXX}dc)J==e8jKvQ^B{>$WoP1wV$|iZdQh;syvgJso0q%J$)fAb>TQe) z=Ie8twhuD6vfyqpwSt!%PK%P&+73ByvQ9D>X4AF!9Y9HFeBJ4#ctx)UN%c*t(mHSf zFA7u_&KP}&M%by6k}0ZDU-eBCsx9NPue6N~jX#Sc>XT%Tj&4w^u!)T=yQ_E;2c36(htPjf+05$Z#EUQd$geAMJ2YEvhLtI-P_ zWYNr4FNs>zS9%kT6G4FhFC@Y`#&aMxC+CJXlomHwT#Ot2{hg z-1|=B@*qoFjMzrI;&F##c1PctP9H>dzva#uk#8ygx|h)cNVyHTxLS&5ki%ODoaUdT zpJe^!Pf|*>(U+$R%Gwkqw7WuOxC#W)-()(U1|Q#`VSIa=#v?wdRg;!aQXFY7Cu~&A zPE5GqIguiio}_Uxf9;vn=&vm0AmdGxo<=LgV=&`)xI}0p4aXlHL}Q=3%+ScYx2Qx> zY=y>blGy&Y%^l>ZXqTc)wpxm!-J&Qqjc^6%1~_)7ef?nHBI7(y+YGi*8+Ecf&+>zw z8lE4dJ7tZhds8XE=bpPLZs|!T8_?R5gQ>yzAeAv29_p6H-fBY}L|cJq3P%m>&Y8GY zb)w|;HQz+Z8ezfgK@=FeN&ijHx_0uT1ok=!OD6548B-xirFgqi5LL=~kV+?)?7^sbJ?R&a zJs9<^ul6QNG03UP*AMm`ghuQg#T;avfHo||Ig=EpGndz9vOdHUXt}m%xi)}y4avj5RW(}B6 z&}e`wKW-GdhO=aOT`Y)A9g}USx}E23sBW^n%~_6*nU{AQXwy{Gv3AxJJz)hOh0~5< zL=(}o&-ukHyGX`^NK3V761A;mmrA>WaQ>*!? zJ5Y1hJzhSDHkoo*iTc*coHPB|33mt@P1!pENtCVD=&4k#AoER{HrnfPw&Gek3b>z& zYC1{bY*m|`f=s2Zkt!*wDRPQRFPgl>4?;6_7jg&b?8JUiieh>anyKMd*As2iiF5XK zlo|XcoknR`UulzGPXeQ~Tv}oHdZTFmU0J^`Zw(F7>YH?`f!}AZp8P3KNf71pevqZb zP(9VyYs|<3kBwc1>W)kUS#RQkY0})tj>L5>4>S&cy6oZ!lIolE_VlAg-D*WnYdL$4 z>-CX>cI~DTSy^R~&+RL(9M7g5(*8!bH6 z3=PUV<3QB4?rcqp9ht+ntyb{?+DW>Dn6!T@idt7nxpI>QX(yP@;39`lkSXtlWN9qN zYiZpQRj$)PJ|=-m?r0QV}-Gxpml$fs-4mr!XnF&HeKl_%;sH& zn`r;W@`7y;`GaWYfBj(JBr84rNKwK%u^Va0C<<1qUX@mhLB>gzQ|D6()Vn?chj5pCH3QgjdR$hy@K~C3-Sf1pqYuDe{gf{5yNe!~{NeUa~&Ze;x zsPrVwp=gTK4ARRrw(FK$Gk>8renHpWboZvU8e_kgUE47&sLoRhMOZLc=SI?3|>7DZDplr)!~P7{r) zo6x$9Mwbm1{glNddlg(O`KU8pPg1xYedm5(ie^F@!o10PlW}-mqGGgsy$XK}Qr@8H z;rMsbcX|Ex%^)cowoUHO?FA}DSvyjqcC_+PstZS@XjMIU5XFGVy%Ck7Im-D6jg{G6 z`ylHC*&EoGI%l~5jx-cOhAulcXeZ%vYTs#CS7D&xNus6oof2)uQ~dnya1g7zs*=M= zA|hni!Tj}uMUN>Q9Q#f?xe5ozlSC`&dxVJM(P2Q%J)vEdZrxe;Q?49APZI9eh;^Wy zv5;x{S6Mq_OB9igG4v!cVy)?@u2pHK#$H1@h=Rn36*WH9J1a-klSHr*d}Jb#F!xuz zh9`bOVswr~dbydznEE0eM26~O^jl<&sCARiZ$1c&*+?>=Y58g>nh}Wzv>|OV=qd71 zT)J|D=~|=0E$3`OK2QEdKD`hbAUIoyLeeFUSvC_EBbr|1^Xwv_fo#4gE&Um}YuPEf zqmcBcm0&l%zYC-4K_WRfewUKEM%m~TSMClr1{rViX;C%XNwYrhDE6ak5*LN0Klczs zw(epy(~FciE7^4)`;PCM+_*skyP)nUihyK2T_ z$kR=}ez53WJ!-=Ks!>!g>pa-9u|r*ERgljJeh?UA^>brxD~x)oeW$+)@)^PpGI@`E zYkBN<#%1JCTMT-7l1Nb$m#NylvRL0CcC|~|8S)fBanB(0B%jv!D|SlDgjtMldXbOL z#I|Gk&!Rwed~>o-cQN9r#yW&LI!iaaNHocKpxkXAm8(Dci*3egwgbcPL14?`cDSY= zm8wSt@enpJ4j%-22eCn2(~=o;hF{notjWa0ID8Q7CX5}|TIpL8!*1MmsV@@O z`OJ{ztBxAf(cmMRY;ICd(9lj|+OIc0V~l-)IO6i!P!yp4^kD48Rf|OC)4Im}3oyza zB(^^MijBWC3j;(ep2gN>kk4HACSN~T^oMmFCoK%kb#2=>YF5u6cZXRq@Wvi(Wy6XB z)t}R2&#ydcQJ{L@9C-!++OOD$E5}&Wr_Kq#KVeDf7vzg!P4NrT z4f+AFMjD&CIsMF0cKV7hvULpdk&A_AJx$^C6wL zGvqq}nFGggITK{1lSKZsU$MWIuNUNV#e-mx58Jgn&q^3NV=FJ0PD%PnA|B>f?9QfX z3DWXOO86<_yBLa*qn7mNO~)2x1|)#g{3adm>f%#QFh^rQEr*>PrKCTa8C#zhmZC|< zo7A{W-3HB@eFup-_OIB^>xPjqm>y*D+p>JuAS-@Xr7e&z#v?reijiU;_?1j1@0lhK z$vg>6)Yz#zn!%@eJ^_q{xGrP(a+HMroZYf>If8uN?28PxQ+kj-B(~!GYP)DP$Y;Pi zNK}jYgn2U@+2))VPil?&T;6J>%gdStj{nG}4>!S#S#eAsKC_Sm$$; zgpOx=lFu87_Eq$|;`TppI09bQGFc1li|Y(I3PR&|9VGfq^2YmoA^SbPi^2{v+VT<=jCaXbFIL*#i zyIvphn(Ez%8-|Ctw8c^F^Y`w)>kRnF@Yq)=<$J6N4_AyaI!HxB4->tyVRa6cCy91bwSzcEIqC)}D|&m3C_2bM z@7-ajIf_q*NFpooO~y%JWj54PS64Vt^n`KwS#Z-SNOb5I;d7^lBwv`ye}1_W`+zhG zLs5$xuua=ezXKBOt0h^7IqFg4mpb`Rj`Gum!oaXYUmZRr?J zPckLZ`dN#^X{<`C#Vrn}n|%FX-y~>IO_84;(xKcf%ku*=`Ta%HsKqh%NjNHV**rc% z%!2O6MG9q!TVu=ls9W`6V6h&*(pae2cf>L&oO@nE%LE_7w zq(f47`}_LAqWM=2ic$7RZK-lld=eU>W6y_!d@i%Rk2^=v=desaqZ2)lB^1LG!Yx0v*y6k-uG6rm1?8Xl^UX*a;BoHM8x$C;}a= zZ8a@efW%-sodF|9$>(?!Cs`TS(WEenK!4tPB=nHS31ppQqB#}$IsxVhA{h7=l8NXw zM5GbAhb$L>b`lhOM=lXvrYFB&hN|Q!_Z;ueUP^)=M|Y zbMBWlIHaBgt!vu&OAI55mSSNahy;9*ameDp=8m|Xst3=Yp%?iyj7YrV=R7aCG@_;! zEvcy13?+JyPvgO}=zQ*s8ae?QiWlWSq_QD9(@l=+wo*)aX39mW6$z?2$_$!x9+c^-MO;exKY%(lpo~tYHp`!)OjvYynP7l&N#%a zbRkL0K?cm}wf6g47*Qi@4vqP*AMBeXmB&#aP@bV+qYt5HH@xh8K&TI0-sIB|l4DnL z6oZaoHuf=a>;su6fhmf%OgYVwOo<}`m-#?qoP81)o{{%R4=6~?w6ME-lU_~|dtoSQ zYZElO>=_#hMlU{k+Im4^viu}rdg65jZc@kw8h#@Tde`2cGgso6I+e*qQ=F;$NhNoXI_DxbB2LUXKx!X=S{?Kq`cLDS_!F97TJ$?w>VWF{H>&sEU zIVBM8(<13_k~yvO&k6-pU(HG#i#I4E zH0nN=0hMzzEt!L#6M1}y2HK>(cO)Ie4KBPn8N#E9d6a_wbeEpI*MX#;1gXuC@ojC= z@=2yUB$twNE?oP>Gt4Gon4V-zJ~0SnUQ1?0G zvJ7J)>2I4>t=rJ!vyzJO$&q+{-|Pr(TKBCGH%_+}7EAFo$db#59h4-(BLInXahLFY`>De5u| zEW#vL+R!f!VFyWk#J*0~%w;LmC`XNFbhNPtPzDwqB-_}i63R%W6pzbE<8x+UQTz&b zy^hRh2f>p?mjlih1kyg9rgYurCnBkF@pwxy~vxH&UBE0O~C zo2)mfeCKW#u_w8p?{OP!j>^n<6(?DE@G@V$gRXd zjT<^ZdOJym`H{+f76;h_L=(iQ&Sx_V-408|Npe(KE_}ll&RKck2Z=>HoaOg0J16t5 zeN56%f-3BA4_upsQl=t*XQmV91d=!DFSj0a#F6tNi^JzhqT$4h=i=L27%VaG>%(NF zlVr}B5*fDkyi3H0441Njk0^vgqp! zc9H4$ogfh02br8q?`4v_XsAY*idqVTi5?^>C@*?kG_XW<6i&Nck6 zAM87bM%C`d0y5qtQ}eZ?5LJ~^+;#CMsIn5oNomL;jZLX~cq(a|sncJ+&D2c>8);UC${f{` z)s!?+2TA2kn)GeySuA*x5KmW3^g5XZB%|nZc@s1@m;U&Wgr*hI*maZ1E~^FHk~PRa zNakeU1(|ZxU5+Kx2&Lql6P1`bE0)&}WSykJ&$c|RLM^m=}-Yj384-uotg4JA<06+ zkCbyAdj?N1c)QL)l383B9!QBjwhFhCEDjpgLXHaaY@{4B0NR@jj#x}Ilw(Us;=7d9 zkE~zmBn6J%@LZ|OR^&K~AE5vX78!dJnYv9UHMq%9hDEm{Q}-Z+);Uu?<-#Pba4@u+ z^f#e@K^|__{o-h;PF-c#-Xhp!*q($Ym&WQKjiM~`GwLf(nxBf(C<;qj+dwF>^Z8Kn zMwjR&Uq9Hl$bf%JF)9UXq)wpd|N;UF-Muic|!>og8g>`{P8&nUOpkgSu?Hje2IZR04=96=`Q z+8Q(q`@@51F4XPzi~`N4ySYqR!Vl8f!MzD0$G$Z@pSkC{lkU?Oq1d{m%t-_1vNxej zjoP=oOpV$H;k!u^H~b#Rx}4NedO5c@p-;lUGjPdWxTuTdM7nU%%HR`l`9ML- zv90c6FVaX4*Dt*m>c9)(KL_CusCDzG-kj-Cq~-VZ*Y)dP|B8ZJbI)Kce>}ifhzm#NYpiAaqJ7G|);T($H(#{pKOW#K#6>5Q^C4~=7oEI=)^v^! zSiWdv%K6g)>Aq;XnBE;lRB+W40g~}r5k>wv$cIFVZDm!t(w`6URdD58xG3EAm9v(K zmrv6nz3eOJ>(7VyDlA)B_-&|(7VyDk>e&Usp!z^XF+g z?>!r{pHhiNH4xJ7sUT?h_6Bs=U?yVoNHEt*F*Fn_jBf0 z`iDcF&-waw{Yt<7-KSs2uKbwWbpHQ)laL4&Opgsxsm?zTpY@L)*FpD=&CjtHzc*dm zq+;@n4n6s=pTuYVV+j7E)<+V5I zzEVPD_#a93mEPB3caK^4hh2Uqn>0Ux6mIPPM{@ZIysyI!f4%S9C-}mb} zDyx%U*EYGY6r~^fAIW{~*L9d^aWSvN{Y*^mClJ}N(jUqFOkUT~F2x3m>Du>gQhk@$ z?34aTu6^IH>u`~O;`>lBtTCR91chbfm(RG%pTuYVJ=((<{cr!z-~YqE{qH&i8S$~f!mdpR#62`M7 z>;W!P>pz|oHmTOvbD9`nexXKFY0S?jGSHtwZ6^NpC&IJ-@#8ueXyb>4)%&k!m;3fd zq|ApbAQbS&XCD5K^X%P=KhGw8=3c*IzsIj|MX(2djQkR@QvZ4%@y&m>dg1Iy2OPo4 z`rH2Kzhgq#hyT7m?!S*~Uzq>)Uvj+YQvApLasNFGj^`~UZ|lP!J_E7;5dXaYP}4r6 zrso-P;n%NwKK1(n+}|9>>=V8p*V%t~-e2s)Z~xt=_BiC9J-Fu~Kc3y=kN@oPJq~%? zIsX~iIbJu&Ki?nkLylMZe6x>3_6yxF_x|JYLZ9#VK4d@se?E}RUn_cabkcwM{1;t( zlvwGO7k%o z{`TMg9?taZs(<@G|BmR0G5+=+<6mQ3avV2tv^BMC|IMv? zx9G>;+`yl2+JF1=ozOk?$G)`x_^1A~|M;gqwg2ev{HLm)e@!X*9x)@EYV4zFc$NQh z{m${G;yDERk3e{N>qb|6{+Ip$JmehQv0yhB?m1l4@roK&z)e1KnV40LB<4L>INHaM zRD=zZgcAtKo$`2)uOIC5ZEZfjALm7R-&LR2Mn=hT5U%4q?r{tx1-r@D5BB*sBoI7) zTSWf$;dfRMx0&vb4erqWaUke&e_T`qeMGjldcXbye2l@e<+dVe*1A7357z$34R4>1 z2!RZXaNoDc*AMpjf-pYTaURkV4G~zIowYQcgxT;PXN6_g=lN|f_W3r{of^;cCS&^^ z*Iq0Q@Fa8+-lSd3QU4?pVV4hrEEerSzJ9Rpzakk#jN8xi8X_+rBytk(-$9bG_)o$& z_h#Q9?Qu-2kKc+FbC9JgV`dk7CLzO>>(C;)OyNn49{rH=8*82*>{^koJHT?!DqQ}+ zp6Y9g;Fz}C6S4u4=*edW2EZkkaGl8DCcsvQooqpN!-F$hq*oDMm`TS|WYHQ^q@f{R zn&ifYw}Pf|!T(MY>F!8y4ECAhI@t9h(mM%OV`76@Y##d%gvyEFeu4m0_*PRS5W{ci z?iN^p1>xSJ4~YWsB5ZO&_}!DjR3hz7G70erg2mI=GZ^~{KjiZW1keHl6duBKm?=EJ zh_Gtd)?GyK!(*)@<1$G3F9NG^p`1(*=DJMb%!Zo@B!npl=Gtwr2wMubIe#eDGKvV# zVu`gBE_y6R$KJn)T2FG?2VtG8R9IR;WEK%TW$diRb&9@gN+>}9B$cs((U(Z9&XMrT z2iE#wVCk5FwHlJj&i7)U&No^7B88%}g<JC9?J|5sK4IEKarP4y#3GlV+8v(m@dP z?VDI-xcinQp>N-$J@2krWo}}XsfzyuS-J)m#Iam=`AIC3_5|HB6AyHl@K*eYyJZFy zdqvu%WAJ`E_eTK?6Y5OWTqnxUQfGFn=+>Fq)NQ(TChEyA6X;B&PXVyZ)TRp$%S=_u z**+{Yk<-UypPm51Wzc;|`G>;U^+S4*8utBIjE$f|P(_y6$X8}r20Fp|>DfFC;Wm#sp zb2^A+CU#C&6Ua=foX7QLnQ3z9pfDAN^ch#MpG;XR-R!cii8jV79#GE5Lue2bY9d#6p5I+NfW>! zdCzwiyBY{*7>kW|M9OV+{h_4RK`2B)@bI#gXsAU7p%M+vZ@zx8@4upiC)H_W-D0*n z1>rqfox)MmO>mE+ayB)x^76`HCHF{)K4QmZx-G?gHDG}S6JHLV1psWGYLQG1dyG#7jM zz%DJBKA0?zW*Pd}0epGQILWBLtXp&KEz;DFK3mCY#Xvl6}m>7o=mRyd6RC z80M0@BUz-@b-MxC&R5zlO;{ddNq+!vgR9uX*8LHlm)M4kZ(b6g%0dkyyq8X&$yoLT zMT*=iBIn-VTy3mnmmIR!l2p3;CMA4c$xccM9S9w_i*0YljS);B()fAxkK4 z0Nrc1-!+nP$i2{md_HT>M|I%qe2};C~5(aG=1XNbU9sd zPa<@>-ek(@8gV5C==K3{Z`Cps^*D-2>j$w66*(McwG7?FG87fF1gJtAScDL$WzzdW zrd+P&;(P`K9X|+KM70RP6%nLagl=LHLZvbhs?bfWLWOe`0N)NllaD_@F^P%CgK+aP z39oC3*`!-y%B9yG$&CC&2j`7%_US{z9d@5LxcBpM?crW^6ZfipkJCNoChjpeX`CaU zr0N}G$JU(g4>xgt2$D?Je3Iq<;K#bu9rkDUh9_vx7qQ$I;^m2?vd^;kK4k5qsn|*`qPNMUwRwh^tlceruNz%14fjwga zZk7a(PJ-qR;!Yy+>?F~2R(f_4l1C?jUo*&Z(-nDil4dZ<6FfQzX0a-lFU$!2$xY%)nEGw-FLLJz@+bbQ}u=8lJ`6zm)s2%k&P4VR{Z~fxt0`Gb9aGh-Ll5`(shDk%$n)5uQ=X4WjtL%t1rOXdmuX(c zM9zzlZ-uXF*!{b~OT9NcMSPLr*4Ve|=I?v!KL|?w_Jef}9ztjEK-n*hDYPV~44YdA z%IpwMQPNNXH$p|VF>4s~9JLlL->De7fQ4CCGsp3c=Sz*71HbcIm0qHZ+R^#*}>aR6?}#nqwWMQ8g{RDn?CLjgcj- z1e*lAcT^+UC?95{^6_>Dpidbj1?;7-j(VJ;IaB%2N)KY|g87?<@z9BsfvH(~zL6}W zwYyd9***)8ONdH{YGJUXMM%Qo6)YVvVewB=OJ*&_SI?0Bt|c6VTwAN=&844g9sx>Z zwTEk$bEDB0bZzxhgUWBLH`$XIx))zY;aY!6q)HG%o_p;Tx}%i=9lTX0cherPH{w_i z#D}LGzTMhLEW-`LZtH|dqBnv=YMSxoCDA`kbJOdg9-D^ZM|EOwye@K2DmK&o$)S*f zl?aD?3I2+8gHS1l0w`5au2{wl=Y=uf$#$Z@Qju)heT%3ib-GgHE!f@mwxK)5LyxRIHGx# zSo+tgpV(r$8cZL8$5Yy)#!XKf%JO*JJ}gT~P?AK%AdxGF%BBY2_z-wWLuUID#-G58 z&Id+y22UO$meGBwZ^jZ!wa5ADJ0Wo~X2`GoHQP2`o30+mU@6f1mLgJe^x4 zga->CI8>dUOenzVOID$Oj;be|0kq6{E+~-!^Jzz>nMy2b-{%8aUishw0k?%9Aw$kX z5sf^pzn@Epm?M9@c@=Hk{KL=_?uc&?#W4Cqc&;$|Y2X_x@E>FvHlNbbf}-w9qGFN~ z&cayhQC@e#7>&!o+DZk%TK3_1z@Y-l4)`Tn(fJFYJ9=~6)|y%yq|he0=>@|>k<4@Y z2)^BR2N$^zD5`y^mQQ5>`ZKLgw2G3d51w5(;wA_|X0S%fO<_K749WsHw$-9obpAl7 zqVC4{#@`)WnIwet)>aL@fTmxaO93>bxqfGv{cc$4VR|q>9+sD>8_dfz2^gAB9r=jf9AK|FwhqV2?J5XHtFaK={MI(!$0nR{!DQfPq>b&E8 z@gvwVVuUiXW%o^g<0nTXM=eh&sZ7Ky%I%vjawknlQ8l$5;iHoJ9&hp%BJPq{KP)u7 z(!p8<*c{BCSysNI9zJ>YQ>v7XHh+`OREuMwOfR(ut&~=sHnP-_Hx@q-WnIc*FD~lxhrp67lQ&_KPg|kyA*g_` z(=#?jTBW5oMMhTY%Wz8ExW@!RlNs_f8woD9QxLy=L%Aq?MQh!Oz?%a$A_*)amoYzf z;L@1Wa@>mZC1fW^!Xot8&1~Lg3_mTB&-dR=0)pg2fNj-TGpaY$On`4x`khpQp~_ZV zg|0=y2Y_cb(`LA+WCX7FWox|Rl+y4Anwedo%ffT@Nz8LqIa+j8xxSYE+3@Kaowe%E zH}eIvm?QMrbb+#khbbxsXXUpR<|@MIdyinht~vV`==b=|CwuFr*Gcbu|3H2_5HmXL zLz6g)e)%W1uQS?f6!Eg)UfqWD>yvptO?z)U81aqK+m^3?8-6aa`YubL)`glh7=sWc zlg1_v?9WNs%DF0r{nxgK3y6t)-%;IO`R&@M?v8uE(u&g@dtSb*3>h@F?@T|}YTqks8AtMvir!o{{VsUulD%ra7J`MKs3iV#m7Dojg9M5~qP~ODp0Mu!>^~0O*UT==HLX0)`Jwk0 z>H_IZ-dH&RtPX5&W4LLBCM0LbY?82rG8?+yixzPYjGn9YGre~fDEUlLQTwiN#7Pww z!M)6OoN|3>;d}Hgl+RlOS@(l4e}wGYH@Dk&xTgofj*0sY0KUYqnMZjYb)8~j?JtgT zhGW+~dH4#x7}G0qrWPt9+$*uYW7L?ECI>;3(qFeZZVuB;JpC=63CXIwP2T<90R~ME zPy%#&JHyqY)TAAI!>JQA)9aBP6Z1;tJ*dO=HN?YyJuRt^`JPve|y-J zYZ(#{=YLoAcq%#F=4oLF$IJ(O{hIpf zYllUKIe1p{7LZqvW@3gt-oyaBZ5aLYZwYEnS5y|J#mAlop+FDVGQWbQcU=zFeFbWy z3cus9i9|W@;hT1xtQ&smyU5Hlm@NQ!J^?U&SE0lAziQq73t;1#{^DujkGOXF?}EF~ z7nDP$OL~|26|z?x*HDMB&Gsgvrk=DFjNTUJA)(R0wADjAve@FnraRSUNu-*-Lzm7wQ z7t2zgNKpqVcpHrI8TfGm(jg%Bt>1b^E6<%-ezJ*g@1Ge|B9x>e1WF4yA_1kX|EtWa z;!;h?6_SGMRE<9a!`8Tlglm_b#cy9uJ!)FOUqN@l^SP`^ERC9?&#_Urr629XZ{GvZ zCNUC%mC(5(-b!euk}XUcC-}yNz*eJyRmpZ*xe}`V?E4WW;6$Y8ZkZEj+7d-vE+Tzh zPruq1t+m>fN_@zel6!>HSt%)4i(swEH6#XE#(gjDCtR@0*vk?(JD7UA&p4m^y~Q!% z5mf6c!d4PWxa?es0*C?BdM$%LI95E~pnCHps!4iNYz;Aij$x`_L)cEqhw+VU*lrT+RU zjo|ztKl;M;Kc75*`DOoOz_HHkz5)9+V&9>eU8x5rFUH!C?LB`YJPb-WQkz{Q*s>et zutJ-{G_u3oBsTR-v0Tof%INRe*zi-Vn?r`pkr!9Pk*=UQ&IdCwD$MGO-RDx zteaH7$=4rlQ)YubeAvn$;m(qV$6yO{i@B4i()9Vp2q;-3fLiW zw}9(kEr{h8r9A6@d{qwUb2`G%_3SEpZd~sB8EcEA2k+#r7{t@eQFdy<8S&*1FxH(Nw(A1mp5V4bNM zau8%4=x?~Ei?*jy=cYFbkgq7XCHVyUvEfH}0G~c$vSHl}kdOM2WGxhwr5rMhO?Xqx z=?^4Ci7uEUA?DL^pR~}hdG$tgnzlPMGteZWLX7%O zhhQtzC)-^S!;+>J@*8IAqKHANY}v-&ze7TtcqUJk2&_VURJvqCIjd<&@RRgqgq{%f zm|A2*9e5JlVfr5&VB>WI#qpXnO=W4XGm*Epef+L`_MR`jE6odS9|-fZ`{4Ov6tt(H zIDc<~yBy^b_d?q$LSR|gI<>ok3=Db~w_j-c^)4%YBU8HsSnz46SeUv11m>KuJJdFA zy}d%ci(ScK!07wm64L%KLvQ?4tuv~j*w#ikwPBahFkEQpn2bxw?U&?&2lIO0?*c7X zTDDw(@3;b@WuC-dAANEZv66lD#~`6UVf}Sc!~KerX*ED ze}8gzzN1_os|FU?vBw%!JG!fxLLZuJ-3iU9%%4)VmvQ@+ES1>BRi_OHSA1ayZ2z^x zJ(xJe#qWdL=C!MDZ~-- zH&OaG3-VCIXgZp4RuWq68ITES=23WUs#uJgAjFA8wS0}R{BI4|Ak;|fTs+Yx`WA=} zs1c*5cZ@Zi$l(-Je*hcX@ls`Ous62uaU?33D-?7zW)=Sc!o3D<-ikYmRA*9Cn;C*o z73}8GfL+@5O-5mj?^wZ>60rJ=S>`9Sm}t4`669@T2iJo#VWh^0U~d zG7i#m_IPNj%T!hhUK?I`foGtN_i{cD6#NUi-wcx-p9qT3E|`=sRGUn&Cgnl% zjh)UG9*tt>9bKM zEQLzqm#GqAcQSg-?ZZUn z;OQJy!nP|$O<=c7*AsOLX&s+#tKaux*}(+;zNRI}P5!bj#q{$_0+(-`WGHbL#0^Wa z*HCur+WMOP!i%_{8Fe!`#`IgN$mclm-PE}9R``u2@v2JVU(n>Kd_W3;?0$v9M{1dA zcyz9;HrWenfT6bf7$?cae~OCPLCAy4VN~JSdzmfew${+&DZ)G-F ziO@CHl8)=6N>Mh}H7RMEQ%n1TM`ad9epcgwjY`){Tw-q;Hib)-lGfO@LNL=zl3bnt zOM}MSjQG}8*Zuo?Z_R*JooD9>Wlle?oq}0Ofu_7030tGl9k%M}^P6-q1y>0l3ZzV}l%BE=kjR7-tLrjB-Q{XsIF)_E3!GfwO^dReQX5NTE3YpQ zu_S3m3gwJp@2=oeZ zC|bszVhIuD=Z1S7Um3rovS>8rg0qAa0gjH07O#A1#>_d)=4MqT0zj84&I6C6aeBWiszY`j)a3$&h zqur+;D~ASWVcY=a*1H2m!5g7QTB-D7N3}{N2)WjlSbl5g?TSIc7j2>p%&vMFxvy>} z+lZJeQb^<(HvS4V#<8txR!}m(|JIp?WKQ}jXqBv$u)kIGr@BgS?U`bsKE;~E+vm&( zGp=uLaTcSynTg>z=ajEA$cs1a%b$e5E*}>L2%PnQH?1KJdaw#_D%2*Iw)V|t3t@K6 zu-?~(QZmnQ;GJqP$lv>iZNSA1Gnz z%9wfzz&z9uQT?NPogdQO>fYOn?_=Tmvs0~%w=eaIoxD1@3n;#qf z+Iht+1rf5u)Oh8^MUJGEvT_762(4y#OD5ql%X!yI=#S}!#Gj?4&Z>C4FH9OufQHD= z5*VPF&lq&!fx*uruaJ3@q?R%`HGSs03M14(4>OKhy>KM}kWT<&B zAhqKpwnr#4#9~-9*|iuXj!r6zdCvz*6#WB@{@txyhRsBN2-b>W$|n#*PtIeXSaB^S z5QA!HuHUo&J5N$Wms;c&LH?B++VK~B>W<|roI}^`l*$PB%Q^gjGg!nGh__)KU}+JKGJI;>Vsu=9zne) z??d#@ib^wl73PXcsmDd;ieKl~U5Bv**Td}O=b=JNXc}!$KtqVdQo$u(0q}Ay(x~wQ zC?!;!Sz19BT?6D6=`LT)Bn2DrRH0OudarVja4RjdP=kf-4nXFCuJ36lkvZ?jq;Z=S z!b{|Q0~vcNv_>bt9f7P5!C3rV`w-^!R25UID-b!b$`jcUCXI}nI@JwN2}RfDawn+z zHq9=bbDsQ}Tw}HF_1yY~cC(gHvU%hI`>E%W>!@k;XHlMc$sBzFLd8- zs5~~lk%@JR-g&~0J#8U<(1epIuF!%t?S|FyuRr}4C*^4W%ci3H50_fOKhtp(FmHk| zYlArh>lF{&FRj@>b=+xkFhsh(Q%=?|6{gw47qsNqJHJsXkC7rBA?WgB<^U~R_D9xjF@cb*>V72K> zFxse};R68ExuQ-46YHuHR($FlydV(|7>wxqalh+Nez{l>HUYyWu&DJ{B5bjpNRr7- zAJm)J|Jh$J__V^0v=wJNVHpPWQX2PDs44D(7v8LqXk7l)TnL!BtTl?&UNTa_UUEnc zG3Lp$eMu0lVrgZcBRN-ONbC&%(rltM{^sEnq4##&Ps5$#eh|B3aX8Bi?yu)DX z+MD@^U3P_=-)Ir+x74C+z<$YLo9s7?;tHDrXTOSo*CgonOC{ z!Mg7aW>2bu9xF$-7xCnn`T?v~uZg)0Zv$;f0*<~9=Ov+ZO>^(@+pQ<-kyFD~kKt0p zaX+fcEy4F>{mcELSxdI3 zfF_mx=%Xg_I2rp9Q8^SDLvCYU8<*_mr$x_F{MVNG)jyo!TL>2(aNP3m56;%sKTOtP zjOtF(4QKGo+$H+gk`UdPm4NzrgUFeA#7GW?W^ei=R7__Pf&%OXWW#7%o8E?@R2$rS zx+>65X{sNhXTlAXUsQPM|yY9zXZ80n{LiRq+pxwCH_+`9b}K6 z!#STS|4K7Pg_hN5c*8L0HW>nC%7oBgp^0%BdK?ZX2TB^DT@!=mZ;CCNaz3H|nf9pr z9}92J`GoOD!H+|{h4~>O@82Ce{)k6PNZ)fHf_z9%ENB&kzRZbc8)Z4Sg_TNNk^LX< zVcpfECpzQtZ;@d}W6#TBc()mq*$)OHK1y5!`F{_WmO%7GAl}Is8D`v5s$<#W=iqLZ zh5us3{K!!OG@2L>rO2Lm|D# z6GxO1ti}BIIL-Qok$6O#$CP&J7UCqT%=%4IG7Y=EoWe4puWrkK;QPB>rtfNajo*M= zhUBQ|#7Ky0>Kj8ml`$GA2p46oGR!HOkBrSp?El`M6Xd@(+0p~Kqtq3S`s(nE>mmei zv!aYqL!YMKnVU7k`mjFvIRSfu-y=Fp- zS1tUOjcPzU9js{k6;-^X55se@pWjY+sR6&Q5jIqd|}N$?Id3>1|_L z-mxwJBSNl&pf-WfmG||oGUiM~H_c>e*x@w2ZZ1iQ;;O}WIj2TdWYFo3Mq{Exm164h zMLp-GVXExmG~COGgn_zC%a!|sYZAgMmQPwmdhlm{&g9o1a$pNpua%5u&Hz|KT%z{`Po&N=of7N;6zyGO zu#~?PLXiZb27$E&mCO<0&hNe^X&7h5-yw!Bse?jc$dI}z-DT0ovSvAf@@rbr5RrIf5%Urz z_VixJe@6;5^xhcLUJS!CA@VsM`joQ#XpoDUT3+$R&kxHnJ1n(3%6P+?cw=M`A5w@u zTT1Bx%^c{;&Dx5*|Iys@l6k(A)(T{CtT{ajz=dE1v+2yyj-|pVLe!9mwD^xcfYC+J zh@tu8g$}YB4mIjc^en968ou%{zFnkzFpHnZEC=*=JaVx0P%*>(&?%j^sX!3IMH0eB zQKLI_iW34>atV)X41;b{p@l)6`3k*1xUu{u3~efO%9;{mdrX*<6=G|xzhBrzkD^yjoZA?O8jA_|>M4_s1Oy z?ZOI1SC#h2eHm!^M=5SxsIsc5S_u5U0LfTkC%e>4KD;12k>PgU~r{a#0!E-s{MiuVkPES-6EH9qLeZ+3w zbpjThGv+r2gLmhE4~xX18Y4J(YcU@_46Y=BlarAl)wn%vnhdiiw0*Tj@0R8?24NWe zTJgPuS6~*l6FYWQSb>@|?@w^Ku4{_+!5dR|!WGrTZ2lDOAyI@u4F)Ydv999QQvBez z%4P3l5zVgQ7{m`!QhD!W8K2v=5`;-*seX;NYSn8CT=}SlMcZ_akFxgpL;)sOvfB6% zuLyY2ez8Is{s=NA8ECbW`Nozp`CaU=chY*@Y*(hh$Dv%%zkmNW! zk5RmPnk2Pw5osdJCJc9r&_9nqCB&-*+hmD~dE0FGP!Cb?g3o>|awz%BleC4gpq*Lj zraf+K2t|ZNLHR>;(q8-Vz$4mIEUcJM%xtWm5!t1sDc?#>-a49+UvU<jF*k#9l$h~7} zjViXXdPD|9O68~qk$F&AcsFWtS~2ec&MT>hy#xf1`W-8{BA3Ii?~`6MZbisHQ9 zISilB>>@U=XBs|RmY(^UtS$cx(UKSUjaVExD-v{O5+7nmb>_0b0#KmtyEB_nT`0lm z;z@$)1~<<+zzJn!+s4M3V_-{8H89AP+Jx&c5__(GBGl#8qC%%8qRFF*Pk^ zr8C}rSH3|htvj{(knmv~K@n9h%`@&b4ccJbS0#yB*D#Kr69S$6B$InD~dc?MO2IHZX4pnX8rc%c%S;L-oCvm<1bOV`0uwnEQW)yak_Z><8F$eGd8n_=t zITO9nRh?`$pwSP9p@%1;n$RcGuI3%$@rMj}tMOh7($8r z_c~kj?xXFwn#8_6mH=66ex8b9yoP59uc;!2Y~?7TjjGvATB0v%r(eIrf%vXnBFa`o zk?*B-Sqjc?6~DyFMB4;oLe*?hu@+-&t_{qd?v}`ZcBu}vxdi7R4fTCv-m))N?kZ@4u)|%CyaF+=`7ux}}9~N~rlSbq&1+nQ9Y*F`@ zKq!q{?tN!BHmtdcqpLuAc;F;jhvQjD?``_Pm2gQ|s8h;d&(~gI0PZ*e5tkF+q%1ES zF*y~6Jown4z74vT;2)UwwXPM6v5Rhlu?VNkk#D}a+$qYIjk>>jUuPHC2H~9 zGNF_EK^JV_o|MH@5f3_Ls!+xIK$G68nvzS)E~!5E(DftywS;(6W^frrt>`o>BT2ek@dWms}vN2mAaurUN4P`>4J? zcHCYC-;e%Z3o9n!UKjiHkL((5D)|6Gjp}SSw}$Nr`anT%yaPSGw2Rk+=uJP{bklHN zN=_&7-M6YjgGYTvo=en(Sj0*Db5U}34bJB0x#1OgO9qh} zmy*;n$n9s$KKe2xzp58)9)Uk}ogX9#XY-wNS?>5qO{wd_$MW(kI0K(*adu^tkdO z9g*q(mdYOys4OYJFYpUpL5jYKqBZqac2Dld+fH9+0;)8y2shMCM}&>$1lz^&oNX%X z`TG*JZ=EmfkLi=F3e%Av=*T~yoA#SB?IX4npGTn8v4o#fgVi8-D$Zcp>Gsbr9*2MC zcO9tFKJ62qDbHyG*kMl-w#aXz!NWJcVX-G)4&soN3VxI1Nv_S#l|lu~uEj_3 z=YFp1s2CYg4mv3ptwWCNFu%>dP!;W+(>4VB;}(TaX!z-UZZCg)ys+YL+}rR=5c2ij zX5;4%NU+>C+F3(qBto_B>=aE>e6`q?!_iPC8oB<{_k!M@snboAHK-~{jJj{Z;=L@3 zxI13LthCft7KC6QtJ>)m?5C37FL$kx=|b(muU5pG#&+EyGz9WYSf~b7eXf(SP9-A4 zTD_Nb(&Q7@vO!cAkSl>|uFt2KI6s9(lhalBXmjX@Ek}80T2R3mUAgY0>7wba7gu$j z>FQ?kTc5U52^%Yqm_>!RdlZfLFtc6W8(r6q%kHTZR6isyD&&=kk~^>R%YR&jX2ty- zaY{Trnj-0W+?dHv_4FBTGwl$&9ys`gt)63BbwA}X?YuB}Z2smRXENO#_ytcJeN$L) zv%%$Z)2rVqldGp&xq0^0&KYmj{JXAHxVjhLZ2cnKaAoFXXo^ zZe9Btff)`F{zZdG+?ea`F=N?%r!|TbKpSlyaGqb=wgMW2Clg6y>;@(Tg?Kq4n^sE3 zs5TSHbat0>P{aE|QaPVhbes4@mFXjuEr-RJZTfq;RvTQ_b^3c1tsu3BuUYm?e!`a; zvXMo$2Zzn_XH-hq;#A5-_U5m@IP@yG*I;Cq@oY~ICB;jTS);e-4Ed~;k;RDc97S{g zi>=|!CgayDIuA`g?9)}Gs#JpLrmLipe!zRX7Dg?qmnp>EP-t8gFCb5<G;pHUO zlq_Y+q(t^rPLYCWF@!W6l$U_37`tqkB%m9>=+Ou*o>h5N(T%RDAAqi-E2={_t&@wH zhoVd_uS&aPmH)Qp%?0B-nZFSt2kHsnhQ!=t*ANiTe*2&oh4JNVL;)Tf1o7?o( zNv{!5m+2bnAe=9W_QsDfrtA`M3~7kM@P5;A7TORM;PnQ3`OngVDKEybGCX9s7%};k zeF4@hDe{6kf1sTtLVLb%<61u{rsR*@NvcO6)!ol zhKWC4Aqq@$bOlB0|F=<62}NJX3`93lXr@$9;vU7@pXb;Q+Z9B~aL`dJ^vc9} zD{Ev;FDtl4NIiH>7$IAJiinYP{nn5#EUKuVsDzH!gLiiB@9ea&eD+XP+#Fh3@|JPd zkyXI@0&0vB9!WYaJ1wLj@Q=4$VoM_VtG@THk6)4A5xnXf^!!>Am>`3ANobm@E+sFN zjvG^*wIUjYw6!fGrz<625E!_k{#w33=+E%N&@p!Yqq7Go$G{YU$AmJn0DEI$lEIdwwBCKyfdTwih&x|{6VRGkvSsd> zqRu4I7M~D>08_Wxpo6`D3Bex+Jz!u0MVxOgI8KyV!0h?)KKQUDmi{51Zi!Z`R}<_Q znjH@o$u(k#?HP6e%m|EMK(^lw^1xFN!lkD2Dado9#q9s0Oppr7$g{(VQudA@gLrUj zj!`1H$-?$b8EV~!rLB|L`vxK3q_S&#^Z zqptIfXyfpeGr{BTkVP+fq5cY!zt&%^M!{2Q&udOfWA9aq4&L9#Oz~`glAgXHWV%{p zq-aNwpnZZC%tIfaQ^?4Hi~m2b%F$0?JT>G zAv4})Ir!xovXzD4Vv1rBSP;HZC~>Xj&J@YGPkMB{RXISLHMi)LFHv1^OaS{%g~%&)Rmm1IM%D^&vxMRaYf@x7Tn41C=LL9o!qm z#O$Q`IE{i9qh}B8{!I8b;SE~psmIq=Wo!p?m-$#Ml``xe^ad(VMpvgsc0g(@B~tP% zQ=ez@EU%p#0c*~vrMrNCyi8xtY5%&*x}DR6zE$3&lCV!af1rImbm&%ktRgbh8t;>E z=cTi5R6;X3T>9^;XyO9tTkWf1@|DX@{85b8P70oOE|QYDXJ!v2!D|%@iunEwD)zon z>v5n`BKD@#tboKV&}bJ0eGRzONRj)s)75pJXJ?J_pV1K%Iz2CokTiI&>+J$vwz$q0 z=NFFEo5q4cQo2dyE_u)3s3u== zzqlSBIW&2dYKCa|OtnQD=u;NfsL;+0iSgk*V*L!|&vPX5DSn~JccRbytX)huG6MR) z&h^Smjr#7f#5;Z&T_0l|9g<$IYIEwxAiWvJgMf$jb zB-{sCf=^ny!`rM!&*=3=sf)CK3+Kxg_blaQHMVqz@||?4Adr+G3YPAGqWs-M1#Sr7 z$CdVH@tXv0!~a)@H>;23G&pmD>KoCp7P+1@`LTM)MDIA(c)<{6H%==_^HolXGbL|r zE3Q1_{<}Ho(FX0vUSb1nI=gu}JlH1_*DI*os?XV*{0Nh@Ygo+@)M+DsWDhq&=gs;P zM^`SWiO$#Gy#MKp;NQoD*-TduhPC`rY_nxT%H!7lUn7%pE;zcTrlaPA6SvbF8_=28 zQS`u!rcui9v5wVI@(zb`$8=|Ld6SG2TEZb$Mr^C2)lm!^1GI$jwdO;N3N@D1k@AgH z@^iv9`a2h^qg0X+-1xt;nz{So*Vb3plbVj@W7_5-K{wesKAL4p1o82uN*Xzj6LT_y zIr+BYDB7zxv$+v>$OgyWR+4IRUpSW@yz{X>=bt;fl6msq4BiQ=>FaeH4T`2cF}kcQ9O`SgCOOp+^>_-(sdehmnua)p5aM zH9tG{Nn%*sg_Q^opJ2KPx-99h9@4L(Q@l2~v$ztSwlH$|cz6h}zRH-fG4IPHHMrC6 zbZkATARVn)S}0MbwX1SF9r|okJ_-BPIc@(Y(?6S?u6}7@_=jqy|FukV!jfP{A4A=K zL2ts6Yme;Ei9L9mUJo7>o_uan=cwG{yLh5+_NKV2OnvK3W(U3>wU_>K5o*p$fxuyO zY4=b7{yMJx-RWo9!e1}0`8z*omQF-_KK6Y6_YgZtWnI_AaE!CT1uy+AI1GQ}eq=Mh zqjE(tG&;!!-OK$IES@RTq+!Vw4?*v-T%Y@RP$w8{ua+$`UCGa^!a4 zOHSS_>C@_vwm|+8YFIfg_!@wgoAZ?3`R=)dPIlr_M3~fD(&~_%x;J7LJ{QHN%RNP{ z)03Z?Y^%umGM8G{=K{Eau^byxsgpVWH1D2nrXQ0C|Gm{%85Gc3LCxRF>EI!{hm`35$D^W37gO2*s zGb;-OI453Qyk5jrNb0Y_O032IcqZBq2w%CU3lUqfp&D+g=DPEk{!yRodp3%@9|%)Q zI0D^%_k8A`t&mZx7CGDRby*i}Sg2pQXM7M7n~9QYo;T_Ewx8q8yxDS|c7T`jq>@x7 zcHiM5$gYE=o}TyfhkE+o6OLd0gZy8t&U`l)iuO7+S5-#Ed*ymu)_biddfedNGcFS{ z12rp8EjKzqNkZ&XQ=S59PN!Yg9bR&3Rs>gYM_v9QS|YTg8WE;Eg_{>lt_Y_2ymMU# zM@8&)mLt4#b!2ML&kHgp?|b4Dq{x!K|xsmB)Qp9S}{uJF=o$KCN2%4kQA zTfDnDU2AoHqN1CTHxu2$bE)hTQVW)a2R>hQe`W8@di$Ft-7t~e1b+}Bt~XQRqS z-0t_gB@@}LPrPr_X;TSj^Ld?I63;qmwFTYoi<#g!WT@!xJdJjgO3yks(!CDOFdg}e z+PIQ6JP*$7pCi|K)IGZ*zkEJ8vu!zu3O`?qOl5mKv#-MVHhZzE!w4PqG#Z6GG(4S= zcE_nl{rzyA>UTd^#}F{=X;hsKLB5m(t#_<)Ia5|EFHADFYaSbB0-gV~2 zY}`mf*a6>eD{1>AV4Q2fs$Foa~ktd(SGBZD4{C{I=YdVY-ir$W(F79vljl30vl?rYuHeDv|)l3aN|K&zV9=aZu z7m56$%6uOCdJ$V;DhlqYCo?t;O>IHmL9Z zHQ4PiJug5Gy5s^*j$_hs{}!EpEV;g(-wb4Elft43^jC9aJ&-_T*XH{2+H3ReCDbIn z#u?RQTaLad^enw*^XS4{PgH*BxA*pw@wvgq_aqn%bCQf=2il?<)s0o@MaaEX z8CX^llpz)Si#PGN+J& z{GJaI1^FU zDnNpmDs{6ihN^FZ{`*oRK&h}}{T|E5>o>C0Y`}&XHSi>&2D4aR*;9E0<$}8q*v|I; zAK@=A7Ih6={a&&quCjVd-TUjOFRNVpC+nlrNQOSvO(SRW18r};EX$kzJ)w;CDqC>> z6Azi_THalm%+>eYx%#k7y6nEJQnYO7s2AT@eM8Fo=WiH`_RViUM%8-E3fzO+;H(P( z2HD>scZ$TLaZb(5*WczJ8l~44!ychAszvUhY)`xtyTpGm=BHcQ^9aV}^(6kK?fv}W za1v2(__OkG5;lhiiN%uxoO$_U0ExvvF^;9%ed}R~FF7f8_#fd5{hObMJ=PsZQ|#7V z8_jbiaTNssm|@szKu*d@ZYkI|K_1r8Ip4)Oe79;2ZR}!Egg+bT!Nk8%!%nonCV?rh znLVI)k0x+%+dr|_O94*sH@AT~J9SqBUJ`HzKc+1Srcf;r^*`vp3!ROSO)Yt#pH(Ci1DT zDVvO-ai^L?Nt91l!$!lgvF7tT0|RE{Ew$obh0AMe>sbL3&OW>N>dp83fs$7C^4bW| z%HFTy#vM3s1@@}IZw11`dcP`{ej2Lf+W7_+z3YCDBPx)i6hZaWr>nnME7@1v0yoQ* zZ&&iL1IsardXz%+J?wyEB&xRN>13OeE8%I|EgcuLr|Rt4#ipiTMFVFM>ydlk~;F=0x@0sDWvAk#W_qOS-HUUpaYpQIN|a z=LC38q2|0Y`c8MVU0E&ae0&6jukpBcS*@f+kNu^FndT2do0B+iwfupzNE}>#fnu%A zfit1<2+Fp)>fu;>@0;Um`8fNBqf@5QTJjodmlFZw*%Hbp12}Xx+_H#0MzS-T5TAlpkMTf*$zet+%5=Q#ea}so6YUG7LZD>bn*7XHWn%R4? z*}oU~235G968!d+I@Ol81Bc9ELK8qFLCI`ftO{jpXN281!E>^x)N)*K6j( zhNkWW)zWhF_XP~gk^US|IC2ffQi3XjGig=ir+P0f_V*t2xvn>|8Ue63qWCRV>d6el zDl#G;!Ou__6-eRa|2R78fT*4(anzA_G)NuY%}=_Hlji6yX#}K81Ub5t7LaZ!kx)RS zyFn17OG1$D{GQ)GyZdHm=55U0&6}N_9rs(U)JGj9=ZfA&QV#yPpj_WgCtk3qMzApW z!m8vhYKxN>=lUfA2BW?QC#p^fnZD8j{}Jp!^YaD!*p(xK=9gLlGhakRDE~v)<^gcGvH@b#il8}4!jltgOZOVJDBgUG@LpW&Zi}@4^yUn< z@$PKYO}^>}mD8u=EkuXt{mGH(0nY1L;}kfJndq?_FMVGn;?|q%Ww(pO`zDt_$+nOB zSZdwHhZ~Pi>MM^h&H%im)dy-_+xA(E=~f0Lj8d&BH#H*&zL|}r2G{u|TT>2%C`OvE zN)l50b|wzwYyR>%PPSf1bk5gYD{DRsL@czXl%mI{^mVfC zzi81Dcp>CHN8u$MQb+vl%(nePt!T_|cOLhl=EypvMess#(u{hMSjme4MrPU)t^a!g;4Q4nMCuQiGA&_q_fV5d3<=Z#sRvbiNTa z;@)#-*Z?yfIpDG6i;0BGpJBzQrK2UqsDy(w?>SgoYZD9y<~`S_-Kzm%>o-@3;)OBz z_WrF4nnO2=<_dJZstv0p86>x;eRpnL(!G^kJ7H~DMS@HBg+aBs_Pzu@=Yw<_h3b7? z6oSt&)D7uH*H+s8;*n3owvDL`_(a9G9~;58)5_-}#Z0g`I}Pk0{do_Bed*M^mIXtZMxkbjBRn?wB3G61l(yG%-v|8l5y zFGM>alY{QW4Ci0Y=4phZy_<2=J#0-EPPD|xMF8U>APw}IFT*VVam#8RU4k`ThMBKM zTK-In%9!}v7;WEv@4yBc{8 zuj*6lGz#TW;1<*AMR^@Bzak$E4QduqyRQ$bICS9>JB$+jNy-;4#mNnX$O{+S`yk#% zKU+5GUy?D|+}RgQonFJ_=*oYv`Q#2i(!K!zw#C>)3g10@pQj_) zfhGiz9EGnl=4hGeOX-|OwmubonK<1luXAeg_1T&*QF7L0i#6ELgQO*vdy6YF>Z!7G zi#4150+vbwf<>jl`ON$(-REixt9sQ^wxTj@{xv8_A4C1)6`bgFieO^$!2 z_$sUP7rf9q1uo1MV^5$h#9J4`*w+*N*dc5pq#|OM>^Q_SnJWDh?lueGsmz3aMd)gB z8H$kk`yDzqWf-5@9u_-k9LDuMDVF}yJj25%ELA9&q8vK#e&XnAmOxT2KRSGO!(Y{*9R6u4VIqBM7dm{GRQ#o)-?mPhz)Ae#dt}iK>zzAH#;wX zOt=*Ir|KUQ)P!S8%DuTr7EPvR7oieVNZv?f*O)2b^=H46w|%!9^!Fr>_d8^SBp7AF z19K`nS#mr08Z7WPWsg1Hp=>DiC(IGyH(XG$bJO(6#JkXm)8>?ZG3#4zN^h}%WVp>m ze6GtXOH3q9_;`g%VL?j~)3qqxG;+;Q1ErBnG8HhOe&PUyE1ok;yjCLa+>4<UQEER%@^xf*?H?7#d~plm|PM{k=~VQTy;g-ovwkQat1 zmJn7I5uN0Tu;x|H4;(5A_rKBQh9v_IS!nW~u{n?em2#8=zz!Zu1*dWhBCvo;YL1po z6(^V=?kvckj!%ZT+k|EaCx&fzP{UY51?rm2Li0qW;VJP}yR(RRB8BT%Q9*rYG7CXE z%Ve%xU<11r6%Z4GW#7-u;7g3KixvQtqH#(3oKjofBGAiraulxujYwjd2Y86T)2Wve zdadx#C;94dUZaiQq?F+;H6bbEe91E_+5+Wd7I-p?kQWAvaGAq6bpdlSTw`KmH9hlG zUXPO0-vyd5(cLu!Nl0X&DJTm{W2RwJ5m6ZL8}8CdWVvIBK_~+VKUQ2mj?CdPpCzcX zYfp3W-P7;i<2cYrG~d7WIAD#b+p^@LeumzK!X+s)e&eX>wqYDR`HFoKDV5B-09Pq| z!wPJ|Z(CW@A7mNapsfv@tAB9;v*PKNN5wkma;Rh|sC2PvK)0U}OOA|bRRKECVHk_l2bQ&8XT%v~S!mW1XK#k9CRk$n z6rq9Y$rCn#;msrIG4RvS*u!WEMW|1o@W^f{0os4R0rwUKrM=889j)ZnwmHdNjs)+J z6#@q#PO{0H7%Z2bl>1zi5f&{FLZ*E2py=Wd6 zVV>1}=j19=G`EMDZWzkR42vP-6xA^-gYV=EMU&t!P^w8E+gJcqMpL5utj*C&CYs&U z8fJbOmNH`l>PI6QQ2G*!O@x{?sFh<>lwcE+E{8?GD@6iuW@` z^oazi&hGzsK3bHRH`!m_!Ju0+rr_^tvy?0zm5Rwh?LdT z8Y5B1w(M#wH1CKf2c^=LlNE6SS}S)9z*B9I-snxI;8H;zv;^z4EQjk3=*MHPPc#-7MxvH{+hH&iX48~!+XYQJk2U!t zV1i{mC;NTcx)R*Q7y>aaMNKGpuvkuCGZLK0?!+ZubK?Hyiwe?aT4$x!Gs8solc62p zI@fjglZ6MSDKh&JUyKozhB;RZ)%roM(@;{yiv@;I>^O3Z~K^e_9scg!ot+Oz+z9pB1+#u^&>X!ro7++HgbpG50Y^13;s`tg*W^O%5Ai2ax#{fO;!gwvc*^BoEOK#2PElP|FE11#?D{X=DG?`6CvNBX)IDG5ns6%fMg@4nfJu!qnN zI-bQTAiS1vf2785wR|2i6w6BEHiWyei;PYnifTA%M>{Xzw4?IX-&{l(FxE(1Me<&4 z*(9Q6&k?$cNQDj|x@k0NM~wwWxPUbOpdevu`emz&NIKsdgN7K*-&8T0*NStFH414& zt|APcHf6|h0Z!3r;rAvIGs3@>g|bR=IdMJ^E(u4p`87M#TJcT`f6;k>?rKJ2W;m!r znI_QP*h$8xRfW-eh4s52u?{Y*2xj9@t~?1$R&cLy9t@0w*(;n7kRvpn(b*c~&7RB0 zbE>W=H1SXGPUvIbxmOj-8f!B9<#?m=7tK|K;yIrH+Fhj%;>X5s_dUXCO1;UT!1Abh z6(wO!6Q1%y>iF8USbG6AeXcCQd~iXGy}*JgTh?H{N2ViNccoonCTmg}mdzy%5o6)C zcNT@ML;+tPcOq8lUlSQQ#WM4PvU&SzHi?hh+JWycT za%PK{cvaAsAE@lsjT)U%JkX^_>9*wCeGvCSI)3^k&b7hX480eg9YAC~q#8)TZH<~#_{N}C*-Chc_NrJLG?QyIjv8t{e;U=}6L&sbz# zMbMF@`y1C^&4jYfpp&&1BbmevzO}{xZtQr`YCWzd@EfP zmfy+!=vh1=t-Iz+c&YAsb}|8=o)ZbAN4+W)<6_*&{ru!3V!gkt0C!MYceg#|RjCk} z%@{0)VEhU4FpK$FUb8!aGV}kntQg4l(y08zuQ1c>jt3no)hdpI~$u; z48bkU-eGRm5H%bQ!y&NV$^3$Cx@X?K0*K*zY0J< zw6in_+vyA_{#7qf(wxsk^;Q<-a2lP^%x4OD7$p0aS}FNCI)F7Yr^Zs{o$wlkWq?2s zehQ*1a*}1%rN{{OZguUnV(ZcgZuV}1BB?Hc6kKPde7FXOJ#?)^yXbwSAtHf@jmtiE z2%lUyhVfI22>5e(2Im9e&U?-@!mGE#FcGU8JJsKAyYD&4(ueqUxy;SZhN;9Sw|y@( z$1+i-RGbbnXe%j0nZ)u-g`TC#JS^Mlp}Kt8!mT32+au?{vzr}#6TN`ftYtUvfRelr z82I82s0ndJYv-p9nk|x>*=voaPaWW!+2Y^vqdd2Y8I^`IQ{LipI-ro^-M1OYF%aJG z_>S-25qMncie>Jl0tz`@nVviPYWyFwIzhF_QBb}?pK}2I00*Y6!nyR1+CB!=#iF8f8JX-o2>(gcR+Dd`6DWm1lMg zC4Bx&XuoA*Xk)6*rm0G^$Til=YYxCQWP)SpFpDO|#^y0C^bq5Q&@~)2HO$ zv0QMBcm2H|wt$gLRS*{wGvJlTBcEEX!jg&$SC9;7jbn{2N`vBI6)5klQ*g_EI%A7+2~;(ll_N#CeGixk6@J^E5dND8U?vK$^-u+HqYRRJy8q`# zjLHZ3Xns!!L;v!U;k@o3;goduNDO6~@WlXHt0C=ubvm}Oz4Blk=lL_`cPM^D?6c7q z_i5*>ZrZe(hmCi=6m$Km`2Eq70XAQANcZuVi;pftm-rex4!?BB7+BG5zsyy>GTwbL zx}8@gsp9Iv?BS>+`QRHT%!;GWL$ewzjmz53`(-Ux8nkn{Q2hD@=Vic6!BNRj26edI z-$naf1q$&8&kv`YYe%%lt}8Eo&0NU17QO!T`%U`_+uv`N_a5pJ?_dA9b*80D@qPR) zwwp2cWc07!*~i$0+lGV->0H?hFWCq6Su+CxP~k_nr;h5wh=a ze(RY?__!!9<3Ku&Nq3dn&h$`YX?c4*7DALqIPe;0Em!lE(PD^JQ`vTK>*==uvA?G9 zS6!`5E0DjppBWDC`cJ*$9JTC~58K)2FKuL(uitHNQ%vRtz7BT#KSo|nFoVp3$t?i0 zr*5lV|KPat?*3{~Jnxt9JfZxtcri;JH|fYK=XdjH-YA8!O$5#h-AB}Qrm z{BjTv(IN^O+75PKn(CPFL+PER4tq~+9}b4*o-B?_u*p8|z8eQFHlZfl@4R^@+4S)4 z@v8svB1)VnHiqn>S}fqx;|Xph!?+SZx5dn3(x)lxy^(1gvDM1f&ZkX>=Xtw%H9s_r zA3g=8{U@-tR_j<;xmtgm_7K1tQsd2c>(DkOn*@TebyZmd)w+Uz5cV)58gxvlY^0@uzM#~_(B*vHbA~25YzJL4Vx}o?- z$it_QyW95r{`SWWUA0evI6lJdIN*n7-HFluXoov@0}{y>(#0cKKBJw;?&>rQ~fzHAij7gT1yslJ(DX% zkC0TO)#h)ZIINZ@`JU}uMt=BW)AP7g%YLLI0)iOQS20EjhIFyF z38qD=2sJFl)doC=WaDXCgD-$`++XDNHK0 z9L}ASAewBx-tg8%&Tx`7mSj*aiyGb>!Q48+k=|7*VJxrji&LVg5!&@aBXqnchUH6kjAFPdje+x%1Epl5 zP7`ZCO*xb(KR)pJ#nOCS+9s0vWtywa-o}0zPm_7@D#F1#sWCphLfdpLuvw0>Vp7R1 z1bC6E3y_RLGzPSXUyp^d>&DWR&!nsupE!#eL^+Osa$%3sO# zoHq-rr!Y=EWVS*AJ8%zl>Ap^(lA-k8dXU#eAdYW6S2jbbUkCjQLzdF)i%TvAUT51T z6(Z+Jr9}{KV|hRp(dCLfZ%ee~Ts{SzTDG8a6$y3o{mUYfU-9r+_b#A@7P3Y`msfe* ztsmze$5)s8VS?9r({q@0u`sTR>1B&jfg|sI zEGWa`&OI-fbBZ$aC4RNG%v|q0@u_R$&Mrb!4C}8^imr!2$~7)%wsfZ1zRmiiI9t2c zRh3_p`c5jfDv?vLs|lKfe5`wF{ebtou&8cFn=dP7kDX#S%=Y}2(XGa~N7mDh4%{W- zy%7)ha)c#_A`VgFBBVbvUcH_|M%hoDl)b0|EZ%kp=l9)oS%YSD9*~!%gg(#m>xYi~ zeJQBvPR3wf`~_;|ioza}qc^*)K|bl3w5)FrCZ;(ghSf>ZGe6{%){iXi8|B#bB|~Q| z8F+-{jqDH3o4e?m}MdS4jY`O3y1x=2o8%0*= zso;6R9t%jiOtOx`gMFz}b>kT;s1WljGZTsEdUY3!To>KR@w?I%eZ(QY-$0Xw6U7iKnn?5|NTtHi*s z{1H`^!b4uT_h-huCL(ResGtrkKk zqWYnNm4?+aCmzNA8jUrbco|v8Uy`Mwj0^pb8O7NtXf7 zxeHgG?uc2+2X~?x0$0Pnvr;x1^bl`m)hI185j2-W8q5cjNRQcjvF{{OV8H6jjFn9U zCzX?~^xeM}WD)pj?%AqfS7(j&C~XZj?-^!OFGN&)mCt}v8gEpK#Jpuq`omKF5>(@xOBTad$A`}W71fa#r-7qd0KeE+8|klnK=wlyt*i7F0?P7sdhO295Zq54JO5jLW@-j+xx11we<*)n^8GC;q*<~7(TU@veRRLfpgBqauBqmWKj1^b)O3y~M%}*uJp46x z9R{D|CkaFVmyZ`7Zv2VM-w8Y8xCvG*j1o@axS^l2DlYhxq9^73&HYr}(1ERr`{E!D zq?E@J8*Dn86}Nht2>C&R(y`N3gy_N|>W*{M(US+`)u;Aw@O5#)qf9Iv|p?9bfIE zcvU#mFt>lr;XV5+$5?Izg>mAsmC7Hl4obQHY zjg-pz(2pqdgrlL9@R>oKeS;Rt{Zd+EZa+$ogoqF7|GhEMJEHPQYQ|LKFzeW8UzJ!I zFhRNXyfmW-ctifS1$U&>ZEMhW7dh(+9Oa^uN%CjrhPgnL<;<7slhPnx+*H5=CK7E) zzq8Ch6(e4DmM*ret~CpJToc0X)y|8Ila(z=zp2Yvgeq(z_=!303DV zdy%8M2Ncwj#!fYH9q)G~ekN22tonHEbViUgxY_cSpU@7ZY_|EN6Gyw~@{d>HF9tue4}k2etmRykI(Dg7f1H`>G>R7|y{pCS&4`SeRW1}e{5;m?Ch`4>C( zQf&B(gwnibE1CWcQj$yiP1+kluxAEi<>)6vY%PLq9-Y_jgZ%NYC$Vui+cAAOAkzhr z!ZXBz~R(NSB@cbw1}WW z5mwaHw2WaOJ04L6uBvW#T5ihcl--;mdy4;nz2RG}5nOI}))fwon5u?a(W;%K(5P?L|;1l(Hr#0SFp*R-hj$5P^*GAEdk0jo@fmjF1xbKq}{g~69_4lvk zEJ{w2wQITx45=mVbqv$;e{W?$olLoB?zgPq9M5+`Y;HorfPL46oQ}VXD`n92qDc|7 zm+;@{N>8v?6RP$8IoFW>EAmX^!Hw#cVTs;(Q`C^WlYU@gt59OE}fZg;c8KmPm4 zBoy6QT>eih*E8~2wP`t~Gb-huM(Nk=dTzB=r~b+kl-I!;`sJ+UEBv1ZMz`KJGqyZM zw)H*4*>iBEk23Y*K1FtpR-wJ^`yq`K?fTrz&O4U#)d0+PGCjY4{CNS-2#oimzh~2w zu>O`KOetfCcdCEJzr1Wr8Pt?Ye0FCm(3lfYNvwVQY#jC8mHF@F=cVQ^=%%{av7xuq zVsAch&5&J9i+O(5EfQ-id_j~n7AG?O^h0^D)WApZUZW@8j3;2!7L=6ok#cr1O}Y29 z`x3BRvCWuc$X0%|h1etZJkG*!0DpLEPG5W)i0<&@gVAdll<_L$tY&L6! zh3I+Ku||Z+(%}8mxNp3?VF7i;YtzK0^9XOzc(v$A-7gjwvP!k4jcEv_&9LtUMtcjl zZjB6i_}|E0ILgADWt)Uh%C5{!`aj7HWWAXRf_d%b3N`Y{?b;C1JYXhnLKS)_5#iX)z2JYXLEheSck; z^6yaEE4Aq_-{1Y`*>q+B9OUfj(Wg&rc71a`xV@>n^##(XyNG)>fAQYAOy;e6JwT^g znFna_v`%WP8}R&>a(}68JQCYo;p{|<_h+SF_zJ&R9B=}MFavtEThqI#ze3J&78A}N zT4jYlJ#nrXHz{y(W3FhD`EzKy55EWdMb%Ea!u=c{<^mvR(vWj$2CUFpzR-f)s8=&G zWBp5&qk&46XG(~;qu_J^jVdJK(vA5~9#(LB!Gns>j4ZwadmeBK;eEqQ-Nu^ZRTkRK ziCAH9LV?(aAAw7fnXR=8&%dL}>yPEPQofsGMzi^~tk6ug zCzS8`Gt@pRd}5ra#X|H_WJ*qoR>|g;Ua&mwqFqsPb=Y`QMwc z+uzVltKE+3;jr&^PZpQU&~e%W-gpRLHj3vduda9CXfJd&aqFRIn*(0OOq!H~{wuur zP0CUZU5qxFLuXyDreG_i*!m%yZdNNBjs5+uEL24R^L|UlIDAcr7$y7H(9{h|a1>bh zbr@^!q7>im(+S>WtH6^)+!{Ns(!uO{v!J&ylx2#|4iZBK?P9%z?rlfHj?+X!aY99z z1T3&(qdwLV6a;m_Trr>hK@5?;KibCl_YZ}+YW%~%9_{SC#ZkfW0xouni+DRj2X#~` z3(-f*&{6U0=(x?ka`WD*1!DOCE%>|BBQy|3Tf&ZD_V~aZ30+srwJxB`ObtD>eIO1y zGMZxJptEBSd?Q-W-g1UiffJ{(kv-2ty*tcOu?XPvF*UJ&usu9dcQyUHPp6apgzL!a z(B0qV-&1gC>rB{pW}?>%&JKss?qjCXbCSvSU#opD-s+9;KD7pb#|vNPe@S92cv=jO zhuBeLwKa&_k-?qi7c9!+Q9hitc4TjgfkHvLFc|HD!Jh02e2}fZx>x0e=xhq6r^f2` z!qh=@1|ED61|Mu>YOkgsJrSY&cLUT|jR|?uMIB{#+wmBdXfEr3?TmDgM?1dIR19!4dMmLk$q}`ft$<_eHg2-bQ2ikSURgl&W(S zqJ1n+LQed`NkvWw{$PTFv1w62g7A?7T4}*A1m?l-Q>mgy?921eUkr-Ia;!S9M{_ha zE2KcM{&u|i1Ov|(P+_Jr{UG>qTojG*>U(;eP(l8$#i5H7D41r1AI#xsR+aw-B`Wyi zt33G)$;&!0hd|!mS_oLb+=DF&0~~+VZ!H%(6R%QNfqVfLlp`1Ftt>kf%(qgpd`-&} z2wYXmJyxqzfVI>P^%P$qhwMe-b~rrYH{o&E^y>` zbm-BC>X(icR)u3QFTcz{TJbG?9KqPTMEu-|0!Gnx3(P@fc3S=hquw&`M|rsdqP0j* zufRiy?F|$53&6A&$%MVJE)*0=MfH(h?v0QwX4nHd^>YF6l)XW8=XTn7tWI<&M2p)x zI#e2bX_>-=ZU1;~w@V;c+o{yU?r%r)Bmf!R=}16t9UBUk`P=Vt+O{V+u|yBnun=MKsB)E+|mvrk(oS>L=*1 z0C<>^Rziytmf2Pg!e^tH^Wu5Aug*g?^1>h3Su3WZI<}%Jr3xDR@^lJ7^}Kd~zs|y; zPvz+C=yQL^+iOK{#8g2R7I4%g)Vq4h-)3gWiA~C77(o^EMyp3Zx^r_doEn>96(oDN@i`5!JAab#g=>O2#NfKL%;ube4oZ%43~CB+CCCUYB41}8QHD&kmO zP#H8cm>XUd)vfyf;=B{2bKANGz2e7aAyo;`yY4YE%wd?!SF*4{EOk}ED{tAn+iHMC z?i~^tGp$7VS+&QaiX;qgFkJ{}o`SVKRS+)4qHuSI@`4aSRiQr=QY{?%hh_LU>h?K@ew;XbDD~?iy&-Lry|sn?f4iaL=cH#kzrjs zpcN}n8`sX;Wi^;NJ82skij{k_Z4=oE%Y^|;$}nxO4?&HMxVsYUURBJH?uaWc+()+{ zA*a`|r`icLpvKOtv|_k5hy)f|wpC%L|3mq92Xw!wYfiLj{uFAiY{j~B5HRe<|1QgMlln-e;6@HHGY7RXW zSa%{DdAgJBUnmte=EMf*54%2ub{|hO+miItQQoPngf%>M*iNW?9v?nmAdHTD^Z|2?hE}Krfw9@wKr`A0e5lf8S$`HB1zJjA}0TZ_T*74 zJ#SM!_zbD4I+Up(th)&&;a7}kC#>g#T2pgn+_Vlz3pX1_f^T*bgo^@sH%Hw1H6}I%m{Zb)1wcgc_aQj+EN*GjGwbNN8Zl(&owjJ zw)Rx}T)L#*NFNPz{Q0ub0T50wrar^ra?t~N%B0OIbY?X779Ob{RPg+r-G1&sB05-W zCfQKScEF0)t|2!xZAsZy0F^eSY&+qDPD(9w6w}BsRZB(_LlEN+3k#Km(FC@zX~Ps9 zyuU%Ig^pEpeH+8hhm>sxdbU?Ci~|18nyAR!*j%?~MbzUiad2W!IHll)1eq{(%T}sj z3KMA_Wm&)DknIjZz9F09?4q*0knQ@9-IlF(C3F%GjPdLe7z9juW3Q`iu?kHf| zV#agpO*!Fk#^iz@BKgXZ%i?sI|HwCOmZi}g#5@hQZnWna zyjX3+N;w`yHVy<`nSL+Oh~e0TMN=L{*nm}Srpk^OuJr(@HyRtaMBuDoDvS)9dFPL^ zHOarT4=lnN?30FALYbYox{N_S1xb@ieVRevt)mPOodkIPd|{yw(4oAgB45}jg&e-3 zKo}(TC5v#CIQD-k{F3qkG!p2rOki-1=lj!V1ca@H!Xo|2MicRzC!;|TT^p=A0p9Le zwqo5;t0IFg*vxj(i;~AKkz?}ycET(u7i`+{6H?52Y9V=En)qOAF-5ktejM(PnWKp+ z+fA9W2;<^?tA|})B5eWnm&!d;v=a4+Y0HUtT$8J0&w)5>$QW#`H3I*E9&QMh64+}1 zl;-HJ`E-L$NS>1>`>PvhDYiJDjIh*5WGd~#AC%>#o9Bs1x4bKXXb-7 za(@FxLwWKnvlFi`Vb7j{d>lP@NmBTPe4Z9ez)vNbQH!_d&V+PM7=fl1P)~00?(1(9FectD@U8J+`{Ph6t z3VQa{%C+`ifF8>i+^<;LN8e-gYZ(XHe4?b@?{I`}g-O#FSLz0wa_i#gZ0g_~+nepL zZ^*lIRvsYthYI&M?^1NZ-%T?=29M;3_>dgt#)Bb%bbalQ(rX)E@x3)pwBr2yf{&r} zR)&G4rS^S6VAWzAL6GxEtfx`Cle9D@E9rf3xj$l_sA8p|(%qoy$tb*C&;Vvo1s>hp ziosTDv7paO8r-Gq6oCar$3`gsP}wwySACWEp$xZ5sYZ?1&RZ~hrJfy-z95BqZ#;9uo^W@0|e>v;%&e_@2?2%`K1^WUv}tVr0C zQr_<6<`YU-l+0-L?_F{-n7SLAZ}7AEbPp#Qbu5yXo2x?S_AU;2HWEeTi)yyYi%q zD{1U)?*ON*l%3G8S$E;D0|Ui$I4_ItIeTGE2^7u#vu>E+cN(zh#z0)i(Uj=FJfL$<$$gnyoTNZ0}O%s zxB=oLTSIVtT+GgDv(^X-ZR!fM{ClgzfwL)tp)-@&Jaf?DiHCvdZOoKjl9s++7F;h& zpl8&jR$c0((Cb$h5Ss;-t7`*l*H1X+f~K)qE^HJZ!b|WrEYzun;dTR2l!VjVVWlv= zJ6MeMe-VpnW$$M$(w#uXu&Trt~9^qEVTSndJo6&s&v{ zkpN~;bExMJA#Lgwn6j&zoZSu>wZRHy&WY};FYEGQ=TdB%vA!{31M&pp&E=RO5;vQS ziS(GEi5LZOy(qX|G|6g0xLD{c>38Oa>K}Aplz*YCk@m$>@1?8QS$5-kDKbr|rLip< zQZ@VKPlYeU0^;NLZe}<8S=HiKb-fSnrq-ZF6}S)XSMrg_VYttZRbjSsJTCn&CwLnJ z4U|$lq4Nh_X|FWy#Ryz{1{;!K#*oAjwJzuB%yat>H8eW#p%X5C9t1hRQ}pn7jq~Rd z4(addQz98~P^}-!!0*cdBh}dyVzy2@l+09saF=+=-KmHkU#@3sg&tK#zswT zqdJ&DcS+em@fQ4MYbKz-OIhTfRrOh`QQ*onrsm>om3z$>(tEO8&*zo7^UD96FCmK! zu8qPA6#+?cIeyY2n=9Kn>ad-m8~PWVgN-4NIIo_`AY0#E%SkkxZZhk){XEsZlfu1$ z_)90<7pRT1U)KQ1BpKCyN(}Gqs77p(R3-tP{L8EqLz0+$=kl2G$m3ncdn7;IfLlN< z`Ct+IuN`EHgRPHZ>4|M&e}6nrR$wVNG>3BXneO;=mBb;^M!V7>t-|e+a&5ngKP)u2 zPtm-!mGd1k$}13h@J!eG`qTv=Oo*_g^VPln%%R@Qy;*H?&_T}5AZ&~i*wAP`vjr|z z-+Hty+!M&&P{%d!?O;be)t!H$u~;2__cc5}?=gfOL?^pF-hTHrBmeQ`bJWj?p%5lE z$E8zOL3v!PAwhZWecL#^KeF#K7+blYqo}~C08alPr@UgbygJ@Vd#VD81P@50ve+Vk zW2TPycqTaPQ9y|!0(8x=qJVNsetfTpl0ubjCo*E#gE%3|)bi}QVW|-B0ClY)+!JJW zHe^#!M4UPLQzl9HRh}}gLf8nNJPu|k6(oG+KP6DWQ^Z@`lXEX|*g*di7;L9YR1pp` zzw6;78hBpTHO%Q1|D83Q<*bK&!^x_Q0PYMuHy~KiS8`Prrdm9vq8~`h& zM5rUr<5raMoTGS#g$u^mRe#fFg>GPYuQr{q6}f zi=)sYoJrn$n44usw_8fzl1UzMx2>l<(YXqZ0MW%u=%`M_pl2!r*Ca;ipfsh%V&M6t zU%5W#4-1nXoSfnJlo zD`RHe>B$uM*I57P)ciQ;Bq+*Bti82%LA)|pE3Oz!L7)hriaLr3%4@E%3<~}7>cI76oyKDUmTs^m(8IB z5*=Ykc$y#C_yZUYW)#f}K4uiQgEu#9K-qzDqC!)Qa@drJ85Pg?fHULdEtRMPN5ae= zm&uvK|BxN4kKoqbMYP$0sEyk>gi(ERTP=We;Ovq^MKV5@B{DMa*_Nj=-gfP&8gt60 zGljA+)dX)#yeI*&cFi0H{j5sOSCT@Hu3X9VDoD+TXN+`SQ>o(pueC3MhpKxYCxoHw zN=cJlVfGosXzcsGWr@LHEHliEknJTx$`(b4Qc;wYq=h6BDea=9<+YSbqU`#eJ8fFt z@9+Ej|KFJpbMHCNIp?|0exB#v88hzWfD?A}rt3(YHYrPoo+-;IXPXSZ|8R0wslk5Y zvK+^Jkz77|jTaufHV8C}FSlB4XJjMn%f0*9VVR?$++9xkE$hXT z94jyfQ>HhO@`WbWU8i}2X{+?s2pP()RpzU-@t5EGAtCV;tftnOD10OSZ!VP-BLKTn z`2Nbz~ghS-2Et zO|Rl4ad+|tt_l5+=Gidr$Pkw!w-`8V%{SrZc3dj00#9vz%Eu>a ztCuAk<&q|wlaiNu?yQKgcv4>Kh^ZW08GucvY4LJrgKxT3q^rm(^T{Q`n0LiRa@kg> zs8(FWAV)UwQrS={JS&y&!-mV!A_mQ74#*Qg0uzz4Ce)~%e6ne&rHO7kQu$!bsc=6T zV*?vf{H|2^@-PDf8{vntu-9^O%6ynab@v%VqpVbPqB{2KbpY$iA|HG_l0L8tPLq%# zt@vCPaHBL`*O4S^9cHXy{ANiXUp2ob9RbowFxkmJlf_)GF-#;h&#<1O z4N#=CQ$&yYP8$mw*%8hHk4Ie{-Svhac+Ge6yRP`Whx?ofd>8*|x22ygv&E94Q^m!7 zTjX3;is$kL-ARjXl@QO}vd)_v8f--(rNOIW-fMlUW52=Bc)M`R@>x7vlwGKO67fQDkmMjyKTMrX3<6b9V z^e{Q6IZ>2!Ju$m6nJ4X1qYF#`eRt0O%%Ik#6z z;An9SWG-stou&n2$sYu<1z?OsZvwPkMG9gr_?0)FP&X-e5s?)n@9 zR(#nU^ZY$I{n}k_&B%1@Nj*iPGr8%0Y2G{jDGQ#~rGbMPj^{2zX-kL36($^#?WgAIuZ+DIzwp9bvPv)pe5LsP zEe%~OYSd20h3DVE3}4#RY<5IoPcg<;smbg}y}4yy=BlxF%@v9x zJHf@+mCnlVpCDRf&KHTIBvLPoTf`*p5-G7`^)+Vch?O`srY0m_D&i=&zJq@zR(j+7 zfjAzp?>nn}zuW5QBsu4Zh^Lfe*5@34SM3s!14m{K-M6rLwEW~Q*A1H*JF=cWcT|e(a{Y>Ur&tQew~XkN2BHGSjAIA?M;eAfSwS z&y#DkT-C@x%&KK*#4T&X!!2YfvSRVt?DXnWbLwJ6sO74S+dy_hHT0g7>odQWaiMxI zRS{3*(TU9`syetSsZq7AZSqj2%cVZIKgFK=Ew?LAZkqMf8rG@+OG`y!L0@V$?^Sf3 z;87yh$;hiX6}nHuN5UkoWR>dP?63v{MfFT9BM_&zVdJqGT!7`|<_?e+SnD41@X&C; zSkLwblryn`pE;n*y`k%&!$hOlN2e<7m%i@}kWx?h{M3CUBNSh!aJuqC0^Qk_L6C?I ztMYQIdozb_%&8uDh8?sBJrNO_w)*BR=#Ha|g3jq!Lg7Hu#E_I{k$j_u;O)>A{&taC zD;+*d9$0R${&DxC2bUqp<-6%|o-y%!iPcjwaD_NKzQmvyjA$%I_2wB5cElhH^RAWhH#oO zou3?o*C%LT*NwD4&A+aF*JKRY+7hI5mX+#r?@A{ zqhxub^`pLmkO35P)(JprFAwSu^v9FCwHADwMt1}k;vT=NxpQm5b-Am~z*}ZzJuJcU z3QuWuqFWKMdXB5ZGdLl(YFaEm;WSO)?Y0v>c`JDBPhD~MN0cahe7vllcWu?Ugv5pd z@77n=Jd@j68t7iuOR}`%=C^XaTX#+H!xo(&^@jAqmN=c&hY{_T zFOZS-x9IqG-exXLolbY$JNi{cYS+i9dBw*Ex?NAc4PZS1--hD7hlPEZcY}`a$ynNb zwdH_+U;G+c&L{1`Q9^rkV}{SWkSQ(f8fi<1#}yLsuv?xXdwR#pqjhK6hWuvk%$?o+ zDYp1!bzS?c`s6sXdt|zx-tx`GiOao;Z{5z!s8zHa$S7(Xy6@S$KTU`s(_Io2n8%~= zXnRJ#F#9)jpIgji^ zy1FbyXXD+>RLI*CZ|)5}vO^h)ty(?yh+z7Ls=oXEsL31f_|Iipex;7l ztfXzw!bHPI&&%rqZ+6Xlk-KU}-N5V~FKg(cZ(p4UPYJyoJ8$T1{c#(#2w1LeG=8$} z^Rm|!7y2nQUnYw|A&0=g5#2iwhKD2J&?gFs#^aISTCrbSwY3orQK1xs4cVW9u%!4> z$$IoixEm65qp>(Rih%Zjflda6#)4x&qa6%kM`6;#89o#y7;D3z``A-hZU`F#BRIl= z63GJKhLJ2|dls2Rfuo?s!4M-l7>**aPl!YqLLZ!i8JTe0x2CViLQ6o%YHNep0A6r5 zVoW%~oa)PjyTKr|?O+~oFhe*rB@E2=btvll(61x)$t-d(-T&JZU$M8Ou*klk2af)A zZ3w+DYkwih_sf7GtZgjeC?fIOO5aEd2w+Emu`g>89*gF&(|~C}7$fXZSQv_pJUB!G zUVLpu!%%4G@W*fn{wo%GWF`fo9Ku!4!ou8WLr4VK(lB zo{r5(XaFEMmBD1`2ap+X3>INQ{(6i;;StVMUseFq4UWY_SMd*T*q__c1nAn>?|*>! zKJH)W$6~)=h{2;Ep`!WFeW^5mIGRl`gnhU-3ld!Dq5*5ZNddd}CoX;+hk&U0Z4y8Q z8i~fFem^&$`uS0SkOQf9g8`CJLYdTHIt_-?MEKA{LdYIJR$#O7R}MM5nv)C-0EfK) zfkP;^w0#k*Us;61{9q9t^_@dF!mk{{VhBG`f-TbjNQoc1^i`h!@00+T1(8ET$uNKx ziyXd~3J|A%rGkyAlc|-%S2<<;E~Y3*NA3Ph1gypnBB0R7Z&ZNckVrW6_vbg^i$wlM zX(Qmk*nfcdBGJ%)_8I`{+gdmr4vxh_D!cftfq|&{Wj2f^3Xajl!Z8|<&O&b-`e*)p zQTTt7RH*m=Q&Kgt2p=lLCp^S2m=d{|JCKh2${kk&b7wo74Gz>03RBIF9zv%5YDQ3B z1nQ4=1dIE@9~}A{d*B#A5Hy>>-x#&%bCIzArg8s3708k;CJLl0KMWlkVJmV7uwpFd!^h6axw{aul%QV&kTdu%OWVSpjgo298Ml>f9rX4703F z?8Bs+`h%Fn@W7?pJH`%BcO)h%ir>HDopRdd#u0vzK&{7qGc2oeb7tX%hPM~b>%M-% z((1m?vfQ^n!5~**-TZl%gxj`StYKmK%SyV5RpxD716NaoO!)`F3mt>_L_nxrra}2~V ze9udj3%~?0W+Sy7g;ht7=^)AuA6dBUdZ+i~g|<3j?sdWU{0=Ck!Vcxsinbd(A#tyh zS8VrXq|LQ5RbqHf?kv3|T(VZy`5aFS4zWi=bMmi)jg5xZ5y4msEN8M<*!o*ndd}0$ zb#>kN+q`#~9=rCc=vc|ybJs)ebIA<{drhD+$y8Kc>e?d6spq$pcx3?5Ph3=w8&kc&DwKu6MtpchkwcPvcS^aOHN5j$7xcc{Y#b z*Sou~zNeu%xc`Fb@^i;F6jGvxhYS0{&h=;p45}98y?anc@J88C{I8u`v9_Vt)$0(k z{pxdSG>2akwGcZg=n?`O{);%wSR=T(DevBJvrL+q-Vz6&eKGf|uodB}>Tr)F*Nkf# z8@*bW(nsU%pq=};#bIydgI!lRoSs#1?rR;Gzp!0&I5*>VTo_+hR0C1uQ zY0YOyVa>bTR25ToadikhH#_`Vq}_{**nh9xSR4przH2vUJ*V*kC%7k>gOig};742m zoyt$G=A4pVG9}HG9zRt#WyO;&$dxY0eQZiqbW%cOQdnqGP?&?8lT%g|h1I8rMlslS zPFY_Cjz$6(Y)NJXIMW$HOjWok&F9C|>}vy;#=*g{1gFEnnZ~)3gA1(B!Od}rbJwj(t@eFtBB4(oX3!HUDVDM$RR zY&QFO${5=+WBlVY_U>!QD#|{x??QSOUr~JCwp4n$f1=FtDbx7UDUMdo$qQ5b5|i3X z^Q+TOlxRNMK}vk` z*7OvqzjC4vR%Mm%&yZOjesEg%;Ox=8d-IphlK1i+huss9fpHT`1o;nV3kq^@T#aqi z{DaK@vP1dB`~L84e+;9(i9F%VxNDt5C6Riq41iRMLKjMH`CssTcWN1-RWr0tdkv| zmZjEbDys#iiJuH98ga**9T zUHItIoLygb)tlz52Q@)@vfai8NpDOxbUrOCzo8>3b9z2tCcTi~yXKt>+12#g#)96% zTqAOJhxla^A~Q|oy;EaboL)G3uO3@I7VRxpllxw2JwL9-z#`-Qx(rh%v(rZyugXtz z_tbV7O`Cr}PCHE}HCxwMWp@?k&M`vAK4i0j&&&GPlmXoUZMa%a$*kbNaj>1Vg-J+~KZ}c`0})g>irWh_rY6)!hhgpOFi%p%&9^YScHUK5Vfo93&c7eQw~wnx-&eWnHe~~=X7E>r zUb4DkK-GVEKijaMPshY%F7tSTTi-d_@#>MM`fjxaDKDRmz715Mqcu9*HM*aEJa=RH z=j>V2{uj&aBeb|22A0mfmkD3rupvayWOm5^^3m#7qPJ-tyVsS|YDv5Ii0o>zdFXZR zb|cetlTnEI)01cOG%s!pzO}b^flIY-K<3;8r)HdvTn=%UgR|ghVcq^0XA3ijKQ)s+ z?3U_Vc6REze9Ul7M)rfL@b!YpZ8D}k@z-MqUS?CJ!(A=j%}H~pn+kMwoZ@x1ZCHWG zD2ceRbjRasE_ah*ovueYYEPw9`nGNf%<6mMz&~IUcj$DTpE1j8V)7csJKP$vy{^vh z@f^S3#q-h``sl*0nOHE>=R%yhAz3a(fg(~RPVu+hP;b!bIA>kcS_4wR5V_Y z=xw@l@ALHAXmWz(j)#m2&NADQuB=t}Z)|xfeVa$$qB@GGEn)_~E}_QQd0ECGk+=e` zwK8Luk-Jaq;asnC`EQ@Vjm>1q^8z6{JsMWyUD?7jOB|Qk?G}=@3|CZN5#xMPM49xl z`hg3na)Lmf(DPrL_Liu(D$x$Px}(-q#qe0xlFhe#RtW5{>?W^VdcJF$(c6>h^J33- zh%{_ywOi_^tdO@wuKtqfK5pKKaoaw0)ufT#HOU=nBAkyaUfI?r?56q~S$uZ!El+5;w3*q9j+H!0KjP@Oo3w zn|!)peo*>)!o2$@z32lZ22tlCzsj_S>_yj&8DSxuJJx+bl3`gDo?{S+a<){ z9BN6rRjqs*jB7f#4az$QVY`d4_j(SBgf96++D3m~`U!2(%+cO^>|W$e&y5I<={LJh zX>WJhHoD-fd1}IFPW)Dp8|Qk$-WO7@lO^kWbQvDck}3xU1U%C*P0G7p-Whl6rae6+ z-&iTRegRPvP2#mcq=^Y@bMNyjJ*3lCw;JDcrI=D6ky+}(@1dDnx8?It{UFELjjemZHR!_qgeRb#!U1RImBpDSA6EnUVAAqqDdsw$eFsO*w& zQcO*``Tpqhkl3k-CB&ZR*1^o4QnC`c&o=vPDXiVNBN9#9lr^~yYV~RK4UE|pq0%d%bhcw4ao7x)j zhv?wfbj?5ReE+N6c+7%q0{ft0mxGRIV>jp z8XK_Vi0_+UKadbc1Vn{`ughb*`A`ajO7}&u0vHquf)zpk-QTk_K|exf^rG14zxVe9 z%;F8PkFOWm+soJYZ~pd9OSOl~I=U=7xyC-mnP3*O$TRD1Jn@(B}ViR<*AQ=i&`Jy)T;k#2ftr=$6bYInzatn-0UW8=4X zOZ3d8R$N{nzQm1Bn(C?qJtNbhFT{QP=x@s&d$9Qx<2(;8 znX+)ER{`(YS2N>4XzO{)|MV43$}suE`Sa7bcdcIiH$R_@n@M>ab8vJct+!8jMckO& zQ1sb~*O^U`b^SvN+^4t2d(J-I?=f|C_vpj5J#o=RlJkAdpBe^cgPa;aOzSoe#tRj6 z)#Z$EPIk0wYYPp2c#lSMa71r)jQ`zWuBCq|J0>_3bQ-WFde^t;mqj5Kv%&M}`E`m|BrKO6(z8;23H~D8bnv ztRNjF7fTyBi%t&?qO#ycdTd0fF5idInCfht z)InY!L3Kf()RBm93qf`es;E%uG&r;{*_$5D(oqTzr}}DXAThpVEK)!{fYhegq8+7LC&Uwp{2UG=EwTbbtjhfDYhD3lz_M!+j_W9VKHM3%GFroyq#L zJ{*t(sf74?`TrJHfH!}p0$}J@GH3%BElW^m@ryD5=}02T7vR;9XmFRW15#59h1J4p zY(S#4kVtLBFOY!wV5mMQJc2Cde=&3s&gu+tTgM0`nC zsKcEo3?{@N4RxG4QXQp9z=PeeyRsd?6-RbgQHNUt??Yxmr6T(%CP>|C!9lghmma}{ z6I8z7&0hTLTG|MR(~D^QZ&RHdYH9hO=^hdSDFy_mWk3hXe2|DXHTb`X-M=j+ROs4tkC`AHY@*{@_vy_PXS_nrbU@XGP+Rn;=6o*2PLPLQZkr5Vj zACNt8poD}XSfOY?j5h{NMtTBGq7x#6cVCzqOeKCf zU@wpOfzlsX&TayR25=wo-HZ`o@PFy`?@jc>c7vpKE-L?gGcwA5vN0+k z6ogb3@C{O0Wdkip#s8am%SS%LQFMnynX#C!WM??1_ z{4y4e2N~?2+ceNnmGkE|3{DelT7GWBVR4|Y`Ewfvsqq^e1_c!xe}=x3L)DE`D7Di~5b1NKJ6p!4EhVgAD3;4EAj)_S9_@ARBOm9i0yD zK!Ng>aD*w%j}C{l4&3ZwY5;fBMj0VB3_(+9q6aCnRnC>P_fhQ$9J c!UMXwg~=i_SZskrp-^Zn2Bx53Xl(@hAG62!4gdfE literal 0 HcmV?d00001 diff --git a/paper/simulations/atlas_joint_impctrl_sqrt_damping_test_extforce_comp.m b/paper/simulations/atlas_joint_impctrl_sqrt_damping_test_extforce_comp.m new file mode 100644 index 0000000..05264e2 --- /dev/null +++ b/paper/simulations/atlas_joint_impctrl_sqrt_damping_test_extforce_comp.m @@ -0,0 +1,242 @@ +% Start the Atlas Arm (v5) joint impctrl +% Test the Model holding a position and exerting external forces +% +% Erstellt Bild 12 aus [VorndammeSchToeHad2016] + +% Quellen +% [VorndammeSchToeHad2016] Vorndamme, Schappler, Tödtheide, Haddadin: +% Soft Robotics for the Hydraulic {A}tlas Arms: Joint Impedance Control +% with Collision Detection and Disturbance Compensation (IROS 2016) + +% Moritz Schappler, schappler@irt.uni-hannover.de, 2015-09 +% (c) Institut für Regelungstechnik, Universität Hannover + +clear +clc +close all +tb_path = fileparts(which('drc_paper_path_init.m')); + +%% Init +atlas_version = uint8(5); +lr = true; +atlas_limb = 1; +atlas_joint_impctrl_sqrt_damping_test_settings_default + +%% Startpose laden +% siehe trajectories/ImpCtrlExperiments_poses/ImpCtrlExperiments_poses.m +q0 = [0, 0, pi/2, pi/2, 0, 0, 0]; +qD0 = zeros(1,AS.NJA); + +%% Trajektorie +qsollDaten.q = q0; +qsollDaten.qD = zeros(1,AS.NJA); +qsollDaten.qDD = zeros(1,AS.NJA); +qsollDaten.t = 0; + +%% Externe Kraft + +% stetiger Kraftverlauf (nicht gewünscht) +% F_start = 0; +% F_end = 100; +% % C3-stetige Trapez-Trajektorie fahren +% zmax = [ F_end ; F_end/1e-1; F_end/1e-3; F_end/1e-4]; +% [ew_t, ew_z, w_z, w_t] = Trapez_nAbl([F_start;0;0], [F_end;0;0], 0, zmax, 1e-3, false); +% +% t_Fext = [w_t; w_t(end)+3; w_t(end)+3+w_t]; +% F_ext = [w_z(1:end,1); w_z(end,1); flipud(w_z(1:end,1))]; + +t_Fext = [0;1;4]; +F_ext = [[0;50;0], zeros(3,5)]; +%% Simulink-Eingangsdaten +simin_q_soll = struct('time', qsollDaten.t, ... + 'signals', struct('values', qsollDaten.q, 'dimensions', NJL), ... + 'name', 'q_soll'); + +simin_qD_soll = struct('time', qsollDaten.t, ... + 'signals', struct('values', qsollDaten.qD, 'dimensions', NJL), ... + 'name', 'qD_soll'); + +simin_qDD_soll = struct('time', qsollDaten.t, ... + 'signals', struct('values', qsollDaten.qDD, 'dimensions', NJL), ... + 'name', 'qD_soll'); + +simin_F0_ext = struct('time', t_Fext, ... + 'signals', struct('values', F_ext, 'dimensions', 6), ... + 'name', 'F0_ext'); + +noise_level=1; + +[a_mdh, d_mdh, ~, ~, rSges_mdh_ORIG, m_ORIG,Iges_mdh_ORIG] = atlas_arm_parameter_mdh(atlas_arm_lr, atlas_version); +MPV_ORIG = atlas_arm_convert_par1_MPV(rSges_mdh_ORIG, m_ORIG, Iges_mdh_ORIG, a_mdh, d_mdh, atlas_version); +% MPV_arm_plant=MPV_ORIG; % MPV for simulated plant +MPV_arm_plant=MPV_ORIG; % MPV for calculating the gravity model +% apply noise to identified parameters +model_noise_ratio = 0.1; +rng(0); % seed for reproducable results +rSges_mdh_NOISE = rSges_mdh_ORIG.*(1-0.5*model_noise_ratio+model_noise_ratio*rand(size(rSges_mdh_ORIG))); +m_NOISE = m_ORIG.*(1-0.5*model_noise_ratio+model_noise_ratio*rand(size(m_ORIG))); +Iges_mdh_NOISE = Iges_mdh_ORIG.*(1-0.5*model_noise_ratio+model_noise_ratio*rand(size(Iges_mdh_ORIG))); +% calculate MPV with noisy data +MPV_arm_model=atlas_arm_convert_par1_MPV(rSges_mdh_NOISE, m_NOISE, Iges_mdh_NOISE, a_mdh, d_mdh, atlas_version); % MPV for calculating the gravity model +MPV_arm_damp=MPV_arm_model; % MPV for calculating the inertia matrix (positive definite) +% set noise levels for simulated measurements +q_noise = 3.4e-4*noise_level; +qD_noise = 5.5e-2*noise_level; +tau_noise = 7.3e-2*noise_level; +F_ext_noise = 2.3*noise_level; +g_noise = 2e-4*noise_level; +% set noise seeds for measurement noises +q_noise_seed = 0; +qD_noise_seed = 0; +tau_noise_seed = 0; +F_ext_noise_seed = 0; +g_noise_seed = 0; +% set noise switches for measurement noises (1=on, 0=off) +q_noise_switch = 1; +qD_noise_switch = 1; +tau_noise_switch = 1; +F_ext_noise_switch = 1; +g_noise_switch = 1; + +%friction parameters from identification +d = [1.30 0.90 1.60 2.70 0.50 0.20 0.20]'; % identified values 0.2*ones(NJL,1); +muC = [2.00 6.70 10.3 6.10 0.10 0.10 3.10]'; % identified values 0.1*ones(NJL,1); + +% controller parameters and gains +K_d = 150*eye(NJL); +D = 0.3*eye(NJL); +K_O = 10*eye(NJL); +T = 0.001; +T1 = 0; +K_tau_K = 1; +K_tau_g = 1; +K_tau_c = 1; +K_tau_D = 1; +K_tau_a = 1; +K_tau_f = 0; +K_tau_e = 0; +K_tau_o = 1; % Beobachter-Kompensation an +K_ext_c = 0; +K_obs_c = 0; +K_fri_o = K_tau_f; +K_ext_o = 0; +K_qD_d = 1; +K_qDD_d = 1; +tau_c = muC.*(1-0.5*model_noise_ratio+model_noise_ratio*rand(size(muC)));% - 4*ones(NJL,1); +B = d.*(1-0.5*model_noise_ratio+model_noise_ratio*rand(size(d)));% - 0.1*ones(NJL,1); +qD_th = 0.05*ones(NJL,1); +tau_th = 0.02*ones(NJL,1); + +%% Configure Model + +load_system(sl_Modellname) +configSet = getActiveConfigSet(sl_Modellname); +set_param(configSet, 'Solver', 'ode4'); +set_param(configSet, 'FixedStep', '1e-4'); + +%% Define Inputs +simin_tau_ext = struct('time', 0, ... + 'signals', struct('values', zeros(1,NJL), 'dimensions', NJL), ... + 'name', 'tau_ext'); +simin_tau_m = struct('time', 0, ... + 'signals', struct('values', zeros(1,NJL), 'dimensions', NJL), ... + 'name', 'tau_m'); + +%% Start Simulation with different settings +FileList = {}; +K_ext_o_Settings = [0, 1, 0]; +K_tau_o_Settings = [1, 1, 0]; +DescList = {}; +for ik = 1:length(K_ext_o_Settings) + K_ext_o = K_ext_o_Settings(ik); + K_tau_o = K_tau_o_Settings(ik); + t1 = tic; + simOut = sim(sl_Modellname, 'StopTime', '10', ... + 'SimulationMode', 'rapid'); % normal + clear sl + sl = get_simulink_outputs(simOut, sl_Modellname); + fprintf('Simulink-Modell berechnet. Rechenzeit: %1.1fs\n', toc(t1)); + FileList{ik} = fullfile(tb_path, 'simulink', 'results', sprintf('atlas5_impctrl_obs_FextO_varobs_%d.mat', ik)); + save(FileList{ik}, 'sl'); + fprintf('Simulationsergebnisse nach %s gespeichert.\n', FileList{ik}); + DescList{ik} = sprintf('Kexto=%d, Ktauo=%d', K_ext_o_Settings(ik), K_tau_o_Settings(ik)); +end + +%% Plot comparison +PlotSettingsStruct = struct('atlas_version', atlas_version, 'I', AS.JI_lArm); +PlotSettingsStruct.Files = FileList; +PlotSettingsStruct.Names = DescList; +atlas_plot_sl_compare + +%% Format plots +dockall + +%% Neues Bild generieren +Erg1 = load(FileList{1}, 'sl'); +sl1 = Erg1.sl; +Erg2 = load(FileList{2}, 'sl'); +sl2 = Erg2.sl; +Erg3 = load(FileList{3}, 'sl'); +sl3 = Erg3.sl; + +figure(99);clf; +axhdl = NaN(3,1); +axhdl(1) = subplot(3,1,1);hold on;grid on; +linhdl = NaN(3,1); +linhdl(1) = plot(sl1.t-0.5, sl1.q(:,1)); +linhdl(2) = plot(sl2.t-0.5, sl2.q(:,1)); +linhdl(3) = plot(sl3.t-0.5, sl3.q(:,1)); +leghdl = line_format_publication(linhdl, {}, {'ext0', 'ext1', 'tauobs0'}); +ylabel('$q_1$ [rad]', 'interpreter', 'latex'); + +axhdl(2) = subplot(3,1,2);hold on;grid on; +linhdl = NaN(3,1); +linhdl(1) = plot(sl1.t-0.5, sl1.tau_ext(:,1)); +linhdl(2) = plot(sl2.t-0.5, sl2.tau_ext(:,1)); +linhdl(3) = plot(sl3.t-0.5, sl3.tau_ext(:,1)); +leghdl = line_format_publication(linhdl, {}, {'ext0', 'ext1', 'tauobs0'}); +ylabel('$\tau_{\mathrm{ext},1}$ [Nm]', 'interpreter', 'latex'); + +axhdl(3) = subplot(3,1,3);hold on;grid on; +linhdl = NaN(3,1); +linhdl(1) = plot(sl1.t-0.5, -sl1.tau_obs(:,1)); +linhdl(2) = plot(sl2.t-0.5, -sl2.tau_obs(:,1)); +linhdl(3) = plot(sl3.t-0.5, -sl3.tau_obs(:,1)); +leghdl = line_format_publication(linhdl, {}, {'ext0', 'ext1', 'tauobs0'}); +ylabel('$\hat{\tau}_{\varepsilon,1}$ [Nm]', 'interpreter', 'latex'); +xlabel('$t$ [s]', 'interpreter', 'latex'); + +figure(99); +linkxaxes; +set(axhdl,'xlim',[0 4.5]); + +set_y_autoscale(99,0.05) + +subplot_expand(99, 3, 1); + +% Gesamt-Formatierung +figure_format_publication(axhdl) +set_size_plot_subplot(99, ... + 8.67, 6, ... + [3 1], ... + 0.13, 0.02, 0.1, 0.15, ... % l r u d + 0.075, 0.04) % x y + +% Gemeinsame Legende +h = legend(leghdl, {'$\kappa_{\mathrm{ext}}=0$', ... + '$\kappa_{\mathrm{ext}}=1$', '$\kappa_\varepsilon=0$'}, ... + 'interpreter', 'latex', 'orientation', 'horizontal'); +set(h, 'Position', [0.42, 0.92, .25, .08]) + +%% Bild speichern +% save figures: Keine Berücksichtigung der externen Kraft im Beobachter +res_path = fullfile(tb_path, 'simulink', 'results', 'atlas_JIC_obs_extforce_cmp'); + +mkdirs(res_path); +Filebasename_res = 'SimExp_ObsExtForce'; +saveas(99, fullfile(res_path, [Filebasename_res, '.fig'])); +export_fig(fullfile(res_path, [Filebasename_res, '.pdf'])); +export_fig(fullfile(res_path, [Filebasename_res, '.eps'])); +export_fig(fullfile(res_path, [Filebasename_res, '.png'])); + +fprintf('Nach %s gespeichert.\n', res_path); \ No newline at end of file diff --git a/paper/simulations/atlas_joint_impctrl_sqrt_damping_test_extforce_noise.m b/paper/simulations/atlas_joint_impctrl_sqrt_damping_test_extforce_noise.m new file mode 100644 index 0000000..180345b --- /dev/null +++ b/paper/simulations/atlas_joint_impctrl_sqrt_damping_test_extforce_noise.m @@ -0,0 +1,334 @@ +% Start the Atlas Arm (v5) joint impctrl +% Test the Model holding a position and exerting external forces + +% Moritz Schappler, schappler@irt.uni-hannover.de, 2015-09 +% (c) Institut für Regelungstechnik, Universität Hannover + +clear +clc +close all +tb_path = fileparts(which('drc_paper_path_init.m')); + +%% Init +atlas_version = uint8(5); +lr = true; +atlas_limb = 1; +atlas_joint_impctrl_sqrt_damping_test_settings_default + +%% Startpose laden +% siehe trajectories/ImpCtrlExperiments_poses/ImpCtrlExperiments_poses.m +q0 = [0, 0, pi/2, pi/2, 0, 0, 0]; +qD0 = zeros(1,AS.NJA); + +%% Trajektorie +qsollDaten.q = q0; +qsollDaten.qD = zeros(1,AS.NJA); +qsollDaten.qDD = zeros(1,AS.NJA); +qsollDaten.t = 0; + +%% Externe Kraft + +% stetiger Kraftverlauf (nicht gewünscht) +% F_start = 0; +% F_end = 100; +% % C3-stetige Trapez-Trajektorie fahren +% zmax = [ F_end ; F_end/1e-1; F_end/1e-3; F_end/1e-4]; +% [ew_t, ew_z, w_z, w_t] = Trapez_nAbl([F_start;0;0], [F_end;0;0], 0, zmax, 1e-3, false); +% +% t_Fext = [w_t; w_t(end)+3; w_t(end)+3+w_t]; +% F_ext = [w_z(1:end,1); w_z(end,1); flipud(w_z(1:end,1))]; + +t_Fext = [0;1;4]; +F_ext = [[0;50;0], zeros(3,5)]; +%% Simulink-Eingangsdaten +simin_q_soll = struct('time', qsollDaten.t, ... + 'signals', struct('values', qsollDaten.q, 'dimensions', NJL), ... + 'name', 'q_soll'); + +simin_qD_soll = struct('time', qsollDaten.t, ... + 'signals', struct('values', qsollDaten.qD, 'dimensions', NJL), ... + 'name', 'qD_soll'); + +simin_qDD_soll = struct('time', qsollDaten.t, ... + 'signals', struct('values', qsollDaten.qDD, 'dimensions', NJL), ... + 'name', 'qD_soll'); + +simin_F0_ext = struct('time', t_Fext, ... + 'signals', struct('values', F_ext, 'dimensions', 6), ... + 'name', 'F0_ext'); +rng(0); % seed for reproducable results +mkdirs(fullfile(tb_path, 'simulink', 'results', 'MdlNoise')); +mkdirs(fullfile(tb_path, 'simulink', 'results', 'MesNoise')); + +%% generate reference data +[a_mdh, d_mdh, ~, ~, rSges_mdh_ORIG, m_ORIG,Iges_mdh_ORIG] = atlas_arm_parameter_mdh(atlas_arm_lr, atlas_version); +MPV_ORIG = atlas_arm_convert_par1_MPV(rSges_mdh_ORIG, m_ORIG, Iges_mdh_ORIG, a_mdh, d_mdh, atlas_version); +% MPV_arm_plant=MPV_ORIG; % MPV for simulated plant +MPV_arm_plant=MPV_ORIG; % MPV for calculating the gravity model +% apply noise to identified parameters +model_noise_ratio = 0; +rSges_mdh_NOISE = rSges_mdh_ORIG.*(1-0.5*model_noise_ratio+model_noise_ratio*rand(size(rSges_mdh_ORIG))); +m_NOISE = m_ORIG.*(1-0.5*model_noise_ratio+model_noise_ratio*rand(size(m_ORIG))); +Iges_mdh_NOISE = Iges_mdh_ORIG.*(1-0.5*model_noise_ratio+model_noise_ratio*rand(size(Iges_mdh_ORIG))); +% calculate MPV with noisy data +MPV_arm_model=atlas_arm_convert_par1_MPV(rSges_mdh_NOISE, m_NOISE, Iges_mdh_NOISE, a_mdh, d_mdh, atlas_version); % MPV for calculating the gravity model +MPV_arm_damp=MPV_arm_model; % MPV for calculating the inertia matrix (positive definite) +% set noise levels for simulated measurements +q_noise = 3.4e-4; +qD_noise = 5.5e-2; +tau_noise = 7.3e-2; +F_ext_noise = 2.3; +g_noise = 2e-4; +% set noise seeds for measurement noises +q_noise_seed = 0; +qD_noise_seed = 0; +tau_noise_seed = 0; +F_ext_noise_seed = 0; +g_noise_seed = 0; +% set noise switches for measurement noises (1=on, 0=off) +q_noise_switch = 0; +qD_noise_switch = 0; +tau_noise_switch = 0; +F_ext_noise_switch = 0; +g_noise_switch = 0; + +%friction parameters from identification +d = [1.30 0.90 1.60 2.70 0.50 0.20 0.20]'; % identified values 0.2*ones(NJL,1); +muC = [2.00 6.70 10.3 6.10 0.10 0.10 3.10]'; % identified values 0.1*ones(NJL,1); + +% controller parameters and gains +K_d = 150*eye(NJL); +D = 0.3*eye(NJL); +K_O = 10*eye(NJL); +T = 0.001; +T1 = 0; +K_tau_K = 1; +K_tau_g = 1; +K_tau_c = 1; +K_tau_D = 1; +K_tau_a = 1; +K_tau_f = 1; +K_tau_e = 0; +K_tau_o = 0; % Beobachter-Kompensation aus +K_ext_c = 0; +K_obs_c = 0; +K_fri_o = K_tau_f; +K_ext_o = 1; +K_qD_d = 1; +K_qDD_d = 1; +tau_c = muC.*(1-0.5*model_noise_ratio+model_noise_ratio*rand(size(muC)));% - 4*ones(NJL,1); +B = d.*(1-0.5*model_noise_ratio+model_noise_ratio*rand(size(d)));% - 0.1*ones(NJL,1); +qD_th = 0.05*ones(NJL,1); +tau_th = 0.02*ones(NJL,1); + +%% Configure Model + +load_system(sl_Modellname) +configSet = getActiveConfigSet(sl_Modellname); +set_param(configSet, 'Solver', 'ode4'); +set_param(configSet, 'FixedStep', '1e-4'); + +%% Define Inputs +simin_tau_ext = struct('time', 0, ... + 'signals', struct('values', zeros(1,NJL), 'dimensions', NJL), ... + 'name', 'tau_ext'); +simin_tau_m = struct('time', 0, ... + 'signals', struct('values', zeros(1,NJL), 'dimensions', NJL), ... + 'name', 'tau_m'); + +%% Start Simulation with different settings +t1 = tic; +simOut = sim(sl_Modellname, 'StopTime', '10', ... + 'SimulationMode', 'rapid'); % normal +clear sl +sl = get_simulink_outputs(simOut, sl_Modellname); +fprintf('Simulink-Modell berechnet. Rechenzeit: %1.1fs\n', toc(t1)); +filename = fullfile(tb_path, 'simulink', 'results', 'MdlNoise', sprintf('atlas5_impctrl_obs_FextO_MdlNoise_ref.mat')); +save(filename, 'sl'); +fprintf('Simulationsergebnisse nach %s gespeichert.\n', filename); + +%% noise level comparison +for noise_level=0:0.01:0.3 + for j=1:10 + [a_mdh, d_mdh, ~, ~, rSges_mdh_ORIG, m_ORIG,Iges_mdh_ORIG] = atlas_arm_parameter_mdh(atlas_arm_lr, atlas_version); + MPV_ORIG = atlas_arm_convert_par1_MPV(rSges_mdh_ORIG, m_ORIG, Iges_mdh_ORIG, a_mdh, d_mdh, atlas_version); + % MPV_arm_plant=MPV_ORIG; % MPV for simulated plant + MPV_arm_plant=MPV_ORIG; % MPV for calculating the gravity model + % apply noise to identified parameters + model_noise_ratio = noise_level; + rSges_mdh_NOISE = rSges_mdh_ORIG.*(1-0.5*model_noise_ratio+model_noise_ratio*rand(size(rSges_mdh_ORIG))); + m_NOISE = m_ORIG.*(1-0.5*model_noise_ratio+model_noise_ratio*rand(size(m_ORIG))); + Iges_mdh_NOISE = Iges_mdh_ORIG.*(1-0.5*model_noise_ratio+model_noise_ratio*rand(size(Iges_mdh_ORIG))); + % calculate MPV with noisy data + MPV_arm_model=atlas_arm_convert_par1_MPV(rSges_mdh_NOISE, m_NOISE, Iges_mdh_NOISE, a_mdh, d_mdh, atlas_version); % MPV for calculating the gravity model + MPV_arm_damp=MPV_arm_model; % MPV for calculating the inertia matrix (positive definite) + % set noise levels for simulated measurements + q_noise = 3.4e-4; + qD_noise = 5.5e-2; + tau_noise = 7.3e-2; + F_ext_noise = 2.3; + g_noise = 2e-4; + % set noise seeds for measurement noises + q_noise_seed = 0; + qD_noise_seed = 0; + tau_noise_seed = 0; + F_ext_noise_seed = 0; + g_noise_seed = 0; + % set noise switches for measurement noises (1=on, 0=off) + q_noise_switch = 1; + qD_noise_switch = 1; + tau_noise_switch = 1; + F_ext_noise_switch = 1; + g_noise_switch = 1; + + %friction parameters from identification + d = [1.30 0.90 1.60 2.70 0.50 0.20 0.20]'; % identified values 0.2*ones(NJL,1); + muC = [2.00 6.70 10.3 6.10 0.10 0.10 3.10]'; % identified values 0.1*ones(NJL,1); + + % controller parameters and gains + K_d = 150*eye(NJL); + D = 0.3*eye(NJL); + K_O = 10*eye(NJL); + T = 0.001; + T1 = 0; + K_tau_K = 1; + K_tau_g = 1; + K_tau_c = 1; + K_tau_D = 1; + K_tau_a = 1; + K_tau_f = 1; + K_tau_e = 0; + K_tau_o = 1; % Beobachter-Kompensation an + K_ext_c = 0; + K_obs_c = 0; + K_fri_o = K_tau_f; +% K_ext_o = 1; + K_qD_d = 1; + K_qDD_d = 1; + tau_c = muC.*(1-0.5*model_noise_ratio+model_noise_ratio*rand(size(muC)));% - 4*ones(NJL,1); + B = d.*(1-0.5*model_noise_ratio+model_noise_ratio*rand(size(d)));% - 0.1*ones(NJL,1); + qD_th = 0.05*ones(NJL,1); + tau_th = 0.02*ones(NJL,1); + + for K_ext_o = 0:1 + %% Configure Model + + load_system(sl_Modellname) + configSet = getActiveConfigSet(sl_Modellname); + set_param(configSet, 'Solver', 'ode4'); + set_param(configSet, 'FixedStep', '1e-4'); + + %% Define Inputs + simin_tau_ext = struct('time', 0, ... + 'signals', struct('values', zeros(1,NJL), 'dimensions', NJL), ... + 'name', 'tau_ext'); + simin_tau_m = struct('time', 0, ... + 'signals', struct('values', zeros(1,NJL), 'dimensions', NJL), ... + 'name', 'tau_m'); + + %% Start Simulation with different settings + t1 = tic; + simOut = sim(sl_Modellname, 'StopTime', '10', ... + 'SimulationMode', 'rapid'); % normal + clear sl + sl = get_simulink_outputs(simOut, sl_Modellname); + fprintf('Simulink-Modell berechnet. Rechenzeit: %1.1fs\n', toc(t1)); + filename = fullfile(tb_path, 'simulink', 'results', 'MdlNoise', sprintf('atlas5_impctrl_obs_FextO_MdlNoise%.2f_Kexto%d_%d.mat',noise_level, K_ext_o, j)); + save(filename, 'sl'); + fprintf('Simulationsergebnisse nach %s gespeichert.\n', filename); + end + end +end + +%% measurement noise comparison +[a_mdh, d_mdh, ~, ~, rSges_mdh_ORIG, m_ORIG,Iges_mdh_ORIG] = atlas_arm_parameter_mdh(atlas_arm_lr, atlas_version); +MPV_ORIG = atlas_arm_convert_par1_MPV(rSges_mdh_ORIG, m_ORIG, Iges_mdh_ORIG, a_mdh, d_mdh, atlas_version); +% MPV_arm_plant=MPV_ORIG; % MPV for simulated plant +MPV_arm_plant=MPV_ORIG; % MPV for calculating the gravity model +% apply noise to identified parameters +model_noise_ratio = 0.1; +rSges_mdh_NOISE = rSges_mdh_ORIG.*(1-0.5*model_noise_ratio+model_noise_ratio*rand(size(rSges_mdh_ORIG))); +m_NOISE = m_ORIG.*(1-0.5*model_noise_ratio+model_noise_ratio*rand(size(m_ORIG))); +Iges_mdh_NOISE = Iges_mdh_ORIG.*(1-0.5*model_noise_ratio+model_noise_ratio*rand(size(Iges_mdh_ORIG))); +% calculate MPV with noisy data +MPV_arm_model=atlas_arm_convert_par1_MPV(rSges_mdh_NOISE, m_NOISE, Iges_mdh_NOISE, a_mdh, d_mdh, atlas_version); % MPV for calculating the gravity model +MPV_arm_damp=MPV_arm_model; % MPV for calculating the inertia matrix (positive definite) +for noise_level=1:100 + % set noise levels for simulated measurements + q_noise = 3.4e-4*noise_level; + qD_noise = 5.5e-2*noise_level; + tau_noise = 7.3e-2*noise_level; + F_ext_noise = 2.3*noise_level; + g_noise = 2e-4*noise_level; + % set noise seeds for measurement noises + q_noise_seed = 0; + qD_noise_seed = 0; + tau_noise_seed = 0; + F_ext_noise_seed = 0; + g_noise_seed = 0; + % set noise switches for measurement noises (1=on, 0=off) + q_noise_switch = 1; + qD_noise_switch = 1; + tau_noise_switch = 1; + F_ext_noise_switch = 1; + g_noise_switch = 1; + + %friction parameters from identification + d = [1.30 0.90 1.60 2.70 0.50 0.20 0.20]'; % identified values 0.2*ones(NJL,1); + muC = [2.00 6.70 10.3 6.10 0.10 0.10 3.10]'; % identified values 0.1*ones(NJL,1); + + % controller parameters and gains + K_d = 150*eye(NJL); + D = 0.3*eye(NJL); + K_O = 10*eye(NJL); + T = 0.001; + T1 = 0; + K_tau_K = 1; + K_tau_g = 1; + K_tau_c = 1; + K_tau_D = 1; + K_tau_a = 1; + K_tau_f = 1; + K_tau_e = 0; + K_tau_o = 1; % Beobachter-Kompensation an + K_ext_c = 0; + K_obs_c = 0; + K_fri_o = K_tau_f; +% K_ext_o = 1; + K_qD_d = 1; + K_qDD_d = 1; + tau_c = muC.*(1-0.5*model_noise_ratio+model_noise_ratio*rand(size(muC)));% - 4*ones(NJL,1); + B = d.*(1-0.5*model_noise_ratio+model_noise_ratio*rand(size(d)));% - 0.1*ones(NJL,1); + qD_th = 0.05*ones(NJL,1); + tau_th = 0.02*ones(NJL,1); + + for K_ext_o=0:1 + %% Configure Model + + load_system(sl_Modellname) + configSet = getActiveConfigSet(sl_Modellname); + set_param(configSet, 'Solver', 'ode4'); + set_param(configSet, 'FixedStep', '1e-4'); + + %% Define Inputs + simin_tau_ext = struct('time', 0, ... + 'signals', struct('values', zeros(1,NJL), 'dimensions', NJL), ... + 'name', 'tau_ext'); + simin_tau_m = struct('time', 0, ... + 'signals', struct('values', zeros(1,NJL), 'dimensions', NJL), ... + 'name', 'tau_m'); + + %% Start Simulation with different settings + t1 = tic; + simOut = sim(sl_Modellname, 'StopTime', '10', ... + 'SimulationMode', 'rapid'); % normal + clear sl + sl = get_simulink_outputs(simOut, sl_Modellname); + fprintf('Simulink-Modell berechnet. Rechenzeit: %1.1fs\n', toc(t1)); + filename = fullfile(tb_path, 'simulink', 'results', 'MesNoise', sprintf('atlas5_impctrl_obs_FextO_MesNoise_Kexto%d_%d.mat', K_ext_o, noise_level)); + save(filename, 'sl'); + fprintf('Simulationsergebnisse nach %s gespeichert.\n', filename); + end +end + +atlas_joint_impctrl_sqrt_damping_test_extforce_noise_plot \ No newline at end of file diff --git a/paper/simulations/atlas_joint_impctrl_sqrt_damping_test_extforce_noise_plot.m b/paper/simulations/atlas_joint_impctrl_sqrt_damping_test_extforce_noise_plot.m new file mode 100644 index 0000000..1f642a3 --- /dev/null +++ b/paper/simulations/atlas_joint_impctrl_sqrt_damping_test_extforce_noise_plot.m @@ -0,0 +1,124 @@ +% Start the Atlas Arm (v5) joint impctrl +% Test the Model holding a position and exerting external forces +% Run `atlas_joint_impctrl_sqrt_damping_test_extforce_noise.m` first. + +% Jonathan Vorndamme, vorndamme@irt.uni-hannover.de, 2016-02 +% (c) Institut für Regelungstechnik, Universität Hannover + +clear +clc +close all +tb_path = fileparts(which('drc_paper_path_init.m')); + + +%% load data and store everything needed for plotting +filename = fullfile(tb_path, 'simulink', 'results', 'MdlNoise', sprintf('atlas5_impctrl_obs_FextO_MdlNoise_ref.mat')); +load(filename); +q_ref = sl.q; +noise_level=0:0.01:0.3; +plotdata.MdlNoise0(length(noise_level),10)=0; +plotdata.NoiseLevel0(length(noise_level),10)=0; +plotdata.MdlNoise1(length(noise_level),10)=0; +plotdata.NoiseLevel1(length(noise_level),10)=0; +for i=1:length(noise_level) + for j=1:10 + for K_ext_o=0:1 + filename = fullfile(tb_path, 'simulink', 'results', 'MdlNoise', sprintf('atlas5_impctrl_obs_FextO_MdlNoise%.2f_Kexto%d_%d.mat',noise_level(i), K_ext_o, j)); + load(filename); + plotdata.(['MdlNoise' num2str(K_ext_o)])(i,j) = sum(trapz(sl.t,(sl.q-q_ref).^2))/(7*(sl.t(end)-sl.t(1))); + plotdata.(['NoiseLevel' num2str(K_ext_o)])(i,j) = noise_level(i); + end + if (mod(j,10)==0) + fprintf('\b\b\b\b\b\b%2d,%3d',i,j); + end + end +end +fprintf('\b\b\b'); + +plotdata.MesNoise0(100)=0; +plotdata.MesNoise1(100)=0; +for i=1:100 + for K_ext_o=0:1 + filename = fullfile(tb_path, 'simulink', 'results', 'MesNoise', sprintf('atlas5_impctrl_obs_FextO_MesNoise_Kexto%d_%d.mat', K_ext_o, i)); + load(filename); + plotdata.(['MesNoise' num2str(K_ext_o)])(i) = sum(trapz(sl.t,(sl.q-q_ref).^2))/(7*(sl.t(end)-sl.t(1))); + end + if (mod(i,10)==0) + fprintf('\b\b\b%3d',i); + end +end +fprintf('\b\b\b>> '); +filename = fullfile(tb_path, 'simulink', 'results', sprintf('atlas5_impctrl_obs_FextO_Noise.mat')); +save(filename,'plotdata'); + +%% Plot comparison +filename = fullfile(tb_path, 'simulink', 'results', sprintf('atlas5_impctrl_obs_FextO_Noise.mat')); +load(filename); + +figure(1); + +axhdl = NaN(2,1); +axhdl(1) = subplot(2,1,1);hold on;grid on; +plot(plotdata.NoiseLevel0(11:end)*100,plotdata.MdlNoise0(11:end)/max([plotdata.MdlNoise0(11:end), plotdata.MdlNoise1(11:end)]),'xb'); +ylabel('$\|\mathrm{MSIE}\|$','interpreter','latex'); + +axhdl(2) = subplot(2,1,2);hold on;grid on; +plot(plotdata.NoiseLevel1(11:end)*100,plotdata.MdlNoise1(11:end)/max([plotdata.MdlNoise0(11:end), plotdata.MdlNoise1(11:end)]),'xb'); +ylabel('$\|\mathrm{MSIE}\|$','interpreter','latex'); +xlabel('Maximum relative model parameter noise [%]'); + +linkxaxes(1); +set_y_autoscale(1,0.05,false) +subplot_expand(1, 2, 1); + +% Gesamt-Formatierung +figure_format_publication(axhdl) +set_size_plot_subplot(1, ... + 8.67, 6, ... + axhdl, ... + 0.14, 0.02, 0.01, 0.15, ... % l r u d + 0.075, 0.04) % x y + +figure(2); + +plot(plotdata.MesNoise0(1:30)/max([plotdata.MesNoise0(1:30) plotdata.MesNoise1(1:30)]),'xb');hold on;grid on; +plot(plotdata.MesNoise1(1:30)/max([plotdata.MesNoise0(1:30) plotdata.MesNoise1(1:30)]),'sr'); +axhdl = findall(2,'type','axes'); +ylabel('$\|\mathrm{MSIE}\|$','interpreter','latex'); +xlabel('Measurement noise amplification'); +legend({'$\kappa_\mathrm{ext}=0$','$\kappa_\mathrm{ext}=1$'}, 'interpreter', 'latex'); + +set_y_autoscale(2,0.05,false) + +% Gesamt-Formatierung +figure_format_publication(axhdl) +set_size_plot_subplot(2, ... + 8.67, 3.3, ... + axhdl, ... + 0.11, 0.02, 0.01, 0.28, ... % l r u d + 0.075, 0.04) % x y + +%% Bilder speichern +% save figures: Keine Berücksichtigung der externen Kraft im Beobachter +res_path = fullfile(tb_path, 'simulink', 'results', 'atlas_JIC_noise_extforce_cmp'); +fig_path = fullfile(tb_path, 'paper', 'simulations'); +mkdirs(res_path); +Filebasename_res = 'SimExp_MdlNoiseExtForce'; +figure(1); +saveas(1, fullfile(res_path, [Filebasename_res, '.fig'])); +export_fig(fullfile(res_path, [Filebasename_res, '.pdf'])); +export_fig(fullfile(fig_path, [Filebasename_res, '.pdf'])); +export_fig(fullfile(res_path, [Filebasename_res, '.eps'])); +export_fig(fullfile(res_path, [Filebasename_res, '.png'])); + +fprintf('Nach %s gespeichert.\n', res_path); + +Filebasename_res = 'SimExp_MesNoiseExtForce'; +figure(2); +saveas(2, fullfile(res_path, [Filebasename_res, '.fig'])); +export_fig(fullfile(res_path, [Filebasename_res, '.pdf'])); +export_fig(fullfile(fig_path, [Filebasename_res, '.pdf'])); +export_fig(fullfile(res_path, [Filebasename_res, '.eps'])); +export_fig(fullfile(res_path, [Filebasename_res, '.png'])); + +fprintf('Nach %s gespeichert.\n', res_path); diff --git a/paper/simulations/getNoiseLevel.m b/paper/simulations/getNoiseLevel.m new file mode 100644 index 0000000..7681c9d --- /dev/null +++ b/paper/simulations/getNoiseLevel.m @@ -0,0 +1,38 @@ +% Helper script to determine noise levels for measured entities +clear all; close all; %#ok +AC=atlas_const(5); +expdata = load_experiment_data('E:\DRC\matlab\experiments\atlas5_ImpCtrl\ImpCtrlv5_E061_R11_20150730_extforce_test\ImpCtrlv5_E061_R11_log_0.mat'); +noise_list={'q','qD','tau'}; +for i=1:length(noise_list) + diff_max = 0; + for j=1:4 + diff_max = max(diff_max, max(expdata.FromRobot.(noise_list{i})(1:4000,AC.JI_lArm(j)))-... + min(expdata.FromRobot.(noise_list{i})(1:4000,AC.JI_lArm(j)))); + noise_level.(noise_list{i})(j)=diff_max; + end +end + +diff_max = 0; +for i=1:3 + diff_max = max(diff_max, max(expdata.FromRobot.F_lH(1:4000,i))-... + min(expdata.FromRobot.F_lH(1:4000,i))); + noise_level.F_lH(i)=diff_max; +end + +g(3,4000)=0; +for i=1:4000 + R=quat2r(expdata.FromRobot.pelvis_x_r(i,:)); + g(:,i)=R'*[0;0;-9.81]; +end + +diff_max = 0; +for i=1:3 + diff_max = max(diff_max, max(g(i,:))-min(g(i,:))); + noise_level.g(i)=diff_max; +end + +noise_list={'q','qD','tau','F_lH', 'g'}; +for i=1:length(noise_list) + fprintf('Rauschamplitude fuer %4s: %7.2e.\n', noise_list{i}, 0.5*max(noise_level.(noise_list{i}))); +end + diff --git a/plotting/atlas_plot_sl_compare.m b/plotting/atlas_plot_sl_compare.m new file mode 100644 index 0000000..7cd12fa --- /dev/null +++ b/plotting/atlas_plot_sl_compare.m @@ -0,0 +1,147 @@ +% Unterschiedliche Durchläufe der Simulink-Simulation plotten +% +% Starten aufgerufen von anderem Skript +% Übergabe: +% PlotSettingsStruct +% Struktur mit Einstellungen zum Plotten +% +% Erstellt Bilder: +% 1 q +% 2 qD +% 3 qDD +% 4 E +% 5 tau_obs +% 6 tau_ext +% 7 F_ext +% 8 tau_m + +% Moritz Schappler, schappler@irt.uni-hannover.de, 2015-08 +% (c) Institut für Regelungstechnik, Universität Hannover + +files = PlotSettingsStruct.Files; +names = PlotSettingsStruct.Names; +I = PlotSettingsStruct.I; +atlas_version = PlotSettingsStruct.atlas_version; +AS = atlas_const(atlas_version); +%% Init +xyz = {'x', 'y', 'z'}; +FM = {'Fx', 'Fy', 'Fz', 'Mx', 'My', 'Mz'}; +%% +for i = [1 2 3 4 5 6 7 8] + figure(i);clf; +end +for i_File = 1:length(files) + + %% Daten laden + load(files{i_File}); + + %% Gelenkwinkel zeichnen + change_current_figure(1); + set(1, 'Name', 'q', 'NumberTitle', 'off'); + if i_File == 1, clf; end + for i = 1:size(sl.q,2) + subplot(3,3,i);hold all; + plot(sl.t, 180/pi*sl.q(:,i)); +% ylabel(sprintf('$q_%d \\text{[deg](%s)}$', i, AS.JN{I(i)}), 'interpreter', 'latex'); + ylabel(sprintf('$q_%d$ [deg]', i), 'interpreter', 'latex'); + grid on; + end + linkxaxes + if i_File==length(files), legend(names, 'interpreter', 'none'); end %% Gelenkwinkel zeichnen + + %% Winkelgeschwindigkeit + change_current_figure(2); + set(2, 'Name', 'qD', 'NumberTitle', 'off'); + if i_File == 1, clf; end + for i = 1:size(sl.q,2) + subplot(3,3,i);hold all; + plot(sl.t, sl.qD(:,i)); +% ylabel(sprintf('$q_%d \\text{[deg](%s)}$', i, AS.JN{I(i)}), 'interpreter', 'latex'); + ylabel(sprintf('qD_%d [rad/s]', i), 'interpreter', 'tex'); + grid on; + end + linkxaxes + if i_File==length(files), legend(names, 'interpreter', 'none'); end + + %% Beschleunigung + change_current_figure(3); + set(3, 'Name', 'qDD', 'NumberTitle', 'off'); + if i_File == 1, clf; end + for i = 1:size(sl.q,2) + subplot(3,3,i);hold all; + plot(sl.t, sl.qDD(:,i)); +% ylabel(sprintf('$q_%d \\text{[deg](%s)}$', i, AS.JN{I(i)}), 'interpreter', 'latex'); + ylabel(sprintf('qDD_%d [rad/s²]', i), 'interpreter', 'tex'); + grid on; + end + linkxaxes + if i_File==length(files), legend(names, 'interpreter', 'none'); end + + %% Energie + change_current_figure(4); + set(4, 'Name', 'E', 'NumberTitle', 'off'); + Label = {'T', 'U', 'E_ges'}; + if i_File == 1, clf; end + for i = 1:3 + subplot(3,1,i);hold all; + plot(sl.t, sl.E(:,i)); + grid on; + ylabel(sprintf('%s [J]', Label{i}), 'interpreter', 'tex'); + end + linkxaxes + if i_File==length(files), legend(names, 'interpreter', 'none'); end + + %% Beobachter-Drehmoment + change_current_figure(5); + set(5, 'Name', 'tau_obs', 'NumberTitle', 'off'); + if i_File == 1, clf; end + for i = 1:size(sl.tau_obs,2) + subplot(3,3,i);hold all; + plot(sl.t, sl.tau_obs(:,i)); + ylabel(sprintf('\\tau_{obs,%d} [Nm]', i), 'interpreter', 'tex'); + grid on; + end + linkxaxes + if i_File==length(files), legend(names, 'interpreter', 'none'); end + + %% Drehmoment aus externen Kräften + change_current_figure(6); + set(6, 'Name', 'tau_ext', 'NumberTitle', 'off'); + if i_File == 1, clf; end + for i = 1:size(sl.tau_ext,2) + subplot(3,3,i);hold all; + plot(sl.t, sl.tau_ext(:,i)); + ylabel(sprintf('\\tau_{ext,%d} [Nm]', i), 'interpreter', 'tex'); + grid on; + end + linkxaxes + if i_File==length(files), legend(names, 'interpreter', 'none'); end + + %% Externe Kräfte + change_current_figure(7); + set(7, 'Name', 'F_ext', 'NumberTitle', 'off'); + if i_File == 1, clf; end + for i = 1:size(sl.out_F0_ext,2) + subplot(3,2,i);hold all; + plot(sl.t, sl.out_F0_ext(:,i)); + ylabel(sprintf('%s [N]/[Nm]', FM{i}), 'interpreter', 'tex'); + grid on; + end + linkxaxes + if i_File==length(files), legend(names, 'interpreter', 'none'); end + + %% Motor-Drehmoment + change_current_figure(8); + set(8, 'Name', 'tau_m', 'NumberTitle', 'off'); + if i_File == 1, clf; end + for i = 1:size(sl.tau_m,2) + subplot(3,3,i);hold all; + plot(sl.t, sl.tau_m(:,i)); + ylabel(sprintf('\\tau_{m,%d} [Nm]', i), 'interpreter', 'tex'); + grid on; + end + linkxaxes + if i_File==length(files), legend(names, 'interpreter', 'none'); end +end + +dockall \ No newline at end of file diff --git a/robot_model/atlas3_arm_fkine_num.m b/robot_model/atlas3_arm_fkine_num.m new file mode 100644 index 0000000..3ade385 --- /dev/null +++ b/robot_model/atlas3_arm_fkine_num.m @@ -0,0 +1,80 @@ +% Calculate Forward Kinematics for Atlas Robot (v3) +% +% Input: +% q [1x6] +% Joint Angles [rad] +% lr [1x1 logical] +% true for left, false for right +% +% Output: +% T_c_urdf [4x4x8] +% homogenious transformation matrices for each body frame +% 1: utorso -> utorso +% 2: utorso -> clav (depending on q1) +% 3: utorso -> scap (depending on q1, q2) +% 4: utorso -> uarm +% 5: utorso -> larm +% 6: utorso -> farm +% 7: utorso -> hand +% 8: utorso -> endpoint +% +% Sources: +% [1] atlas_v3.urdf +% + +% Moritz Schappler, schappler@irt.uni-hannover.de, 2014-11 +% (c) Institut für Regelungstechnik, Leibniz Universität Hannover + + +function T_c_urdf = atlas3_arm_fkine_num(q, lr) +%% Init +%#codegen +% Coder Information +assert(isa(q,'double') && isreal(q) && all(size(q) == [1 6]), ... + 'Joint angles q have to be [1x6] double'); +assert(isa(lr,'logical') && all(size(lr) == [1 1]), ... + 'Left/Right flag has to be [1x1] logical'); + + +p_num = atlas3_arm_parameter_urdf(lr); + +%% Frame to Frame Transformations +T_urdf = NaN(4,4,7); + +% T_urdf: Overview over the indices +% 1 shy: utorso -> clav +% 2 shx: clav -> scap +% 3 ely: scap -> uarm +% 4 elx: uarm -> larm +% 5 wry: larm -> farm +% 6 wrx: farm -> hand +% 7 hand -> endpoint + +% 1 shy: utorso -> clav +T_urdf(:,:,1) = transl(p_num(1:3)) * angvec2tr(q(1), [0, p_num(4:5)]); + +% 2 shx: clav -> scap +T_urdf(:,:,2) = transl([0, p_num(6:7)]) * trotx(q(2)); + +% 3 ely: scap -> uarm +T_urdf(:,:,3) = transl([0, p_num(8:9)]) * troty(q(3)); + +% 4 elx: uarm -> larm +T_urdf(:,:,4) = transl([0, p_num(10:11)]) * trotx(q(4)); + +% 5 wry: larm -> farm +T_urdf(:,:,5) = transl([0, p_num(12:13)]) * troty(q(5)); + +% 6 wrx: farm -> hand +T_urdf(:,:,6) = transl([0, p_num(14:15)]) * trotx(q(6)); + +% 7 hand -> endpoint +T_urdf(:,:,7) = eye(4); + +%% Kumulierte Transformationsmatrizen +T_c_urdf = NaN(4,4,8); +T_c_urdf(:,:,1) = eye(4); + +for j = 2:8 + T_c_urdf(:,:,j) = T_c_urdf(:,:,j-1) * T_urdf(:,:,j-1); +end \ No newline at end of file diff --git a/robot_model/atlas3_arm_parameter_urdf.m b/robot_model/atlas3_arm_parameter_urdf.m new file mode 100644 index 0000000..6e49d5c --- /dev/null +++ b/robot_model/atlas3_arm_parameter_urdf.m @@ -0,0 +1,141 @@ +% Return Parameter of the Atlas Robot (v3) (hard coded) +% +% Input: +% lr +% true for left, false for right +% +% Output: +% p_num [15x1] +% Numeric Values of Kinematic Parameters +% rSges_num [6x3] +% Center of Gravity of all indepedent bodies (arm only) in urdf frames +% m_num [6x1] +% masses of all indepedent bodies (arm only) +% Iges_num [6x6] +% inertia of all indepedent bodies (arm only) +% rows: bodies +% columns: inertia tensor entries. Order: xx, yy, zz, xy, xz, yz +% +% Sources: +% [1] atlas_v3.urdf + +% Moritz Schappler, schappler@irt.uni-hannover.de, 2014-11 +% (c) Institut für Regelungstechnik, Leibniz Universität Hannover + +function [p_num, rSges_num, m_num, Iges_num] = atlas3_arm_parameter_urdf(lr) + +%% Init +% Coder Information +%#codegen + +assert(isa(lr,'logical') && all(size(lr) == [1 1])); + +p_num = NaN(1,15); + +Iges_num = NaN(6,6); +rSges_num = NaN(6,3); +%% Kinematic Parameters +% Source: [1] + +% 1 shy: utorso -> clav +if lr == true % left + p_num(1:3) = [0.06441, 0.13866, 0.10718]; + p_num(4:5) = [0.5, 0.866025]; % 60° +else + p_num(1:3) = [0.06441, -0.13866, 0.10718]; + p_num(4:5) = [0.5, -0.866025]; +end + +% 2 shx: clav -> scap +if lr == true % left + p_num(6:7) = [0.14035 0.19609]; +else + p_num(6:7) = [-0.14035 0.19609]; +end + +% 3 ely: scap -> uarm +if lr == true % left + p_num(8:9) = [0.187, 0.016]; +else + p_num(8:9) = [-0.187, 0.016]; +end + +% 4 elx: uarm -> larm +if lr == true % left + p_num(10:11) = [0.119, 0.00921]; +else + p_num(10:11) = [-0.119, 0.00921]; +end + +% 5 wry: larm -> farm +if lr == true % left + p_num(12:13) = [0.187, -0.00921]; +else + p_num(12:13) = [-0.187, -0.00921]; +end + +% 6 wrx: farm -> hand +if lr == true % left + p_num(14:15) = [0.119, 0.00921]; +else + p_num(14:15) = [-0.119, 0.00921]; +end + +%% Output Parameters: Center of Mass +% center of mass coordinates in body reference frames. Source: [1] + +% (1) clav +if lr == true % left + rSges_num(1,:) = [0, 0.048, 0.084]; + rSges_num(3,:) = [0, -0.065, 0];% (3) uarm + rSges_num(5,:) = [0, -0.065, 0]; % (5) farm +else + rSges_num(1,:) = [0, -0.048, 0.084]; + rSges_num(3,:) = [0, 0.065, 0];% (3) uarm + rSges_num(5,:) = [0, 0.065, 0]; % (5) farm +end +rSges_num(2,:) = [0, 0, 0];% (2) scap +rSges_num(4,:) = [0, 0, 0]; % (4) larm +rSges_num(6,:) = [0, 0, 0];% (6) hand + + +%% Output Parameters: Mass +% Source: [2] +m_num = [3.45; ... % (1) clav + 3.012; ...% (2) scap + 3.388; ...% (3) uarm + 2.509; ...% (4) larm + 3.388; ...% (5) farm + 2.509]; % (6) hand + +%% Output Parameters: Inertias +% Order: Ixx, Iyy, Izz, Ixy, Ixz, Iyz + +% (1) clav +if lr == true % left + % + Iges_num(1,:) = [0.011, 0.009, 0.004, 0, 0, -0.004]; +else + % + Iges_num(1,:) = [0.011, 0.009, 0.004, 0, 0, 0.004]; +end + +% (2) scap +% +Iges_num(2,:) = [0.00319, 0.00583, 0.00583, 0, 0, 0]; + +% (3) uarm +% +Iges_num(3,:) = [0.00656, 0.00358, 0.00656, 0, 0, 0]; + +% (4) larm +% +Iges_num(4,:) = [0.00265, 0.00446, 0.00446, 0, 0, 0]; + +% (5) farm +% +Iges_num(5,:) = [0.00656, 0.00358, 0.00656, 0, 0, 0]; + +% (6) hand +% +Iges_num(6,:) = [0.00265, 0.00446, 0.00446, 0, 0, 0]; diff --git a/robot_model/atlas3_leg_convert_urdf_mdh.m b/robot_model/atlas3_leg_convert_urdf_mdh.m new file mode 100644 index 0000000..37fb600 --- /dev/null +++ b/robot_model/atlas3_leg_convert_urdf_mdh.m @@ -0,0 +1,65 @@ +% Convert dynamic parameters from urdf to mdh for atlas v3 leg +% +% Input: +% lr [1x1 logical] +% true for left, false for right +% rSges_num_urdf [6x3 double] +% center of mass of all atlas arm bodies in urdf frames +% Iges_num_urdf [6x6 double] +% inertia of all atlas arm bodies in urdf frames +% order: xx, yy, zz, xy, xz, yz +% +% Output: +% rSges_num_mdh [6x3 double] +% center of mass of all atlas arm bodies in MDH frames +% Iges_num_mdh [6x6 double] +% inertia of all atlas arm bodies in MDH frames +% order: xx, yy, zz, xy, xz, yz + +% Moritz Schappler, schappler@irt.uni-hannover.de, 2015-03 +% (c) Institut für Regelungstechnik, Universität Hannover + + +function [rSges_num_mdh, Iges_num_mdh] = atlas3_leg_convert_urdf_mdh(lr, rSges_num_urdf, Iges_num_urdf) + +%% Init +% Coder Information +%#codegen + +assert(isa(lr,'logical') && all(size(lr) == [1 1])); +assert(isa(rSges_num_urdf,'double') && all(size(rSges_num_urdf) == [6 3])); +assert(isa(Iges_num_urdf,'double') && all(size(Iges_num_urdf) == [6 6])); + +%% get frames +p_num = atlas3_leg_parameter_urdf(lr); +T_c_mdh_urdf_hc = NaN(4,4,8); % Transformation from urdf to mdh frame (hard coded) +for i = 1:8 + T_c_mdh_urdf_hc(:,:,i) = eye(4); +end +% T_c_mdh(:,:,j+1)\T_c_urdf(:,:,j+1) +T_c_mdh_urdf_hc(:,:,1) = transl([0;0;p_num(1)]); + +T_c_mdh_urdf_hc(:,:,2) = trotz(-pi/2); + +T_c_mdh_urdf_hc(:,:,3) = troty(pi/2)*trotz(pi)*transl([-p_num(2);0;0]); + +phi = -atan(p_num(4)/p_num(5)); +T_c_mdh_urdf_hc(:,:,4) = trotz(phi)*troty(pi/2)*trotz(pi/2); + +T_c_mdh_urdf_hc(:,:,5) = troty(pi/2)*trotz(pi/2); + +T_c_mdh_urdf_hc(:,:,6) = troty(pi/2)*trotz(pi/2); + +T_c_mdh_urdf_hc(:,:,7) = troty(pi/2)*trotz(pi); +%% Convert center of mass +rSges_num_mdh = NaN(6,3); +for i = 1:6 + rSges_num_mdh(i,:) = (eye(3,4)*T_c_mdh_urdf_hc(:,:,i+1) * [rSges_num_urdf(i,:)';1])'; +end +%% Convert Inertia +Iges_num_mdh = NaN(6,6); +for i = 1:6 + I_i_urdf = inertiavector2matrix(Iges_num_urdf(i,:)); + I_i_mdh = T_c_mdh_urdf_hc(1:3,1:3,i+1) * I_i_urdf * T_c_mdh_urdf_hc(1:3,1:3,i+1)'; + Iges_num_mdh(i,:) = inertiamatrix2vector(I_i_mdh); +end \ No newline at end of file diff --git a/robot_model/atlas3_leg_fkine_num.m b/robot_model/atlas3_leg_fkine_num.m new file mode 100644 index 0000000..824bf78 --- /dev/null +++ b/robot_model/atlas3_leg_fkine_num.m @@ -0,0 +1,75 @@ +% Calculate Forward Kinematics for Atlas Robot Leg (v3) +% +% Input: +% q [1x6] +% Joint Angles [rad] +% lr [1x1 logical] +% true for left, false for right +% +% Output: +% T_c_urdf [4x4x7] +% homogenious transformation matrices for each body frame +% 1: pelvis -> pelvis +% 2: pelvis -> glut +% 3: pelvis -> lglut +% 4: pelvis -> uleg +% 5: pelvis -> lleg +% 6: pelvis -> talus +% 7: pelvis -> foot +% +% Sources: +% [1] atlas_v3.urdf + +% Moritz Schappler, schappler@irt.uni-hannover.de, 2014-11 +% (c) Institut für Regelungstechnik, Leibniz Universität Hannover + + +function T_c_urdf = atlas3_leg_fkine_num(q, lr) +%% Init +%#codegen +% Coder Information +assert(isa(q,'double') && isreal(q) && all(size(q) == [1 6]), ... + 'Joint angles q have to be [1x6] double'); +assert(isa(lr,'logical') && all(size(lr) == [1 1]), ... + 'Left/Right flag has to be [1x1] logical'); + + +p_num = atlas3_leg_parameter_urdf(lr); + +%% Frame to Frame Transformations +T_urdf = NaN(4,4,7); + +% T_urdf: Overview over the indices +% 1 hpz: pelvis -> uglut +% 2 hpx: uglut -> lglut +% 3 hpy: lglut -> uleg +% 4 kny: uleg -> lleg +% 5 aky: lleg -> talus +% 6 akx: talus -> foot + + +% 1 hpz: pelvis -> uglut +T_urdf(:,:,1) = transl([0, p_num(1), 0]) * trotz(q(1)); + +% 2 hpx: uglut -> lglut +T_urdf(:,:,2) = trotx(q(2)); +% +% 3 hpy: lglut -> uleg +T_urdf(:,:,3) = transl([p_num(2), 0, p_num(3)]) * troty(q(3)); +% +% 4 kny: uleg -> lleg +T_urdf(:,:,4) = transl([p_num(4), 0, p_num(5)]) * troty(q(4)); +% +% 5 aky: lleg -> talus +T_urdf(:,:,5) = transl([0,0,p_num(6)]) * troty(q(5)); +% +% 6 akx: talus -> foot +T_urdf(:,:,6) = trotx(q(6)); + +%% Kumulierte Transformationsmatrizen +T_c_urdf = NaN(4,4,7); +T_c_urdf(:,:,1) = eye(4); + +for j = 2:7 + T_c_urdf(:,:,j) = T_c_urdf(:,:,j-1) * T_urdf(:,:,j-1); +end \ No newline at end of file diff --git a/robot_model/atlas3_leg_parameter_mdh.m b/robot_model/atlas3_leg_parameter_mdh.m new file mode 100644 index 0000000..fcc5241 --- /dev/null +++ b/robot_model/atlas3_leg_parameter_mdh.m @@ -0,0 +1,65 @@ +% Return MDH Parameter of the Atlas Robot Leg (v3) (hard coded) +% +% Input: +% lr +% true for left, false for right +% +% Output: +% a_mdh, d_mdh, alpha_mdh, q_offset_mdh [6x1] +% Numeric Values of Kinematic Parameters, MDH-Notation +% rSges_num [6x3] +% Center of Gravity of all indepedent bodies (arm only) in urdf frames +% m_num [6x1] +% masses of all indepedent bodies (arm only) +% Iges_num [6x6] +% inertia of all indepedent bodies (arm only) +% rows: bodies +% columns: inertia tensor entries. Order: xx, yy, zz, xy, xz, yz +% +% Sources: +% [1] atlas_v3.urdf +% [2] [KhalilKle1986] + +function [a_mdh, d_mdh, alpha_mdh, q_offset_mdh, ... + rSges_num_mdh, m_num_mdh, Iges_num_mdh] = atlas3_leg_parameter_mdh(lr) + +assert(isa(lr,'logical') && all(size(lr) == [1 1]), ... + 'Left/Right flag has to be [1x1] logical'); + +[p_num_urdf, rSges_num_urdf, m_num_urdf, Iges_num_urdf] = atlas3_leg_parameter_urdf(lr); + + +%% Calculate MDH kinematic Parameter +alpha_mdh = zeros(6,1); +a_mdh = zeros(6,1); +q_offset_mdh = zeros(6,1); +d_mdh = zeros(6,1); + +% set MDH parameters with values from urdf-file +% Um z-Achse so drehen, dass nächste Drehachse die y0-Achse wird +q_offset_mdh(1) = pi/2; + +alpha_mdh(2) = pi/2; +q_offset_mdh(2) = pi/2; +d_mdh(2) = p_num_urdf(2); + +alpha_mdh(3) = pi/2; +a_mdh(3) = p_num_urdf(3); +phi = -atan(p_num_urdf(4)/p_num_urdf(5)); +q_offset_mdh(3) = -phi; + +a_mdh(4) = -sqrt(p_num_urdf(4)^2 + p_num_urdf(5)^2); +q_offset_mdh(4) = phi; + +a_mdh(5) = p_num_urdf(6); + +alpha_mdh(6) = -pi/2; +% a_mdh(6) = -p_num_urdf(6); + +%% Calculate MDH dynamic parameters + +% Different frame position and orientation + +m_num_mdh = m_num_urdf; + +[rSges_num_mdh, Iges_num_mdh] = atlas3_leg_convert_urdf_mdh(lr, rSges_num_urdf, Iges_num_urdf); \ No newline at end of file diff --git a/robot_model/atlas3_leg_parameter_urdf.m b/robot_model/atlas3_leg_parameter_urdf.m new file mode 100644 index 0000000..a72a3d9 --- /dev/null +++ b/robot_model/atlas3_leg_parameter_urdf.m @@ -0,0 +1,105 @@ +% Return Parameter of the Atlas Robot (v3) (hard coded) +% +% Input: +% lr +% true for left, false for right +% +% Output: +% p_num [6x1] +% Numeric Values of Kinematic Parameters +% rSges_num [6x3] +% Center of Gravity of all independent bodies (leg only) in urdf frames +% m_num [6x1] +% masses of all independent bodies (leg only) +% Iges_num [6x6] +% inertia of all independent bodies (leg only) +% rows: bodies +% columns: inertia tensor entries. Order: xx, yy, zz, xy, xz, yz +% +% Sources: +% [1] atlas_v3.urdf + +% Moritz Schappler, schappler@irt.uni-hannover.de, 2014-11 +% (c) Institut für Regelungstechnik, Leibniz Universität Hannover + +function [p_num, rSges_num, m_num, Iges_num] = atlas3_leg_parameter_urdf(lr) + +%% Init +% Coder Information +%#codegen + +assert(isa(lr,'logical') && all(size(lr) == [1 1])); + +p_num = NaN(1,6); +Iges_num = NaN(6,6); +rSges_num = NaN(6,3); +%% Kinematic Parameters +% Source: [1] + +% 1 hpz: pelvis -> uglut +if lr == true % left + p_num(1) = 0.089; +else + p_num(1) = -0.089; +end + +% 2 hpx: uglut -> lglut + +% 3 hpy: lglut -> uleg +p_num(2:3) = [0.05, -0.05]; + +% 4 kny: uleg -> lleg +p_num(4:5) = [-0.05,-0.374]; + +% 5 aky: lleg -> talus +p_num(6) = -0.422; + +% 6 akx: talus -> foot + +%% Output Parameters: Mass +m_num = [0.648; ... % (1) uglut + 0.866; ... % (2) lglut + 9.209; ...% (3) uleg + 5.479; ... % (4) lleg + 0.125; ...% (5) talus + 2.05]; % (6) foot + +%% Output Parameters: Center of Mass +% center of mass coordinates in body reference frames. Source: [1] +if lr == true % left + rSges_num(1,:) = [0.00529262, -0.00344732, 0.00313046]; % (1) uglut + rSges_num(2,:) = [0.0133341, 0.0170484, -0.0312052]; % (2) lglut +else + rSges_num(1,:) = [0.00529262, 0.00344732, 0.00313046]; % (1) uglut + rSges_num(2,:) = [0.0133341, -0.0170484, -0.0312052]; % (2) lglut +end +rSges_num(3,:) = [0, 0, -0.21]; % (3) uleg +rSges_num(4,:) = [0.001, 0, -0.187]; % (4) lleg +rSges_num(5,:) = [0, 0, 0]; % (5) talus +rSges_num(6,:) = [0.027, 0, -0.067]; % (6) foot + +%% Output Parameters: Inertias +% Order: Ixx, Iyy, Izz, Ixy, Ixz, Iyz + +% (1) uglut +% +Iges_num(1,:) = [0.00074276, 0.000688179, 0.00041242, -3.79607e-08, -2.79549e-05, -3.2735e-08]; +% (2) lglut +% +Iges_num(2,:) = [0.000691326, 0.00126856, 0.00106487, 2.24344e-05, 2.50508e-06, -0.000137862]; + +% (3) uleg +% +Iges_num(3,:) = [0.09, 0.09, 0.02, 0, 0, 0]; + +% (4) lleg +% +Iges_num(4,:) = [0.077, 0.076, 0.01, 0, -0.003, 0]; + +% (5) talus +% +Iges_num(5,:) = [1.01674e-05, 8.42775e-06, 1.30101e-05, 0, 0, 0]; + +% (6) foot +% +Iges_num(6,:) = [0.002, 0.007, 0.008, 0, 0, 0]; \ No newline at end of file diff --git a/robot_model/atlas3_torso_parameter_urdf.m b/robot_model/atlas3_torso_parameter_urdf.m new file mode 100644 index 0000000..afffaa6 --- /dev/null +++ b/robot_model/atlas3_torso_parameter_urdf.m @@ -0,0 +1,79 @@ +% Return Parameter of the Atlas Robot (v3) (hard coded) +% +% Input: +% +% Output: +% p_num [1x5] +% Numeric Values of Kinematic Parameters +% rSges_num [5x3] +% Center of Gravity of all independent bodies (torso only) in urdf frames +% m_num [5x1] +% masses of all independent bodies (torso only) +% Iges_num [5x6] +% inertia of all independent bodies (torso only) +% rows: bodies +% columns: inertia tensor entries. Order: xx, yy, zz, xy, xz, yz +% +% Sources: +% [1] atlas_v3.urdf + +% Moritz Schappler, schappler@irt.uni-hannover.de, 2014-11 +% (c) Institut für Regelungstechnik, Leibniz Universität Hannover + +function [p_num, rSges_num, m_num, Iges_num] = atlas3_torso_parameter_urdf() + +%% Init +% Coder Information +%#codegen + +p_num = NaN(1,5); +Iges_num = NaN(6,6); +%% Kinematic Parameters +% Source: [1] +% 1 back_bkz: pelvis -> ltorso +p_num(1) = -0.0125; + +% 2 back_bky: ltorso -> mtorso +p_num(2) = 0.16197; + +% 3 back_bkx: mtorso -> utorso +p_num(3) = 0.05; + +% 4 neck_ry: utorso -> head +p_num(4:5) = [0.21672, 0.53796]; + +%% Output Parameters: Mass +m_num = [17.882; ... % (1) pelvis + 2.409; ... % (2) ltorso + 0.69; ... % (3) mtorso + 52.007; ... % (4) utorso + 0]; + +%% Output Parameters: Center of Mass +% center of mass coordinates in body reference frames. Source: [1] +rSges_num = [ ... + [0.0111, 0, 0.0271]; ... (1) pelvis + [-0.0112984, -3.15366e-06, 0.0746835]; ... % (2) ltorso + [-0.00816266 -0.0131245 0.0305974]; ...% (3) mtorso + [-0.0923, 0, 0.3]; ... % (4) utorso + [0,0,0]]; +%% Output Parameters: Inertias +% Order: Ixx, Iyy, Izz, Ixy, Ixz, Iyz + +% (1) pelvis +% +Iges_num(1,:) = [0.1244, 0.0958, 0.1167, 0.0008, -0.0007, -0.0005]; + +% (2) ltorso +% +Iges_num(2,:) = [0.0039092, 0.00341694, 0.00174492, -5.04491e-08, -0.000342157, 4.87119e-07]; + +% (3) mtorso +% +Iges_num(3,:) = [0.000454181, 0.000483282, 0.000444215, 6.10764e-05, 3.94009e-05, 5.27463e-05]; + +% (4) utorso +% +Iges_num(4,:) = [1.466, 1.51, 1.3, 0.00362, 0.336, 0.001]; + +Iges_num(5,:) = zeros(1,6); \ No newline at end of file diff --git a/robot_model/atlas4_arm_fkine_num.m b/robot_model/atlas4_arm_fkine_num.m new file mode 100644 index 0000000..563a30b --- /dev/null +++ b/robot_model/atlas4_arm_fkine_num.m @@ -0,0 +1,80 @@ +% Calculate Forward Kinematics for Atlas Robot (v4) +% +% Input: +% q [1x6] +% Joint Angles [rad] +% lr [1x1 logical] +% true for left, false for right +% +% Output: +% T_c_urdf [4x4x8] +% homogenious transformation matrices for each body frame +% 1: utorso -> utorso +% 2: utorso -> clav (depending on q1) +% 3: utorso -> scap (depending on q1, q2) +% 4: utorso -> uarm +% 5: utorso -> larm +% 6: utorso -> farm +% 7: utorso -> hand +% 8: utorso -> endpoint +% +% Sources: +% [1] atlas_v4.urdf +% + +% Moritz Schappler, schappler@irt.uni-hannover.de, 2015-01 +% (c) Institut für Regelungstechnik, Leibniz Universität Hannover + + +function T_c_urdf = atlas4_arm_fkine_num(q, lr) +%% Init +%#codegen +% Coder Information +assert(isa(q,'double') && isreal(q) && all(size(q) == [1 6]), ... + 'Joint angles q have to be [1x6] double'); +assert(isa(lr,'logical') && all(size(lr) == [1 1]), ... + 'Left/Right flag has to be [1x1] logical'); + + +p_num = atlas4_arm_parameter_urdf(lr); + +%% Frame to Frame Transformations +T_urdf = NaN(4,4,7); + +% T_urdf: Overview over the indices +% 1 shz: utorso -> clav +% 2 shx: clav -> scap +% 3 ely: scap -> uarm +% 4 elx: uarm -> larm +% 5 wry: larm -> farm +% 6 wrx: farm -> hand +% 7 hand -> endpoint + +% 1 shz: utorso -> clav +T_urdf(:,:,1) = transl(p_num(1:3)) * trotz(q(1)); + +% 2 shx: clav -> scap +T_urdf(:,:,2) = transl([0, p_num(6:7)]) * trotx(q(2)); + +% 3 ely: scap -> uarm +T_urdf(:,:,3) = transl([0, p_num(8:9)]) * troty(q(3)); + +% 4 elx: uarm -> larm +T_urdf(:,:,4) = transl([0, p_num(10:11)]) * trotx(q(4)); + +% 5 wry: larm -> farm +T_urdf(:,:,5) = transl([0, p_num(12:13)]) * troty(q(5)); + +% 6 wrx: farm -> hand +T_urdf(:,:,6) = transl([0, p_num(14:15)]) * trotx(q(6)); + +% 7 hand -> endpoint +T_urdf(:,:,7) = eye(4); + +%% Kumulierte Transformationsmatrizen +T_c_urdf = NaN(4,4,8); +T_c_urdf(:,:,1) = eye(4); + +for j = 2:8 + T_c_urdf(:,:,j) = T_c_urdf(:,:,j-1) * T_urdf(:,:,j-1); +end \ No newline at end of file diff --git a/robot_model/atlas4_arm_parameter_urdf.m b/robot_model/atlas4_arm_parameter_urdf.m new file mode 100644 index 0000000..3d6b241 --- /dev/null +++ b/robot_model/atlas4_arm_parameter_urdf.m @@ -0,0 +1,148 @@ +% Return Parameter of the Atlas Robot (v4) (hard coded) +% +% Input: +% lr +% true for left, false for right +% +% Output: +% p_num [15x1] +% Numeric Values of Kinematic Parameters +% rSges_num [6x3] +% Center of Gravity of all indepedent bodies (arm only) in urdf frames +% m_num [6x1] +% masses of all indepedent bodies (arm only) +% Iges_num [6x6] +% inertia of all indepedent bodies (arm only) +% rows: bodies +% columns: inertia tensor entries. Order: xx, yy, zz, xy, xz, yz +% +% Sources: +% [1] atlas_v3.urdf + +% Moritz Schappler, schappler@irt.uni-hannover.de, 2014-11 +% (c) Institut für Regelungstechnik, Leibniz Universität Hannover + +function [p_num, rSges_num, m_num, Iges_num] = atlas4_arm_parameter_urdf(lr) + +%% Init +% Coder Information +%#codegen + +assert(isa(lr,'logical') && all(size(lr) == [1 1])); + +p_num = NaN(1,15); + +Iges_num = NaN(6,6); +rSges_num = NaN(6,3); +%% Kinematic Parameters +% Source: [1] + +% 1 shz: utorso -> clav +if lr == true % left + p_num(1:3) = [0.1406, 0.2036, 0.4776];%0.2256, 0.4776]; + p_num(4:5) = [0, 1]; % z-axis +else + p_num(1:3) = [0.1406, -0.2036, 0.4776];%-0.2256, 0.4776]; + p_num(4:5) = [0, 1]; +end + +% 2 shx: clav -> scap +if lr == true % left + p_num(6:7) = [0.0981 -0.2511];%0.11, -0.245]; +else + p_num(6:7) = [-0.0981 -0.2511];%-0.11, -0.245]; +end + +% 3 ely: scap -> uarm +if lr == true % left + p_num(8:9) = [0.187, -0.016]; +else + p_num(8:9) = [-0.187, -0.016]; +end + +% 4 elx: uarm -> larm +if lr == true % left + p_num(10:11) = [0.119, 0.0092]; +else + p_num(10:11) = [-0.119, 0.0092]; +end + +% 5 wry: larm -> farm +if lr == true % left + p_num(12:13) = [0.187, -0.0092]; +else + p_num(12:13) = [-0.187, -0.0092]; +end + +% 6 wrx: farm -> hand +if lr == true % left + p_num(14:15) = [0.119, 0.0092]; +else + p_num(14:15) = [-0.119, 0.0092]; +end + +%% Output Parameters: Center of Mass +% center of mass coordinates in body reference frames. Source: [1] + +if lr == true % left + rSges_num(1,:) = [0, -0.00, -0.284]; % (1) clav + rSges_num(3,:) = [0, -0.065, 0];% (3) uarm + rSges_num(5,:) = [0, -0.065, 0]; % (5) farm +else + rSges_num(1,:) = [0, 0.00, -0.284]; % (1) clav + rSges_num(3,:) = [0, 0.065, 0];% (3) uarm + rSges_num(5,:) = [0, 0.065, 0]; % (5) farm +end +rSges_num(2,:) = [0, 0, 0];% (2) scap +rSges_num(4,:) = [0, 0, 0]; % (4) larm +rSges_num(6,:) = [0, 0, 0];% (6) hand + + +%% Output Parameters: Mass +% Source: [2] +m_num = [3.45; ... % (1) clav + 3.012; ...% (2) scap + 3.388; ...% (3) uarm + 2.509; ...% (4) larm + 3.388; ...% (5) farm + 2.509]; % (6) hand + +%% Output Parameters: Inertias +% Order: Ixx, Iyy, Izz, Ixy, Ixz, Iyz + +% TODO: Rotate inertia with rpy +% (1) clav +if lr == true % left + % + % + % The inertia is given in a different frame. Rotate inertia tensor into + % the body frame + I_inertiaframe = inertiavector2matrix([0.011, 0.009, 0.004, 0, 0, -0.004]); + R_bodyframe_inertiaframe = rotx(0.5); + I_bodyframe = R_bodyframe_inertiaframe*I_inertiaframe*R_bodyframe_inertiaframe'; + Iges_num(1,:) = inertiamatrix2vector(I_bodyframe); +else + % + % + Iges_num(1,:) = [0.011, 0.009, 0.004, 0, 0, 0.004]; +end + +% (2) scap +% +Iges_num(2,:) = [0.00319, 0.00583, 0.00583, 0, 0, 0]; + +% (3) uarm +% +Iges_num(3,:) = [0.00656, 0.00358, 0.00656, 0, 0, 0]; + +% (4) larm +% +Iges_num(4,:) = [0.00265, 0.00446, 0.00446, 0, 0, 0]; + +% (5) farm +% +Iges_num(5,:) = [0.00656, 0.00358, 0.00656, 0, 0, 0]; + +% (6) hand +% +Iges_num(6,:) = [0.00265, 0.00446, 0.00446, 0, 0, 0]; diff --git a/robot_model/atlas4_leg_convert_urdf_mdh.m b/robot_model/atlas4_leg_convert_urdf_mdh.m new file mode 100644 index 0000000..88fb598 --- /dev/null +++ b/robot_model/atlas4_leg_convert_urdf_mdh.m @@ -0,0 +1,65 @@ +% Convert dynamic parameters from urdf to mdh for atlas v4 leg +% +% Input: +% lr [1x1 logical] +% true for left, false for right +% rSges_num_urdf [6x3 double] +% center of mass of all atlas arm bodies in urdf frames +% Iges_num_urdf [6x6 double] +% inertia of all atlas arm bodies in urdf frames +% order: xx, yy, zz, xy, xz, yz +% +% Output: +% rSges_num_mdh [6x3 double] +% center of mass of all atlas arm bodies in MDH frames +% Iges_num_mdh [6x6 double] +% inertia of all atlas arm bodies in MDH frames +% order: xx, yy, zz, xy, xz, yz + +% Moritz Schappler, schappler@irt.uni-hannover.de, 2015-03 +% (c) Institut für Regelungstechnik, Universität Hannover + + +function [rSges_num_mdh, Iges_num_mdh] = atlas4_leg_convert_urdf_mdh(lr, rSges_num_urdf, Iges_num_urdf) + +%% Init +% Coder Information +%#codegen + +assert(isa(lr,'logical') && all(size(lr) == [1 1])); +assert(isa(rSges_num_urdf,'double') && all(size(rSges_num_urdf) == [6 3])); +assert(isa(Iges_num_urdf,'double') && all(size(Iges_num_urdf) == [6 6])); + +%% get frames +p_num = atlas4_leg_parameter_urdf(lr); +T_c_mdh_urdf_hc = NaN(4,4,8); % Transformation from urdf to mdh frame (hard coded) +for i = 1:8 + T_c_mdh_urdf_hc(:,:,i) = eye(4); +end +% T_c_mdh(:,:,j+1)\T_c_urdf(:,:,j+1) +T_c_mdh_urdf_hc(:,:,1) = transl([0;0;p_num(1)]); + +T_c_mdh_urdf_hc(:,:,2) = trotz(-pi/2); + +T_c_mdh_urdf_hc(:,:,3) = troty(pi/2)*trotz(pi)*transl([-p_num(2);0;0]); + +phi = -atan(p_num(5)/p_num(6)); +T_c_mdh_urdf_hc(:,:,4) = trotz(phi)*troty(pi/2)*trotz(pi/2); + +T_c_mdh_urdf_hc(:,:,5) = troty(pi/2)*trotz(pi/2); + +T_c_mdh_urdf_hc(:,:,6) = troty(pi/2)*trotz(pi/2); + +T_c_mdh_urdf_hc(:,:,7) = troty(pi/2)*trotz(pi); +%% Convert center of mass +rSges_num_mdh = NaN(6,3); +for i = 1:6 + rSges_num_mdh(i,:) = (eye(3,4)*T_c_mdh_urdf_hc(:,:,i+1) * [rSges_num_urdf(i,:)';1])'; +end +%% Convert Inertia +Iges_num_mdh = NaN(6,6); +for i = 1:6 + I_i_urdf = inertiavector2matrix(Iges_num_urdf(i,:)); + I_i_mdh = T_c_mdh_urdf_hc(1:3,1:3,i+1) * I_i_urdf * T_c_mdh_urdf_hc(1:3,1:3,i+1)'; + Iges_num_mdh(i,:) = inertiamatrix2vector(I_i_mdh); +end \ No newline at end of file diff --git a/robot_model/atlas4_leg_fkine_num.m b/robot_model/atlas4_leg_fkine_num.m new file mode 100644 index 0000000..a529518 --- /dev/null +++ b/robot_model/atlas4_leg_fkine_num.m @@ -0,0 +1,75 @@ +% Calculate Forward Kinematics for Atlas Robot Leg (v4) +% +% Input: +% q [1x6] +% Joint Angles [rad] +% lr [1x1 logical] +% true for left, false for right +% +% Output: +% T_c_urdf [4x4x7] +% homogenious transformation matrices for each body frame +% 1: pelvis -> pelvis +% 2: pelvis -> glut +% 3: pelvis -> lglut +% 4: pelvis -> uleg +% 5: pelvis -> lleg +% 6: pelvis -> talus +% 7: pelvis -> foot +% +% Sources: +% [1] atlas_v3.urdf + +% Moritz Schappler, schappler@irt.uni-hannover.de, 2015-01 +% (c) Institut für Regelungstechnik, Leibniz Universität Hannover + + +function T_c_urdf = atlas4_leg_fkine_num(q, lr) +%% Init +%#codegen +% Coder Information +assert(isa(q,'double') && isreal(q) && all(size(q) == [1 6]), ... + 'Joint angles q have to be [1x6] double'); +assert(isa(lr,'logical') && all(size(lr) == [1 1]), ... + 'Left/Right flag has to be [1x1] logical'); + + +p_num = atlas4_leg_parameter_urdf(lr); + +%% Frame to Frame Transformations +T_urdf = NaN(4,4,7); + +% T_urdf: Overview over the indices +% 1 hpz: pelvis -> uglut +% 2 hpx: uglut -> lglut +% 3 hpy: lglut -> uleg +% 4 kny: uleg -> lleg +% 5 aky: lleg -> talus +% 6 akx: talus -> foot + + +% 1 hpz: pelvis -> uglut +T_urdf(:,:,1) = transl([0, p_num(1), 0]) * trotz(q(1)); + +% 2 hpx: uglut -> lglut +T_urdf(:,:,2) = trotx(q(2)); +% +% 3 hpy: lglut -> uleg +T_urdf(:,:,3) = transl(p_num(2:4)) * troty(q(3)); +% +% 4 kny: uleg -> lleg +T_urdf(:,:,4) = transl([p_num(5), 0, p_num(6)]) * troty(q(4)); +% +% 5 aky: lleg -> talus +T_urdf(:,:,5) = transl([0,0,p_num(7)]) * troty(q(5)); +% +% 6 akx: talus -> foot +T_urdf(:,:,6) = trotx(q(6)); + +%% Kumulierte Transformationsmatrizen +T_c_urdf = NaN(4,4,7); +T_c_urdf(:,:,1) = eye(4); + +for j = 2:7 + T_c_urdf(:,:,j) = T_c_urdf(:,:,j-1) * T_urdf(:,:,j-1); +end \ No newline at end of file diff --git a/robot_model/atlas4_leg_parameter_mdh.m b/robot_model/atlas4_leg_parameter_mdh.m new file mode 100644 index 0000000..bb411a1 --- /dev/null +++ b/robot_model/atlas4_leg_parameter_mdh.m @@ -0,0 +1,65 @@ +% Return MDH Parameter of the Atlas Robot Leg (v4) (hard coded) +% +% Input: +% lr +% true for left, false for right +% +% Output: +% a_mdh, d_mdh, alpha_mdh, q_offset_mdh [6x1] +% Numeric Values of Kinematic Parameters, MDH-Notation +% rSges_num [6x3] +% Center of Gravity of all indepedent bodies (arm only) in urdf frames +% m_num [6x1] +% masses of all indepedent bodies (arm only) +% Iges_num [6x6] +% inertia of all indepedent bodies (arm only) +% rows: bodies +% columns: inertia tensor entries. Order: xx, yy, zz, xy, xz, yz +% +% Sources: +% [1] atlas_v4.urdf +% [2] [KhalilKle1986] + +function [a_mdh, d_mdh, alpha_mdh, q_offset_mdh, ... + rSges_num_mdh, m_num_mdh, Iges_num_mdh] = atlas4_leg_parameter_mdh(lr) + +assert(isa(lr,'logical') && all(size(lr) == [1 1]), ... + 'Left/Right flag has to be [1x1] logical'); + +[p_num_urdf, rSges_num_urdf, m_num_urdf, Iges_num_urdf] = atlas4_leg_parameter_urdf(lr); + + +%% Calculate MDH kinematic Parameter +alpha_mdh = zeros(6,1); +a_mdh = zeros(6,1); +q_offset_mdh = zeros(6,1); +d_mdh = zeros(6,1); + +% set MDH parameters with values from urdf-file +% Um z-Achse so drehen, dass nächste Drehachse die y0-Achse wird +q_offset_mdh(1) = pi/2; + +alpha_mdh(2) = pi/2; +q_offset_mdh(2) = pi/2; +d_mdh(2) = p_num_urdf(2); + +alpha_mdh(3) = pi/2; +a_mdh(3) = p_num_urdf(4); +phi = -atan(p_num_urdf(5)/p_num_urdf(6)); +q_offset_mdh(3) = -phi; +d_mdh(3) = p_num_urdf(3); + +a_mdh(4) = -sqrt(p_num_urdf(5)^2 + p_num_urdf(6)^2); +q_offset_mdh(4) = phi; + +a_mdh(5) = p_num_urdf(7); + +alpha_mdh(6) = -pi/2; + +%% Calculate MDH dynamic parameters + +% Different frame position and orientation + +m_num_mdh = m_num_urdf; + +[rSges_num_mdh, Iges_num_mdh] = atlas4_leg_convert_urdf_mdh(lr, rSges_num_urdf, Iges_num_urdf); \ No newline at end of file diff --git a/robot_model/atlas4_leg_parameter_urdf.m b/robot_model/atlas4_leg_parameter_urdf.m new file mode 100644 index 0000000..2710c2c --- /dev/null +++ b/robot_model/atlas4_leg_parameter_urdf.m @@ -0,0 +1,114 @@ +% Return URDF Parameter of the Atlas Robot (v4) leg (hard coded) +% +% Input: +% lr +% true for left, false for right +% +% Output: +% p_num [6x1] +% Numeric Values of Kinematic Parameters +% rSges_num [6x3] +% Center of Gravity of all independent bodies (leg only) in urdf frames +% m_num [6x1] +% masses of all independent bodies (leg only) +% Iges_num [6x6] +% inertia of all independent bodies (leg only) +% rows: bodies +% columns: inertia tensor entries. Order: xx, yy, zz, xy, xz, yz +% +% Sources: +% [1] atlas_v5_simple_shapes_with_head.urdf + +% Moritz Schappler, schappler@irt.uni-hannover.de, 2014-11 +% (c) Institut für Regelungstechnik, Leibniz Universität Hannover + +function [p_num, rSges_num, m_num, Iges_num] = atlas4_leg_parameter_urdf(lr) + +%% Init +% Coder Information +%#codegen + +assert(isa(lr,'logical') && all(size(lr) == [1 1])); + +p_num = NaN(1,7); +Iges_num = NaN(6,6); +%% Kinematic Parameters +% Source: [1] + +% 1 hpz: pelvis -> uglut +if lr == true % left + p_num(1) = 0.089; +else + p_num(1) = -0.089; +end +% 2 hpx: uglut -> lglut +% no transformation +% 3 hpy: lglut -> uleg +if lr == true % left + p_num(2:4) = [0.05, 0.0225, -0.066]; +else + p_num(2:4) = [0.05, -0.0225, -0.066]; +end +% 4 kny: uleg -> lleg +p_num(5:6) = [-0.05,-0.374]; +% 5 aky: lleg -> talus +p_num(7) = -0.422; +% 6 akx: talus -> foot +% no transformation + +%% Output Parameters: Mass +m_num = [1.959; ... % (1) uglut + 0.898; ... % (2) lglut + 8.204; ... % (3) uleg + 4.515; ... % (4) lleg + 0.125; ... % (5) talus + 2.410]; % (6) foot + +%% Output Parameters: Center of Mass +% center of mass coordinates in body reference frames. Source: [1] +rSges_num = [... + [0.00529262, -0.00344732, 0.00313046];... % (1) uglut + [0.0133341, 0.0170484, -0.0312052];... % (2) lglut + [0, 0, -0.21];... % (3) uleg + [0.001, 0, -0.187];... % (4) lleg + [0, 0, 0];... % (5) talus + [0.027, 0, -0.067]]; % (6) foot +if lr == false + rSges_num(2,2) = - rSges_num(2,2); + rSges_num(1,2) = - rSges_num(1,2); +end +%% Output Parameters: Inertias +% Order: Ixx, Iyy, Izz, Ixy, Ixz, Iyz + +% (1) uglut +% left +% +% right +% +if lr == true + Iges_num(1,:) = [0.00074276, 0.000688179, 0.00041242, -3.79607e-08, -2.79549e-05, -3.2735e-08]; +else + Iges_num(1,:) = [0.00074276, 0.000688179, 0.00041242, 3.79607e-08, -2.79549e-05, 3.2735e-08]; +end +% (2) lglut +% left +% +% right +% +if lr == true + Iges_num(2,:) = [0.000691326, 0.00126856, 0.00106487, -2.24344e-05, 2.50508e-06, 0.000137862]; +else + Iges_num(2,:) = [0.000691326, 0.00126856, 0.00106487, 2.24344e-05, 2.50508e-06, -0.000137862]; +end +% (3) uleg +% +Iges_num(3,:) = [0.09, 0.09, 0.02, 0, 0, 0]; +% (4) lleg +% +Iges_num(4,:) = [0.077, 0.076, 0.01, 0, -0.003, 0]; +% (5) talus +% +Iges_num(5,:) = [1.01674e-05, 8.42775e-06, 1.30101e-05, 0, 0, 0]; +% (6) foot +% +Iges_num(6,:) = [0.002, 0.007, 0.008, 0, 0, 0]; \ No newline at end of file diff --git a/robot_model/atlas4_torso_parameter_urdf.m b/robot_model/atlas4_torso_parameter_urdf.m new file mode 100644 index 0000000..422058d --- /dev/null +++ b/robot_model/atlas4_torso_parameter_urdf.m @@ -0,0 +1,79 @@ +% Return Parameter of the Atlas Robot (v4) (hard coded) +% +% Input: +% +% Output: +% p_num [1x5] +% Numeric Values of Kinematic Parameters +% rSges_num [5x3] +% Center of Gravity of all independent bodies (torso only) in urdf frames +% m_num [5x1] +% masses of all independent bodies (torso only) +% Iges_num [5x6] +% inertia of all independent bodies (torso only) +% rows: bodies +% columns: inertia tensor entries. Order: xx, yy, zz, xy, xz, yz +% +% Sources: +% [1] atlas_v3.urdf + +% Moritz Schappler, schappler@irt.uni-hannover.de, 2014-11 +% (c) Institut für Regelungstechnik, Leibniz Universität Hannover + +function [p_num, rSges_num, m_num, Iges_num] = atlas4_torso_parameter_urdf() + +%% Init +% Coder Information +%#codegen + +p_num = NaN(1,5); +Iges_num = NaN(6,6); +%% Kinematic Parameters +% Source: [1] +% 1 back_bkz: pelvis -> ltorso +p_num(1) = -0.0125; + +% 2 back_bky: ltorso -> mtorso +p_num(2) = 0.162; + +% 3 back_bkx: mtorso -> utorso +p_num(3) = 0.05; + +% 4 neck_ry: utorso -> head +p_num(4:5) = [0.2546, 0.6215]; + +%% Output Parameters: Mass +m_num = [17.882; ... % (1) pelvis + 2.409; ... % (2) ltorso + 0.69; ... % (3) mtorso + 63.73; ... % (4) utorso + 0]; + +%% Output Parameters: Center of Mass +% center of mass coordinates in body reference frames. Source: [1] +rSges_num = [ ... + [0.0111, 0, 0.0271]; ... (1) pelvis + [-0.0112984, -3.15366e-06, 0.0746835]; ... % (2) ltorso + [-0.00816266 -0.0131245 0.0305974]; ...% (3) mtorso + [-0.0581, 0, 0.3056]; ... % (4) utorso + [0,0,0]]; +%% Output Parameters: Inertias +% Order: Ixx, Iyy, Izz, Ixy, Ixz, Iyz + +% (1) pelvis +% +Iges_num(1,:) = [0.1244, 0.0958, 0.1167, 0.0008, -0.0007, -0.0005]; + +% (2) ltorso +% +Iges_num(2,:) = [0.0039092, 0.00341694, 0.00174492, -5.04491e-08, -0.000342157, 4.87119e-07]; + +% (3) mtorso +% +Iges_num(3,:) = [0.000454181, 0.000483282, 0.000444215, 6.10764e-05, 3.94009e-05, 5.27463e-05]; + +% (4) utorso +% +Iges_num(4,:) = [1.466, 1.51, 1.3, 0.00362, 0.336, 0.001]; + +Iges_num(5,:) = zeros(1,6); \ No newline at end of file diff --git a/robot_model/atlas5_arm_convert_urdf_mdh.m b/robot_model/atlas5_arm_convert_urdf_mdh.m new file mode 100644 index 0000000..a660b15 --- /dev/null +++ b/robot_model/atlas5_arm_convert_urdf_mdh.m @@ -0,0 +1,105 @@ +% Convert dynamic parameters from urdf to mdh (v5) +% +% Input: +% lr [1x1 logical] +% true for left, false for right +% rSges_num_urdf [7x3 double] +% center of mass of all atlas arm bodies in urdf frames +% Iges_num_urdf [7x6 double] +% inertia of all atlas arm bodies in urdf frames +% order: xx, yy, zz, xy, xz, yz +% +% Output: +% rSges_num_mdh [7x3 double] +% center of mass of all atlas arm bodies in MDH frames +% Iges_num_mdh [7x6 double] +% inertia of all atlas arm bodies in MDH frames +% order: xx, yy, zz, xy, xz, yz + +% Moritz Schappler, schappler@irt.uni-hannover.de, 2015-01 +% (c) Institut für Regelungstechnik, Universität Hannover + + +function [rSges_num_mdh, Iges_num_mdh] = ... + atlas5_arm_convert_urdf_mdh(lr, rSges_num_urdf, Iges_num_urdf) + +%% Init +% Coder Information +%#codegen + +assert(isa(lr,'logical') && all(size(lr) == [1 1])); +assert(isa(rSges_num_urdf,'double') && all(size(rSges_num_urdf) == [7 3])); +assert(isa(Iges_num_urdf,'double') && all(size(Iges_num_urdf) == [7 6])); + + +%% get frames +% hard coded transformations calculated in testfunctions/atlas_transformation_urdf_mdh_test +p_num = atlas5_arm_parameter_urdf(lr); +T_c_mdh_urdf_hc = NaN(4,4,8); % Transformation from urdf to mdh frame (hard coded) +for i = 1:8 + T_c_mdh_urdf_hc(:,:,i) = eye(4); +end + + T_c_mdh_urdf_hc(:,:,1) = [ + 0.0000 -1.0000 0 p_num(2) + 1.0000 0.0000 0 -p_num(1) + 0 0 1.0000 -p_num(3) + 0 0 0 1.0000]; + + T_c_mdh_urdf_hc(:,:,2) = [ + 0.0000 -1.0000 0 0 + 1.0000 0.0000 0 0 + 0 0 1.0000 -p_num(7) + 0 0 0 1.0000]; + if lr == false + T_c_mdh_urdf_hc(2,4,2) = -T_c_mdh_urdf_hc(2,4,2); + end + + T_c_mdh_urdf_hc(:,:,3) = [ + -0.0000 0 1.0000 -0.0000 + 0.0000 -1.0000 0.0000 0 + 1.0000 0.0000 0.0000 0 + 0 0 0 1.0000]; + + T_c_mdh_urdf_hc(:,:,4) = [ + -0.0000 0.0000 1.0000 -0.0000 + 1.0000 0 0.0000 0 + 0.0000 1.0000 -0.0000 -p_num(10) + 0 0 0 1.0000]; + + if lr % correct signchange from last version to this + T_c_mdh_urdf_hc(3,4,4) = -T_c_mdh_urdf_hc(3,4,4); + end + + T_c_mdh_urdf_hc(:,:,5) = [ + -0.0000 0.0000 1.0000 -0.0000 + 0.0000 -1.0000 0.0000 0.0000 + 1.0000 0.0000 0.0000 0 + 0 0 0 1.0000]; + % bis hierhin identisch mit v4 + T_c_mdh_urdf_hc(:,:,6) = [[[0,0,1;1,0,0;0,1,0], [0;0;0]];[0,0,0,1]]; + T_c_mdh_urdf_hc(:,:,7) = [[[0,0,1;0,-1,0;1,0,0], [0;0;0]];[0,0,0,1]]; + T_c_mdh_urdf_hc(:,:,8) = [[[0,0,1;1,0,0;0,1,0], [0;0;0]];[0,0,0,1]]; + + if lr % add additional transformations in new kinematic of simple shapes urdf + T_c_mdh_urdf_hc(:,:,2) = T_c_mdh_urdf_hc(:,:,2) * trotz(3.14159265359); % shz->shx rotz pi + T_c_mdh_urdf_hc(:,:,3) = T_c_mdh_urdf_hc(:,:,3) * trotz(3.14159265359); % shx->ely rotz pi (from before) + T_c_mdh_urdf_hc(:,:,4) = T_c_mdh_urdf_hc(:,:,4) * trotz(3.14159265359); % ely->elx rotz pi (from before) + T_c_mdh_urdf_hc(:,:,5) = T_c_mdh_urdf_hc(:,:,5) * trotz(3.14159265359); % elx->wry rotz pi (from before) + T_c_mdh_urdf_hc(:,:,6) = T_c_mdh_urdf_hc(:,:,6) * trotz(3.14159265359) * troty(3.14159265359); % wry->wrx rotz pi (from before) and roty pi + T_c_mdh_urdf_hc(:,:,7) = T_c_mdh_urdf_hc(:,:,7) * trotz(3.14159265359) * troty(3.14159265359); % wrx->wry2 rotz pi (from before) and roty pi (from before) + T_c_mdh_urdf_hc(:,:,8) = T_c_mdh_urdf_hc(:,:,8) * trotz(3.14159265359); % wry2->ee rotz pi (from before), roty pi from before compensated by additional roty pi + end + +%% Convert center of mass +rSges_num_mdh = NaN(7,3); +for i = 1:7 + rSges_num_mdh(i,:) = (T_c_mdh_urdf_hc(1:3,1:4,i+1) * [rSges_num_urdf(i,:)';1])'; +end +%% Convert Inertia +Iges_num_mdh = NaN(7,6); +for i = 1:7 + I_i_urdf = inertiavector2matrix(Iges_num_urdf(i,:)); + I_i_mdh = T_c_mdh_urdf_hc(1:3,1:3,i+1) * I_i_urdf * T_c_mdh_urdf_hc(1:3,1:3,i+1)'; + Iges_num_mdh(i,:) = inertiamatrix2vector(I_i_mdh); +end \ No newline at end of file diff --git a/robot_model/atlas5_arm_coriolisvec_fb_plin_minpar_sym_lag_varpar.m b/robot_model/atlas5_arm_coriolisvec_fb_plin_minpar_sym_lag_varpar.m new file mode 100644 index 0000000..196c025 --- /dev/null +++ b/robot_model/atlas5_arm_coriolisvec_fb_plin_minpar_sym_lag_varpar.m @@ -0,0 +1,46 @@ +% Calculate joint torque vector of coriolis and centripetal forces for +% Atlas Robot (v5) +% from Maple symbolic code generation in MDH frames +% Berechnung mit Regressorform (Parameterlineare Form) +% Minimal-Parametersatz (neu gruppierte Parameter) +% +% Input: +% q [1x7] +% Joint Angles [rad] +% qD [1x7] +% Joint Velocities [rad/s] +% MPV [45x1] +% minimum parameter vector (regrouped dynamic parameters) +% lr [1x1 logical] +% true for left, false for right +% +% Output: +% cq [1x7] +% joint torque vector of coriolis and centripetal forces [Nm] +% + +% Moritz Schappler, schappler@irt.uni-hannover.de, 2015-02 +% (c) Institut für Regelungstechnik, Leibniz Universität Hannover + +function tauc = atlas5_arm_coriolisvec_fb_plin_minpar_sym_lag_varpar(q, qD, MPV, lr) + +%% Init +%#codegen +% Coder Information +assert(isa(q,'double') && isreal(q) && all(size(q) == [1 7]), ... + 'atlas5_arm_coriolisvec_fb_plin_minpar_sym_lag_varpar: Joint angles q have to be [1x7] double'); +assert(isa(qD,'double') && isreal(qD) && all(size(qD) == [1 7]), ... + 'atlas5_arm_coriolisvec_fb_plin_minpar_sym_lag_varpar: Joint Velocities qD have to be [1x7] double'); +assert(isa(MPV,'double') && isreal(MPV) && all(size(MPV) == [45 1]), ... + 'atlas5_arm_coriolisvec_fb_plin_minpar_sym_lag_varpar: Minimum Parameter vector has to be [45x1] double'); +assert(isa(lr,'logical') && all(size(lr) == [1 1]), ... + 'atlas5_arm_coriolisvec_fb_plin_minpar_sym_lag_varpar: Left/Right flag has to be [1x1] logical'); + +%% Kinematik-Parameter +[a_mdh, d_mdh, ~, q_offset_mdh] = atlas5_arm_parameter_mdh(lr); + +%% Regressor-Matrix +tauc_regressor = atlas5_arm_coriolisvec_fb_regressor_minpar_sym_lag_varpar(q, qD, a_mdh, d_mdh, q_offset_mdh, lr); + +%% Gelenkmoment +tauc = (tauc_regressor*MPV)'; diff --git a/robot_model/atlas5_arm_coriolisvec_fb_regressor_minpar_sym_lag_varpar.m b/robot_model/atlas5_arm_coriolisvec_fb_regressor_minpar_sym_lag_varpar.m new file mode 100644 index 0000000..cbbab85 --- /dev/null +++ b/robot_model/atlas5_arm_coriolisvec_fb_regressor_minpar_sym_lag_varpar.m @@ -0,0 +1,1004 @@ +% Calculate joint torque vector of coriolis and centripetal forces for +% Atlas Robot (v5) +% from Maple symbolic code generation in MDH frames +% +% Input: +% q [1x7] +% Joint Angles [rad] +% qD [1x7] +% Joint Velocities [rad/s] +% a_mdh, d_mdh, q_offset_mdh [6x1] double +% kinematic parameters [m], [rad] +% lr [1x1 logical] +% true for left, false for right +% +% Output: +% cq [1x7] +% joint torque vector of coriolis and centripetal forces [Nm] +% + +% Moritz Schappler, schappler@irt.uni-hannover.de, 2015-03 +% (c) Institut für Regelungstechnik, Leibniz Universität Hannover + +function tauc_regressor = atlas5_arm_coriolisvec_fb_regressor_minpar_sym_lag_varpar(q, qD, a_mdh, d_mdh, q_offset_mdh, lr) +%% Init +% Coder Information +%#codegen +assert(isa(q,'double') && isreal(q) && all(size(q) == [1 7]), ... + 'Joint angles q have to be [1x7] double'); +assert(isa(qD,'double') && isreal(qD) && all(size(qD) == [1 7]), ... + 'Joint Velocities qD have to be [1x7] double'); +assert(isa(a_mdh,'double') && isreal(a_mdh) && all(size(a_mdh) == [7 1]), ... + 'a_mdh has to be [7x1] double'); +assert(isa(d_mdh,'double') && isreal(d_mdh) && all(size(d_mdh) == [7 1]), ... + 'd_mdh has to be [7x1] double'); +assert(isa(q_offset_mdh,'double') && isreal(q_offset_mdh) && all(size(q_offset_mdh) == [7 1]), ... + 'q_offset_mdh has to be [7x1] double'); +assert(isa(lr,'logical') && all(size(lr) == [1 1])); + +qs2 = q(2); +qs3 = q(3); +qs4 = q(4); +qs5 = q(5); +qs6 = q(6); +qs7 = q(7); + +qsD1 = qD(1); +qsD2 = qD(2); +qsD3 = qD(3); +qsD4 = qD(4); +qsD5 = qD(5); +qsD6 = qD(6); +qsD7 = qD(7); +%% Get MDH Parameters + +d3 = d_mdh(3); +d5 = d_mdh(5); + +a2 = a_mdh(2); +a3 = a_mdh(3); +a4 = a_mdh(4); +a5 = a_mdh(5); +a6 = a_mdh(6); + +qoffset2 = q_offset_mdh(2); + +%% Maple Generated Calculation +% from codeexport/atlas5_arm_coriolisvec_fb_regressor_minpar_mapleexport.m + +t3024 = qs2 + qoffset2; +t3016 = cos(t3024); +t3041 = sin(qs3); +t3571 = t3016 * t3041; +t3321 = qsD2 * t3571; +t2964 = qsD1 * t3321; +t3047 = cos(qs3); +t3042 = sin(qs2); +t3048 = cos(qs2); +t3055 = qsD1 ^ 2; +t3501 = t3048 * t3055; +t3309 = t3042 * t3501; +t2980 = t3047 * t3309; +t3078 = t2980 + t2964; +t3015 = sin(t3024); +t3206 = a3 * t3016 + d3 * t3015; +t2923 = a2 + t3206; +t3593 = t2923 * t3047; +t3094 = qsD1 * t3593; +t3631 = t3041 * qsD2; +t3370 = d3 * t3631; +t2826 = -t3094 + t3370; +t3054 = qsD2 ^ 2; +t3502 = t3047 * t3054; +t3013 = a3 * t3502; +t3711 = a2 * t3042; +t3014 = t3055 * t3711; +t3575 = t3015 * t3041; +t2979 = qsD1 * t3575; +t3231 = qsD2 * t2979; +t3030 = t3042 ^ 2; +t3567 = t3030 * t3055; +t3110 = qsD3 * t2826 - t3047 * t3014 - t3013 + (-t3047 * t3567 - t3231) * a3; +t2578 = -d3 * t3078 - t3110; +t3531 = t3041 * t3047; +t3312 = t3015 * t3531; +t2946 = qsD1 * t3312; +t2936 = qsD2 * t2946; +t3029 = t3041 ^ 2; +t3035 = t3047 ^ 2; +t3001 = t3035 - t3029; +t3036 = t3048 ^ 2; +t3565 = t3036 * t3055; +t2768 = 0.4e1 * t2936 - t3001 * (-t3054 + t3565); +t3040 = sin(qs4); +t3046 = cos(qs4); +t3203 = a5 * t3046 + d5 * t3040; +t2973 = a4 + t3203; +t3051 = qsD5 ^ 2; +t3573 = t3015 * t3047; +t2927 = qsD1 * t3573 - t3631; +t2764 = qsD3 * t2927 - t3078; +t3019 = t3047 * qsD2; +t2925 = t2979 + t3019; +t3676 = qsD4 * t2925; +t3254 = t2768 + t3676; +t2550 = -t3040 * t2764 + t3046 * t3254; +t3052 = qsD4 ^ 2; +t3342 = qsD3 * t3573; +t2969 = qsD1 * t3342; +t3357 = qsD3 * t3631; +t2832 = t2964 + t2969 - t3357; +t3542 = t3040 * t2832; +t2666 = -t3542 + (-t3052 - t3676) * t3046; +t3918 = t2666 - t2550; +t3945 = a4 * t2768 - t3918 * a5 - t2973 * t3051 + t2578; +t3039 = sin(qs5); +t3944 = 0.2e1 * t3039; +t3940 = qsD4 + t2925; +t2863 = t3940 * t3046; +t3552 = t3039 * t2863; +t2805 = t3046 * t2826; +t3708 = a4 * t3040; +t3352 = d5 + t3708; +t2619 = t2927 * t3352 - t2805; +t3112 = t2923 * t3041; +t3095 = qsD1 * t3112; +t2827 = d3 * t3019 + t3095; +t3202 = a5 * t3040 - d5 * t3046; +t2623 = t2925 * t3202 - t2827; +t2959 = t3202 * qsD4; +t3045 = cos(qs5); +t3942 = t2619 * t3039 + (-t2623 - t2959) * t3045; +t3534 = t3040 * t3047; +t3574 = t3015 * t3046; +t3119 = t3016 * t3534 + t3574; +t2866 = t3119 * qsD1; +t3503 = t3046 * t3047; +t3576 = t3015 * t3040; +t2867 = (-t3016 * t3503 + t3576) * qsD1; +t3205 = a3 * t3015 - d3 * t3016; +t2915 = t3205 * qsD1; +t3180 = -d3 + t3202; +t3672 = qsD4 * t3041; +t3680 = qsD3 * t3047; +t3687 = qsD1 * t3015; +t3939 = -a4 * t3687 - a5 * t2866 - d5 * t2867 - t2915 * t3047 - t3180 * t3680 - t3203 * t3672; +t3002 = t3016 * qsD1; +t3008 = -a4 * t3047 - a3; +t3505 = t3046 * t3008; +t3099 = qsD4 * (-d3 * t3534 - t3505); +t3700 = d3 * t3046; +t3350 = d5 + t3700; +t3596 = t2915 * t3046; +t3681 = qsD3 * t3041; +t3938 = (t3002 * t3352 - t3596) * t3041 - t3099 - (-t3350 - t3708) * t3681; +t3509 = t3046 * t2764; +t2549 = -t3040 * t3254 - t3509; +t2911 = t3040 * t2927; +t3781 = t3002 + qsD3; +t2944 = t3046 * t3781; +t3147 = 0.2e1 * t2944 - t2911; +t2626 = a4 * t3147 - t2805; +t3028 = t3040 ^ 2; +t3034 = t3046 ^ 2; +t3000 = -t3034 + t3028; +t3891 = 0.2e1 * t3040; +t3858 = t2944 * t3891; +t2760 = -t2927 * t3000 + t3858; +t3278 = -d5 * t2760 - t2626; +t3937 = d5 * t2549 - qsD5 * t3278 - t3945; +t3936 = 0.2e1 * t3940; +t3270 = qsD3 * t3046 + qsD5; +t3648 = qsD5 * t3046; +t3271 = -qsD3 - t3648; +t3347 = qsD1 * t3571; +t3513 = t3045 * t3047; +t3536 = t3040 * t3045; +t3935 = t3270 * t3513 + (-qsD4 * t3536 + t3039 * t3271) * t3041 - t2867 * t3045 - t3039 * t3347; +t2804 = t3040 * t2826; +t3009 = qsD3 * t3019; +t3782 = t3205 * qsD2; +t3109 = qsD1 * t3782; +t3181 = -d3 * t3009 - t3047 * t3109; +t2677 = -qsD3 * t3095 + t3181; +t3686 = qsD2 * t3015; +t3356 = qsD1 * t3686; +t2965 = t3046 * t3356; +t3208 = -0.2e1 * t2965; +t3720 = -0.2e1 * qsD4; +t3301 = t3708 * t3720; +t3570 = t3016 * t3047; +t3320 = qsD2 * t3570; +t3232 = qsD1 * t3320; +t2968 = qsD3 * t2979; +t3399 = t2968 + t3009; +t2831 = -t3232 + t3399; +t3590 = t2927 * t3046; +t3809 = -qsD4 * t3590 + t2831 * t3040; +t3173 = t3046 * t2677 + t3781 * t3301 + (t3208 + t3809) * a4; +t2446 = qsD4 * t2804 + t3173; +t2812 = t3046 * t2831; +t3673 = qsD4 * t3034; +t3807 = -qsD4 * t3028 + t3673; +t3748 = qsD4 * t3858 - t3040 * t2812 + t2927 * t3807; +t2554 = -t3034 * t3356 - t3748; +t3535 = t3040 * t3046; +t2888 = t2927 * t3535; +t2943 = t3034 * t3781; +t3386 = t3781 * t3720; +t3719 = 0.2e1 * qsD4; +t2556 = -0.4e1 * qsD4 * t2888 + t3000 * t2831 + t2943 * t3719 + t3028 * t3386 + t3040 * t3208; +t3410 = -qsD3 * t3094 + t3041 * t3109; +t2676 = d3 * t3357 + t3410; +t2791 = -t2888 + t2943; +t3651 = qsD5 * t3039; +t3375 = a5 * t3651; +t3300 = -0.2e1 * t3375; +t3649 = qsD5 * t3045; +t3373 = d5 * t3649; +t3702 = a5 * t3045; +t3394 = 0.2e1 * t3702; +t3022 = t3052 * t3040; +t3592 = t2925 * t3040; +t3599 = t2832 * t3046; +t2665 = qsD4 * t3592 + t3022 - t3599; +t3554 = t3039 * t2665; +t3693 = d5 * t3045; +t3934 = d5 * t3554 + qsD5 * t3942 + t3045 * t2446 + t2554 * t3394 + t2556 * t3693 + t3039 * t2676 + t2791 * t3300 - t2827 * t3649 - t2863 * t3373; +t3303 = t3565 / 0.2e1; +t2843 = t3029 * t3303 + t2936 + t3035 * t3054 / 0.2e1; +t3709 = a3 * t3042; +t3105 = d3 * t3036 + (-a2 - t3709) * t3048; +t2876 = d3 * t3054 + t3055 * t3105; +t3090 = t3567 / 0.2e1 + qsD3 * (t3002 + qsD3 / 0.2e1); +t3789 = 0.2e1 * t3046; +t3072 = t3090 * t3789; +t3707 = a4 * t3046; +t3108 = a4 * t3072 + t3046 * t2578 - t2764 * t3708 + 0.2e1 * t2843 * t3707 - t3040 * t2876; +t2898 = -qsD2 * a3 - a4 * t2925; +t2663 = t2827 * t3040 + t2898 * t3046; +t3679 = qsD4 * t2663; +t2372 = t3108 - t3679; +t3213 = t3041 * t3309; +t3345 = qsD2 * t3573; +t3230 = qsD1 * t3345; +t3797 = -a3 * t3230 - d3 * t3213 + qsD3 * t2827 + (a3 * (t3054 + t3567) + t3014) * t3041; +t2577 = -d3 * t3232 - t3797; +t3004 = t3041 * t3502; +t3311 = t3036 * t3531; +t3132 = -t3055 * t3311 + t3004; +t3578 = t3001 * t3015; +t3346 = qsD2 * t3578; +t2797 = -qsD1 * t3346 + t3132; +t2510 = -a4 * t2797 + t2577; +t2962 = t3040 * t3356; +t3413 = t2812 + t2962; +t3405 = t2944 - t2911; +t3890 = qsD4 * t3405; +t2600 = t3413 - t3890; +t3540 = t3040 * t3781; +t3406 = qsD4 * t3540 + t2965; +t2601 = -t3406 + t3809; +t3096 = qsD3 * t3112; +t3821 = -a4 * t3686 - t3096; +t3056 = t2601 * a5 - t2600 * d5 + qsD1 * t3821 + t3181; +t3414 = a4 * t3542 - t3046 * t2676; +t3077 = t3414 - t3679; +t3690 = t2832 * d5; +t3069 = t3077 + t3690; +t3104 = qsD3 * t2925 - t3213; +t2762 = t3104 + t3232; +t3510 = t3046 * t2762; +t3152 = t3040 * t2797 + t3510; +t2522 = -t3152 - t3890; +t3568 = t3029 * t3054; +t3084 = t3035 * t3303 - t2936 + t3568 / 0.2e1; +t3361 = -0.2e1 * t3535; +t3850 = t2764 * t3000; +t2545 = t3040 * t3072 + t3084 * t3361 - t3850; +t3518 = t3045 * t2545; +t3811 = -t2522 * t3039 - t3518; +t3933 = -d5 * t3811 + (t2372 - t3069) * t3045 + (t2510 - t3056) * t3039; +t2862 = t3940 * t3040; +t2684 = a4 * t3590 + t2804; +t3577 = t3015 * t3029; +t3348 = qsD1 * t3577; +t2754 = -qsD2 * t3348 + t3035 * t3356 - t3132; +t3368 = t2754 * t3789; +t3606 = t2762 * t3040; +t3734 = -(t3368 + t3606) * a4 - t3046 * t2577; +t2411 = qsD4 * t2684 - t3734; +t3675 = qsD4 * t2927; +t2667 = t2754 + t3675; +t2724 = t3040 * t3510; +t3417 = t3028 * t2754 - t2724; +t3794 = 0.2e1 * a5; +t3775 = (-t3417 + t2667) * t3794; +t3120 = t2411 + t3775; +t3374 = a5 * t3649; +t3050 = qsD6 ^ 2; +t3547 = t3039 * t3050; +t2571 = t2762 * t3000 + t3040 * t3368; +t3695 = d5 * t2571; +t3932 = -t2862 * t3374 + (t3120 + t3695) * t3045 + t2973 * t3547 - t3934 + t3937 * t3039; +t3504 = t3046 * t3016; +t2896 = t3015 * t3534 - t3504; +t3530 = t3042 * t3048; +t3682 = qsD3 * t3015; +t3721 = 0.2e1 * qsD1; +t3128 = t3530 * t3721 - t3682; +t2821 = -t3041 * t3128 + t3320; +t3722 = -0.2e1 * qsD1; +t2852 = t3311 * t3722 - t3346; +t3151 = -t2821 * t3046 - t2852 * t3040; +t2583 = qsD4 * t2896 + t3151; +t3150 = t2821 * t3040 - t2852 * t3046; +t3572 = t3016 * t3040; +t3118 = t3015 * t3503 + t3572; +t3855 = qsD4 * t3118; +t2584 = -t3150 - t3855; +t3532 = t3041 * t3046; +t3338 = qsD3 * t3532; +t3671 = qsD4 * t3047; +t2654 = (-qsD4 - t3019) * t3504 + (t3338 + (qsD2 + t3671) * t3040) * t3015; +t3538 = t3040 * t3041; +t3340 = qsD3 * t3538; +t2655 = qsD2 * t3119 - t3015 * t3340 + t3855; +t3698 = d3 * t3048; +t3710 = a3 * t3030; +t3080 = 0.2e1 * (-a2 + t3698) * t3042 - 0.2e1 * t3710; +t3733 = qsD1 * t3080 - qsD3 * t2923; +t3931 = -a4 * t2852 + t3041 * t3733 + t3821 + (t2583 - t2654) * d5 + (-t2584 - t2655) * a5; +t2937 = t3047 * t2964; +t3343 = t3035 * t3682; +t2966 = qsD1 * t3343; +t3377 = 0.2e1 * t3019; +t3259 = t3041 * t3377; +t3071 = (t3259 + t3348) * qsD3 - t2966; +t2720 = -t2937 + t3071; +t3053 = qsD3 ^ 2; +t3023 = t3053 * t3047; +t2842 = t3023 + (-qsD2 * t3575 + qsD3 * t3570) * qsD1; +t2926 = t3781 * t3041; +t2887 = t2926 * t3535; +t2913 = qsD2 * t3029 - t2946; +t2890 = t3028 * t2913; +t3598 = t2913 * t3034; +t3792 = 0.4e1 * qsD4; +t2460 = t2720 * t3361 + t3000 * t2842 + t2887 * t3792 + t2890 * t3719 + t3598 * t3720; +t3358 = qsD3 * t3002; +t3398 = t3030 - t3036; +t3776 = t3398 * t3055; +t3805 = t3776 + t3358; +t2771 = -t3047 * t3805 - t3231; +t3214 = t3035 * t3309; +t2860 = -t2937 - t3214; +t2920 = -qsD1 * t3682 + t3309; +t3262 = t3040 * t3789; +t2564 = -t3262 * (t2860 - t2920) + t3000 * t2771; +t3911 = t2460 - t2564; +t3539 = t3040 * t3008; +t2893 = t3047 * t3350 - t3539; +t2910 = t3180 * t3041; +t2713 = t2893 * t3045 + t2910 * t3039; +t3659 = qsD5 * t2713; +t3930 = t3039 * t3938 - t3045 * t3939 - t3659; +t2822 = t3047 * t3128 + t3321; +t2948 = qsD2 * t3312; +t3566 = t3035 * t3036; +t2901 = qsD1 * t3566 - t2948; +t2939 = qsD1 * t3030 + qsD3 * t3016; +t3762 = t2901 - t2939; +t3125 = t3762 * t3262; +t2587 = t3000 * t2822 - t3125; +t3508 = t3046 * t2822; +t2782 = t3040 * t3508; +t2604 = t3028 * t2901 + t3034 * t2939 + t2782; +t2900 = t3029 * t3036 * qsD1 + t2948; +t3336 = qsD4 * t3575; +t2823 = t3336 + t2900; +t3594 = t2923 * t3046; +t3091 = t3015 * t3352 + t3594; +t3138 = 0.2e1 * t2900 + 0.2e1 * t2939 + t3336; +t2902 = t3105 * qsD1; +t3198 = qsD4 * t3112 + 0.2e1 * t2902; +t3849 = t3041 * t3782; +t2622 = -t3047 * t3733 + t3849; +t3511 = t3046 * t2622; +t3543 = t3040 * t2822; +t3685 = qsD2 * t3016; +t3595 = t2923 * t3040; +t3735 = -a4 * (qsD2 * t3572 + qsD4 * t3574) + qsD4 * t3595 + t3782 * t3046; +t3929 = -t3091 * t3680 - (d5 * t3685 - t3735) * t3041 - (t2604 + t2823) * t3794 - d5 * t2587 - t3511 + t3198 * t3040 - (t3046 * t3138 + t3543) * a4; +t3433 = t2571 - t2556; +t2740 = -t2887 + t3598; +t3018 = t3035 * qsD2; +t2912 = t2946 + t3018; +t2880 = t2912 + t3671; +t3027 = t3039 ^ 2; +t3033 = t3045 ^ 2; +t2879 = -qsD1 * t3578 + t3259; +t3252 = t2879 + t3672; +t2928 = t3781 * t3047; +t3541 = t3040 * t2928; +t2687 = t3046 * t3252 - t3541; +t3549 = t3039 * t3045; +t3318 = t2687 * t3549; +t2501 = t2740 * t3033 + t2880 * t3027 + t3318; +t2739 = t2890 + t2887; +t2697 = qsD5 * t3538 + t2739; +t3928 = t2697 - t2501; +t3533 = t3041 * t3045; +t3824 = -t3045 * t3347 + t3271 * t3533 + (qsD4 * t3538 - t3047 * t3270 + t2867) * t3039; +t3927 = -t2740 + t2880; +t3926 = -qsD6 * t3538 + t3935; +t2792 = t3028 * t3781 + t2888; +t2624 = t2792 * t3033 - t2862 * t3549; +t2761 = t2791 + t3648; +t3925 = t2761 - t2624; +t3514 = t3045 * t3046; +t2931 = t3039 * t3047 + t3041 * t3514; +t3816 = qsD3 * t3534 + qsD4 * t3532; +t3924 = qsD6 * t2931 + t2866 + t3816; +t2725 = t3040 * t3509; +t3412 = t3028 * t3084 + t3034 * t3090; +t2565 = -t2725 + t3412; +t2710 = qsD4 * (qsD4 / 0.2e1 + t2925) + t2843; +t3515 = t3045 * t2710; +t3360 = 0.2e1 * t3515; +t2778 = t3046 * t2797; +t2814 = -t3540 - t3590; +t2523 = qsD4 * t2814 + t2778 - t3606; +t3622 = t2523 * t3039; +t3838 = t2565 * t3394 + (t3360 - t3622) * a5 + t3933; +t3923 = -t2927 * t3045 + t3552; +t3506 = t3046 * t2928; +t2686 = -t3040 * t3252 - t3506; +t3195 = -qsD5 * t2686 - t3911; +t3316 = t2913 * t3535; +t2709 = t2926 * t3000 - 0.2e1 * t3316; +t3610 = t2709 * t3039; +t3922 = (t3610 + t3935) * qsD5 + t3045 * t3195; +t3341 = qsD3 * t3571; +t3500 = t3053 * t3041; +t3123 = -qsD4 * t2879 - t3041 * t3052 + t3500 - (-t3341 - t3345) * qsD1; +t3199 = 0.4e1 * qsD3 * t3312; +t3349 = t3001 * t3002; +t3780 = 0.2e1 * t3001 * qsD3; +t2743 = qsD1 * t3199 + (-t3349 + t3780) * qsD2; +t3331 = qsD4 * t3503; +t3419 = qsD3 * t3331 + t3046 * t2743; +t2480 = -qsD4 * t3506 + t3040 * t3123 + t3419; +t2770 = t3041 * t3805 - t3230; +t3179 = t3041 * t2980; +t2833 = -qsD2 * t3349 + 0.2e1 * t3179; +t3507 = t3046 * t2833; +t2562 = qsD4 * t2867 - t3040 * t2770 + t3507; +t3920 = t2480 - t2562; +t3919 = t2522 - t2600; +t2753 = t2925 * t3514 + t2927 * t3039; +t3546 = t3039 * t3051; +t3917 = -qsD5 * t2753 + t2760 * t3651 + t3040 * t3546 + ((-qsD4 * t3046 + t2863) * qsD5 + t3433) * t3045; +t3038 = sin(qs6); +t3603 = t2814 * t3045; +t2675 = t3039 * t3940 + t3603; +t3660 = qsD5 * t2675; +t2365 = t3660 + t3811; +t2811 = t3045 * t2832; +t3555 = t3039 * t2600; +t2449 = t2811 - t3555 - t3660; +t3833 = t2365 + t2449; +t3916 = t3833 * t3038; +t3371 = a3 * t3687; +t3085 = -d3 * t3781 + t3371; +t3302 = -0.2e1 * a3 * t3631; +t2662 = -a4 * t2879 + t3047 * t3085 + t3302; +t3140 = -a5 * t2687 + d5 * t2686 + t2662; +t2799 = a3 * t3377 + t3041 * t3085; +t3701 = d3 * t3040; +t3064 = a4 * (t2912 * t3789 + t2926 * t3040) - 0.2e1 * qsD2 * t3701 + t3046 * t2799; +t2552 = t3099 + t3064; +t3279 = -d5 * t2709 - t2552; +t3823 = t2739 + t2880; +t3730 = t3794 * t3823 - t3279; +t3149 = t2893 * t3039 - t2910 * t3045; +t3854 = qsD5 * t3149; +t3875 = t3039 * t3939 + t3045 * t3938 + t3854; +t3914 = -t3140 * t3039 - t3045 * t3730 + t3854 + t3875; +t2617 = a4 * t3016 - a5 * t2896 + d5 * t3118 + t3593; +t2733 = t3091 * t3041; +t2513 = t2617 * t3045 - t2733 * t3039; +t3662 = qsD5 * t2513; +t3913 = -t3039 * t3931 + t3045 * t3929 - t3662; +t3706 = a5 * t2814; +t2625 = d5 * t3405 + t3706; +t3615 = t2663 * t3045; +t2496 = t2625 * t3039 - t3615; +t3853 = qsD5 + t3405; +t3130 = -d5 * t3853 - t3706; +t3284 = a5 * t3936 - t2663; +t3912 = t3039 * t3130 + t3045 * t3284 - t2496; +t2553 = -t3028 * t3356 + t3748; +t2580 = -t2754 * t3034 - t2724; +t3826 = t2553 - t2580; +t3044 = cos(qs6); +t3910 = -t3038 * t3924 + t3044 * t3926; +t3751 = t2842 * t3535 + t2926 * t3807 + t3316 * t3719; +t2471 = t3034 * t2720 - t3751; +t2736 = t2771 * t3535; +t2576 = t2860 * t3034 + t2920 * t3028 - t2736; +t3825 = -t2576 + t2471; +t3909 = d5 * t3936; +t3273 = -0.2e1 * t3009; +t3400 = t3041 * t3273 + t2966; +t2692 = t2937 + (-t3348 - t3672) * qsD3 + t3400; +t3215 = t3029 * t3309; +t2859 = t2937 - t3215; +t3335 = qsD4 * t3571; +t2788 = qsD1 * t3335 + t2859; +t3908 = t2692 - t2788; +t3268 = qsD4 * t3045 + qsD6; +t3632 = qsD6 * t3045; +t3269 = qsD4 + t3632; +t3550 = t3039 * t3044; +t3328 = qsD5 * t3550; +t3520 = t3044 * t3046; +t3907 = -t2753 * t3044 + t3038 * t3592 - t3268 * t3520 + (t3038 * t3269 + t3328) * t3040; +t3401 = a3 * t2969 + qsD3 * t3302; +t3403 = a3 * t2964 + d3 * t3231; +t3699 = d3 * t3047; +t2644 = (-t3053 - t3358) * t3699 + t3401 + t3403; +t3369 = qsD2 * t3700; +t3591 = t2926 * t3046; +t3098 = t3046 * t2644 - 0.2e1 * t2720 * t3707 + t2842 * t3708 + t2912 * t3301 + t3369 * t3720 + (qsD4 * t3539 + (-t3331 + t3340) * d3 + (-t3338 + t3591) * a4) * qsD4; +t3544 = t3040 * t2799; +t2378 = -qsD4 * t3544 + t3098; +t3239 = d3 * t3341; +t3288 = a3 * t3273 + d3 * t3500 + qsD1 * t3239; +t3402 = a3 * t3232 + d3 * t3230; +t2544 = -a3 * t2968 - a4 * t2743 + t3288 + t3402; +t2907 = qsD4 * t3541; +t3201 = -qsD3 * t3671 - t2743; +t2481 = t3040 * t3201 + t3046 * t3123 + t2907; +t3557 = t3039 * t2481; +t2470 = t3028 * t2720 + t3751; +t3827 = t2470 + t2692; +t3906 = d5 * t3557 + qsD5 * t3930 + t3045 * t2378 + t2460 * t3693 + t3039 * t2544 + t2662 * t3649 + t2686 * t3373 + t3300 * t3823 + t3394 * t3827; +t3209 = (a2 + 0.2e1 * t3709) * t3048; +t3070 = (d3 * t3398 + t3209) * t3055; +t3684 = qsD3 * t2915; +t3905 = t3070 - t3684; +t3021 = t3051 * t3045; +t3904 = t2760 * t3649 + t3040 * t3021 - t3433 * t3039 + (-t3552 + t3923) * qsD5; +t2864 = t3040 * t2898; +t3185 = a4 * t3599 + qsD4 * t2864 + t3040 * t2676; +t3601 = t2827 * t3046; +t2464 = -qsD4 * t3601 + t3185; +t3616 = t2663 * t3039; +t2495 = t2625 * t3045 + t3616; +t3359 = 0.2e1 * t2811; +t3817 = -t2601 * t3039 - t3405 * t3649; +t3903 = a5 * t3359 + d5 * t3817 - qsD5 * t2495 + t3045 * t2464 + t3300 * t3940; +t3155 = -t2686 * t3039 - t2709 * t3045; +t3902 = t3911 * t3039 + (-t3155 + t3824) * qsD5; +t3305 = t2523 * t3549; +t3411 = t3028 * t3090 + t3034 * t3084; +t3292 = t2725 + t3411; +t3434 = -t3027 * t2710 - t3033 * t3292; +t2380 = t3305 - t3434; +t2494 = qsD5 * (qsD5 / 0.2e1 + t3405) + t2565; +t3559 = t3038 * t3044; +t3364 = 0.2e1 * t3559; +t3365 = -0.2e1 * t3559; +t3026 = t3038 ^ 2; +t3032 = t3044 ^ 2; +t2998 = -t3032 + t3026; +t3852 = t2365 * t2998; +t3899 = -t2380 * t3365 - t2494 * t3364 - t3852; +t3351 = -a5 + t3701; +t3353 = -a5 - t3707; +t3597 = t2915 * t3040; +t3793 = 0.2e1 * d5; +t3898 = a5 * t2709 + t3544 + 0.2e1 * t3369 + (d3 * t3503 - t3539) * t3719 + (t2740 + t2880) * t3793 + (t2912 * t3891 - t3591) * a4 - (t3002 * t3353 - t3597) * t3041 + (-t3351 + t3707) * t3681; +t3310 = t3041 * t3530; +t3224 = qsD2 * t3310; +t3498 = t3054 * t3016; +t2648 = qsD2 * t3199 - t3001 * t3498 + (-t3036 * t3780 + 0.4e1 * t3047 * t3224) * qsD1; +t3222 = t3530 * t3680; +t3226 = 0.2e1 * t3398; +t3242 = t3015 * (t3053 - t3054); +t2703 = t3047 * t3242 + (t3226 * t3631 - 0.2e1 * t3222) * qsD1; +t2408 = t3046 * t2648 - t3040 * t2703 + (t2654 + t3151) * qsD4; +t2999 = t3033 - t3027; +t3388 = 0.2e1 * t3045; +t3263 = t3039 * t3388; +t2605 = t2901 * t3034 + t2939 * t3028 - t2782; +t3424 = t2605 - t2823; +t3820 = -t2999 * t2584 + t3424 * t3263; +t3897 = -qsD5 * t3820 + t2408 * t3549; +t3344 = qsD3 * t3577; +t3404 = -qsD2 * t3343 - t3016 * t3004; +t3114 = qsD2 * t3344 + t3404; +t3223 = qsD3 * t3311; +t2661 = (-t3018 * t3530 - t3223) * t3721 + t3114; +t2702 = t3041 * t3242 + (-qsD3 * t3310 - t3019 * t3398) * t3721; +t2914 = t3128 * qsD2; +t2385 = (-t2661 + t2914) * t3262 + t2782 * t3792 + (t3719 * t3762 + t2702) * t3000; +t2409 = -t3040 * t2648 - t3046 * t2703 + (t2655 + t3150) * qsD4; +t3107 = t3321 + t3342; +t3075 = qsD5 * t3118 + t3107; +t3197 = qsD5 * t3575 + t2654; +t2506 = t3039 * t3075 + t3045 * t3197; +t3159 = -t2583 * t3045 + t2587 * t3039; +t2279 = -t3045 * t2385 - t3039 * t2409 + (t2506 + t3159) * qsD5; +t2784 = t3039 * t3575 - t3045 * t3118; +t3158 = t2583 * t3039 + t2587 * t3045; +t2422 = qsD5 * t2784 - t3158; +t3390 = 0.2e1 * t3038; +t3264 = t3044 * t3390; +t3304 = t2584 * t3549; +t2428 = t2605 * t3033 + t2823 * t3027 + t3304; +t2558 = -qsD5 * t2896 + t2604; +t3443 = t2428 - t2558; +t3810 = -t2998 * t2422 + t3443 * t3264; +t3896 = -qsD6 * t3810 - t2279 * t3559; +t3895 = t3050 * t3038 - t3833 * t3044; +t3363 = -0.2e1 * t3549; +t3856 = t2792 * t3363; +t2616 = -t2862 * t2999 + t3856; +t3650 = qsD5 * t3040; +t3249 = t2760 + t3650; +t2602 = t3045 * t2863 + t3039 * t3249; +t3619 = t2602 * t3038; +t3327 = qsD5 * t3549; +t3258 = -0.4e1 * t3327; +t3652 = qsD5 * t3033; +t3653 = qsD5 * t3027; +t3813 = 0.2e1 * t3652 - 0.2e1 * t3653; +t3834 = t2553 * t3363 - t2792 * t3813 - t2862 * t3258 + t3263 * (t2580 - t2667) + t3918 * t2999; +t3537 = t3040 * t3044; +t3551 = t3039 * t3040; +t3870 = (-t2925 - t3269) * t3537 + (qsD5 * t3551 - t3046 * t3268 - t2753) * t3038; +t3614 = t2665 * t3045; +t3877 = -t2549 * t3045 + t3614 - t3904; +t3477 = t3038 * t3834 - t3044 * (-qsD6 * t2616 + t3877) - (t3619 - t3870) * qsD6; +t2484 = t2999 * t2687 + t3263 * t3927; +t2929 = -t3039 * t3532 + t3513; +t2508 = qsD5 * t2929 - t2686 * t3045 + t3610; +t3625 = t2508 * t3038; +t3362 = 0.2e1 * t3549; +t3836 = t2471 * t3363 + t2687 * t3258 + t2692 * t3362 + t3263 * (t2576 - t2788) + t3920 * t2999 + t3927 * t3813; +t3871 = t3038 * t3926 + t3044 * t3924; +t3677 = qsD4 * t2866; +t2561 = -t3046 * t2770 - t3040 * t2833 + t3677; +t3626 = t2481 * t3045; +t3882 = -t2561 * t3045 + t3626 - t3902; +t3487 = t3038 * t3836 - t3044 * (-qsD6 * t2484 + t3882) - (t3625 - t3871) * qsD6; +t2473 = t2619 * t3045 + t2623 * t3039; +t2477 = a5 * t2760 + t2792 * t3793 - t2804 + (0.2e1 * t3540 + t3590) * a4; +t2618 = t2927 * t3353 - t2804; +t3086 = qsD5 * t2973 + t2791 * t3794 - t3278; +t3277 = d5 * t2863 + t2827; +t3139 = a5 * t2862 - t3277; +t2392 = t3039 * t3139 + t3045 * t3086; +t3103 = t2959 * t3039 - t2973 * t3649 - t2392; +t3397 = 0.2e1 * t3708; +t3893 = a4 * qsD4 * t2911 + t2754 * t3397 + (t2577 - t2677) * t3040; +t3462 = (t2667 - t3826) * t3793 + t3433 * a5 + (-qsD4 * t3147 + t2812 + 0.2e1 * t2962 - t3510) * a4 + t3893; +t3894 = (-qsD6 * (-t2473 - t3103) + t3462) * t3038 + (-qsD6 * (t2477 - t2618) - t3932) * t3044; +t2593 = t3047 * t3905 + t3403; +t3286 = t3398 * a3; +t3393 = -0.2e1 * t3698; +t2851 = t3014 + (t3042 * t3393 + t3286) * t3055; +t3376 = a4 * t3002; +t3822 = t2859 + t2920; +t3892 = t3046 * t2851 + t3397 * t3822 + (t2593 - t2644) * t3040 + (-(-t3040 * t3376 + t3596) * t3041 + a4 * t3340 + qsD4 * t3505 + (qsD4 * t3534 + t3338) * d3 - t3064) * qsD4; +t2775 = (t3046 * t3376 + t3597) * t3041; +t3802 = -(t2771 * t3040 + t3789 * t3822) * a4 - t3046 * t2593 + t3040 * t2851; +t2404 = qsD4 * t2775 - t3802; +t2575 = t3028 * t2860 + t3034 * t2920 + t2736; +t3774 = (t2575 + t2788) * t3794; +t3121 = t2404 + t3774; +t2527 = -a4 * t2833 - t3041 * t3905 + t3402; +t3142 = -a5 * t2562 + d5 * t2561 + t2527; +t3696 = d5 * t2564; +t3704 = a5 * t3039; +t3888 = -(-t2687 * t3702 + t3039 * t3279) * qsD5 + t2480 * t3704 + t3142 * t3039 + (t3121 + t3696) * t3045 - t3906; +t3887 = -t3662 + t3913; +t2783 = t3015 * t3533 + t3039 * t3118; +t3307 = t2422 * t3559; +t3886 = qsD6 * t2783 - t3032 * t2428 - t2558 * t3026 + t2605 * t3027 + t2823 * t3033 - t3304 + t3307; +t3431 = -t3040 * t2578 - t3046 * t2876; +t3097 = a4 * t3509 - t3431 + (t2843 + t3090) * t3397; +t2664 = -t2864 + t3601; +t3678 = qsD4 * t2664; +t3885 = -t3097 - t3678 - (t2710 + t3292) * t3793 - t2464 + (-t2545 - t2832) * a5; +t3276 = (-0.2e1 * t3002 - qsD3) * qsD3; +t2373 = -t3678 + (-t3509 + (-0.2e1 * t2843 + t3276 - t3567) * t3040) * a4 + t3431; +t2478 = (t3568 - 0.2e1 * t2936 + (-t3030 + t3566) * t3055 + t3276) * t3535 + t3850; +t3285 = t2478 * t3794 + t2373; +t2467 = -0.2e1 * t2725 - t3411 + t3412; +t3715 = 0.2e1 * t2467; +t3145 = d5 * t3715 + t3285; +t3697 = d5 * t2523; +t3204 = -a5 * t2522 - t3697; +t3884 = -t3039 * t3204 - t3045 * t3145 - d5 * t3021 + qsD5 * t3616 + (-qsD5 * t3603 - t3555) * a5 + t3903; +t3883 = t2561 * t3039 - t3557 + t3922; +t3092 = t3015 * t3353 + t3595; +t3777 = t3198 * t3046; +t3779 = t3138 * t3040; +t3881 = a5 * t2587 + t3040 * t2622 + t3777 + (t2605 + t2823) * t3793 + (-t3508 + t3779) * a4 + t3092 * t3680 + (-a5 * t3685 + qsD4 * t3594 - t3782 * t3040 + (-qsD2 * t3504 + qsD4 * t3576) * a4) * t3041; +t2509 = qsD5 * t2931 + t3155; +t3880 = qsD6 * t2929 - t2501 * t3032 + t2509 * t3559 - t2697 * t3026 + t2740 * t3027 + t2880 * t3033 - t3318; +t3879 = -t2478 * t3362 + t2814 * t3258 - t2999 * t3919 + t3039 * t3359 + t3813 * t3940; +t3878 = t3039 * t2549 - t3554 + t3917; +t2603 = -t3045 * t3249 + t3552; +t3876 = t2603 * t3559 - t2624 * t3032 - t2761 * t3026 + t3027 * t2792 + (qsD6 * t3040 + t2862 * t3045) * t3039; +t2453 = qsD5 * t3816 + t2470; +t2520 = -qsD5 * t2866 + t2575; +t3767 = t2453 - t2520; +t3656 = qsD5 * t3405; +t3716 = -0.2e1 * t2467; +t3250 = t3716 - t3656; +t3874 = -t3045 * t3250 + t3021 - t3622 - t3817; +t2534 = -qsD4 * t3650 + t2554; +t2536 = qsD5 * t3592 - t3417; +t3873 = t2534 - t2536; +t2653 = t2814 * t3549 + t3027 * t3940; +t2750 = t3853 * t3039; +t3553 = t3039 * t2814; +t3872 = -t2653 * t3032 + t2750 * t3559 + t3033 * t3940 + (qsD6 - t3553) * t3045; +t3635 = qsD6 * t3032; +t3636 = qsD6 * t3026; +t3815 = 0.2e1 * t3635 - 0.2e1 * t3636; +t2595 = t3045 * t2600; +t3808 = t3652 - t3653; +t2908 = t3045 * t3940; +t3857 = t2908 * t3944; +t3749 = qsD5 * t3857 + t3039 * t2595 + t2814 * t3808; +t2423 = t3027 * t2832 + t3749; +t3655 = qsD5 * t2814; +t2442 = t2478 + t3655; +t2721 = t2750 * t3636; +t3238 = t2653 * t3365; +t3867 = qsD6 * t3238 + t3032 * t2423 - t3026 * t2442 - t3559 * t3874 + t2721; +t3738 = t2480 * t3549 + t2687 * t3808 + (-0.2e1 * t2740 + 0.2e1 * t2880) * t3327; +t2316 = t3033 * t2471 + t3027 * t2692 + t3738; +t2502 = t2509 * t3636; +t3323 = qsD6 * t3559; +t3256 = 0.2e1 * t3323; +t3257 = -0.2e1 * t3323; +t3866 = t3032 * t2316 + t2501 * t3257 + t2697 * t3256 + t3026 * t3767 - t3559 * t3883 + t2502; +t3750 = qsD5 * t3856 + t2666 * t3549 - t2862 * t3808; +t2383 = t3033 * t2553 + t3750; +t2589 = t2603 * t3636; +t3865 = t3032 * t2383 + t2624 * t3257 + t2761 * t3256 + t3026 * t3873 - t3559 * t3878 + t2589; +t3521 = t3044 * t3045; +t2613 = -t2814 * t3038 - t3405 * t3521; +t2639 = t2814 * t2999 + t3857; +t3517 = t3045 * t2601; +t3100 = -qsD6 * t2639 + t2523 * t3045 - t3517 - t3547 + (-t3250 + t3051 + t3656) * t3039; +t3322 = qsD6 * t3521; +t2751 = t3853 * t3045; +t3522 = t3044 * t2751; +t3469 = qsD5 * t3322 + t3879 * t3044 + (-t2613 - t3522) * qsD6 + t3100 * t3038; +t2892 = t3047 * t3351 + t3505; +t2611 = t2713 * t3044 - t2892 * t3038; +t3608 = t2720 * t3040; +t3468 = -(-t2842 * t3046 - 0.2e1 * t3608) * a4 - t2771 * t3707 + (-t3908 - t3825) * t3793 - t3911 * a5 + t3892; +t3497 = -t3888 * t3044 + (-qsD6 * t2611 + t3038 * t3914 - t3044 * t3898) * qsD6 + t3468 * t3038; +t3714 = -0.2e1 * t2478; +t3466 = a5 * t3715 + d5 * t3714 + t2372 - t3077 - 0.2e1 * t3690; +t3560 = t3038 * t3039; +t3634 = qsD6 * t3038; +t3494 = -t3466 * t3038 - t3884 * t3044 + (t3912 * t3038 + t3909 * t3044 + a5 * t3634 - (qsD5 * t3560 - t3322) * d5) * qsD6; +t3558 = t3038 * t3045; +t2612 = t2814 * t3044 - t3405 * t3558; +t3562 = t3038 * t2751; +t3860 = t3038 * (-qsD5 * t3632 - t3879) + (t2612 + t3562) * qsD6 + t3100 * t3044; +t3859 = t3038 * t3838 - t3044 * t3885; +t3229 = 0.2e1 * t2565 + 0.2e1 * t2710; +t3851 = t2523 * t2999; +t3063 = -t3039 * t3069 + t3045 * t3056; +t3486 = (-a5 * t2523 + d5 * t2522 + t2510) * t3045 + (-a5 * t3229 - d5 * t2545 - t2372) * t3039 - t3063; +t3839 = t3486 * t3044; +t2674 = t2908 - t3553; +t3519 = t3045 * t2522; +t3160 = -t3039 * t2545 + t3519; +t2363 = qsD5 * t2674 - t3160; +t3295 = qsD5 * t2908 + t3039 * t2832 + t2595; +t3329 = qsD5 * t3553; +t2448 = t3295 - t3329; +t3456 = t2363 - t2448; +t3049 = qsD7 ^ 2; +t3237 = t3853 * t3364; +t3087 = t3033 * t2710 + t3027 * t3292; +t2341 = t3087 - 0.2e1 * t3305 + t3434; +t3638 = qsD6 * t2674; +t3247 = 0.2e1 * t2341 + t3638; +t3819 = -t2674 * t3634 + (t3049 - t3247) * t3038 + qsD7 * (t2675 * t2998 + t2675 + t3237) - t3895; +t3804 = t3776 + 0.2e1 * t3358; +t3803 = qsD5 * t3536 + t3923; +t3801 = qsD4 * (t3789 * (t2900 + t2939) + t3543) - t2702 * t3046; +t3800 = -qsD5 * t2662 - t2378; +t3267 = qsD7 * t3044 + qsD5; +t3588 = t2973 * t3039; +t3798 = qsD7 * (t3039 * t3086 - t3045 * t3139 + t3267 * t3588 - t3942) - t3894; +t3495 = t3038 * t3885 + t3044 * t3838; +t3162 = -t3038 * t2484 - t3044 * t2508; +t3488 = t3882 * t3038 + t3836 * t3044 + (t3162 + t3910) * qsD6; +t3156 = -t3044 * t2602 - t3038 * t2616; +t3478 = t3877 * t3038 + t3834 * t3044 + (t3156 + t3907) * qsD6; +t3391 = 0.2e1 * qsD6; +t3791 = 0.2e1 * qsD7; +t3037 = sin(qs7); +t3025 = t3037 ^ 2; +t3043 = cos(qs7); +t3031 = t3043 ^ 2; +t2997 = t3031 - t3025; +t3790 = 0.2e1 * t2997; +t3713 = -0.2e1 * t3040; +t3564 = t3037 * t3043; +t3788 = 0.2e1 * t3564; +t3786 = qsD6 * (t2713 * t3038 + t2892 * t3044); +t2514 = t2617 * t3039 + t2733 * t3045; +t2732 = t3092 * t3041; +t3785 = qsD6 * (t2514 * t3038 + t2732 * t3044); +t3772 = t3038 * t3881 + t3044 * t3887 + t3785; +t3319 = t2365 * t3559; +t3453 = t3032 * t2380 + t3026 * t2494; +t3771 = -t3319 + t3453 + t3305 - qsD6 * (qsD6 / 0.2e1 + t2674) - t3087; +t3661 = qsD5 * t2514; +t3769 = t3039 * t3929 + t3045 * t3931 - t3661; +t3688 = qsD1 * qsD2; +t3275 = -0.2e1 * t3042 * t3688; +t3207 = t3048 * t3275; +t3761 = t3029 * t3207 + t3223 * t3721; +t3299 = -0.2e1 * t3374; +t3396 = -0.2e1 * t3704; +t3760 = d5 * t3626 + qsD5 * t3875 + t3045 * t2544 + t2687 * t3375 + t3823 * t3299 + t3827 * t3396; +t3703 = a5 * t3044; +t3758 = -qsD6 * t3703 + (qsD6 * t3558 + t3328) * d5 - t3912 * t3044 + t3909 * t3038; +t3757 = t3038 * t3898 + t3044 * t3914 + t3786; +t2515 = t3039 * t3519; +t3756 = t3027 * t2478 + t3033 * t2832 + t2515 - t3749; +t3755 = a5 * t3329 + t2832 * t3396 + t3940 * t3299 + (-t3517 + t3546) * d5 + qsD5 * t2496; +t3754 = d5 * t3614 + qsD5 * t2473 + t2554 * t3396 + t3045 * t2676 + t2791 * t3299 - t2862 * t3375; +t3079 = -t3045 * (qsD5 * t3044 + qsD7) + qsD6 * t3560; +t3633 = qsD6 * t3039; +t3243 = t2639 + t3633; +t3739 = -t3038 * t3243 + t2613 + t3079 - t3522; +t2456 = (-t2923 * t3053 + t3054 * t3206) * t3041 + (t3080 * t3681 + ((0.2e1 * a2 + 0.4e1 * t3709) * t3048 + d3 * t3226) * t3019) * qsD1; +t2820 = ((a2 + t3393) * t3042 + t3286) * t3688; +t3732 = -(t2902 * t3713 - (-a4 * t3576 - t3594) * t3680 - t3735 * t3041 + t3511) * qsD4 - t2456 * t3040 - 0.2e1 * t2820 * t3046; +t3422 = -t3114 + t2914 + t3761; +t3228 = 0.2e1 * t3422; +t2301 = t2820 * t3713 + t3046 * t2456 + (-t3777 + (-qsD3 * t3593 - t2622 + t3849) * t3040) * qsD4 + (t3040 * t2702 + t3046 * t3228 + ((t2822 + t3107) * t3046 - t3779) * qsD4) * a4; +t3421 = -t2702 * t3535 - t2822 * t3673; +t3602 = t2822 * t3028; +t2397 = t3028 * t2661 + t3034 * t2914 - t3421 + (0.2e1 * t3535 * t3762 - t3602) * qsD4; +t2597 = qsD4 * t3342 + (t3335 - t3344) * qsD2 - t3404 + t3761; +t3728 = d5 * t2385 + (t2397 + t2597) * t3794 + t2301; +t2547 = t2562 * t3549; +t2410 = t2576 * t3033 + t2788 * t3027 + t2547; +t3255 = 0.4e1 * t3323; +t3492 = t3264 * (t2410 - t2520) + t2316 * t3365 + t2453 * t3364 + t2509 * t3255 + t3883 * t2998 + t3928 * t3815; +t2530 = t2550 * t3549; +t2386 = t2580 * t3033 + t2667 * t3027 + t2530; +t3484 = t3264 * (t2386 - t2536) + t2383 * t3365 + t2534 * t3364 + t2603 * t3255 + t3878 * t2998 + t3925 * t3815; +t2384 = -t2478 * t3033 + t2515; +t3725 = t3264 * (t2384 - t2442) + t2423 * t3365 + t2750 * t3255 - t3815 * t2653 + t3874 * t2998; +t3718 = -0.2e1 * t2380 * t3026 - 0.2e1 * t2494 * t3032 - 0.4e1 * t3319 + 0.2e1 * t3453; +t3717 = -0.2e1 * t2341; +t3654 = qsD5 * t2862; +t3645 = qsD6 * t2509; +t2568 = -t2675 * t3038 - t3044 * t3853; +t3644 = qsD6 * t2568; +t3643 = qsD6 * t2603; +t2634 = t2784 * t3044 + t2896 * t3038; +t3639 = qsD6 * t2634; +t3637 = qsD6 * t2675; +t2668 = qsD6 + t2674; +t3613 = t2675 * t3044; +t3607 = t2750 * t3032; +t3604 = t3405 * t3039; +t3561 = t3038 * t3853; +t3526 = t3044 * t2363; +t2443 = t3044 * t2448; +t3499 = t3054 * t3015; +t3491 = -t2410 * t3032 - t2509 * t3635 + t3866; +t3282 = -t2404 - t3696; +t3489 = -t2480 * t3702 + (d5 * t3155 - t3045 * t2552) * qsD5 - t3142 * t3045 + t3760 + (-d5 * t2460 - t3282 + t3774 + t3800) * t3039; +t3485 = -(-t3045 * t3229 + t3622) * a5 + t3933; +t3483 = -t3045 * t3204 - a5 * t2595 + (d5 * t3604 + t3615) * qsD5 + t3755 + (t3145 - t2464) * t3039; +t3482 = -t2386 * t3032 - t2603 * t3635 + t3865; +t3481 = (-t3247 - t3050 - t3638) * t3044 - t3916; +t3479 = -qsD6 * t3607 - t2384 * t3032 + t3867; +t3476 = t2449 + t3899; +t3189 = t3045 * t3292; +t2345 = (t3189 - t3515) * t3944 - t3851; +t3475 = -t2675 * t3255 + (t2345 - t2601) * t3364 + t3456 * t2998 - t3815 * t3853; +t2646 = t2675 * t3636; +t3296 = qsD6 * t3237 + t3026 * t2601 + t2646; +t3474 = t2345 * t3032 - t2675 * t3635 + t3296 + (-t2443 + t3526) * t3038; +t2369 = t3851 + (-0.2e1 * t3189 + t3360) * t3039; +t2293 = -t2369 * t3038 - t3526 + t3644; +t2347 = -t3038 * t2601 + t2443 + t3644; +t3473 = -t2293 + t2347; +t3472 = t2293 + t2347; +t2366 = t3044 * t2369; +t2569 = -t3561 + t3613; +t2294 = qsD6 * t2569 - t2363 * t3038 + t2366; +t2769 = qsD6 * t3561; +t3244 = t2601 + t3637; +t2348 = t3038 * t2448 + t3044 * t3244 - t2769; +t3471 = -t2294 + t2348; +t3467 = t3824 * qsD6 + t3825 * t3027 + t3033 * t3908 + t2547 - t3738; +t3464 = t2316 - t2410; +t3459 = qsD6 * t3803 - t2667 * t3033 + t3027 * t3826 + t2530 - t3750; +t3458 = -qsD5 * t3633 - qsD6 * t3604 + t3756; +t3452 = t2383 - t2386; +t3451 = -t2384 + t2423; +t3441 = t3716 - t3051; +t3440 = -t2481 + t2561; +t3437 = -t2523 + t2601; +t3436 = t2549 - t2665; +t3415 = t2764 - t2832; +t3367 = -0.4e1 * t3564; +t3281 = -t2411 - t3695; +t3261 = a2 * t3048 * t3688; +t3253 = t2768 + 0.2e1 * t3676; +t2336 = t2345 - t3637; +t3194 = -qsD7 * t2513 + t3772 + t3785; +t3193 = t2568 * t3791 - t3049 + t3718; +t3192 = qsD7 * (t2514 * t3044 - t2732 * t3038) + t3661 - t3769; +t2507 = -t3039 * t3197 + t3045 * t3075; +t3191 = -qsD7 * t2634 + t2507 - t3810; +t3113 = qsD6 * (-t2784 * t3038 + t2896 * t3044); +t2393 = t3044 * t2506 + t3038 * t2655 + t3113; +t2421 = qsD5 * t2783 + t3159; +t3167 = -t3044 * t2421 + t3038 * t3820; +t3190 = qsD7 * t2783 + t2393 - t3113 - t3167; +t3166 = t2421 * t3038 + t3044 * t3820; +t3057 = -t2923 * t3023 + d3 * t3222 * t3721 + qsD2 * t3239 + t3499 * t3699 + t3016 * t3013 - 0.2e1 * t3041 * t3261 + (-a3 * t3686 + t3782) * t3681 + (t3711 + t3710) * t3680 * t3722 + (-0.4e1 * a3 * t3224 - 0.2e1 * t3370 * t3398) * qsD1; +t3144 = -a4 * t2648 - a5 * t2408 + d5 * t2409 + t3057; +t3137 = qsD7 * t3149 + t3757 + t3786; +t3136 = qsD7 * t2611 + t3039 * t3730 - t3140 * t3045 + t3659 - t3930; +t2846 = t2931 * t3044 - t3038 * t3538; +t3135 = -qsD7 * t2846 + t2998 * t2509 + t3264 * t3928 + t3824; +t3134 = qsD7 * t2929 - qsD6 * (-t2931 * t3038 - t3041 * t3537) - t3162 + t3910; +t3116 = d5 * qsD7 * t3039 - qsD6 * (-d5 * t3558 + t3703) + t3758; +t3111 = qsD7 * t3551 - qsD6 * (t3038 * t3536 - t3520) - t3156 + t3907; +t3101 = t2770 + t3123; +t3093 = t2750 * t2998 + t3238 + (-t3405 - t3267) * t3039; +t3088 = qsD7 * (a5 * t3038 + d5 * t3521) + t3039 * t3284 - t3045 * t3130 + t2495 + t3373; +t3082 = a5 * t3919 + qsD5 * t2663 + t3697; +t2930 = -t3038 * t3046 - t3040 * t3521; +t3067 = -qsD7 * t2930 + t2998 * t2603 + t3264 * t3925 + t3803; +t3065 = -qsD5 * t2552 - t2527 + (-qsD5 * t2709 - t2561) * d5 - t3920 * a5; +t3062 = -qsD5 * t2626 + (-qsD5 * t2760 - t2549) * d5 + t3945; +t2415 = t2473 * t3044 - t2618 * t3038; +t3058 = (t2959 * t3550 + t2973 * t3079 - t3044 * t2392 - (-qsD6 * t3588 - t2477) * t3038 + t2415) * qsD7 + t3754 - t3937 * t3045 + (-d5 * t2556 - t2446 + (t2959 + t3277) * qsD5 - t3281 + t3775) * t3039; +t2632 = t2668 * t3038; +t2563 = -t2675 * t3559 + t3026 * t3853; +t2517 = t3044 * t3243 - t3562; +t2445 = qsD6 * t2930 + t2616 * t3044 - t3619; +t2398 = t3034 * t2661 + t3028 * t2914 + (-t3125 + t3602) * qsD4 + t3421; +t2394 = t3038 * t2506 - t3044 * t2655 + t3639; +t2358 = qsD6 * t2846 + t2484 * t3044 - t3625; +t2352 = -qsD5 * t2655 + t2397; +t2326 = -t3166 + t3639; +t2280 = t3039 * t2385 - t3045 * t2409 + (t2507 + t3158) * qsD5; +t2273 = t3033 * t2398 + t3027 * t2597 + t3897; +t2272 = (-t2398 + t2597) * t3263 - 0.4e1 * t3304 * qsD5 + (-0.2e1 * qsD5 * t3424 + t2408) * t2999; +t2262 = (t2380 - t2494) * t3264 - t3852; +t2261 = qsD6 * t2507 + t3027 * t2398 + t3033 * t2597 - t3897; +t2253 = a5 * t2385 + (t2398 + t2597) * t3793 + (t3040 * t3228 + t3801) * a4 - t3732; +t2237 = -t3038 * t2272 - t3044 * t2280 + (-t2394 + t3166) * qsD6; +t2236 = t3044 * t2272 - t3038 * t2280 + (t2393 + t3167) * qsD6; +t2235 = t3032 * t2273 + t3026 * t2352 + t3896; +t2234 = (-t2273 + t2352) * t3264 + 0.4e1 * t3307 * qsD6 + (t3391 * t3443 + t2279) * t2998; +t2233 = qsD5 * t3913 - t3728 * t3039 + t3144 * t3045; +t2232 = qsD5 * t3769 + t3144 * t3039 + t3045 * t3728; +t2230 = t3044 * t2232 - t3038 * t2253 + ((-qsD6 * t2514 - t3881) * t3044 + (qsD6 * t2732 + t3887) * t3038) * qsD6; +tauc_regressor = [0 0 0 t3207 t3688 * t3226 -t3498 t3499 0 0.2e1 * t3261 a2 * t3275 t2661 t2648 t2702 t2703 t2914 t2456 t3057 t2398 t2385 t2408 t2409 t2597 t2301 (t3422 * t3713 - t3801) * a4 + t3732 t2273 t2272 t2279 t2280 t2352 t2232 t2233 t2235 t2234 t2236 t2237 t2261 t2230 qsD6 * t3772 - t3038 * t2232 - t3044 * t2253 t2236 * t3564 + t3031 * t2235 + t3025 * t2261 + (t2997 * t2326 + t3788 * t3886) * qsD7 t2997 * t2236 + (-t2235 + t2261) * t3788 + (t2326 * t3367 + t3790 * t3886) * qsD7 -t3043 * t2234 - t3037 * t2237 + (t3037 * t3191 + t3043 * t3190) * qsD7 t3037 * t2234 - t3043 * t2237 + (-t3037 * t3190 + t3043 * t3191) * qsD7 qsD7 * t2394 + t3026 * t2273 + t3032 * t2352 - t3896 t3043 * t2230 + t3037 * t2233 + (t3037 * t3194 - t3043 * t3192) * qsD7 -t3037 * t2230 + t3043 * t2233 + (t3037 * t3192 + t3043 * t3194) * qsD7; 0 0 0 t3309 -t3776 0 0 0 -a2 * t3501 t3014 t3071 + t3214 -0.2e1 * t3179 + 0.2e1 * (qsD2 * t3001 + 0.2e1 * t2946) * qsD3 t3047 * t3804 + t3023 (-t3053 - t3804) * t3041 -t2920 (t3684 - t3055 * t3209 + (-t3053 - t3805) * d3) * t3047 + t3401 ((-t2915 - t3371) * qsD3 + t3070) * t3041 + t3288 t3825 t3911 -t3507 + (-t2867 - t3506) * qsD4 + t3101 * t3040 + t3419 -t3677 + t2907 + (t2833 + t3201) * t3040 + t3101 * t3046 t3215 - qsD3 * t3672 + (-t3335 - t3344) * qsD1 + t3400 (-t2775 - t3544) * qsD4 + t3098 + t3802 (0.2e1 * t3608 + (-t2771 + t2842) * t3046) * a4 + t3892 t3464 t3836 t3039 * t3440 + t3922 t3045 * t3440 + t3902 t3767 t3065 * t3039 + ((-qsD5 * t2687 - 0.2e1 * t2575 - 0.2e1 * t2788) * a5 + t3282) * t3045 + t3906 t3065 * t3045 + (d5 * t3195 + t3121 + t3800) * t3039 + t3760 (-t2410 - t3645) * t3032 + t3866 t3492 t3488 -t3487 t3467 t3497 t3757 * qsD6 + t3038 * t3888 + t3468 * t3044 t3488 * t3564 + t3491 * t3031 + t3467 * t3025 + (t2997 * t2358 + t3788 * t3880) * qsD7 t3488 * t2997 + (t3467 - t3491) * t3788 + (t2358 * t3367 + t3790 * t3880) * qsD7 -t3492 * t3043 + t3487 * t3037 + (t3037 * t3135 + t3043 * t3134) * qsD7 t3487 * t3043 + t3492 * t3037 + (-t3037 * t3134 + t3043 * t3135) * qsD7 -t2502 + t3464 * t3026 + t3871 * qsD7 + (t3645 + t3767) * t3032 + (-t3391 * t3928 + t3883) * t3559 t3497 * t3043 + t3489 * t3037 + (t3037 * t3137 - t3043 * t3136) * qsD7 t3489 * t3043 - t3497 * t3037 + (t3037 * t3136 + t3043 * t3137) * qsD7; 0 0 0 0 0 0 0 0 0 0 t2754 -t2768 -t3104 - 0.2e1 * t3232 + t3399 0.2e1 * t2964 + t2969 + t2980 + (-t2927 - t3631) * qsD3 -t3356 (d3 * t3320 - t3096) * qsD1 + t3181 + t3797 (-t2980 + (qsD3 - t3002) * t3631) * d3 - t3110 + t3410 t3826 -t3433 t3415 * t3040 + (-t3052 - t3253) * t3046 t3040 * t3253 + t3046 * t3415 + t3022 -t2667 (-t2684 + t2804) * qsD4 + t3173 + t3734 ((0.2e1 * t3356 + t3675) * t3040 + (-t2762 + t2831 + t3386) * t3046) * a4 + t3893 t3452 t3834 t3436 * t3039 + t3917 t3045 * t3436 + t3904 t2554 + t3417 - t3654 ((0.2e1 * t3417 - 0.2e1 * t2667 + t3654) * a5 + t3281) * t3045 + t3062 * t3039 + t3934 t3062 * t3045 + (-t2446 + (t2827 + t2959) * qsD5 + (qsD5 * t2863 + t3433) * d5 + t3120) * t3039 + t3754 (-t2386 - t3643) * t3032 + t3865 t3484 t3478 -t3477 t3459 t3894 t3462 * t3044 + t3932 * t3038 + (t2477 * t3038 + t3044 * t3103 + t2415) * qsD6 t3478 * t3564 + t3482 * t3031 + t3459 * t3025 + (t2997 * t2445 + t3788 * t3876) * qsD7 t3478 * t2997 + (t3459 - t3482) * t3788 + (t2445 * t3367 + t3790 * t3876) * qsD7 -t3484 * t3043 + t3477 * t3037 + (t3037 * t3067 + t3043 * t3111) * qsD7 t3477 * t3043 + t3484 * t3037 + (-t3037 * t3111 + t3043 * t3067) * qsD7 -t2589 + t3452 * t3026 + t3870 * qsD7 + (t3643 + t3873) * t3032 + (-t3391 * t3925 + t3878) * t3559 t3058 * t3037 - t3043 * t3798 t3037 * t3798 + t3058 * t3043; 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 t2478 t3716 t3152 + t3413 t2778 + (-t2762 - t2831) * t3040 + (t2814 + t3590) * qsD4 + t3406 t2832 (t2664 - t3601) * qsD4 + t3097 + t3185 t3108 - t3414 t3451 t3879 t3021 + (t2467 + t3656) * t3388 + t3437 * t3039 t3437 * t3045 + (t3441 - 0.2e1 * t3656) * t3039 -t2442 t3082 * t3039 + (-t2373 + t3441 * d5 + (t3714 - t3655) * a5) * t3045 + t3903 t3082 * t3045 + (-d5 * t3250 - t2464 + t3285) * t3039 + t3755 (-qsD6 * t2750 - t2384) * t3032 + t3867 t3725 t3469 t3860 -t3633 * t3853 + t3756 -t3494 t3758 * qsD6 - t3038 * t3884 + t3466 * t3044 t3469 * t3564 + t3479 * t3031 + t3458 * t3025 + (t2997 * t2517 + t3788 * t3872) * qsD7 t3469 * t2997 + (t3458 - t3479) * t3788 + (t2517 * t3367 + t3790 * t3872) * qsD7 -t3725 * t3043 - t3860 * t3037 + (t3093 * t3037 - t3043 * t3739) * qsD7 -t3860 * t3043 + t3725 * t3037 + (t3037 * t3739 + t3093 * t3043) * qsD7 -qsD7 * t2612 - t2442 * t3032 - t2721 + t3451 * t3026 + (qsD7 * t3550 + t3607) * qsD6 + (qsD7 * t3649 + (t2653 * t3391 + t3874) * t3044) * t3038 -t3494 * t3043 + t3483 * t3037 + (t3037 * t3116 - t3043 * t3088) * qsD7 t3483 * t3043 + t3494 * t3037 + (t3037 * t3088 + t3043 * t3116) * qsD7; 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 t2345 t3717 (-t2674 - t3553) * qsD5 + t3160 + t3295 -t3518 + t2811 + (-t2522 - t2600) * t3039 t2601 -d5 * t3160 + t3039 * t2372 - t3045 * t2510 + t2523 * t3702 + t3229 * t3704 + t3063 t3838 t2336 * t3032 + t3456 * t3559 + t3296 -t3475 -t3916 + (t3717 - t3050 - 0.2e1 * t3638) * t3044 (t2341 + t3638) * t3390 + t3895 -t2336 -t3839 t3486 * t3038 -t3025 * t2336 + t3481 * t3564 + t3474 * t3031 + (-0.2e1 * t2563 * t3564 - t2632 * t2997) * qsD7 t3481 * t2997 - t2563 * qsD7 * t3790 + (t2632 * t3791 - t2336 - t3474) * t3788 t3037 * t3819 + t3475 * t3043 -t3475 * t3037 + t3043 * t3819 t3026 * t2345 - t2646 + t3244 * t3032 + (-t2668 * qsD7 + (-0.2e1 * qsD6 * t3853 - t3456) * t3044) * t3038 t3037 * t3485 - t3043 * t3839 t3037 * t3839 + t3043 * t3485; 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 t2262 t3718 t3526 + t2443 + (t2369 - t2601) * t3038 -t3044 * t2601 + t2366 + t2769 + (-t2363 - t2448) * t3038 + (t2569 - t3613) * qsD6 t2449 t3859 t3495 t3031 * t2262 + t3025 * t2449 + t3473 * t3564 + (t2569 * t2997 + t2668 * t3788) * qsD7 (-t2262 + t2449) * t3788 + t3473 * t2997 + (t2569 * t3367 + t2668 * t3790) * qsD7 t3037 * t3471 - t3043 * t3193 t3037 * t3193 + t3043 * t3471 -qsD7 * t2569 - t3899 t3859 * t3043 -t3859 * t3037; 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 -t2997 * t2294 + t3771 * t3788 0.2e1 * t2294 * t3788 + 0.2e1 * t2997 * t3771 t3037 * t3476 + t3043 * t3472 -t3037 * t3472 + t3043 * t3476 t2348 t3037 * t3495 - t3043 * t3486 t3037 * t3486 + t3043 * t3495;]; \ No newline at end of file diff --git a/robot_model/atlas5_arm_e_kinetic_fb_reg_minpar_sym_lag_varpar.m b/robot_model/atlas5_arm_e_kinetic_fb_reg_minpar_sym_lag_varpar.m new file mode 100755 index 0000000..b95f62b --- /dev/null +++ b/robot_model/atlas5_arm_e_kinetic_fb_reg_minpar_sym_lag_varpar.m @@ -0,0 +1,179 @@ +% Calculate Kinetic Energy for Atlas Robot Arm (v5) +% Use matlab function from symbolic calculations +% Berechnung mit Regressorform (Parameterlineare Form) +% Minimal-Parametersatz (neu gruppierte Parameter) +% +% Input: +% q [1x7] +% Joint Angles [rad] +% lr +% true for left, false for right +% +% Output: +% T [1x45] +% Geometry Vector of Kinetic Energy + +% Moritz Schappler, schappler@irt.uni-hannover.de, 2015-02 +% (c) Institut für Regelungstechnik, Universität Hannover + +function T_regressor = atlas5_arm_e_kinetic_fb_reg_minpar_sym_lag_varpar( ... + q, qD, a_mdh, d_mdh, q_offset_mdh) +%% Init +% Coder Information +%#codegen +assert(isa(q,'double') && isreal(q) && all(size(q) == [1 7])); +assert(isa(qD,'double') && isreal(qD) && all(size(qD) == [1 7])); +assert(isa(a_mdh,'double') && isreal(a_mdh) && all(size(a_mdh) == [7 1]), ... + 'a_mdh has to be [7x1] double'); +assert(isa(d_mdh,'double') && isreal(d_mdh) && all(size(d_mdh) == [7 1]), ... + 'd_mdh has to be [7x1] double'); +assert(isa(q_offset_mdh,'double') && isreal(q_offset_mdh) && all(size(q_offset_mdh) == [7 1]), ... + 'q_offset_mdh has to be [7x1] double'); + +qs1 = q(1); +qs2 = q(2); +qs3 = q(3); +qs4 = q(4); +qs5 = q(5); +qs6 = q(6); +qs7 = q(7); + +qsD1 = qD(1); +qsD2 = qD(2); +qsD3 = qD(3); +qsD4 = qD(4); +qsD5 = qD(5); +qsD6 = qD(6); +qsD7 = qD(7); +%% Get MDH Parameters + +d3 = d_mdh(3); +d5 = d_mdh(5); + +a2 = a_mdh(2); +a3 = a_mdh(3); +a4 = a_mdh(4); +a5 = a_mdh(5); +a6 = a_mdh(6); + +qoffset2 = q_offset_mdh(2); + + +%% Maple Generated Calculation +% from codeexport/atlas5_arm_energy_kinetic_regressor_minpar_mapleexport.m + +t105 = sin(qs3); +t106 = sin(qs2); +t112 = cos(qs2); +t114 = qsD1 ^ 2; +t137 = t112 * t114; +t128 = t106 * t137; +t111 = cos(qs3); +t87 = t111 * qsD2; +t129 = qsD1 * t87; +t88 = qs2 + qoffset2; +t86 = cos(t88); +t152 = t105 * t128 - t86 * t129; +t104 = sin(qs4); +t110 = cos(qs4); +t85 = sin(t88); +t69 = (a3 * t86 + d3 * t85 + a2) * qsD1; +t62 = d3 * t87 + t105 * t69; +t146 = qsD1 * t85; +t74 = t105 * t146 + t87; +t68 = -qsD2 * a3 - t74 * a4; +t118 = -t104 * t62 - t110 * t68; +t100 = t112 ^ 2; +t142 = t100 * t114; +t126 = t142 / 0.2e1; +t113 = qsD2 ^ 2; +t150 = t113 / 0.2e1; +t123 = t85 * t129; +t76 = t105 * t123; +t93 = t105 ^ 2; +t99 = t111 ^ 2; +t63 = t93 * t126 + t99 * t150 + t76; +t94 = t106 ^ 2; +t144 = t94 * t114; +t83 = t86 * qsD1; +t72 = t144 / 0.2e1 + qsD3 * (t83 + qsD3 / 0.2e1); +t148 = t63 + t72; +t124 = 0.2e1 * t148; +t138 = t105 * qsD2; +t120 = -d3 * t138 + t111 * t69; +t130 = qsD1 * t138; +t46 = qsD3 * t120 + (a3 * t85 - d3 * t86) * t130 + (a3 * t113 + (a3 * t94 + (-d3 * t112 + a2) * t106) * t114) * t111; +t75 = -t111 * t146 + t138; +t55 = qsD3 * t75 + t111 * t128 + t86 * t130; +t66 = d3 * t113 + (d3 * t100 + (-a3 * t106 - a2) * t112) * t114; +t32 = t110 * t46 - t104 * t66 + qsD4 * t118 + (t104 * t55 + t110 * t124) * a4; +t135 = 0.2e1 * t104; +t64 = t99 * t126 + t93 * t150 - t76; +t92 = t104 ^ 2; +t98 = t110 ^ 2; +t42 = (-t98 + t92) * t55 + (-t64 + t72) * t110 * t135; +t145 = t110 * t55; +t53 = t104 * t145; +t43 = t92 * t64 + t98 * t72 + t53; +t52 = qsD4 * (qsD4 / 0.2e1 + t74) + t63; +t151 = 0.2e1 * (t43 + t52) * a5 + d5 * t42 + t32; +t81 = t83 + qsD3; +t147 = t104 * t75 + t110 * t81; +t143 = qsD1 * qsD2; +t101 = sin(qs7); +t107 = cos(qs7); +t141 = t101 * t107; +t102 = sin(qs6); +t108 = cos(qs6); +t140 = t102 * t108; +t103 = sin(qs5); +t109 = cos(qs5); +t139 = t103 * t109; +t134 = a2 * t106 * t114; +t133 = t85 * t143; +t54 = qsD3 * t74 - t152; +t56 = -(t99 - t93) * t133 + (t113 - t142) * t111 * t105; +t39 = -qsD4 * t147 - t104 * t56 - t110 * t54; +t59 = -t104 * t81 + t110 * t75; +t73 = qsD4 + t74; +t51 = t103 * t73 + t109 * t59; +t30 = qsD5 * t51 - t103 * t39 - t109 * t42; +t132 = t30 * t140; +t40 = qsD4 * t59 - t104 * t54 + t110 * t56; +t131 = t40 * t139; +t125 = -t103 * t59 + t109 * t73; +t57 = qsD5 + t147; +t119 = -t102 * t51 - t108 * t57; +t49 = t104 * t68 - t110 * t62; +t115 = -qsD3 * t62 + a3 * t123 + (-t134 + (-t113 - t144) * a3) * t105 + t152 * d3; +t117 = -a4 * t56 - a5 * t40 + d5 * t39 + t115; +t116 = qsD4 * t49 - t104 * t46 - t110 * t66; +t97 = t109 ^ 2; +t96 = t108 ^ 2; +t95 = t107 ^ 2; +t91 = t103 ^ 2; +t90 = t102 ^ 2; +t89 = t101 ^ 2; +t50 = qsD6 + t125; +t48 = t73 * d5 - t49; +t47 = -t73 * a5 - t118; +t45 = -t102 * t57 + t108 * t51; +t44 = t98 * t64 + t92 * t72 - t53; +t41 = t81 * a4 + a5 * t147 - t59 * d5 + t120; +t37 = qsD5 * (qsD5 / 0.2e1 + t147) + t43; +t36 = t103 * t41 + t109 * t48; +t35 = -t103 * t48 + t109 * t41; +t34 = t97 * t44 + t91 * t52 + t131; +t33 = -t102 * t47 + t108 * t36; +t31 = (t97 - t91) * t40 + 0.2e1 * (-t44 + t52) * t139; +t29 = qsD5 * t125 + t103 * t42 - t109 * t39; +t28 = t91 * t44 - t131 + t97 * t52 + qsD6 * (qsD6 / 0.2e1 + t125); +t27 = a5 * t42 + 0.2e1 * (t44 + t52) * d5 + (t104 * t124 - t145) * a4 - t116; +t26 = qsD6 * t45 - t102 * t29 + t108 * t31; +t25 = qsD6 * t119 - t102 * t31 - t108 * t29; +t24 = t96 * t34 + t90 * t37 - t132; +t23 = (-t96 + t90) * t30 + 0.2e1 * (-t34 + t37) * t140; +t22 = qsD5 * t35 + t117 * t103 + t151 * t109; +t21 = -qsD5 * t36 - t151 * t103 + t117 * t109; +t20 = t108 * t22 - t102 * t27 + qsD6 * (-t102 * t36 - t108 * t47); +T_regressor = [t114 / 0.2e1 0 0 t126 -t128 -t133 -t86 * t143 t150 t134 a2 * t137 t64 t56 t55 t54 t72 t46 t115 t44 t42 t40 t39 t52 t32 (-t148 * t135 + t145) * a4 + t116 t34 t31 t30 t29 t37 t22 t21 t24 t23 t26 t25 t28 t20 -qsD6 * t33 - t102 * t22 - t108 * t27 t26 * t141 + t95 * t24 + t89 * t28 (t95 - t89) * t26 + 0.2e1 * (-t24 + t28) * t141 -t107 * t23 - t101 * t25 + qsD7 * (t101 * t50 + t107 * t45) t101 * t23 - t107 * t25 + qsD7 * (-t101 * t45 + t107 * t50) t90 * t34 + t132 + t96 * t37 + qsD7 * (qsD7 / 0.2e1 - t119) t107 * t20 + t101 * t21 + qsD7 * (-t101 * t33 + t107 * t35) -t101 * t20 + t107 * t21 + qsD7 * (-t101 * t35 - t107 * t33);]; \ No newline at end of file diff --git a/robot_model/atlas5_arm_energy_kinetic_fb_plin_minpar_sym_lag_varpar.m b/robot_model/atlas5_arm_energy_kinetic_fb_plin_minpar_sym_lag_varpar.m new file mode 100755 index 0000000..421a8e2 --- /dev/null +++ b/robot_model/atlas5_arm_energy_kinetic_fb_plin_minpar_sym_lag_varpar.m @@ -0,0 +1,41 @@ +% Calculate Potential Energy for Atlas robot Arm (v5) +% Use matlab function from symbolic calculations +% Berechnung mit Regressorform (Parameterlineare Form) +% Minimal-Parametersatz (neu gruppierte Parameter) +% +% Input: +% q +% Joint Angles [rad] +% MPV [45x1] +% minimum parameter vector (regrouped dynamic parameters) +% lr +% true for left, false for right +% +% Output: +% T [1x1] +% Kinetic Energy + +% Moritz Schappler, schappler@irt.uni-hannover.de, 2015-03 +% (c) Institut für Regelungstechnik, Universität Hannover + +function T = atlas5_arm_energy_kinetic_fb_plin_minpar_sym_lag_varpar( ... + q, qD, MPV, lr) +%% Init +% Coder Information +%#codegen +assert(isa(q,'double') && isreal(q) && all(size(q) == [1 7]), ... + 'Joint angles q have to be [1x7] double'); +assert(isa(qD,'double') && isreal(qD) && all(size(qD) == [1 7])); +assert(isa(MPV,'double') && isreal(MPV) && all(size(MPV) == [45 1]), ... + 'Minimum Parameter vector has to be [45x1] double'); +assert(isa(lr,'logical') && all(size(lr) == [1 1])); + +%% Kinematik-Parameter +[a_mdh, d_mdh, ~, q_offset_mdh] = atlas5_arm_parameter_mdh(lr); + +%% Regressor-Matrix +T_regressor = atlas5_arm_e_kinetic_fb_reg_minpar_sym_lag_varpar( ... +q, qD, a_mdh, d_mdh, q_offset_mdh); + +%% Energie +T = (T_regressor*MPV)'; \ No newline at end of file diff --git a/robot_model/atlas5_arm_energy_potential_plin_minpar_sym_lag_varpar.m b/robot_model/atlas5_arm_energy_potential_plin_minpar_sym_lag_varpar.m new file mode 100755 index 0000000..f70c28a --- /dev/null +++ b/robot_model/atlas5_arm_energy_potential_plin_minpar_sym_lag_varpar.m @@ -0,0 +1,43 @@ +% Calculate Potential Energy for Atlas robot Arm (v5) +% Use matlab function from symbolic calculations +% Berechnung mit Regressorform (Parameterlineare Form) +% Minimal-Parametersatz (neu gruppierte Parameter) +% +% Input: +% q +% Joint Angles [rad] +% MPV [45x1] +% minimum parameter vector (regrouped dynamic parameters) +% lr +% true for left, false for right +% +% Output: +% U [1x1] +% Potential Energy + +% Moritz Schappler, schappler@irt.uni-hannover.de, 2015-03 +% (c) Institut für Regelungstechnik, Universität Hannover + +function U = atlas5_arm_energy_potential_plin_minpar_sym_lag_varpar( ... + q, g0_utorso, MPV, lr) +%% Init +% Coder Information +%#codegen +assert(isa(q,'double') && isreal(q) && all(size(q) == [1 7]), ... + 'Joint angles qs have to be [1x7] double'); +assert(isa(g0_utorso,'double') && isreal(g0_utorso) && all(size(g0_utorso) == [1 3]), ... + 'Gravitation vector has to be [1x3] double'); +assert(isa(MPV,'double') && isreal(MPV) && all(size(MPV) == [45 1]), ... + 'Minimum Parameter vector has to be [45x1] double'); +assert(isa(lr,'logical') && all(size(lr) == [1 1])); + +%% Kinematik-Parameter +p_num_urdf = atlas5_arm_parameter_urdf(lr); +[a_mdh, d_mdh, ~, q_offset_mdh] = atlas5_arm_parameter_mdh(lr); + +%% Regressor-Matrix +U_regressor = atlas5_arm_energy_potential_regressor_minpar_sym_lag_varpar( ... + q, g0_utorso, p_num_urdf, a_mdh, d_mdh, q_offset_mdh, lr); + +%% Gelenkmoment +U = (U_regressor*MPV)'; \ No newline at end of file diff --git a/robot_model/atlas5_arm_energy_potential_regressor_minpar_sym_lag_varpar.m b/robot_model/atlas5_arm_energy_potential_regressor_minpar_sym_lag_varpar.m new file mode 100755 index 0000000..b4b1fa3 --- /dev/null +++ b/robot_model/atlas5_arm_energy_potential_regressor_minpar_sym_lag_varpar.m @@ -0,0 +1,114 @@ +% Calculate Potential Energy for Atlas robot Arm (v5) +% Use matlab function from symbolic calculations +% Berechnung mit Regressorform (Parameterlineare Form) +% Minimal-Parametersatz (neu gruppierte Parameter) +% +% Input: +% q +% Joint Angles [rad] +% lr +% true for left, false for right +% +% Output: +% U_regressor [1x45] +% Regressorform of Potential Energy (Gravitation) + +% Moritz Schappler, schappler@irt.uni-hannover.de, 2015-02 +% (c) Institut für Regelungstechnik, Universität Hannover + +function U_regressor = atlas5_arm_energy_potential_regressor_minpar_sym_lag_varpar( ... + q, g0_utorso, p_num_urdf, a_mdh, d_mdh, q_offset_mdh, lr) +%% Init +% Coder Information +%#codegen +assert(isa(q,'double') && isreal(q) && all(size(q) == [1 7])); +assert(isa(g0_utorso,'double') && isreal(g0_utorso) && all(size(g0_utorso) == [1 3]), ... + 'Gravitation vector has to be [1x3] double'); +assert(isa(p_num_urdf,'double') && isreal(p_num_urdf) && all(size(p_num_urdf) == [1 13]), ... + 'p_num_urdf has to be [1x13] double'); +assert(isa(a_mdh,'double') && isreal(a_mdh) && all(size(a_mdh) == [7 1]), ... + 'a_mdh has to be [7x1] double'); +assert(isa(d_mdh,'double') && isreal(d_mdh) && all(size(d_mdh) == [7 1]), ... + 'd_mdh has to be [7x1] double'); +assert(isa(q_offset_mdh,'double') && isreal(q_offset_mdh) && all(size(q_offset_mdh) == [7 1]), ... + 'q_offset_mdh has to be [7x1] double'); +assert(isa(lr,'logical') && all(size(lr) == [1 1])); + +qs1 = q(1); +qs2 = q(2); +qs3 = q(3); +qs4 = q(4); +qs5 = q(5); +qs6 = q(6); +qs7 = q(7); + +%% Get MDH Parameters + +p4 = p_num_urdf(4); +p5 = p_num_urdf(5); + +d3 = d_mdh(3); +d5 = d_mdh(5); + +a2 = a_mdh(2); +a3 = a_mdh(3); +a4 = a_mdh(4); +a5 = a_mdh(5); +a6 = a_mdh(6); + +qoffset2 = q_offset_mdh(2); + +% Gravitation Vector in utorso frame +g1 = g0_utorso(1); +g2 = g0_utorso(2); +g3 = g0_utorso(3); +%% Maple Generated Calculation +% from codeexport/atlas5_arm_energy_potential_regressor_minpar_mapleexport.m +constant = 0; + +t192 = (a5 ^ 2); +t205 = 3 * t192; +t204 = 3 * constant; +t203 = 4 * constant; +t172 = g2 * p5 - g3 * p4; +t183 = sin(qs1); +t189 = cos(qs1); +t169 = -t183 * g1 + t189 * t172; +t171 = -g2 * p4 - g3 * p5; +t177 = qs2 + qoffset2; +t173 = sin(t177); +t174 = cos(t177); +t164 = t174 * t169 - t173 * t171; +t168 = -t189 * g1 - t183 * t172; +t182 = sin(qs3); +t188 = cos(qs3); +t161 = t188 * t164 + t182 * t168; +t191 = d3 ^ 2; +t194 = (a3 ^ 2); +t202 = (t191 - t194); +t201 = (t191 + t194); +t200 = constant * a3; +t199 = constant * a4; +t198 = constant * a5; +t197 = constant * d3; +t196 = constant * d5; +t163 = t173 * t169 + t174 * t171; +t181 = sin(qs4); +t187 = cos(qs4); +t157 = t187 * t161 - t181 * t163; +t160 = -t182 * t164 + t188 * t168; +t180 = sin(qs5); +t186 = cos(qs5); +t154 = -t180 * t157 + t186 * t160; +t156 = t181 * t161 + t187 * t163; +t193 = a4 ^ 2; +t190 = d5 ^ 2; +t185 = cos(qs6); +t184 = cos(qs7); +t179 = sin(qs6); +t178 = sin(qs7); +t176 = 2 * t197; +t175 = 2 * t196; +t155 = t186 * t157 + t180 * t160; +t153 = t185 * t155 - t179 * t156; +U_regressor = [(6 * a2 ^ 2 + 5 * t194 + 1) * constant (6 * constant * a2) + t169 t168 + constant t176 + constant * t202 + (t193 + t202) * t203 (5 * d3 + 1) * t200 0 0 constant + t176 + constant * t201 + (t193 + t201) * t203 t164 + (5 * t200) -t163 - constant - (5 * t197) (-4 * t193 + t205) * constant -t199 0 0 (1 + 4 * t193 + t205) * constant (4 * t199) + t161 t160 + constant t175 + (t190 - t192) * t204 (3 * d5 + 1) * t198 0 0 constant + t175 + (t190 + t192) * t204 t157 + (3 * t198) -t156 - constant - (3 * t196) 0 0 0 0 constant t155 t154 + constant 0 0 0 0 constant t153 -t179 * t155 - t185 * t156 - constant -constant 0 0 0 0 t184 * t153 + t178 * t154 -t178 * t153 + t184 * t154;]; \ No newline at end of file diff --git a/robot_model/atlas5_arm_fkine.m b/robot_model/atlas5_arm_fkine.m new file mode 100755 index 0000000..7b353e3 --- /dev/null +++ b/robot_model/atlas5_arm_fkine.m @@ -0,0 +1,40 @@ +% Calculate Forward Kinematics for Atlas Robot (v5) +% +% Input: +% q [1x7] +% Joint Angles [rad] +% lr [1x1 logical] +% true for left, false for right +% +% Output: +% T_c_urdf [4x4x9] +% homogenious transformation matrices for each body frame +% 1: utorso -> utorso +% 2: utorso -> clav +% 3: utorso -> scap +% 4: utorso -> uarm +% 5: utorso -> larm +% 6: utorso -> ufarm +% 7: utorso -> lfarm +% 8: utorso -> hand +% 9: utorso -> endpoint +% +% Sources: +% [1] atlas_v5.urdf +% + +% Moritz Schappler, schappler@irt.uni-hannover.de, 2015-01 +% (c) Institut für Regelungstechnik, Leibniz Universität Hannover + + +function T_c_urdf = atlas5_arm_fkine(q, lr) +%% Init +%#codegen +% Coder Information +assert(isa(q,'double') && isreal(q) && all(size(q) == [1 7]), ... + 'Joint angles q have to be [1x7] double'); +assert(isa(lr,'logical') && all(size(lr) == [1 1]), ... + 'Left/Right flag has to be [1x1] logical'); + +%% Calculation +T_c_urdf = atlas5_arm_fkine_num(q, lr); \ No newline at end of file diff --git a/robot_model/atlas5_arm_fkine_num.m b/robot_model/atlas5_arm_fkine_num.m new file mode 100644 index 0000000..559e4db --- /dev/null +++ b/robot_model/atlas5_arm_fkine_num.m @@ -0,0 +1,103 @@ +% Calculate Forward Kinematics for Atlas Robot (v5) +% +% Input: +% q [1x7] +% Joint Angles [rad] +% lr [1x1 logical] +% true for left, false for right +% +% Output: +% T_c_urdf [4x4x9] +% homogenious transformation matrices for each body frame +% 1: utorso -> utorso +% 2: utorso -> clav (depending on q1) +% 3: utorso -> scap (depending on q1, q2) +% 4: utorso -> uarm +% 5: utorso -> larm +% 6: utorso -> ufarm +% 7: utorso -> lfarm +% 8: utorso -> hand +% 9: utorso -> endpoint +% +% Sources: +% [1] atlas_v5_simple_shapes_with_head.urdf + +% Moritz Schappler, schappler@irt.uni-hannover.de, 2015-01 +% (c) Institut für Regelungstechnik, Leibniz Universität Hannover + + +function T_c_urdf = atlas5_arm_fkine_num(q, lr) +%% Init +%#codegen +% Coder Information +assert(isa(q,'double') && isreal(q) && all(size(q) == [1 7]), ... + 'Joint angles q have to be [1x7] double'); +assert(isa(lr,'logical') && all(size(lr) == [1 1]), ... + 'Left/Right flag has to be [1x1] logical'); + +p_num = atlas5_arm_parameter_urdf(lr); + +%% Frame to Frame Transformations +T_urdf = NaN(4,4,8); + +% T_urdf: Overview over the indices +% 1 shz: utorso -> clav +% 2 shx: clav -> scap +% 3 ely: scap -> uarm +% 4 elx: uarm -> larm +% 5 wry: larm -> ufarm +% 6 wrx: ufarm -> lfarm +% 7 wry2:lfarm -> hand +% 8 hand -> endpoint + +% 1 shz: utorso -> clav +if lr + T_urdf(:,:,1) = transl(p_num(1:3)) * trotz(3.14159265359) * trotz(q(1)); +else + T_urdf(:,:,1) = transl(p_num(1:3)) * trotz(q(1)); +end +% 2 shx: clav -> scap +if lr + T_urdf(:,:,2) = transl([0, p_num(6:7)]) * trotx(-q(2)); +else + T_urdf(:,:,2) = transl([0, p_num(6:7)]) * trotx(q(2)); +end +% 3 ely: scap -> uarm +if lr + T_urdf(:,:,3) = transl([0, p_num(8:9)]) * troty(-q(3)); +else + T_urdf(:,:,3) = transl([0, p_num(8:9)]) * troty(q(3)); +end +% 4 elx: uarm -> larm +if lr + T_urdf(:,:,4) = transl([0, p_num(10:11)]) * trotx(-q(4)); +else + T_urdf(:,:,4) = transl([0, p_num(10:11)]) * trotx(q(4)); +end +% 5 wry: larm -> ufarm +if lr + T_urdf(:,:,5) = transl([0, p_num(12:13)]) * troty(3.14159265359) * troty(-q(5)); +else + T_urdf(:,:,5) = transl([0, p_num(12:13)]) * troty(q(5)); +end +% 6 wrx: ufarm -> lfarm +T_urdf(:,:,6) = trotx(q(6)); +% 7 wry2: lfarm -> hand +if lr + T_urdf(:,:,7) = troty(3.14159265359) * troty(-q(7)); +else + T_urdf(:,:,7) = troty(q(7)); +end +% 8 hand -> endpoint +if lr + T_urdf(:,:,8) = trotz(pi); +else + T_urdf(:,:,8) = eye(4); +end + +%% Kumulierte Transformationsmatrizen +T_c_urdf = NaN(4,4,9); +T_c_urdf(:,:,1) = eye(4); +for j = 2:9 + T_c_urdf(:,:,j) = T_c_urdf(:,:,j-1) * T_urdf(:,:,j-1); +end \ No newline at end of file diff --git a/robot_model/atlas5_arm_gravload_plin_minpar_sym_lag_varpar.m b/robot_model/atlas5_arm_gravload_plin_minpar_sym_lag_varpar.m new file mode 100755 index 0000000..d66dee2 --- /dev/null +++ b/robot_model/atlas5_arm_gravload_plin_minpar_sym_lag_varpar.m @@ -0,0 +1,45 @@ +% Calculate Gravitation Load for Atlas Robot Arms (v5) +% Use Code from Maple symbolic Code Generation +% Berechnung mit Regressorform (Parameterlineare Form) +% +% Input: +% q [1x7] +% Joint Angles [rad] +% g0_utorso [1x3] +% gravitation vector in utorso frame [m/s^2] +% MPV [45x1] +% minimum parameter vector (regrouped dynamic parameters) +% lr +% true for left, false for right +% +% Output: +% taug [1x7] +% joint torques required to compensate gravitation load + +% Moritz Schappler, schappler@irt.uni-hannover.de, 2015-02 +% (c) Institut für Regelungstechnik, Universität Hannover + +function taug = atlas5_arm_gravload_plin_minpar_sym_lag_varpar( ... + q, g0_utorso, MPV, lr) +%% Init +% Coder Information +%#codegen +assert(isa(q,'double') && isreal(q) && all(size(q) == [1 7]), ... + 'atlas5_arm_gravload_plin_minpar_sym_lag_varpar:Joint angles q have to be [1x7] double'); +assert(isa(g0_utorso,'double') && isreal(g0_utorso) && all(size(g0_utorso) == [1 3]), ... + 'atlas5_arm_gravload_plin_minpar_sym_lag_varpar:Gravitation vector has to be [1x3] double'); +assert(isa(MPV,'double') && isreal(MPV) && all(size(MPV) == [45 1]), ... + 'atlas5_arm_gravload_plin_minpar_sym_lag_varpar:Minimum Parameter vector has to be [45x1] double'); +assert(isa(lr,'logical') && all(size(lr) == [1 1]), ... + 'atlas5_arm_gravload_plin_minpar_sym_lag_varpar:Left/Right Flag has to be [1x1] logical'); + +%% Kinematik-Parameter +p_num_urdf = atlas5_arm_parameter_urdf(lr); +[~, ~, ~, q_offset_mdh] = atlas5_arm_parameter_mdh(lr); + +%% Regressor-Matrix +taug_regressor = atlas5_arm_gravload_regressor_minpar_sym_lag_varpar( ... + q, g0_utorso, p_num_urdf, q_offset_mdh); + +%% Gravitationslast +taug = (taug_regressor*MPV)'; diff --git a/robot_model/atlas5_arm_gravload_regressor_minpar_sym_lag_varpar.m b/robot_model/atlas5_arm_gravload_regressor_minpar_sym_lag_varpar.m new file mode 100755 index 0000000..8a849d6 --- /dev/null +++ b/robot_model/atlas5_arm_gravload_regressor_minpar_sym_lag_varpar.m @@ -0,0 +1,113 @@ +% Berechnung der Regressormatrix (parameterlineare Form) für die +% Gravitationslast (atlas v5) +% +% Parametersatz 2 (Trägheit (zweites Moment), Masse*Schwerpunkt (erstes +% Moment), Masse) +% +% Input: +% q [1x7] +% Joint Angles [rad] +% g0_utorso [1x3] +% gravitation vector in utorso frame [m/s^2] +% lr +% true for left, false for right +% +% Output: +% taug_regressor [6x60] +% Regressormatrix zur Multiplikation mit dem (vollen) Parametervektor + +% Moritz Schappler, schappler@irt.uni-hannover.de, 2015-03 +% (c) Institut für Regelungstechnik, Universität Hannover + +function taug_regressor = atlas5_arm_gravload_regressor_minpar_sym_lag_varpar( ... + q, g0_utorso, p_num_urdf, q_offset_mdh) +%% Init +% Coder Information +%#codegen +assert(isa(q,'double') && isreal(q) && all(size(q) == [1 7]), ... + 'Joint angles q have to be [1x7] double'); +assert(isa(g0_utorso,'double') && isreal(g0_utorso) && all(size(g0_utorso) == [1 3]), ... + 'Gravitation vector has to be [1x3] double'); +assert(isa(p_num_urdf,'double') && isreal(p_num_urdf) && all(size(p_num_urdf) == [1 13]), ... + 'p_num_urdf has to be [1x13] double'); +assert(isa(q_offset_mdh,'double') && isreal(q_offset_mdh) && all(size(q_offset_mdh) == [7 1]), ... + 'q_offset_mdh has to be [7x1] double'); + +qs1 = q(1); +qs2 = q(2); +qs3 = q(3); +qs4 = q(4); +qs5 = q(5); +qs6 = q(6); +qs7 = q(7); + +%% Get MDH Parameters +p4 = p_num_urdf(4); +p5 = p_num_urdf(5); + +qoffset2 = q_offset_mdh(2); + +% Gravitation Vector in base frame (utorso) +g1 = g0_utorso(1); +g2 = g0_utorso(2); +g3 = g0_utorso(3); + +%% Maple Generated Calculation +% from codeexport/atlas5_arm_gravload_regressor_minpar_mapleexport.m + +t261 = sin(qs1); +t235 = g2 * p5 - g3 * p4; +t250 = cos(qs1); +t232 = -t250 * g1 - t261 * t235; +t239 = qs2 + qoffset2; +t236 = sin(t239); +t260 = t236 * t232; +t233 = -t261 * g1 + t250 * t235; +t234 = -g2 * p4 - g3 * p5; +t237 = cos(t239); +t231 = t237 * t233 - t236 * t234; +t249 = cos(qs3); +t244 = sin(qs3); +t256 = t244 * t232; +t227 = t249 * t231 + t256; +t230 = t236 * t233 + t237 * t234; +t243 = sin(qs4); +t248 = cos(qs4); +t220 = t243 * t227 + t248 * t230; +t242 = sin(qs5); +t259 = t242 * t220; +t251 = t249 * t232; +t226 = -t244 * t231 + t251; +t258 = t243 * t226; +t257 = t244 * t230; +t221 = t248 * t227 - t243 * t230; +t247 = cos(qs5); +t212 = -t242 * t221 + t247 * t226; +t246 = cos(qs6); +t255 = t246 * t212; +t254 = t247 * t220; +t253 = t248 * t226; +t252 = t249 * t230; +t245 = cos(qs7); +t241 = sin(qs6); +t240 = sin(qs7); +t229 = -t244 * t233 + t237 * t251; +t228 = -t249 * t233 - t237 * t256; +t225 = t248 * t229 - t243 * t260; +t224 = t243 * t229 + t248 * t260; +t223 = -t243 * t231 - t248 * t252; +t222 = t248 * t231 - t243 * t252; +t219 = t247 * t225 + t242 * t228; +t218 = -t242 * t225 + t247 * t228; +t217 = t247 * t223 + t242 * t257; +t216 = -t242 * t223 + t247 * t257; +t215 = -t242 * t227 + t247 * t253; +t214 = -t247 * t227 - t242 * t253; +t213 = t247 * t221 + t242 * t226; +t211 = t246 * t215 - t241 * t258; +t210 = t246 * t219 - t241 * t224; +t209 = -t241 * t221 - t246 * t254; +t208 = t246 * t217 - t241 * t222; +t207 = t246 * t213 - t241 * t220; +t206 = -t241 * t213 - t246 * t220; +taug_regressor = [0 t232 -t233 0 0 0 0 0 t237 * t232 -t260 0 0 0 0 0 t229 t228 0 0 0 0 0 t225 -t224 0 0 0 0 0 t219 t218 0 0 0 0 0 t210 -t241 * t219 - t246 * t224 0 0 0 0 0 t245 * t210 + t240 * t218 -t240 * t210 + t245 * t218; 0 0 0 0 0 0 0 0 -t230 -t231 0 0 0 0 0 -t252 t257 0 0 0 0 0 t223 -t222 0 0 0 0 0 t217 t216 0 0 0 0 0 t208 -t241 * t217 - t246 * t222 0 0 0 0 0 t245 * t208 + t240 * t216 -t240 * t208 + t245 * t216; 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 t226 -t227 0 0 0 0 0 t253 -t258 0 0 0 0 0 t215 t214 0 0 0 0 0 t211 -t241 * t215 - t246 * t258 0 0 0 0 0 t245 * t211 + t240 * t214 -t240 * t211 + t245 * t214; 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 -t220 -t221 0 0 0 0 0 -t254 t259 0 0 0 0 0 t209 -t246 * t221 + t241 * t254 0 0 0 0 0 t245 * t209 + t240 * t259 -t240 * t209 + t245 * t259; 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 t212 -t213 0 0 0 0 0 t255 -t241 * t212 0 0 0 0 0 -t240 * t213 + t245 * t255 -t245 * t213 - t240 * t255; 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 t206 -t207 0 0 0 0 0 t245 * t206 -t240 * t206; 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 -t240 * t207 + t245 * t212 -t245 * t207 - t240 * t212;]; \ No newline at end of file diff --git a/robot_model/atlas5_arm_inertia_plin_minpar_regressor_sym_lag_varpar.m b/robot_model/atlas5_arm_inertia_plin_minpar_regressor_sym_lag_varpar.m new file mode 100644 index 0000000..42530f4 --- /dev/null +++ b/robot_model/atlas5_arm_inertia_plin_minpar_regressor_sym_lag_varpar.m @@ -0,0 +1,569 @@ +% Calculate joint inertia matrix for Atlas robot Arm (v5) +% Use matlab function from symbolic Maple calculations +% Berechnung mit Regressorform (Parameterlineare Form) +% Minimal-Parametersatz (neu gruppierte Parameter) +% +% Input: +% q +% Joint Angles [rad] +% a_mdh, d_mdh, q_offset_mdh [7x1] double +% kinematic parameters [m], [rad] +% lr +% true for left, false for right +% +% Output: +% Mq [7x7] +% Joint Mass-Matrix + +% Moritz Schappler, schappler@irt.uni-hannover.de, 2015-03 +% (c) Institut für Regelungstechnik, Universität Hannover + + +function MM_regressor = atlas5_arm_inertia_plin_minpar_regressor_sym_lag_varpar(q, a_mdh, d_mdh, q_offset_mdh, lr) +%% Init +% Coder Information +%#codegen +assert(isa(q,'double') && isreal(q) && all(size(q) == [1 7]), ... + 'Joint angles qs have to be [1x7] double'); +assert(isa(a_mdh,'double') && isreal(a_mdh) && all(size(a_mdh) == [7 1]), ... + 'a_mdh has to be [7x1] double'); +assert(isa(d_mdh,'double') && isreal(d_mdh) && all(size(d_mdh) == [7 1]), ... + 'd_mdh has to be [7x1] double'); +assert(isa(q_offset_mdh,'double') && isreal(q_offset_mdh) && all(size(q_offset_mdh) == [7 1]), ... + 'q_offset_mdh has to be [7x1] double'); +assert(isa(lr,'logical') && all(size(lr) == [1 1])); + +qs2 = q(2); +qs3 = q(3); +qs4 = q(4); +qs5 = q(5); +qs6 = q(6); +qs7 = q(7); + +%% Get MDH Parameters + +d3 = d_mdh(3); +d5 = d_mdh(5); + +a2 = a_mdh(2); +a3 = a_mdh(3); +a4 = a_mdh(4); +a5 = a_mdh(5); + +qoffset2 = q_offset_mdh(2); + + +%% Maple Generated Calculation +% from codeexport/atlas5_arm_inertia_regressor_minpar_mapleexport.m + +t4278 = sin(qs5); +t4485 = -0.2e1 * t4278; +t4447 = 2 * a5; +t4477 = 2 * d5; +t4284 = cos(qs5); +t4394 = t4284 * t4278; +t4330 = 0.2e1 * t4394; +t4277 = sin(qs6); +t4283 = cos(qs6); +t4398 = t4283 * t4277; +t4484 = 0.2e1 * t4398; +t4276 = sin(qs7); +t4282 = cos(qs7); +t4403 = t4282 * t4276; +t4483 = 0.2e1 * t4403; +t4263 = qs2 + qoffset2; +t4261 = sin(t4263); +t4262 = cos(t4263); +t4207 = a3 * t4262 + d3 * t4261 + a2; +t4286 = cos(qs3); +t4190 = t4286 * t4207; +t4279 = sin(qs4); +t4285 = cos(qs4); +t4387 = t4286 * t4261; +t4360 = t4285 * t4387; +t4437 = t4262 * t4279; +t4098 = -a4 * (t4360 + 0.2e1 * t4437) - t4279 * t4190; +t4287 = cos(qs2); +t4275 = t4287 ^ 2; +t4281 = sin(qs2); +t4205 = d3 * t4275 + (-a3 * t4281 - a2) * t4287; +t4269 = t4281 ^ 2; +t4280 = sin(qs3); +t4268 = t4280 ^ 2; +t4434 = t4268 * t4275; +t4325 = t4269 + t4434; +t4296 = 0.2e1 * t4325; +t4407 = t4281 * t4287; +t4334 = t4286 * t4407; +t4328 = 0.2e1 * t4334; +t4467 = -0.2e1 * t4279; +t4464 = a3 * t4269; +t4158 = (t4464 + (-d3 * t4287 + a2) * t4281) * t4286; +t4473 = 0.2e1 * t4158; +t4038 = t4285 * t4473 + t4205 * t4467 + (t4279 * t4328 + t4285 * t4296) * a4; +t4267 = t4279 ^ 2; +t4273 = t4285 ^ 2; +t4316 = t4285 * t4334; +t4303 = t4279 * t4316; +t4274 = t4286 ^ 2; +t4430 = t4274 * t4275; +t4139 = t4267 * t4430 + t4273 * t4269 + 0.2e1 * t4303; +t4482 = (t4139 + t4434) * t4447 + t4038; +t4449 = t4285 * d3; +t4462 = a4 * t4279; +t4217 = (-t4449 + t4462) * t4280; +t4245 = -t4273 + t4267; +t4389 = t4285 * t4279; +t4378 = 0.2e1 * t4389; +t4481 = t4280 * (a5 * t4378 + d5 * t4245) + t4217; +t4456 = d5 * t4279; +t4480 = t4285 * (a4 + t4456) + a5 * t4273; +t4329 = -0.2e1 * t4268 * t4389; +t4435 = t4267 * t4268; +t4463 = a3 * t4286; +t4313 = a4 * t4274 + t4463; +t4452 = t4279 * d3; +t4469 = 0.2e1 * t4285 * t4313 - 0.2e1 * t4452; +t4479 = d5 * t4329 + (t4274 + t4435) * t4447 + t4469; +t4188 = (a3 * t4261 - d3 * t4262) * t4280; +t4461 = a4 * t4280; +t4084 = t4285 * t4188 + (0.2e1 * t4360 + t4437) * t4461; +t4322 = t4279 * t4360; +t4134 = (t4245 * t4262 + 0.2e1 * t4322) * t4280; +t4359 = t4262 * t4389; +t4143 = (-t4267 * t4387 + t4359) * t4280; +t4386 = t4286 * t4280; +t4225 = t4261 * t4386; +t4478 = (t4143 + t4225) * t4447 + d5 * t4134 + t4084; +t4431 = t4273 * t4268; +t4457 = a5 * t4285; +t4476 = -0.2e1 * t4449 - 0.2e1 * (t4274 + t4431) * d5 - 0.2e1 * (-t4268 * t4457 + t4313) * t4279; +t4117 = t4245 * t4334 + (t4269 - t4430) * t4389; +t4475 = 0.2e1 * t4117; +t4474 = t4480 * t4485; +t4397 = t4283 * t4284; +t4168 = (-t4267 * t4397 - t4277 * t4389) * t4278; +t4472 = 0.2e1 * t4168; +t4259 = t4284 * t4285; +t4170 = (t4259 * t4268 + t4278 * t4386) * t4279; +t4471 = 0.2e1 * t4170; +t4388 = t4285 * t4286; +t4171 = (-t4275 * t4388 + t4279 * t4407) * t4280; +t4470 = 0.2e1 * t4171; +t4468 = 0.2e1 * t4277; +t4466 = 0.2e1 * t4284; +t4465 = a2 * t4281; +t4460 = a4 * t4285; +t4459 = a4 * t4286; +t4455 = d5 * t4285; +t4454 = d5 * t4286; +t4453 = t4278 * d5; +t4451 = t4280 * d3; +t4450 = t4284 * d5; +t4448 = t4286 * d3; +t4446 = t4117 * t4278; +t4445 = t4117 * t4284; +t4187 = -t4360 - t4437; +t4444 = t4187 * t4278; +t4443 = t4187 * t4284; +t4442 = t4207 * t4279; +t4264 = t4276 ^ 2; +t4270 = t4282 ^ 2; +t4242 = t4270 - t4264; +t4441 = t4242 * t4277; +t4266 = t4278 ^ 2; +t4272 = t4284 ^ 2; +t4244 = t4272 - t4266; +t4440 = t4244 * t4279; +t4227 = t4245 * t4280; +t4246 = t4274 - t4268; +t4439 = t4246 * t4261; +t4438 = t4261 * t4285; +t4436 = t4266 * t4267; +t4271 = t4283 ^ 2; +t4433 = t4271 * t4266; +t4432 = t4272 * t4267; +t4362 = t4279 * t4387; +t4390 = t4285 * t4262; +t4186 = t4362 - t4390; +t4056 = a4 * t4262 - a5 * t4186 - d5 * t4187 + t4190; +t4231 = t4280 * t4261; +t4376 = d5 * t4231; +t4260 = t4285 * t4280; +t4348 = t4279 * t4231; +t4385 = a4 * t4348 + t4207 * t4260; +t4100 = t4376 + t4385; +t4011 = t4056 * t4278 + t4100 * t4284; +t4289 = t4280 * (t4442 + (-a5 - t4460) * t4261); +t3983 = -t4277 * t4011 - t4283 * t4289; +t4429 = t4276 * t3983; +t4249 = -a3 - t4459; +t4203 = -d3 * t4388 + t4249 * t4279; +t4184 = -t4203 + t4454; +t4311 = a5 * t4279 - t4455; +t4308 = -d3 + t4311; +t4192 = t4308 * t4280; +t4092 = t4184 * t4284 + t4192 * t4278; +t4391 = t4285 * t4249; +t4291 = t4391 + (-a5 + t4452) * t4286; +t4043 = -t4277 * t4092 - t4283 * t4291; +t4428 = t4276 * t4043; +t4363 = t4278 * t4231; +t4119 = t4363 + t4443; +t4071 = t4119 * t4277 - t4186 * t4283; +t4427 = t4276 * t4071; +t4343 = t4284 * t4260; +t4413 = t4278 * t4286; +t4213 = t4343 + t4413; +t4411 = t4279 * t4283; +t4347 = t4280 * t4411; +t4152 = t4213 * t4277 + t4347; +t4426 = t4276 * t4152; +t4393 = t4284 * t4279; +t4396 = t4283 * t4285; +t4209 = t4277 * t4393 - t4396; +t4425 = t4276 * t4209; +t4417 = t4277 * t4284; +t4221 = a5 * t4283 - d5 * t4417; +t4424 = t4276 * t4221; +t4423 = t4276 * t4278; +t4251 = t4276 * t4283; +t4010 = t4056 * t4284 - t4100 * t4278; +t4422 = t4277 * t4010; +t4091 = -t4184 * t4278 + t4192 * t4284; +t4421 = t4277 * t4091; +t4408 = t4280 * t4284; +t4361 = t4261 * t4408; +t4118 = t4361 - t4444; +t4420 = t4277 * t4118; +t4351 = t4278 * t4260; +t4392 = t4284 * t4286; +t4210 = -t4351 + t4392; +t4419 = t4277 * t4210; +t4215 = t4311 * t4278; +t4418 = t4277 * t4215; +t4252 = t4277 * t4278; +t4416 = t4278 * t4186; +t4312 = -t4456 - t4457; +t4228 = a4 - t4312; +t4415 = t4278 * t4228; +t4253 = t4278 * t4279; +t4414 = t4278 * t4282; +t4254 = t4278 * t4285; +t4412 = t4279 * t4188; +t4255 = t4279 * t4280; +t4410 = t4279 * t4286; +t4409 = t4280 * t4207; +t4406 = t4282 * t4071; +t4405 = t4282 * t4152; +t4404 = t4282 * t4209; +t4402 = t4282 * t4277; +t4256 = t4282 * t4283; +t4401 = t4282 * t4284; +t4009 = t4283 * t4010; +t4086 = t4283 * t4091; +t4400 = t4283 * t4118; +t4399 = t4283 * t4210; +t4199 = t4283 * t4215; +t4257 = t4283 * t4278; +t4395 = t4284 * t4186; +t4219 = t4284 * t4228; +t4234 = t4286 * t4262; +t4384 = 0.2e1 * t4454; +t4383 = -0.2e1 * t4403; +t4381 = -0.2e1 * t4398; +t4379 = -0.2e1 * t4394; +t4377 = -0.2e1 * t4386; +t4375 = d5 * t4257; +t4165 = (t4275 * t4410 + t4285 * t4407) * t4280; +t4061 = -0.2e1 * t4165 * t4278 - 0.2e1 * t4445; +t4373 = t4061 * t4398; +t4145 = -t4234 * t4285 + t4279 * t4439; +t4065 = -t4134 * t4284 - t4145 * t4278; +t4372 = t4065 * t4398; +t4147 = -t4245 * t4387 + 0.2e1 * t4359; +t4336 = t4261 * t4260; +t4096 = -t4147 * t4284 + t4278 * t4336; +t4371 = t4096 * t4398; +t4370 = t4119 * t4398; +t4146 = -t4234 * t4279 - t4246 * t4438; +t4369 = t4146 * t4394; +t4368 = t4170 * t4398; +t4367 = t4171 * t4394; +t4179 = -t4245 * t4408 + t4278 * t4388; +t4366 = t4179 * t4398; +t4365 = t4187 * t4394; +t4364 = t4213 * t4398; +t4358 = t4276 * t4401; +t4357 = t4276 * t4397; +t4356 = t4277 * t4415; +t4355 = t4277 * t4253; +t4354 = t4277 * t4396; +t4353 = t4277 * t4219; +t4236 = t4278 * t4255; +t4352 = t4279 * t4414; +t4350 = t4282 * t4257; +t4349 = t4278 * t4392; +t4346 = t4283 * t4393; +t4344 = t4280 * t4407; +t4342 = t4276 * t4402; +t4237 = t4278 * t4402; +t4341 = t4282 * t4397; +t4238 = t4277 * t4257; +t4340 = t4228 * t4257; +t4339 = t4279 * t4257; +t4338 = t4283 * t4394; +t4239 = t4278 * t4393; +t4240 = t4280 * t4393; +t4337 = t4284 * t4389; +t4241 = t4279 * t4260; +t4335 = t4285 * t4386; +t4324 = t4186 * t4238; +t4323 = t4278 * t4361; +t4321 = t4276 * t4352; +t4320 = t4276 * t4350; +t4319 = t4277 * t4347; +t4318 = t4277 * t4346; +t4317 = t4278 * t4343; +t4315 = t4228 * t4237; +t4189 = a3 * t4387 - d3 * t4234; +t4314 = -t4464 - t4465; +t4310 = 0.2e1 * t4320; +t4307 = t4279 * t4323; +t4306 = t4278 * t4319; +t4305 = t4285 * t4318; +t4304 = t4286 * t4317; +t4302 = t4158 * t4467 - 0.2e1 * t4205 * t4285; +t4097 = t4285 * t4190 + (-t4362 + 0.2e1 * t4390) * a4; +t4160 = t4262 * t4273 - t4322; +t4299 = d5 * t4147 + t4160 * t4447 + t4097; +t4298 = a4 * t4439 - a5 * t4146 + d5 * t4145 + t4189; +t4230 = d3 * t4344; +t4297 = -a5 * t4171 + d5 * t4165 + t4230 + (t4275 * t4459 + t4314) * t4280; +t4294 = 0.2e1 * t4362 - t4390; +t4211 = t4276 * t4284 + t4350; +t4293 = t4257 * t4276 - t4401; +t4292 = t4308 * t4286; +t4290 = t4280 * (t4261 * t4311 - t4207); +t4288 = 0.2e1 * t4249 * t4280 + 0.2e1 * t4312 * t4386; +t4265 = t4277 ^ 2; +t4250 = t4276 * t4277; +t4247 = d5 * t4252; +t4243 = -t4271 + t4265; +t4235 = t4276 * t4252; +t4232 = t4280 * t4262; +t4226 = t4243 * t4278; +t4223 = a5 * t4397 - d5 * t4277; +t4222 = a5 * t4277 + d5 * t4397; +t4218 = (t4452 + t4460) * t4280; +t4216 = t4311 * t4284; +t4214 = t4282 * t4221; +t4212 = -t4277 * t4285 - t4346; +t4206 = t4283 * t4219; +t4204 = d5 * t4267 + (a4 + t4457) * t4279; +t4202 = -d3 * t4410 - t4391; +t4201 = t4211 * d5; +t4200 = t4293 * d5; +t4198 = t4272 * t4286 - t4317; +t4197 = t4266 * t4286 + t4317; +t4196 = t4271 * t4285 - t4318; +t4195 = t4265 * t4285 + t4318; +t4194 = t4264 * t4284 + t4320; +t4193 = t4276 * t4356; +t4185 = -t4203 + t4384; +t4182 = t4244 * t4260 + 0.2e1 * t4349; +t4181 = -t4243 * t4393 + 0.2e1 * t4354; +t4180 = t4242 * t4257 + 0.2e1 * t4358; +t4178 = -t4244 * t4411 - t4259 * t4277; +t4177 = -t4243 * t4414 + t4357; +t4176 = t4227 * t4278 + t4284 * t4388; +t4175 = -t4259 * t4283 + t4277 * t4440; +t4174 = t4243 * t4423 + t4341; +t4173 = d5 * t4423 - t4222 * t4282; +t4172 = -d5 * t4414 - t4222 * t4276; +t4169 = (-t4260 * t4272 - t4349) * t4279; +t4167 = (-t4271 * t4393 - t4354) * t4278; +t4166 = (-t4257 * t4270 - t4358) * t4277; +t4164 = (-t4254 * t4268 + t4284 * t4386) * t4279; +t4163 = (-t4260 * t4266 + t4349) * t4279; +t4162 = (t4267 * t4417 - t4283 * t4389) * t4278; +t4161 = (-t4265 * t4393 + t4354) * t4278; +t4159 = t4262 * t4267 + t4322; +t4157 = t4480 * t4284; +t4154 = t4213 * t4283 - t4255 * t4277; +t4153 = t4212 * t4282 + t4253 * t4276; +t4151 = -t4212 * t4276 + t4352; +t4150 = (-t4244 * t4286 + 0.2e1 * t4317) * t4279; +t4149 = (t4243 * t4285 + 0.2e1 * t4318) * t4278; +t4148 = (-t4242 * t4284 + t4310) * t4277; +t4144 = (-t4273 * t4387 - t4359) * t4280; +t4142 = t4267 * t4269 + t4273 * t4430 - 0.2e1 * t4303; +t4141 = t4266 * t4274 + t4272 * t4431 + 0.2e1 * t4304; +t4140 = t4265 * t4273 + t4271 * t4432 + 0.2e1 * t4305; +t4138 = t4266 * t4431 + t4272 * t4274 - 0.2e1 * t4304; +t4137 = t4255 * t4265 - t4364; +t4136 = t4255 * t4271 + t4364; +t4135 = t4212 * t4403 + t4253 * t4264; +t4130 = (a4 * t4438 - t4442) * t4280; +t4129 = t4213 * t4243 + 0.2e1 * t4319; +t4128 = t4212 * t4242 + 0.2e1 * t4321; +t4127 = t4197 * t4271 - t4306; +t4126 = t4195 * t4270 - t4277 * t4321; +t4125 = t4197 * t4265 + t4306; +t4124 = (t4341 - t4423) * t4228; +t4123 = t4211 * t4228; +t4122 = (-t4357 - t4414) * t4228; +t4121 = t4293 * t4228; +t4120 = (-t4460 + a5 * t4245 + (-d3 - 0.2e1 * t4455) * t4279) * t4280; +t4116 = t4244 * t4335 + (t4274 - t4431) * t4394; +t4115 = -t4243 * t4337 + (t4273 - t4432) * t4398; +t4114 = t4182 * t4283 - t4240 * t4277; +t4113 = -t4181 * t4282 + t4276 * t4339; +t4112 = -t4182 * t4277 - t4240 * t4283; +t4111 = t4181 * t4276 + t4282 * t4339; +t4110 = t4231 * t4272 - t4365; +t4109 = t4231 * t4266 + t4365; +t4108 = t4199 * t4282 + t4216 * t4276; +t4107 = -t4199 * t4276 + t4216 * t4282; +t4105 = t4197 * t4381 + t4236 * t4243; +t4104 = t4195 * t4383 - t4242 * t4355; +t4103 = t4187 * t4244 + 0.2e1 * t4323; +t4102 = t4159 * t4272 - t4307; +t4101 = t4159 * t4266 + t4307; +t4099 = 0.2e1 * t4376 + t4385; +t4095 = t4147 * t4278 + t4284 * t4336; +t4094 = -d5 * t4240 - t4278 * t4202 + (-t4343 - 0.2e1 * t4413) * a5; +t4093 = -d5 * t4236 + t4284 * t4202 + (-t4351 + 0.2e1 * t4392) * a5; +t4089 = t4159 * t4379 - t4244 * t4348; +t4088 = t4154 * t4282 + t4210 * t4276; +t4087 = -t4154 * t4276 + t4210 * t4282; +t4085 = -t4294 * t4461 - t4412; +t4083 = 0.2e1 * t4157 * t4283 - 0.2e1 * t4204 * t4277; +t4082 = t4154 * t4403 + t4210 * t4264; +t4081 = t4154 * t4242 + t4210 * t4483; +t4080 = t4150 * t4283 - t4176 * t4277; +t4079 = -t4149 * t4282 - t4175 * t4276; +t4078 = -t4150 * t4277 - t4176 * t4283; +t4077 = t4149 * t4276 - t4175 * t4282; +t4076 = t4137 * t4270 - t4210 * t4342; +t4075 = -t4129 * t4282 + t4276 * t4399; +t4074 = t4129 * t4276 + t4282 * t4399; +t4073 = t4137 * t4383 - t4242 * t4419; +t4072 = t4119 * t4283 + t4186 * t4277; +t4070 = t4169 * t4271 + t4241 * t4265 - t4366; +t4069 = t4167 * t4270 + t4178 * t4403 + t4239 * t4264; +t4068 = t4169 * t4265 + t4241 * t4271 + t4366; +t4067 = -t4186 * t4265 - t4370; +t4066 = -t4186 * t4271 + t4370; +t4064 = t4134 * t4278 - t4145 * t4284; +t4063 = t4278 * t4292 + t4284 * t4481; +t4062 = -t4278 * t4481 + t4284 * t4292; +t4060 = 0.2e1 * t4116 * t4283 - 0.2e1 * t4164 * t4277; +t4059 = -0.2e1 * t4165 * t4284 + 0.2e1 * t4446; +t4058 = -0.2e1 * t4116 * t4277 - 0.2e1 * t4164 * t4283; +t4057 = t4119 * t4243 + t4186 * t4381; +t4055 = t4109 * t4271 + t4324; +t4054 = t4109 * t4265 - t4324; +t4053 = t4142 * t4272 + t4266 * t4434 + 0.2e1 * t4367; +t4052 = t4141 * t4271 + t4265 * t4435 - 0.2e1 * t4368; +t4051 = t4142 * t4266 + t4272 * t4434 - 0.2e1 * t4367; +t4050 = t4243 * t4179 + (-t4169 + t4241) * t4484; +t4049 = t4242 * t4178 + (-t4167 + t4239) * t4483; +t4048 = t4103 * t4283 + t4277 * t4395; +t4047 = -t4103 * t4277 + t4283 * t4395; +t4046 = t4093 * t4283 - t4185 * t4277; +t4045 = -t4093 * t4277 - t4185 * t4283; +t4044 = t4092 * t4283 - t4277 * t4291; +t4042 = t4109 * t4381 - t4243 * t4416; +t4041 = t4282 * t4043; +t4040 = t4244 * t4470 + (-t4142 + t4434) * t4330; +t4039 = t4243 * t4471 + (-t4141 + t4435) * t4484; +t4037 = t4144 * t4272 + t4225 * t4266 + t4369; +t4036 = t4144 * t4266 + t4225 * t4272 - t4369; +t4035 = -t4105 * t4282 - t4112 * t4276; +t4034 = t4105 * t4276 - t4112 * t4282; +t4033 = t4244 * t4146 + (-t4144 + t4225) * t4330; +t4032 = t4288 * t4278 + t4284 * t4479; +t4031 = -t4278 * t4479 + t4288 * t4284; +t4030 = a5 * t4147 + t4159 * t4477 - t4098; +t4029 = d5 * t4395 - t4278 * t4130 + (-0.2e1 * t4363 - t4443) * a5; +t4028 = d5 * t4416 + t4284 * t4130 + (0.2e1 * t4361 - t4444) * a5; +t4027 = t4089 * t4283 - t4095 * t4277; +t4026 = -t4089 * t4277 - t4095 * t4283; +t4025 = t4086 * t4282 - t4092 * t4276; +t4024 = -t4086 * t4276 - t4092 * t4282; +t4023 = t4114 * t4403 + t4127 * t4270 + t4198 * t4264; +t4022 = t4072 * t4282 + t4118 * t4276; +t4021 = -t4072 * t4276 + t4118 * t4282; +t4020 = t4072 * t4403 + t4118 * t4264; +t4019 = t4242 * t4114 + (-t4127 + t4198) * t4483; +t4018 = t4063 * t4283 - t4120 * t4277; +t4017 = -t4063 * t4277 - t4120 * t4283; +t4016 = t4072 * t4242 + t4118 * t4483; +t4015 = t4067 * t4270 - t4118 * t4342; +t4014 = -t4057 * t4282 + t4276 * t4400; +t4013 = t4057 * t4276 + t4282 * t4400; +t4012 = t4067 * t4383 - t4242 * t4420; +t4008 = t4102 * t4271 + t4160 * t4265 - t4371; +t4007 = t4102 * t4265 + t4160 * t4271 + t4371; +t4006 = a5 * t4134 + t4144 * t4477 + t4412 + (a4 * t4294 + t4261 * t4384) * t4280; +t4005 = t4046 * t4282 + t4094 * t4276; +t4004 = -t4046 * t4276 + t4094 * t4282; +t4003 = -t4044 * t4282 - t4091 * t4276; +t4002 = -t4044 * t4276 + t4091 * t4282; +t4001 = t4243 * t4096 + (-t4102 + t4160) * t4484; +t4000 = -t4050 * t4282 - t4078 * t4276; +t3999 = t4050 * t4276 - t4078 * t4282; +t3998 = t4032 * t4283 + t4277 * t4476; +t3997 = t4028 * t4283 - t4099 * t4277; +t3996 = -t4028 * t4277 - t4099 * t4283; +t3995 = (t4142 + t4434) * t4477 + (t4279 * t4296 - 0.2e1 * t4316) * a4 + a5 * t4475 - t4302; +t3994 = t4040 * t4283 - t4059 * t4277; +t3993 = -t4040 * t4277 - t4059 * t4283; +t3992 = -t4042 * t4282 - t4047 * t4276; +t3991 = t4042 * t4276 - t4047 * t4282; +t3990 = t4278 * t4290 + t4284 * t4299; +t3989 = -t4278 * t4299 + t4284 * t4290; +t3988 = t4070 * t4270 + t4080 * t4403 + t4163 * t4264; +t3987 = t4033 * t4283 - t4064 * t4277; +t3986 = -t4033 * t4277 - t4064 * t4283; +t3985 = t4242 * t4080 + (-t4070 + t4163) * t4483; +t3984 = t4011 * t4283 - t4277 * t4289; +t3982 = t4282 * t3983; +t3981 = t4053 * t4271 + t4139 * t4265 - t4373; +t3980 = t4037 * t4271 + t4143 * t4265 - t4372; +t3979 = t4037 * t4265 + t4143 * t4271 + t4372; +t3978 = t4018 * t4282 + t4062 * t4276; +t3977 = -t4018 * t4276 + t4062 * t4282; +t3976 = t4243 * t4061 + (-t4053 + t4139) * t4484; +t3975 = t4048 * t4403 + t4055 * t4270 + t4110 * t4264; +t3974 = t4243 * t4065 + (-t4037 + t4143) * t4484; +t3973 = t4242 * t4048 + (-t4055 + t4110) * t4483; +t3972 = t4298 * t4278 + t4284 * t4478; +t3971 = -t4278 * t4478 + t4298 * t4284; +t3970 = -t4001 * t4282 - t4026 * t4276; +t3969 = t4001 * t4276 - t4026 * t4282; +t3968 = t4009 * t4282 - t4011 * t4276; +t3967 = -t4009 * t4276 - t4011 * t4282; +t3966 = t3997 * t4282 + t4029 * t4276; +t3965 = -t3997 * t4276 + t4029 * t4282; +t3964 = t3990 * t4283 - t4030 * t4277; +t3963 = -t3990 * t4277 - t4030 * t4283; +t3962 = 0.2e1 * t4297 * t4278 + t4284 * t4482 + t4445 * t4477; +t3961 = -0.2e1 * d5 * t4446 - t4278 * t4482 + t4297 * t4466; +t3960 = t4008 * t4270 + t4027 * t4403 + t4101 * t4264; +t3959 = t4242 * t4027 + (-t4008 + t4101) * t4483; +t3958 = -t3984 * t4282 - t4010 * t4276; +t3957 = -t3984 * t4276 + t4010 * t4282; +t3956 = -t3974 * t4282 - t3986 * t4276; +t3955 = t3974 * t4276 - t3986 * t4282; +t3954 = t3972 * t4283 - t4006 * t4277; +t3953 = -t3972 * t4277 - t4006 * t4283; +t3952 = t3962 * t4283 - t3995 * t4277; +t3951 = t3964 * t4282 + t3989 * t4276; +t3950 = -t3964 * t4276 + t3989 * t4282; +t3949 = t3980 * t4270 + t3987 * t4403 + t4036 * t4264; +t3948 = t4242 * t3987 + (-t3980 + t4036) * t4483; +t3947 = t3954 * t4282 + t3971 * t4276; +t3946 = -t3954 * t4276 + t3971 * t4282; +MM_regressor = [1 0 0 t4275 -0.2e1 * t4407 0 0 0 0.2e1 * t4465 0.2e1 * a2 * t4287 t4430 t4275 * t4377 t4328 -0.2e1 * t4344 t4269 t4473 0.2e1 * t4280 * t4314 + 0.2e1 * t4230 t4142 t4475 t4470 0.2e1 * t4165 t4434 t4038 0.2e1 * (-t4279 * t4325 + t4316) * a4 + t4302 t4053 t4040 t4061 t4059 t4139 t3962 t3961 t3981 t3976 t3994 t3993 t4051 t3952 -t3962 * t4277 - t3995 * t4283 t3981 * t4270 + t3994 * t4403 + t4051 * t4264 t4242 * t3994 + (-t3981 + t4051) * t4483 -t3976 * t4282 - t3993 * t4276 t3976 * t4276 - t3993 * t4282 t4053 * t4265 + t4139 * t4271 + t4373 t3952 * t4282 + t3961 * t4276 -t3952 * t4276 + t3961 * t4282; 0 0 0 0 0 -t4261 -t4262 0 0 0 -t4225 -t4439 t4232 t4234 0 t4188 t4189 t4144 t4134 t4146 t4145 t4225 t4084 t4085 t4037 t4033 t4065 t4064 t4143 t3972 t3971 t3980 t3974 t3987 t3986 t4036 t3954 t3953 t3949 t3948 t3956 t3955 t3979 t3947 t3946; 0 0 0 0 0 0 0 0 0 0 0 0 -t4387 t4231 t4262 t4190 -t4409 t4159 t4147 -t4348 -t4336 0 t4097 t4098 t4102 t4089 t4096 t4095 t4160 t3990 t3989 t4008 t4001 t4027 t4026 t4101 t3964 t3963 t3960 t3959 t3970 t3969 t4007 t3951 t3950; 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 t4187 t4186 t4231 t4130 -t4385 t4109 t4103 -t4416 -t4395 0 t4028 t4029 t4055 t4042 t4048 t4047 t4110 t3997 t3996 t3975 t3973 t3992 t3991 t4054 t3966 t3965; 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 t4119 t4118 -t4186 t4010 -t4011 t4067 t4057 -t4420 -t4400 0 t4009 -t4422 t4015 t4012 t4014 t4013 t4066 t3968 t3967; 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 t4072 -t4071 t4118 t3983 -t3984 t4020 t4016 t4427 t4406 0 t3982 -t4429; 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 t4022 t4021 t4071 t3957 t3958; 0 0 0 0 0 -t4261 -t4262 0 0 0 -t4225 -t4439 t4232 t4234 0 t4188 t4189 t4144 t4134 t4146 t4145 t4225 t4084 t4085 t4037 t4033 t4065 t4064 t4143 t3972 t3971 t3980 t3974 t3987 t3986 t4036 t3954 t3953 t3949 t3948 t3956 t3955 t3979 t3947 t3946; 0 0 0 0 0 0 0 1 0 0 t4268 0.2e1 * t4386 0 0 0 0.2e1 * t4463 -0.2e1 * a3 * t4280 t4431 t4329 0.2e1 * t4335 t4279 * t4377 t4274 t4469 -0.2e1 * t4279 * t4313 - 0.2e1 * t4449 t4141 0.2e1 * t4116 t4471 0.2e1 * t4164 t4435 t4032 t4031 t4052 t4039 t4060 t4058 t4138 t3998 -t4032 * t4277 + t4283 * t4476 t4052 * t4270 + t4060 * t4403 + t4138 * t4264 t4242 * t4060 + (-t4052 + t4138) * t4483 -t4039 * t4282 - t4058 * t4276 t4039 * t4276 - t4058 * t4282 t4141 * t4265 + t4271 * t4435 + 0.2e1 * t4368 t3998 * t4282 + t4031 * t4276 -t3998 * t4276 + t4031 * t4282; 0 0 0 0 0 0 0 0 0 0 0 0 t4280 t4286 0 -t4451 -t4448 -t4241 t4227 -t4410 -t4388 0 t4217 t4218 t4169 t4150 t4179 t4176 t4241 t4063 t4062 t4070 t4050 t4080 t4078 t4163 t4018 t4017 t3988 t3985 t4000 t3999 t4068 t3978 t3977; 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 t4260 -t4255 t4286 t4202 t4203 t4197 t4182 t4236 t4240 0 t4093 t4094 t4127 t4105 t4114 t4112 t4198 t4046 t4045 t4023 t4019 t4035 t4034 t4125 t4005 t4004; 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 t4213 t4210 t4255 t4091 -t4092 t4137 t4129 -t4419 -t4399 0 t4086 -t4421 t4076 t4073 t4075 t4074 t4136 t4025 t4024; 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 t4154 -t4152 t4210 t4043 -t4044 t4082 t4081 t4426 t4405 0 t4041 -t4428; 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 t4088 t4087 t4152 t4002 t4003; 0 0 0 0 0 0 0 0 0 0 0 0 -t4387 t4231 t4262 t4190 -t4409 t4159 t4147 -t4348 -t4336 0 t4097 t4098 t4102 t4089 t4096 t4095 t4160 t3990 t3989 t4008 t4001 t4027 t4026 t4101 t3964 t3963 t3960 t3959 t3970 t3969 t4007 t3951 t3950; 0 0 0 0 0 0 0 0 0 0 0 0 t4280 t4286 0 -t4451 -t4448 -t4241 t4227 -t4410 -t4388 0 t4217 t4218 t4169 t4150 t4179 t4176 t4241 t4063 t4062 t4070 t4050 t4080 t4078 t4163 t4018 t4017 t3988 t3985 t4000 t3999 t4068 t3978 t3977; 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 t4267 t4378 0 0 0 0.2e1 * t4460 -0.2e1 * t4462 t4432 t4267 * t4379 -0.2e1 * t4337 t4278 * t4378 t4273 0.2e1 * t4157 t4474 t4140 0.2e1 * t4115 t4472 0.2e1 * t4162 t4436 t4083 -0.2e1 * t4157 * t4277 - 0.2e1 * t4204 * t4283 t4140 * t4270 + t4168 * t4483 + t4264 * t4436 t4242 * t4472 + (-t4140 + t4436) * t4483 -0.2e1 * t4115 * t4282 - 0.2e1 * t4162 * t4276 0.2e1 * t4115 * t4276 - 0.2e1 * t4162 * t4282 t4265 * t4432 + t4271 * t4273 - 0.2e1 * t4305 t4083 * t4282 + t4276 * t4474 -t4083 * t4276 + t4282 * t4474; 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 -t4279 -t4285 0 0 0 -t4239 -t4440 t4254 t4259 0 t4215 t4216 t4167 t4149 t4178 t4175 t4239 t4199 -t4418 t4069 t4049 t4079 t4077 t4161 t4108 t4107; 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 -t4393 t4253 t4285 t4219 -t4415 t4195 t4181 -t4355 -t4339 0 t4206 -t4353 t4126 t4104 t4113 t4111 t4196 t4124 t4122; 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 t4212 t4209 t4253 -t4356 -t4340 t4135 t4128 -t4425 -t4404 0 -t4315 t4193; 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 t4153 t4151 -t4209 -t4121 -t4123; 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 t4187 t4186 t4231 t4130 -t4385 t4109 t4103 -t4416 -t4395 0 t4028 t4029 t4055 t4042 t4048 t4047 t4110 t3997 t3996 t3975 t3973 t3992 t3991 t4054 t3966 t3965; 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 t4260 -t4255 t4286 t4202 t4203 t4197 t4182 t4236 t4240 0 t4093 t4094 t4127 t4105 t4114 t4112 t4198 t4046 t4045 t4023 t4019 t4035 t4034 t4125 t4005 t4004; 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 -t4279 -t4285 0 0 0 -t4239 -t4440 t4254 t4259 0 t4215 t4216 t4167 t4149 t4178 t4175 t4239 t4199 -t4418 t4069 t4049 t4079 t4077 t4161 t4108 t4107; 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 t4266 t4330 0 0 0 a5 * t4466 a5 * t4485 t4433 t4266 * t4381 0.2e1 * t4338 t4277 * t4379 t4272 0.2e1 * t4223 -0.2e1 * a5 * t4417 - 0.2e1 * d5 * t4283 t4264 * t4272 + t4270 * t4433 + t4284 * t4310 0.2e1 * t4242 * t4338 + 0.2e1 * (t4272 - t4433) * t4403 (t4256 * t4266 + t4276 * t4394) * t4468 (-t4251 * t4266 + t4282 * t4394) * t4468 t4265 * t4266 -0.2e1 * a5 * t4423 + 0.2e1 * t4223 * t4282 -0.2e1 * a5 * t4414 - 0.2e1 * t4223 * t4276; 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 t4278 t4284 0 -t4453 -t4450 -t4238 t4226 -t4417 -t4397 0 -t4375 t4247 t4166 t4148 t4177 t4174 t4238 -t4201 t4200; 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 t4257 -t4252 t4284 t4221 -t4222 t4194 t4180 t4235 t4237 0 t4214 -t4424; 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 t4211 -t4293 t4252 t4172 t4173; 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 t4119 t4118 -t4186 t4010 -t4011 t4067 t4057 -t4420 -t4400 0 t4009 -t4422 t4015 t4012 t4014 t4013 t4066 t3968 t3967; 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 t4213 t4210 t4255 t4091 -t4092 t4137 t4129 -t4419 -t4399 0 t4086 -t4421 t4076 t4073 t4075 t4074 t4136 t4025 t4024; 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 -t4393 t4253 t4285 t4219 -t4415 t4195 t4181 -t4355 -t4339 0 t4206 -t4353 t4126 t4104 t4113 t4111 t4196 t4124 t4122; 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 t4278 t4284 0 -t4453 -t4450 -t4238 t4226 -t4417 -t4397 0 -t4375 t4247 t4166 t4148 t4177 t4174 t4238 -t4201 t4200; 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 t4265 t4484 0 0 0 0 0 t4270 * t4265 t4265 * t4383 t4282 * t4381 t4276 * t4484 t4271 0 0; 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 -t4277 -t4283 0 0 0 -t4342 -t4441 t4251 t4256 0 0 0; 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 -t4402 t4250 t4283 0 0; 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 t4072 -t4071 t4118 t3983 -t3984 t4020 t4016 t4427 t4406 0 t3982 -t4429; 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 t4154 -t4152 t4210 t4043 -t4044 t4082 t4081 t4426 t4405 0 t4041 -t4428; 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 t4212 t4209 t4253 -t4356 -t4340 t4135 t4128 -t4425 -t4404 0 -t4315 t4193; 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 t4257 -t4252 t4284 t4221 -t4222 t4194 t4180 t4235 t4237 0 t4214 -t4424; 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 -t4277 -t4283 0 0 0 -t4342 -t4441 t4251 t4256 0 0 0; 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0 t4264 t4483 0 0 0 0 0; 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 t4276 t4282 0 0 0; 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 t4022 t4021 t4071 t3957 t3958; 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 t4088 t4087 t4152 t4002 t4003; 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 t4153 t4151 -t4209 -t4121 -t4123; 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 t4211 -t4293 t4252 t4172 t4173; 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 -t4402 t4250 t4283 0 0; 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 t4276 t4282 0 0 0; 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 0 0;]; \ No newline at end of file diff --git a/robot_model/atlas5_arm_inertia_plin_minpar_sym_lag_varpar.m b/robot_model/atlas5_arm_inertia_plin_minpar_sym_lag_varpar.m new file mode 100644 index 0000000..ed0a00b --- /dev/null +++ b/robot_model/atlas5_arm_inertia_plin_minpar_sym_lag_varpar.m @@ -0,0 +1,52 @@ +% Calculate joint inertia matrix for Atlas robot Arm (v5) +% Use matlab function from symbolic Maple calculations +% Berechnung mit Regressorform (Parameterlineare Form) +% Minimal-Parametersatz (neu gruppierte Parameter) +% +% Input: +% q +% Joint Angles [rad] +% MPV [45x1] +% minimum parameter vector (regrouped dynamic parameters) +% lr +% true for left, false for right +% +% Output: +% Mq [7x7] +% Joint Mass-Matrix + +% Source: +% [1] Robotik I Skript + +% Moritz Schappler, schappler@irt.uni-hannover.de, 2015-02 +% (c) Institut für Regelungstechnik, Universität Hannover + + +function MM = atlas5_arm_inertia_plin_minpar_sym_lag_varpar(q, MPV, lr) + +%% Init +%#codegen +% Coder Information +assert(isa(q,'double') && isreal(q) && all(size(q) == [1 7]), ... + 'atlas5_arm_inertia_plin_minpar_sym_lag_varpar: Joint angles q have to be [1x7] double'); +assert(isa(MPV,'double') && isreal(MPV) && all(size(MPV) == [45 1]), ... + 'atlas5_arm_inertia_plin_minpar_sym_lag_varpar: Minimum Parameter vector has to be [45x1] double'); +assert(isa(lr,'logical') && all(size(lr) == [1 1]), ... + 'atlas5_arm_inertia_plin_minpar_sym_lag_varpar: Left/Right flag has to be [1x1] logical'); + +%% Kinematik-Parameter +[a_mdh, d_mdh, ~, q_offset_mdh] = atlas5_arm_parameter_mdh(lr); + +%% Regressor-Matrix +MM_regressor = atlas5_arm_inertia_plin_minpar_regressor_sym_lag_varpar(q, a_mdh, d_mdh, q_offset_mdh, lr); + +%% Massenmatrix +MM = zeros(7,7); +% TODO: Symmetrie der Massenmatrix berücksichtigen +for i = 1:7 + for j = 1:7 + for k = 1:45 + MM(i,j) = MM(i,j) + MM_regressor(7*(i-1)+j,k)*MPV(k); + end + end +end \ No newline at end of file diff --git a/robot_model/atlas5_arm_jacobig.m b/robot_model/atlas5_arm_jacobig.m new file mode 100755 index 0000000..ee1093a --- /dev/null +++ b/robot_model/atlas5_arm_jacobig.m @@ -0,0 +1,28 @@ +% Calculate geometric jacobian for Atlas robot (v5) +% +% Input: +% q [1x7] +% Joint Angles [rad] +% lr [1x1] +% true for left, false for right +% +% +% Source: +% [1] Robotik I Skript + +% Moritz Schappler, schappler@irt.uni-hannover.de, 2015-01 +% (c) Institut für Regelungstechnik, Universität Hannover + +function JG = atlas5_arm_jacobig(q, lr) +%% Init + +%#codegen +% Coder Information +assert(isa(q,'double') && isreal(q) && all(size(q) == [1 7]), ... + 'atlas5_arm_jacobig: Joint angles q have to be [1x7] double'); +assert(isa(lr,'logical') && all(size(lr) == [1 1]), ... + 'atlas5_arm_jacobig: Left/Right flag has to be [1x1] logical'); + +%% Calculation + +JG = atlas5_arm_jacobig_num(q, lr); \ No newline at end of file diff --git a/robot_model/atlas5_arm_jacobig_num.m b/robot_model/atlas5_arm_jacobig_num.m new file mode 100755 index 0000000..23dbca9 --- /dev/null +++ b/robot_model/atlas5_arm_jacobig_num.m @@ -0,0 +1,82 @@ +% Calculate geometric jacobian for Atlas robot (v4) +% +% Input: +% q +% Joint Angles [rad] +% lr +% true for left, false for right +% +% Output: +% JG [6x7] double +% Geometrische Jacobi-Matrix + +% Moritz Schappler, schappler@irt.uni-hannover.de, 2015-03 +% (c) Institut für Regelungstechnik, Universität Hannover + +function JG = atlas5_arm_jacobig_num(q, lr) %#codegen +%% Init +% Coder Information +%#codegen +assert(isa(q,'double') && isreal(q) && all(size(q) == [1 7]), ... + 'q has to be [1x7] double'); +assert(isa(lr,'logical') && all(size(lr) == [1 1]), ... + 'lr has to be [1x1] logical'); + +JG = NaN(6, 7); + +%% Forward Kinematics +T_c_urdf = atlas5_arm_fkine(q, lr); + +% T_c_urdf(:,:,3) is the body frame of the first body (upper shoulder) +% q1 turns around the z-axis of this frame + +%% Geometric Calculations + +for i = 1:7 + % Get rotation axis of the joint. See fkine + if i == 1 + ax = T_c_urdf(1:3,3, i+1); % z-Axis + elseif i == 2 + if lr + ax = -T_c_urdf(1:3,1, i+1); % neg. x-Axis + else + ax = T_c_urdf(1:3,1, i+1); % x-Axis + end + elseif i == 3 + if lr + ax = -T_c_urdf(1:3,2, i+1); % neg. y-Axis + else + ax = T_c_urdf(1:3,2, i+1); % y-Axis + end + elseif i == 4 + if lr + ax = -T_c_urdf(1:3,1, i+1); % neg. x-Axis + else + ax = T_c_urdf(1:3,1, i+1); % x-Axis + end + elseif i == 5 + if lr + ax = -T_c_urdf(1:3,2, i+1); % neg. y-Axis + else + ax = T_c_urdf(1:3,2, i+1); % y-Axis + end + elseif i == 6 + ax = T_c_urdf(1:3,1, i+1); % x-Axis + else % i == 7 + if lr + ax = -T_c_urdf(1:3,2, i+1); % neg. y-Axis + else + ax = T_c_urdf(1:3,2, i+1); % y-Axis + end + end + + % vectors from joints to endeffector + r = T_c_urdf(1:3,4, 8) - T_c_urdf(1:3,4, i+1); + + % lever arm from joint to endeffector on joint axis + ar = cross(ax, r); + + % Compose geometric Jacobian + JG(:,i) = [ar; ax]; +end + diff --git a/robot_model/atlas5_arm_parameter_mdh.m b/robot_model/atlas5_arm_parameter_mdh.m new file mode 100644 index 0000000..4961fe3 --- /dev/null +++ b/robot_model/atlas5_arm_parameter_mdh.m @@ -0,0 +1,83 @@ +% Return MDH Parameter of the Atlas Robot (v4) (hard coded) +% +% Input: +% lr +% true for left, false for right +% +% Output: +% a_mdh, d_mdh, alpha_mdh, q_offset_mdh [6x1] +% Numeric Values of Kinematic Parameters, MDH-Notation +% rSges_num [6x3] +% Center of Gravity of all indepedent bodies (arm only) in urdf frames +% m_num [6x1] +% masses of all indepedent bodies (arm only) +% Iges_num [6x6] +% inertia of all indepedent bodies (arm only) +% rows: bodies +% columns: inertia tensor entries. Order: xx, yy, zz, xy, xz, yz +% +% Sources: +% [1] atlas_v5_simple_shapes_with_head.urdf +% [2] [KhalilKle1986] + +% Moritz Schappler, schappler@irt.uni-hannover.de, 2015-03 +% (c) Institut für Regelungstechnik, Universität Hannover + +function [a_mdh, d_mdh, alpha_mdh, q_offset_mdh, ... + rSges_num_mdh, m_num_mdh, Iges_num_mdh] = atlas5_arm_parameter_mdh(lr) + +assert(isa(lr,'logical') && all(size(lr) == [1 1]), ... + 'Left/Right flag has to be [1x1] logical'); + +%% URDF Parameter +[p_num_urdf, rSges_num_urdf, m_num_urdf, Iges_num_urdf] = atlas5_arm_parameter_urdf(lr); + +%% Calculate MDH kinematic Parameter +alpha_mdh = zeros(7,1); +a_mdh = zeros(7,1); +q_offset_mdh = zeros(7,1); +d_mdh = zeros(7,1); + +% set MDH parameters with values from urdf-file + +d_mdh(1) = p_num_urdf(7); + +alpha_mdh(2) = -pi/2; +if lr + a_mdh(2) = p_num_urdf(6); +else + a_mdh(2) = -p_num_urdf(6); +end +q_offset_mdh(2) = -pi/2; + +alpha_mdh(3) = pi/2; +a_mdh(3) = p_num_urdf(9); +if lr + d_mdh(3) = -p_num_urdf(8) - p_num_urdf(10); +else + d_mdh(3) = p_num_urdf(8) + p_num_urdf(10); +end + +alpha_mdh(4) = -pi/2; +a_mdh(4) = p_num_urdf(11); + +% bis hierhin gleich + +alpha_mdh(5) = pi/2; +a_mdh(5) = p_num_urdf(13); +if lr + d_mdh(5) = -p_num_urdf(12); +else + d_mdh(5) = p_num_urdf(12); +end + +alpha_mdh(6) = -pi/2; + +alpha_mdh(7) = pi/2; + +%% Calculate MDH dynamic parameters + +% Different frame position and orientation + +m_num_mdh = m_num_urdf; +[rSges_num_mdh, Iges_num_mdh] = atlas5_arm_convert_urdf_mdh(lr, rSges_num_urdf, Iges_num_urdf); \ No newline at end of file diff --git a/robot_model/atlas5_arm_parameter_urdf.m b/robot_model/atlas5_arm_parameter_urdf.m new file mode 100644 index 0000000..5639f4f --- /dev/null +++ b/robot_model/atlas5_arm_parameter_urdf.m @@ -0,0 +1,119 @@ +% Return Parameter of the Atlas Robot (v5) (hard coded from urdf file) +% +% Input: +% lr +% true for left, false for right +% +% Output: +% p_num [15x1] +% Numeric Values of Kinematic Parameters +% rSges_num [6x3] +% Center of Gravity of all indepedent bodies (arm only) in urdf frames +% m_num [6x1] +% masses of all indepedent bodies (arm only) +% Iges_num [6x6] +% inertia of all indepedent bodies (arm only) +% rows: bodies +% columns: inertia tensor entries. Order: xx, yy, zz, xy, xz, yz +% +% Sources: +% [1] data/atlas_v5_simple_shapes_with_head.urdf + +% Moritz Schappler, schappler@irt.uni-hannover.de, 2015-03 +% (c) Institut für Regelungstechnik, Leibniz Universität Hannover + +function [p_num, rSges_num, m_num, Iges_num] = atlas5_arm_parameter_urdf(lr) + +%% Init +% Coder Information +%#codegen + +assert(isa(lr,'logical') && all(size(lr) == [1 1])); + +p_num = NaN(1,13); + +Iges_num = NaN(7,6); +rSges_num = NaN(7,3); +%% Kinematic Parameters +% Source: [1] + +% 1 shz: utorso -> clav +if lr == true % left + p_num(1:3) = [0.1406, 0.2256, 0.4776]; + p_num(4:5) = [0, 1]; % z-axis +else + p_num(1:3) = [0.1406, -0.2256, 0.4776]; + p_num(4:5) = [0, 1]; +end +% 2 shx: clav -> scap +p_num(6:7) = [-0.11 -0.245]; +% 3 ely: scap -> uarm +p_num(8:9) = [-0.187, -0.016]; +% 4 elx: uarm -> larm +p_num(10:11) = [-0.119, 0.0092]; +% 5 wry: larm -> ufarm +p_num(12:13) = [-0.29955, -0.00921]; +% 6 wrx: ufarm -> lfarm +% no transformation +% 7 wry2: lfarm -> hand +% no transformation + +%% Output Parameters: Center of Mass +% center of mass coordinates in body reference frames. Source: [1] + +rSges_num(1,:) = [0 0 -.084]; % (1) clav +rSges_num(2,:) = [0, 0, 0]; % (2) scap +rSges_num(3,:) = [0, 0.065, 0]; % (3) uarm +rSges_num(4,:) = [0, 0, 0]; % (4) larm +% (5) ufarm +if lr == true % left + rSges_num(5,:) = [.00015 .08296 -.00037]; +else + rSges_num(5,:) = [.00015 .08296 .00037]; +end +% (6) lfarm +if lr == true % left + rSges_num(6,:) = [.00017 -.02515 -.00163]; +else + rSges_num(6,:) = [.00017 -.02515 .00163]; +end +% (7) hand +if lr == true % left + rSges_num(7,:) = [-.00016 -.08159 .00002]; +else + rSges_num(7,:) = [ .00016 -.08159 .00002]; +end + +%% Output Parameters: Mass +% Source: [1] +m_num = [4.466;... % (1) clav + 3.899;... % (2) scap + 4.386;... % (3) uarm + 3.248;... % (4) larm + 2.4798;... % (5) ufarm + 0.648;... % (6) lfarm + 0.5839]; % (7) hand +%% Output Parameters: Inertias +% Order: Ixx, Iyy, Izz, Ixy, Ixz, Iyz + +% (1) clav +% +Iges_num(1,:) = [0.011, 0.009, 0.004, 0, 0, 0.004]; +% (2) scap +% +Iges_num(2,:) = [0.00319, 0.00583, 0.00583, 0, 0, 0]; +% (3) uarm +% +Iges_num(3,:) = [0.00656, 0.00358, 0.00656, 0, 0, 0]; +% (4) larm +% +Iges_num(4,:) = [0.00265, 0.00446, 0.00446, 0, 0, 0]; +% (5) ufarm +% +Iges_num(5,:) = [0.012731, 0.002857, 0.011948, 0, 0, 0]; +% (6) lfarm +% +Iges_num(6,:) = [0.000764, 0.000429, 0.000825, 0, 0, 0]; +% (7) hand +% +Iges_num(7,:) = [0.000388, 0.000477, 0.000379, 0, 0, 0]; \ No newline at end of file diff --git a/robot_model/atlas5_simple_shapes_stf_plot_transformation.m b/robot_model/atlas5_simple_shapes_stf_plot_transformation.m new file mode 100644 index 0000000..697d51c --- /dev/null +++ b/robot_model/atlas5_simple_shapes_stf_plot_transformation.m @@ -0,0 +1,73 @@ +% Hard coded transformations between urdf kinematics from +% b1fd87405f181721888af26eb3646d55f8ddb8ab to the urdf kinematics from +% 2ef658d873147440ee853191c8382e125e952a09 in order to be able to plot the robot +% with the new kinematics from data/atlas_v5_simple_shapes_with_head.urdf. +% +% Input: none +% +% Output: +% T_c_urdf_l_neu_alt [4x4x9] +% homogenious transformation matrices for each body frame from T_c_urdf_l_new +% to T_c_urdf_l_old. +% +% Sources: +% [1] data/atlas_v5_simple_shapes_with_head.urdf + +% Jonathan Vorndamme, vorndamme@irt.uni-hannover.de, 2017-08 +% (c) Institut für Regelungstechnik, Leibniz Universität Hannover + +function T_c_urdf_l_new_old = atlas5_simple_shapes_stf_plot_transformation() + +T_c_urdf_l_new_old(:,:,1) = [ + -1 0 0 0 + 0 -1 0 0 + 0 0 1 0 + 0 0 0 1]; + +T_c_urdf_l_new_old(:,:,2) = [ + -1 0 0 0 + 0 -1 0 0 + 0 0 1 0 + 0 0 0 1]; + +T_c_urdf_l_new_old(:,:,3) = [ + -1 0 0 0 + 0 -1 0 0 + 0 0 1 0 + 0 0 0 1]; + +T_c_urdf_l_new_old(:,:,4) = [ + -1 0 0 0 + 0 -1 0 0 + 0 0 1 0 + 0 0 0 1]; + +T_c_urdf_l_new_old(:,:,5) = [ + -1 0 0 0 + 0 -1 0 0 + 0 0 1 0 + 0 0 0 1]; + +T_c_urdf_l_new_old(:,:,6) = [ + 1 0 0 0 + 0 -1 0 0 + 0 0 -1 0 + 0 0 0 1]; + +T_c_urdf_l_new_old(:,:,7) = [ + 1 0 0 0 + 0 -1 0 0 + 0 0 -1 0 + 0 0 0 1]; + +T_c_urdf_l_new_old(:,:,8) = [ + -1 0 0 0 + 0 -1 0 0 + 0 0 1 0 + 0 0 0 1]; + +T_c_urdf_l_new_old(:,:,9) = [ + 1 0 0 0 + 0 1 0 0 + 0 0 1 0 + 0 0 0 1]; \ No newline at end of file diff --git a/robot_model/atlas5_torso_parameter_urdf.m b/robot_model/atlas5_torso_parameter_urdf.m new file mode 100644 index 0000000..a008d6a --- /dev/null +++ b/robot_model/atlas5_torso_parameter_urdf.m @@ -0,0 +1,76 @@ +% Return Parameter of the Atlas Robot (v5) (hard coded) +% +% Input: +% +% Output: +% p_num [1x5] +% Numeric Values of Kinematic Parameters +% rSges_num [5x3] +% Center of Gravity of all independent bodies (torso only) in urdf frames +% m_num [5x1] +% masses of all independent bodies (torso only) +% Iges_num [5x6] +% inertia of all independent bodies (torso only) +% rows: bodies +% columns: inertia tensor entries. Order: xx, yy, zz, xy, xz, yz +% +% Sources: +% [1] atlas_v5_simple_shapes_with_head.urdf +% +% Only checked the first two joints + +% Moritz Schappler, schappler@irt.uni-hannover.de, 2014-11 +% (c) Institut für Regelungstechnik, Leibniz Universität Hannover + +function [p_num, rSges_num, m_num, Iges_num] = atlas5_torso_parameter_urdf() + +%% Init +% Coder Information +%#codegen + +p_num = NaN(1,5); +Iges_num = NaN(5,6); +%% Kinematic Parameters +% Source: [1] +% 1 back_bkz: pelvis -> ltorso +p_num(1) = -0.0125; +% 2 back_bky: ltorso -> mtorso +p_num(2) = 0.162; +% 3 back_bkx: mtorso -> utorso +p_num(3) = 0.05; +% 4 neck_ry: utorso -> head +p_num(4:5) = [0.2546, 0.6215]; + +%% Output Parameters: Mass +m_num = [9.509;... % (1) pelvis + 2.270;... % (2) ltorso + 0.799;... % (3) mtorso + 84.409;... % (4) utorso + 1]; % (5) head: homogene Kugel m=1kg, r=20cm + +%% Output Parameters: Center of Mass +% center of mass coordinates in body reference frames. Source: [1] +rSges_num = [... + [0.0111, 0, 0.0271];... % (1) pelvis + [-0.0112984, -3.15366e-06, 0.0746835];... % (2) ltorso + [-0.00816266 -0.0131245 0.0305974];... % (3) mtorso + [-0.0622, 0.0023, 0.3157];... % (4) utorso + [0,0,0]]; % (5) head +%% Output Parameters: Inertias +% Order: Ixx, Iyy, Izz, Ixy, Ixz, Iyz + +% (1) pelvis +% +Iges_num(1,:) = [0.1244, 0.0958, 0.1167, 0.0008, -0.0007, -0.0005]; +% (2) ltorso +% +Iges_num(2,:) = [0.0039092, 0.00341694, 0.00174492, -5.04491e-08, -0.000342157, 4.87119e-07]; +% (3) mtorso +% +Iges_num(3,:) = [0.000454181, 0.000483282, 0.000444215, -6.10764e-05, 3.94009e-05, 5.27463e-05]; +% (4) utorso +% +Iges_num(4,:) = [1.577, 1.602, 0.565, -0.032, 0.102, 0.047]; +% (5) head +% +Iges_num(5,:) = [0.016, 0.016, 0.016, 0, 0, 0]; % (5) head: homogene Kugel m=1kg, r=20cm \ No newline at end of file diff --git a/robot_model/atlas_arm_convert_mdh_par1_par2.m b/robot_model/atlas_arm_convert_mdh_par1_par2.m new file mode 100644 index 0000000..9d43d9b --- /dev/null +++ b/robot_model/atlas_arm_convert_mdh_par1_par2.m @@ -0,0 +1,55 @@ +% Convert dynamic parameters for atlas arm from parameter set 1 to set 2 +% +% set 1: +% Mass, Center of Mass, Inertia around CoM +% set 2: +% Mass, First Moment, Inertia round Frame Origin +% +% Input: +% rSges_num_urdf [Nx3 double] +% center of mass of all atlas arm bodies +% ISges_num [Nx6 double] +% inertia of all atlas arm bodies around Center of Mass +% order: xx, yy, zz, xy, xz, yz +% +% Output: +% mrSges_num [Nx3 double] +% first moment of all atlas arm bodies +% Ifges_num [Nx6 double] +% inertia of all atlas arm bodies in around frame origin +% order: xx, yy, zz, xy, xz, yz + +% Moritz Schappler, schappler@irt.uni-hannover.de, 2015-02 +% (c) Institut für Regelungstechnik, Universität Hannover + + +function [mrSges_num, Ifges_num] = ... + atlas_arm_convert_mdh_par1_par2(rSges_num, ISges_num, m_num) + +%% Init +% Coder Information +%#codegen + +assert(isa(rSges_num,'double') && all(size(rSges_num) <= [7 3])); +assert(isa(ISges_num,'double') && all(size(ISges_num) <= [7 6])); +assert(isa(m_num,'double') && all(size(m_num) <= [7 1])); + +N = size(rSges_num,1); +%% Erstes Moment +mrSges_num = NaN(N,3); +for i = 1:N + mrSges_num(i,:) = m_num(i) * rSges_num(i,:); +end + +%% Trägheitstensor um das Körperkoordinatensystem +Ifges_num = NaN(N,6); +for i = 1:N + % Trägheitstensor um den Schwerpunkt + I_iSi = inertiavector2matrix(ISges_num(i,:)); + + % Steinerscher-Verschiebungssatz: Trägheitstensor um Koordinatensystem + I_ii = inertia_steiner(I_iSi, rSges_num(i,:)', m_num(i)); + + % Ausgabe zusammenstellen + Ifges_num(i,:) = inertiamatrix2vector(I_ii); +end \ No newline at end of file diff --git a/robot_model/atlas_arm_fkine.m b/robot_model/atlas_arm_fkine.m new file mode 100644 index 0000000..c14ca8a --- /dev/null +++ b/robot_model/atlas_arm_fkine.m @@ -0,0 +1,46 @@ +% Calculate Forward Kinematics for Atlas Robot (all versions) +% +% Input: +% q [1x(N)] +% Joint Angles [rad] +% lr [1x1 logical] +% true for left, false for right +% version [1x1 uint8] +% Version of the robot (e.g. 3, 4, 5) +% +% Output: +% T_c_urdf [4x4x(N+2)] +% homogenious transformation matrices for each body frame +% 1: utorso -> utorso +% 2: utorso -> clav +% 3: utorso -> scap +% 4: utorso -> uarm +% 5: utorso -> larm +% ... + + +% Moritz Schappler, schappler@irt.uni-hannover.de, 2015-01 +% (c) Institut für Regelungstechnik, Leibniz Universität Hannover + + +function T_c_urdf = atlas_arm_fkine(q, lr, version) +%% Init +%#codegen +% Coder Information +assert(isa(q,'double') && isreal(q) && all(size(q) <= [1 7]), ... + 'Joint angles q have to be [1xN] double'); +assert(isa(lr,'logical') && all(size(lr) == [1 1]), ... + 'Left/Right flag has to be [1x1] logical'); +assert(isa(version,'uint8') && all(size(version) == [1 1]), ... + 'version number has to be [1x1] uint8'); + +%% Calculation +if version == 3 + T_c_urdf = atlas3_arm_fkine_num(q, lr); +elseif version == 4 + T_c_urdf = atlas4_arm_fkine_num(q, lr); +elseif version == 5 + T_c_urdf = atlas5_arm_fkine_num(q, lr); +else + error('Version %d not implemented yet', version); +end diff --git a/robot_model/atlas_arm_parameter_mdh.m b/robot_model/atlas_arm_parameter_mdh.m new file mode 100644 index 0000000..9c274ef --- /dev/null +++ b/robot_model/atlas_arm_parameter_mdh.m @@ -0,0 +1,46 @@ +% Return MDH Parameter of the Atlas Robot (different versions) +% +% Input: +% lr +% true for left, false for right +% version +% 3, 4 or 5 +% +% Output: N joints +% a_mdh, d_mdh, alpha_mdh, q_offset_mdh +% Numeric Values of Kinematic Parameters, MDH-Notation +% rSges_num [Nx3] +% Center of Gravity of all indepedent bodies (arm only) in urdf frames +% m_num [Nx1] +% masses of all indepedent bodies (arm only) +% Iges_num [Nx6] +% inertia of all indepedent bodies (arm only) +% rows: bodies +% columns: inertia tensor entries. Order: xx, yy, zz, xy, xz, yz +% +% Sources: +% [1] [KhalilKle1986] + +% Moritz Schappler, schappler@irt.uni-hannover.de, 2014-11 +% (c) Institut für Regelungstechnik, Leibniz Universität Hannover + +function [a_mdh, d_mdh, alpha_mdh, q_offset_mdh, ... + rSges_num_mdh, m_num_mdh, Iges_num_mdh] = atlas_arm_parameter_mdh(lr, version) + +assert(isa(lr,'logical') && all(size(lr) == [1 1]), ... + 'Left/Right flag has to be [1x1] logical'); +assert(isa(version,'uint8') && all(size(version) == [1 1]), ... + 'version to be [1x1] uint8'); +%% URDF Parameter +if version == 3 + [a_mdh, d_mdh, alpha_mdh, q_offset_mdh, ... + rSges_num_mdh, m_num_mdh, Iges_num_mdh] = atlas3_arm_parameter_mdh(lr); +elseif version == 4 + [a_mdh, d_mdh, alpha_mdh, q_offset_mdh, ... + rSges_num_mdh, m_num_mdh, Iges_num_mdh] = atlas4_arm_parameter_mdh(lr); +elseif version == 5 + [a_mdh, d_mdh, alpha_mdh, q_offset_mdh, ... + rSges_num_mdh, m_num_mdh, Iges_num_mdh] = atlas5_arm_parameter_mdh(lr); +else + error('Version %d not implemented', version); +end diff --git a/robot_model/atlas_arm_parameter_urdf.m b/robot_model/atlas_arm_parameter_urdf.m new file mode 100644 index 0000000..af62ebb --- /dev/null +++ b/robot_model/atlas_arm_parameter_urdf.m @@ -0,0 +1,40 @@ +% Return Parameter of the Atlas Robot (all versions) (hard coded) +% +% Input: +% lr +% true for left, false for right +% +% Output: +% p_num [15x1] +% Numeric Values of Kinematic Parameters +% rSges_num [6x3] +% Center of Gravity of all indepedent bodies (arm only) in urdf frames +% m_num [6x1] +% masses of all indepedent bodies (arm only) +% Iges_num [6x6] +% inertia of all indepedent bodies (arm only) +% rows: bodies +% columns: inertia tensor entries. Order: xx, yy, zz, xy, xz, yz + +% Moritz Schappler, schappler@irt.uni-hannover.de, 2015-02 +% (c) Institut für Regelungstechnik, Leibniz Universität Hannover + +function [p_num, rSges_num, m_num, Iges_num] = atlas_arm_parameter_urdf(lr, version) + +%% Init +% Coder Information +%#codegen + +assert(isa(lr,'logical') && all(size(lr) == [1 1])); +assert(isa(version,'uint8') && all(size(version) == [1 1]), ... + 'version number has to be [1x1] uint8'); + +if version == 3 + [p_num, rSges_num, m_num, Iges_num] = atlas3_arm_parameter_urdf(lr); +elseif version == 4 + [p_num, rSges_num, m_num, Iges_num] = atlas4_arm_parameter_urdf(lr); +elseif version == 5 + [p_num, rSges_num, m_num, Iges_num] = atlas5_arm_parameter_urdf(lr); +else + error('Version %d not implemented yet', version); +end \ No newline at end of file diff --git a/robot_model/atlas_calc_impctrl_output.m b/robot_model/atlas_calc_impctrl_output.m new file mode 100644 index 0000000..3719c42 --- /dev/null +++ b/robot_model/atlas_calc_impctrl_output.m @@ -0,0 +1,156 @@ +% Prüfe Ausgaben des Gelenkimpedanzreglers mit Eingangsdaten aus Roboterversuchen +% Notwendig zum laufen: Assert-Befehl in sqrt-damping-block in Impedanzregler muss entfernt werden. +% TODO: Änderung der Impedanzregler-Parameter berücksichtigen +% TODO: SL mit tuneable parameters, um schneller neu zu berechnen. + +% Moritz Schappler, schappler@irt.uni-hannover.de, 2015-04 +% (c) Institut für Regelungstechnik, Universität Hannover + +% function [out_tau_Soll, out_tau_obs, out_tau_ext_mes] = atlas_calc_impctrl_output(Data, atlas_version, lr) + +out_t = []; + +% gestelltes Soll-Drehmoment +out_tau_Soll = []; +% Beobachter-Störmoment aus Simulink-Modell +out_tau_obs = []; +% Soll-Drehmoment ohne Beobachter-Störmoment +out_tau_Soll_wo_obs = []; +out_tau_ext_mes = []; + +chains = {'left_arm', 'right_arm'}; +AS = atlas_const(atlas_version, lr); +if lr == true + ich = 1; +else + ich = 2; +end +atlas_arm_lr = lr; +Strct = Data.ToRobot.(sprintf('ImpCtrlGains_%s', chains{ich})); + + +% Loop over all different parameter changes of the controller. Execute the +% simulink-model again each time. +for i_change = 1:length(Strct.t)-1 + + %% Set Gains of Impedance Controller + K_d = diag([Strct.K_d_shz(i_change); Strct.K_d_shx(i_change); Strct.K_d_ely(i_change); Strct.K_d_elx(i_change); Strct.K_d_wry(i_change); Strct.K_d_wrx(i_change); Strct.K_d_wry2(i_change)]); + D = diag([Strct.D_shz(i_change); Strct.D_shx(i_change); Strct.D_ely(i_change); Strct.D_elx(i_change); Strct.D_wry(i_change); Strct.D_wrx(i_change); Strct.D_wry2(i_change)]); + + K_tau_K = Strct.K_tau_K(i_change); + K_tau_D = Strct.K_tau_D(i_change); + + K_tau_g = Strct.K_tau_g(i_change); + K_tau_c = Strct.K_tau_c(i_change); + K_tau_a = Strct.K_tau_a(i_change); + K_tau_f = Strct.K_tau_f(i_change); + K_tau_e = Strct.K_tau_e(i_change); + K_tau_o = Strct.K_tau_o(i_change); + K_ext_c = Strct.K_ext_c(i_change); + K_obs_c = Strct.K_obs_c(i_change); + K_fri_o = Strct.K_fri_o(i_change); + K_ext_o = Strct.K_ext_o(i_change); + + K_qD_d = Strct.K_qD_d(i_change); + K_qDD_d = Strct.K_qDD_d(i_change); + T1 = Strct.T1(i_change); + K_O = Strct.K_O(i_change) * eye(AS.NJA); + T = 1e-3; + + qD_th = [Strct.qD_th_shz(i_change); Strct.qD_th_shx(i_change); Strct.qD_th_ely(i_change); Strct.qD_th_elx(i_change); Strct.qD_th_wry(i_change); Strct.qD_th_wrx(i_change); Strct.qD_th_wry2(i_change)]; + tau_th = [Strct.tau_th_shz(i_change); Strct.tau_th_shx(i_change); Strct.tau_th_ely(i_change); Strct.tau_th_elx(i_change); Strct.tau_th_wry(i_change); Strct.tau_th_wrx(i_change); Strct.tau_th_wry2(i_change)]; + + tau_c = [Strct.tau_c_shz(i_change); Strct.tau_c_shx(i_change); Strct.tau_c_ely(i_change); Strct.tau_c_elx(i_change); Strct.tau_c_wry(i_change); Strct.tau_c_wrx(i_change); Strct.tau_c_wry2(i_change)]; + B = [Strct.B_shz(i_change); Strct.B_shx(i_change); Strct.B_ely(i_change); Strct.B_elx(i_change); Strct.B_wry(i_change); Strct.B_wrx(i_change); Strct.B_wry2(i_change)]; + + if lr == true + MPV_arm_damp = MPV_lArm_damp; + MPV_arm_model = MPV_lArm_model; + else + MPV_arm_damp = MPV_rArm_damp; + MPV_arm_model = MPV_rArm_model; + end + + + %% Set Inputs + simin_q_mess = struct('time', Data.FromRobot.t, ... + 'signals', struct('values', Data.FromRobot.q(:,AS.JI_Arm), 'dimensions', AS.NJA), ... + 'name', 'q_mess'); + simin_qD_mess = struct('time', Data.FromRobot.t, ... + 'signals', struct('values', Data.FromRobot.qD(:,AS.JI_Arm), 'dimensions', AS.NJA), ... + 'name', 'qD_mess'); + simin_q_soll = struct('time', Data.ToRobot.t, ... + 'signals', struct('values', Data.ToRobot.q(:,AS.JI_Arm), 'dimensions', AS.NJA), ... + 'name', 'q_soll'); + simin_qD_soll = struct('time', Data.ToRobot.t, ... + 'signals', struct('values', Data.ToRobot.qD(:,AS.JI_Arm), 'dimensions', AS.NJA), ... + 'name', 'qD_soll'); + simin_qDD_soll = struct('time', Data.ToRobot.t, ... + 'signals', struct('values', Data.ToRobot.qDD(:,AS.JI_Arm), 'dimensions', AS.NJA), ... + 'name', 'qDD_soll'); + % Calculate Gravity in utorso + G_utorso = NaN(length(Data.FromRobot.t), 3); + for i = 1:length(Data.FromRobot.t) + R_pelvis = quat2r_mex(Data.FromRobot.pelvis_x_r(i,:)); + T_pelvis_utorso = atlas_T_pelvis_utorso_mex(Data.FromRobot.q(i,:), atlas_version); + R_utorso = R_pelvis * T_pelvis_utorso(1:3,1:3); + G_utorso(i,:) = R_utorso'*[0;0;-9.81]; + end + simin_g_mess= struct('time', Data.FromRobot.t, ... + 'signals', struct('values', G_utorso, 'dimensions', 3), ... + 'name', 'g_mess'); + simin_tauJ_mess = struct('time', Data.FromRobot.t, ... + 'signals', struct('values', Data.FromRobot.tau(:,AS.JI_Arm), 'dimensions', AS.NJA), ... + 'name', 'tauJ_mess'); + % Die ROS-Implementierung nutzte F_lH_raw (von Mai bis Juli). Damit war + % die linke Hand im falschen KS. + % Eigentlich hätte F_lH_calib genutzt werden sollen (Kalibrierung auf die + % korrekt gedrehten Daten angewendet). + if lr == true + F_ext_hand = Data.FromRobot.F_lH_raw_calib; + else + F_ext_hand = Data.FromRobot.F_rH_raw_calib; + end + F_ext_utorso = NaN(size(F_ext_hand)); + % rotate external force into utorso base frame + for i = 1:size(F_ext_hand,1) + T_0_EE = atlas_arm_fkine_mex(Data.FromRobot.q(i,AS.JI_Arm), lr, atlas_version); + F_ext_utorso(i,1:3) = t2r(T_0_EE(:,:,end))*(F_ext_hand(i,1:3))'; + F_ext_utorso(i,4:6) = t2r(T_0_EE(:,:,end))*(F_ext_hand(i,4:6))'; + end + + simin_F_ext_mess = struct('time', Data.FromRobot.t, ... + 'signals', struct('values', F_ext_utorso, 'dimensions', 6), ... + 'name', 'F_ext_mess'); + + %% Calculate Simulink Model + sl_Modellname = 'atlas5_arm_impctrl_iotest'; + starttime = Strct.t(i_change); + if i_change == 1 + stoptime = Strct.t(i_change+1); + else + stoptime = Data.FromRobot.t(end); + end + if stoptime <= starttime + 1e-3 + continue % protect against wrong time settings in input data + end + tic; + fprintf('Berechne Reglerausgang mit Simulink-Modell für Zeit [%1.4f, %1.4f]\n', ... + starttime, stoptime); + simOut = sim(sl_Modellname, 'StopTime', num2str(stoptime), 'StartTime', num2str(starttime)); % num2str(Data.FromRobot.t(end)) + fprintf('\tRechenzeit: %1.1fs\n', toc); + sl_logsout = simOut.get('logsout'); + sl_y = simOut.get('yout'); + sl_t = simOut.get('tout'); + + %% Get Signals from Logsout + sl = get_simulink_outputs(simOut, sl_Modellname); + + out_tau_ext_mes = [out_tau_ext_mes; sl.tau_ext_mes]; %#ok + out_tau_obs = [out_tau_obs; sl.tau_obs]; %#ok + out_tau_Soll = [out_tau_Soll; sl.tau_Soll]; %#ok + out_tau_Soll_wo_obs = [out_tau_Soll_wo_obs; ... + sl.tau_Soll - K_ext_o * sl.tau_obs]; %#ok + out_t = [out_t; sl.t]; %#ok + +end \ No newline at end of file diff --git a/robot_model/atlas_const.m b/robot_model/atlas_const.m new file mode 100644 index 0000000..b22cbfd --- /dev/null +++ b/robot_model/atlas_const.m @@ -0,0 +1,354 @@ +% Constants for the Atlas Robot +% +% Input: +% version [1x1 uint8] +% Atlas Model Version number +% lr +% true for left, false for right +% +% Output: +% AtlasStruct +% Structure with several helpful constants +% .JI_Torso +% Indices to access torso joints +% .JI_lLeg +% Indices to access left leg joints +% .JI_rLeg +% Indices to access right leg joints +% .JI_lArm +% Indices to access left arm joints +% .JI_rArm +% Indices to access right arm joints +% .JN +% Joint Names (Cell Array) +% .LI_Torso +% Indices to access torso links +% .LI_lLeg +% Indices to access left leg links +% .LI_rLeg +% Indices to access right leg links +% .LI_lArm +% Indices to access left arm links +% .LI_rArm +% Indices to access right arm links +% .LN +% Link Names (Cell Array +% .qmin +% lower joint position limit +% .qmax +% upper joint position limit +% .NJ +% Number of all Joints +% .NJA +% Number of Joints of the Arm +% .taumax +% joint effor limit +% .hydr_r +% moment arm of the hydraulic force +% .hydr_Apos +% .hydr_Aneg +% .k_motor_elec +% Electric motor constant [Nm/A] +% .gear_ratio_elec +% gear ratio of electric joints +% +% Sources: +% [1] atlas_v3.urdf +% [2] atlas_v4.urdf +% [3] atlas_v5.urdf +% [4] Atlas v4 ActuatorData.xls +% (Material/BDI_atlas4_20150114_SupplementalRobotData) + +% Moritz Schappler, schappler@irt.uni-hannover.de, 2014-12 +% (c) Institut für Regelungstechnik, Universität Hannover + +function AtlasStruct = atlas_const(version, lr) +% assert(isa(lr,'logical') && all(size(lr) == [1 1])); + +AtlasStruct = struct('version', version); + +%% Joint and Link Indexes and Names + +if version == 3 || version == 4 % Both versions nearly identical + % Joint Indices + AtlasStruct.JI_Torso = 1:4; + AtlasStruct.JI_lLeg = 5:10; + AtlasStruct.JI_rLeg = 11:16; + AtlasStruct.JI_lArm = 17:22; + AtlasStruct.JI_rArm = 23:28; + + % Link Indices + AtlasStruct.LI_Torso = 1:5; % pelvis, ltorso, mtorso, utorso, head + AtlasStruct.LI_lLeg = 6:11; % uglut, lglut, uleg, lleg, talus, foot + AtlasStruct.LI_rLeg = 12:17; + AtlasStruct.LI_lArm = 18:23; % clav, scap, uarm, larm, farm, hand + AtlasStruct.LI_rArm = 24:29; + AtlasStruct.NL = 29; + + % joint names + JointNameCell = {'back_bkz'; 'back_bky'; 'back_bkx'; 'neck_ry'; ... + 'l_leg_hpz'; 'l_leg_hpx'; 'l_leg_hpy'; 'l_leg_kny'; 'l_leg_aky'; 'l_leg_akx'; ... + 'r_leg_hpz'; 'r_leg_hpx'; 'r_leg_hpy'; 'r_leg_kny'; 'r_leg_aky'; 'r_leg_akx'; ... + 'l_arm_shy'; 'l_arm_shx'; 'l_arm_ely'; 'l_arm_elx'; 'l_arm_wry'; 'l_arm_wrx'; ... + 'r_arm_shy'; 'r_arm_shx'; 'r_arm_ely'; 'r_arm_elx'; 'r_arm_wry'; 'r_arm_wrx'}; + AtlasStruct.JN = JointNameCell; + if version == 4 + AtlasStruct.JN{AtlasStruct.JI_lArm(1)} = 'l_arm_shz'; + AtlasStruct.JN{AtlasStruct.JI_rArm(1)} = 'r_arm_shz'; + end + + % Link Names + LinkNameCell = {'pelvis'; 'ltorso'; 'mtorso'; 'utorso'; 'head'; ... + 'l_uglut'; 'l_lglut'; 'l_uleg'; 'l_lleg'; 'l_talus'; 'l_foot'; ... + 'r_uglut'; 'r_lglut'; 'r_uleg'; 'r_lleg'; 'r_talus'; 'r_foot'; ... + 'l_clav'; 'l_scap'; 'l_uarm'; 'l_larm'; 'l_farm'; 'l_hand'; ... + 'r_clav'; 'r_scap'; 'r_uarm'; 'r_larm'; 'r_farm'; 'r_hand'}; + AtlasStruct.LN = LinkNameCell; + + % Number of Joints + AtlasStruct.NJ = 28; + AtlasStruct.NJA = 6; +end + +if version == 5 + % Joint Indices + AtlasStruct.JI_Torso = 1:4; + AtlasStruct.JI_lLeg = 5:10; + AtlasStruct.JI_rLeg = 11:16; + AtlasStruct.JI_lArm = 17:23; + AtlasStruct.JI_rArm = 24:30; + + % Link Indices + AtlasStruct.LI_Torso = 1:5; % pelvis, ltorso, mtorso, utorso, head + AtlasStruct.LI_lLeg = 6:11; % uglut, lglut, uleg, lleg, talus, foot + AtlasStruct.LI_rLeg = 12:17; + AtlasStruct.LI_lArm = 18:24; % clav, scap, uarm, larm, ufarm, lfarm, hand + AtlasStruct.LI_rArm = 25:31; + AtlasStruct.NL = 31; + + % joint names + JointNameCell = {'back_bkz'; 'back_bky'; 'back_bkx'; 'neck_ry'; ... + 'l_leg_hpz'; 'l_leg_hpx'; 'l_leg_hpy'; 'l_leg_kny'; 'l_leg_aky'; 'l_leg_akx'; ... + 'r_leg_hpz'; 'r_leg_hpx'; 'r_leg_hpy'; 'r_leg_kny'; 'r_leg_aky'; 'r_leg_akx'; ... + 'l_arm_shz'; 'l_arm_shx'; 'l_arm_ely'; 'l_arm_elx'; 'l_arm_wry'; 'l_arm_wrx'; 'l_arm_wry2'; ... + 'r_arm_shz'; 'r_arm_shx'; 'r_arm_ely'; 'r_arm_elx'; 'r_arm_wry'; 'r_arm_wrx'; 'r_arm_wry2'}; + AtlasStruct.JN = JointNameCell; + + % Link Names + LinkNameCell = {'pelvis'; 'ltorso'; 'mtorso'; 'utorso'; 'head'; ... + 'l_uglut'; 'l_lglut'; 'l_uleg'; 'l_lleg'; 'l_talus'; 'l_foot'; ... + 'r_uglut'; 'r_lglut'; 'r_uleg'; 'r_lleg'; 'r_talus'; 'r_foot'; ... + 'l_clav'; 'l_scap'; 'l_uarm'; 'l_larm'; 'l_ufarm'; 'l_lfarm'; 'l_hand'; ... + 'r_clav'; 'r_scap'; 'r_uarm'; 'r_larm'; 'r_ufarm'; 'r_lfarm'; 'r_hand'}; + + AtlasStruct.LN = LinkNameCell; + + AtlasStruct.tau_max = NaN(28,1); % not set yet + AtlasStruct.q_min = NaN(28,1); % not set yet + AtlasStruct.q_max = NaN(28,1); % not set yet + + % Number of Joints + AtlasStruct.NJ = 30; + AtlasStruct.NJA = 7; + +end + +% Transmission Ratio [m] and Areas [m²] of the hydraulic joints [Source: 4] +if version == 4 || version == 5 + % Insert Data for Atlas v4 + AtlasStruct.hydr_r = [zeros(16,1);... % torso, legs + 0.006998;ones(5,1)*0.005123;... % left arm + 0.006998;ones(5,1)*0.005123]; % right arm + AtlasStruct.hydr_Apos = [zeros(16,1);... % torso, legs + 514.6*1e-6; 1007.4*1e-6; 641.3*1e-6; 1134.1*1e-6; 641.3*1e-6; 641.3*1e-6;... % left arm + 641.3*1e-6; 1134.1*1e-6; 514.6*1e-6; 1007.4*1e-6; 514.6*1e-6; 514.6*1e-6]; % right arm + AtlasStruct.hydr_Aneg = [zeros(16,1);... % torso, legs + 641.3*1e-6; 1134.1*1e-6; 514.6*1e-6; 1007.4*1e-6; 514.6*1e-6; 514.6*1e-6;... % left arm + 514.6*1e-6; 1007.4*1e-6; 641.3*1e-6; 1134.1*1e-6; 641.3*1e-6; 641.3*1e-6]; % right arm + + % change indexes and fill with NaN for electric forearms of arm upgrade + if version == 5 + AtlasStruct.hydr_r = [AtlasStruct.hydr_r(1:16); ... % torso, legs + AtlasStruct.hydr_r(17:20); NaN(3,1); % left arm v4 with electric forearm + AtlasStruct.hydr_r(23:26); NaN(3,1)]; % right arm v4 with electric forearm + AtlasStruct.hydr_Apos = [AtlasStruct.hydr_Apos(1:16); ... % torso, legs + AtlasStruct.hydr_Apos(17:20); NaN(3,1); % left arm v4 with electric forearm + AtlasStruct.hydr_Apos(23:26); NaN(3,1)]; % right arm v4 with electric forearm + AtlasStruct.hydr_Aneg = [AtlasStruct.hydr_Aneg(1:16); ... % torso, legs + AtlasStruct.hydr_Aneg(17:20); NaN(3,1); % left arm v4 with electric forearm + AtlasStruct.hydr_Aneg(23:26); NaN(3,1)]; % right arm v4 with electric forearm + end +end + +AtlasStruct.NJL = 6; % Number of Links in Leg +%% Limits +if version == 3 + % effort limit in urdf tbd + + % lower [position] limit in urdf + q_min = [ ... + NaN(4,1); ...% torso tbd + NaN(6,1); NaN(6,1); ... % legs tbd + -1.5708; -1.5708; 0; 0; 0; -1.1781; ... % l_arm_shz, l_arm_shx, l_arm_ely, l_arm_elx, l_arm_wry, l_arm_wrx + -1.5708; -1.5708; 0; -2.35619; 0; -1.1781];% r_arm_shz, r_arm_shx, r_arm_ely, r_arm_elx, r_arm_wry, r_arm_wrx + + + % upper [position] limit in urdf + q_max = [ ... + NaN(4,1); ...% torso tbd + NaN(6,1); NaN(6,1); ... % legs tbd + 0.785398; 1.5708; 3.14159; 2.35619; 3.14159; 1.1781; ... % l_arm_shz, l_arm_shx, l_arm_ely, l_arm_elx, l_arm_wry, l_arm_wrx + 0.785398; 1.5708; 3.14159; 0; 3.14159; 1.1781];% r_arm_shz, r_arm_shx, r_arm_ely, r_arm_elx, r_arm_wry, r_arm_wrx + + % leave unset + qD_max = NaN(28,1); + + % leave unset + tau_max = NaN(28,1); + + AtlasStruct.q_min = q_min; + AtlasStruct.q_max = q_max; + AtlasStruct.tau_max = tau_max; + AtlasStruct.qD_max = qD_max; +end + +if version == 4 + AtlasStruct.JN{AtlasStruct.JI_lArm(1)} = 'l_arm_shz'; + AtlasStruct.JN{AtlasStruct.JI_rArm(1)} = 'r_arm_shz'; + + % effort limit in urdf + tau_max = [ ... + 62; 245; 163; 5; ... % 'back_bkz'; 'back_bky'; 'back_bkx'; 'neck_ry' + NaN(6,1); NaN(6,1); ... % legs tbd + 198; 159; 106; 159; 106; 56; ...% l_arm_shz, l_arm_shx, l_arm_ely, l_arm_elx, l_arm_wry + 198; 159; 106; 159; 106; 56]; + + % velocity limit in urdf set to 12 rad/s for the arms. + % set the limits lower to assure safety + qD_max = [ ... + NaN(4,1); ... % 'back_bkz'; 'back_bky'; 'back_bkx'; 'neck_ry' + NaN(6,1); NaN(6,1); ... % legs tbd + 4; 4; 3; 3; 2; 2; ...% l_arm_shz, l_arm_shx, l_arm_ely, l_arm_elx, l_arm_wry + 4; 4; 3; 3; 2; 2]; + + % lower [position] limit in urdf + q_min = [ ... + NaN(4,1); ...% torso tbd + NaN(6,1); NaN(6,1); ... % legs tbd + -1.5708; -1.5708; 0; 0; 0; -1.1781; ... % l_arm_shz, l_arm_shx, l_arm_ely, l_arm_elx, l_arm_wry, l_arm_wrx + -0.785398; -1.5708; 0; -2.35619; 0; -1.1781];% r_arm_shz, r_arm_shx, r_arm_ely, r_arm_elx, r_arm_wry, r_arm_wrx + + + % upper [position] limit in urdf + q_max = [ ... + NaN(4,1); ...% torso tbd + NaN(6,1); NaN(6,1); ... % legs tbd + 0.785398; 1.5708; 3.14159; 2.35619; 3.14159; 1.1781; ... % l_arm_shz, l_arm_shx, l_arm_ely, l_arm_elx, l_arm_wry, l_arm_wrx + 1.5708; 1.5708; 3.14159; 0; 3.14159; 1.1781];% r_arm_shz, r_arm_shx, r_arm_ely, r_arm_elx, r_arm_wry, r_arm_wrx + + AtlasStruct.tau_max = tau_max; + AtlasStruct.qD_max = qD_max; + AtlasStruct.tau_min = -tau_max; + AtlasStruct.qD_min = -qD_max; + AtlasStruct.q_min = q_min; + AtlasStruct.q_max = q_max; +end + +% Sign Vector: Show which signs of joint positions have to be changed for +% symmetric pose: +if version == 3 || version == 4 + AtlasStruct.q_Arm_mirror = [-1, -1, 1, -1, 1, -1]; +elseif version == 5 + AtlasStruct.q_Arm_mirror = [-1, -1, 1, -1, 1, -1, 1]; +end +AtlasStruct.q_Leg_mirror = [-1, -1, 1, 1, 1, -1]; + +if version == 5 + + % lower [position] limit in urdf + q_min = [ ... + -0.663225; -0.219388; -0.523599; -0.602139; ...% 'back_bkz'; 'back_bky'; 'back_bkx'; 'neck_ry' + -0.174358; -0.523599; -1.61234; 0; -1; -0.8; ... % l_leg_hpz, l_leg_hpx, l_leg_hpy, l_leg_kny, l_leg_aky, l_leg_akx + -0.786794; -0.523599; -1.61234; 0; -1; -0.8; ... % r_leg_hpz, r_leg_hpx, r_leg_hpy, r_leg_kny, r_leg_aky, r_leg_akx + -1.5708; -1.5708; 0; 0; -3.011; -1.7628; -2.9671; ... % l_arm_shz, l_arm_shx, l_arm_ely, l_arm_elx, l_arm_wry, l_arm_wrx, l_arm_wry2 + -0.785398; -1.5708; 0; -2.35619; -3.011; -1.7628; -2.9671];% r_arm_shz, r_arm_shx, r_arm_ely, r_arm_elx, r_arm_wry, r_arm_wrx, r_arm_wry2 + + + % upper [position] limit in urdf + q_max = [ ... + 0.663225; 0.538783; 0.523599; 1.14319; ...% 'back_bkz'; 'back_bky'; 'back_bkx'; 'neck_ry' + 0.786794; 0.523599; 0.65764; 2.35637; 0.7; 0.8; ... % l_leg_hpz, l_leg_hpx, l_leg_hpy, l_leg_kny, l_leg_aky, l_leg_akx + 0.174358; 0.523599; 0.65764; 2.35637; 0.7; 0.8; ... % r_leg_hpz, r_leg_hpx, r_leg_hpy, r_leg_kny, r_leg_aky, r_leg_akx + 0.785398; 1.5708; 3.14159; 2.35619; 3.011; 1.7628; 2.9671; ... % l_arm_shz, l_arm_shx, l_arm_ely, l_arm_elx, l_arm_wry, l_arm_wrx, l_arm_wry2 + 1.5708; 1.5708; 3.14159; 0; 3.011; 1.7628; 2.9671];% r_arm_shz, r_arm_shx, r_arm_ely, r_arm_elx, r_arm_wry, r_arm_wrx, r_arm_wry2 + + % velocity limit in urdf set to 12 rad/s for the arms. + % set the limits lower to assure safety + % set limits of electrical motors very low so they do not overheat + qD_max = [ ... + 12; 9; 12; 6.28; ... % 'back_bkz'; 'back_bky'; 'back_bkx'; 'neck_ry' + 12*ones(6,1); ... % l_leg_hpz, l_leg_hpx, l_leg_hpy, l_leg_kny, l_leg_aky, l_leg_akx + 12*ones(6,1); ... % r_leg_hpz, r_leg_hpx, r_leg_hpy, r_leg_kny, r_leg_aky, r_leg_akx + 4; 4; 3; 3; 2.5; 2.5; 2.5; ...% l_arm_shz, l_arm_shx, l_arm_ely, l_arm_elx, l_arm_wry, l_arm_wrx, l_arm_wry2 + 4; 4; 3; 3; 2.5; 2.5; 2.5]; + + % effort limit in urdf (aus v4) + tau_max = [ ... + 106; 445; 300; 25; ... % 'back_bkz'; 'back_bky'; 'back_bkx'; 'neck_ry' + 275; 530; 840; 890; 740; 360; ... % l_leg_hpz, l_leg_hpx, l_leg_hpy, l_leg_kny, l_leg_aky, l_leg_akx + 275; 530; 840; 890; 740; 360; ... % r_leg_hpz, r_leg_hpx, r_leg_hpy, r_leg_kny, r_leg_aky, r_leg_akx + 87; 99; 63; 112; 25; 25; 25; ...% l_arm_shz, l_arm_shx, l_arm_ely, l_arm_elx, l_arm_wry, l_arm_wrx, l_arm_wry2 + 87; 99; 63; 112; 25; 25; 25]; + + + AtlasStruct.tau_max = tau_max; + AtlasStruct.qD_max = qD_max; + AtlasStruct.tau_min = -tau_max; + AtlasStruct.qD_min = -qD_max; + + AtlasStruct.q_min = q_min; + AtlasStruct.q_max = q_max; + + AtlasStruct.k_motor_elec = 0.12679; %[Nm/A] + AtlasStruct.gear_ratio_elec = [100; 100; 99; 100; 100; 99]; + % for all joints, for easier indexing + AtlasStruct.k_motor_elec_all = 0.12679*ones(30,1); %[Nm/A] + AtlasStruct.gear_ratio_elec_all = [NaN(20,1); 100; 100; 99; NaN(4,1); 100; 100; 99]; +end + +%% Fuß-Geometrie +% Bestimmt mit data/atlas_footsole_generation.m +% Eckpunkte des äußeren Vierecks aller Punkte der Fußsohle. Im URDF-KS foot +if version == 5 + AtlasStruct.footsole_left = [... + -0.0877 -0.0626 -0.0765; ... + -0.0877 0.0661 -0.0765; ... + 0.1728 -0.0626 -0.0765; ... + 0.1728 0.0661 -0.0765]; + AtlasStruct.footsole_right = [... + -0.0877 -0.0661 -0.0765; ... + -0.0877 0.0626 -0.0765; ... + 0.1728 -0.0661 -0.0765; ... + 0.1728 0.0626 -0.0765]; +else + AtlasStruct.footsole_left = NaN(4,3); + AtlasStruct.footsole_right = NaN(4,3); +end + +%% Daten für eine Körperseite +% Export Joint and Link Indices for the requested arm +if nargin > 1 + if lr == true % left + AtlasStruct.LI_Leg = AtlasStruct.LI_lLeg; + AtlasStruct.LI_Arm = AtlasStruct.LI_lArm; + AtlasStruct.JI_Leg = AtlasStruct.JI_lLeg; + AtlasStruct.JI_Arm = AtlasStruct.JI_lArm; + AtlasStruct.footsole = AtlasStruct.footsole_left; + else % right + AtlasStruct.LI_Leg = AtlasStruct.LI_rLeg; + AtlasStruct.LI_Arm = AtlasStruct.LI_rArm; + AtlasStruct.JI_Leg = AtlasStruct.JI_rLeg; + AtlasStruct.JI_Arm = AtlasStruct.JI_rArm; + AtlasStruct.footsole = AtlasStruct.footsole_right; + end +end diff --git a/robot_model/atlas_identification_experiment_test.m b/robot_model/atlas_identification_experiment_test.m new file mode 100644 index 0000000..271e6de --- /dev/null +++ b/robot_model/atlas_identification_experiment_test.m @@ -0,0 +1,1324 @@ +% Plot different measured values from robot experiments +% This script is called by a settings file creating the structure +% SettingsStruct in the workspace +% +% Creates the following figures: +% the figures for each limb are ordered left arm, right arm, left leg, +% right leg. +% 1 Joint positions (all joints) +% 2 Joint velocities (all joints) +% 3 Joint torques (all joints) +% 4 FT sensors (all joints) +% 8 IMU +% 11-14 limb joint positions +% 15-18 limb joint velocities +% 21-24 limb joint accelerations +% 25-28 limb joint torques +% 31-34 limb cartesian error +% 35-38 limb collision detection +% 40 electric motor data +% 41-42 hydraulics data +% 51-54 impedance controller gains +% 61-62 impedance controller output +% 65-66 impedance controller output (observer) +% 71-72 impedance controller output +% 73-74 stiffness comparison (cartesian) +% 75-76 stiffness comparison (joint space) +% 80-81 robot plots +% 91-94 limb cartesian endpoint velocity +% +% Sources: +% [1] Robotik I Skript (WS_2014_15) + +% TODO: Move appending of files to own function +% TODO: Experimentnamen als Titel oben in jedes Bild + +% Moritz Schappler, schappler@irt.uni-hannover.de, 2015-02 +% (c) Institut für Regelungstechnik, Universität Hannover + +% oft aufgerufene Funktionen kompilieren +Mex_Erstellen({'atlas_arm_invdyn_fb_plin_minpar_sym_lag_varpar', ... +'atlas_leg_invdyn_fb_plin_minpar_sym_lag_varpar', ... +'atlas_arm_gravload_plin_minpar_sym_lag_varpar', ... +'atlas_leg_gravload_plin_minpar_sym_lag_varpar', ... +'atlas_arm_fkine', ... +'atlas_arm_jacobig', ... +'quat2r', ... +'apply_FT_calibration', ... +'atlas_T_pelvis_utorso'}); + +% suppress warnings +%#ok<*CCAT> +%% User Settings + +% Alle Einstellungen hier NAN setzen +mode = SettingsStruct.mode; +file_number_range = SettingsStruct.file_number_range; +atlas_version = SettingsStruct.atlas_version; +N_calc = SettingsStruct.N_calc; +if N_calc > 1e5 + try %#ok + h = parpool; % use parallel computation only when needed. + h.IdleTimeout = 60*24; % one day + end +end +plot_robot = SettingsStruct.plot_robot; +data_path = SettingsStruct.data_path; +eval_path = SettingsStruct.eval_path; +plot_q_all = SettingsStruct.plot_q_all; +plot_qD_all = SettingsStruct.plot_qD_all; +plot_tau_all = SettingsStruct.plot_tau_all; +plot_tau_ext = SettingsStruct.plot_tau_ext; +plot_FT = SettingsStruct.plot_FT; +if ~isfield(SettingsStruct, 'calib_Fext') + calib_Fext = 'first'; +else + calib_Fext = SettingsStruct.calib_Fext; +end +plot_IMU = SettingsStruct.plot_IMU; +plot_q_limb = SettingsStruct.plot_q_limb; +plot_qD_limb = SettingsStruct.plot_qD_limb; +plot_qDD_limb = SettingsStruct.plot_qDD_limb; +plot_tau_limb = SettingsStruct.plot_tau_limb; +plot_elecmot = SettingsStruct.plot_elecmot; +plot_hydraulics = SettingsStruct.plot_hydraulics; +plot_actuator_state = SettingsStruct.plot_actuator_state; +plot_actuator_raw = SettingsStruct.plot_actuator_raw; +plot_arm_error = SettingsStruct.plot_arm_error; +if isfield(SettingsStruct, 'plot_EE_velo') + plot_EE_velo = SettingsStruct.plot_EE_velo; +else + plot_EE_velo = false(1,4); +end +plot_impctrl = SettingsStruct.plot_impctrl; +plot_impctrl_sl = SettingsStruct.plot_impctrl_sl; +plot_colldet = SettingsStruct.plot_colldet; +plot_stiffness = SettingsStruct.plot_stiffness; +save_plot = SettingsStruct.save_plot; + +MPV_lArm_damp = SettingsStruct.MPV_lArm_damp; +MPV_lArm_model = SettingsStruct.MPV_lArm_model; +MPV_rArm_damp = SettingsStruct.MPV_rArm_damp; +MPV_rArm_model = SettingsStruct.MPV_rArm_model; +% Einstellungen Laden + + +% TODO: Alle Einstellungen hier anzeigen und prüfen + + +%% Dateien laden +for file_number = file_number_range +%% Init + +% if lr == true % left +% data_path = fullfile(tb_path, 'trajexport','l_arm','out'); +% else +% data_path = fullfile(tb_path, 'trajexport','r_arm','out'); +% end +files = dir(fullfile(data_path, '*.mat')); + +% Print File List +for i = 1:length(files) + fprintf('[%d/%d] %s\n', i, length(files), files(i).name); +end + +if strcmp(mode, 'single') + if ~exist(data_path, 'file') + error('Folder %s does not exist.', data_path); + end + if length(files) < file_number + error('Folder %s has no mat file number %d', data_path, file_number); + end + filename = files(file_number).name; + % load arbitrary data file + Data = load_experiment_data(fullfile(data_path, filename)); + figtitle = filename; +elseif strcmp(mode, 'all') + % Append the data + empty_struct = struct('t', [], 'q', [], 'qD', [], 'qDD', [], 'tau', [], ... + 'F_lH', [], 'F_lF', [], 'F_rH', [], 'F_rF', [], ... + 'pelvis_x_r', [], 'pelvis_xD_r', [], 'pelvis_xDD_t', []); + Data = struct('FromRobot', empty_struct, 'ToRobot', empty_struct); + t_End = 0; + if isempty(files) + error('no files found in %s', data_path); + end + for i = 1:length(files) + filename = files(i).name; + DataTmp = load_experiment_data(fullfile(data_path, filename)); + Data.FromRobot.t = [Data.FromRobot.t; t_End+DataTmp.FromRobot.t]; + Data.FromRobot.q = [Data.FromRobot.q; DataTmp.FromRobot.q]; + Data.FromRobot.qD = [Data.FromRobot.qD; DataTmp.FromRobot.qD]; + Data.FromRobot.qDD = [Data.FromRobot.qDD; DataTmp.FromRobot.qDD]; + Data.FromRobot.tau = [Data.FromRobot.tau; DataTmp.FromRobot.tau]; + + Data.FromRobot.pelvis_x_r = [Data.FromRobot.pelvis_x_r; DataTmp.FromRobot.pelvis_x_r]; + Data.FromRobot.pelvis_xD_r = [Data.FromRobot.pelvis_xD_r; DataTmp.FromRobot.pelvis_xD_r]; + Data.FromRobot.pelvis_xDD_t = [Data.FromRobot.pelvis_xDD_t; DataTmp.FromRobot.pelvis_xDD_t]; + + Data.FromRobot.F_lH = [Data.FromRobot.F_lH; DataTmp.FromRobot.F_lH]; + Data.FromRobot.F_lF = [Data.FromRobot.F_lF; DataTmp.FromRobot.F_lF]; + Data.FromRobot.F_rH = [Data.FromRobot.F_rH; DataTmp.FromRobot.F_rH]; + Data.FromRobot.F_rF = [Data.FromRobot.F_rF; DataTmp.FromRobot.F_rF]; + + Data.ToRobot.t = [Data.ToRobot.t; t_End+DataTmp.ToRobot.t]; + Data.ToRobot.q = [Data.ToRobot.q; DataTmp.ToRobot.q]; + Data.ToRobot.qD = [Data.ToRobot.qD; DataTmp.ToRobot.qD]; + Data.ToRobot.qDD = [Data.ToRobot.qDD; DataTmp.ToRobot.qDD]; + Data.ToRobot.tau = [Data.ToRobot.tau; DataTmp.ToRobot.tau]; + + % nächste Startzeit + t_End = max(Data.FromRobot.t(end), Data.ToRobot.t(end))+0.15; + + % Mit NaN beenden (damit nicht durchgezeichnet wird zwischen einzelnen + % Messwert-Dateien + Data.FromRobot.t = [Data.FromRobot.t; Data.FromRobot.t(end)+0.1]; + Data.FromRobot.q = [Data.FromRobot.q; NaN(1,28)]; + Data.FromRobot.qD = [Data.FromRobot.qD; NaN(1,28)]; + Data.FromRobot.qDD = [Data.FromRobot.qDD; NaN(1,28)]; + Data.FromRobot.tau = [Data.FromRobot.tau; NaN(1,28)]; + + Data.FromRobot.F_lH = [Data.FromRobot.F_lH; NaN(1,6)]; + Data.FromRobot.F_lF = [Data.FromRobot.F_lF; NaN(1,6)]; + Data.FromRobot.F_rH = [Data.FromRobot.F_rH; NaN(1,6)]; + Data.FromRobot.F_rF = [Data.FromRobot.F_rF; NaN(1,6)]; + + Data.FromRobot.pelvis_x_r = [Data.FromRobot.pelvis_x_r; NaN(1,4)]; + Data.FromRobot.pelvis_xD_r = [Data.FromRobot.pelvis_xD_r; NaN(1,3)]; + Data.FromRobot.pelvis_xDD_t = [Data.FromRobot.pelvis_xDD_t; NaN(1,3)]; + + Data.ToRobot.t = [Data.ToRobot.t; Data.ToRobot.t(end)+0.1]; + Data.ToRobot.q = [Data.ToRobot.q; NaN(1,AS.NJ)]; + Data.ToRobot.qD = [Data.ToRobot.qD; NaN(1,AS.NJ)]; + Data.ToRobot.qDD = [Data.ToRobot.qDD; NaN(1,AS.NJ)]; + Data.ToRobot.tau = [Data.ToRobot.tau; NaN(1,AS.NJ)]; + end + figtitle = 'all Files'; +else + error('mode %s not defined!', mode); +end + + +AS = atlas_const(atlas_version); +FT_Names = {'Fx', 'Fy', 'Fz', 'Mx', 'My', 'Mz'}; +chains = {'left_arm', 'right_arm', 'left_leg', 'right_leg'}; +% parallel pool for dynamic calculation +% try +% parpool('local') +% end +% Mex_Erstellen({'atlas_arm_gravload_vps', 'atlas_arm_invdyn_fb_vps'}); + +if ~isempty(Data.ToRobot.t) + TLim = minmax2(Data.ToRobot.t'); +else + TLim = minmax2(Data.FromRobot.t'); +end + +% if ~isempty(Data.ToRobot.t) +% Data.ToRobot.t = NaN; +% Data.ToRobot.q = [Data.ToRobot.q; NaN(1,AS.NJ)]; +% Data.ToRobot.qD = [Data.ToRobot.qD; NaN(1,AS.NJ)]; +% Data.ToRobot.qDD = [Data.ToRobot.qDD; NaN(1,AS.NJ)]; +% Data.ToRobot.tau = [Data.ToRobot.tau; NaN(1,AS.NJ)]; +% end + +%% Add Fields +Data.FromRobot.tau_ext = NaN(length(Data.FromRobot.t), AS.NJ); +Data.FromRobot.Dq = NaN(length(Data.FromRobot.t), AS.NJ); + +%% F/T Calibration +if strcmp(calib_Fext, 'ImpCtrl') + settings_fields = {'ImpCtrlGains_left_arm', 'ImpCtrlGains_right_arm'}; + for lr = [true, false] + AS = atlas_const(atlas_version, lr); + + % use impedance controller F/T calibration as reference + if isfield(Data.ToRobot, settings_fields{2-lr}) + ImpCtrlStrct = Data.ToRobot.(settings_fields{2-lr}); % temporary variable for changing + + % load FT data + if lr == true + F_Mess = Data.FromRobot.F_lH_raw; + else + F_Mess = Data.FromRobot.F_rH_raw; + end + + % calibrate sensor data + F_mess_calib = NaN(size(F_Mess)); + calib_data = [ImpCtrlStrct.mass(1); ImpCtrlStrct.COM_x(1); ImpCtrlStrct.COM_y(1); ImpCtrlStrct.COM_z(1); ... + ImpCtrlStrct.offset_F_x(1); ImpCtrlStrct.offset_F_y(1); ImpCtrlStrct.offset_F_z(1); ... + ImpCtrlStrct.offset_T_x(1); ImpCtrlStrct.offset_T_y(1); ImpCtrlStrct.offset_T_z(1)]; + for i = 1:size(F_mess_calib,1) + F_mess_calib(i,:) = apply_FT_calibration_mex(F_Mess(i,1:6), ... + Data.FromRobot.q(i,:), Data.FromRobot.q(i,AS.JI_Arm), ... + Data.FromRobot.pelvis_x_r(i,:), ... + lr, Data.FromRobot.atlas_version, calib_data(1), ... + calib_data(2:4), calib_data(5:10)); + end + % rotation has to happen after the calibration, because calibration + % offset is recorded with rotated sensor. + if lr == true + Data.FromRobot.F_lH_raw_calib = F_mess_calib; + Data.FromRobot.F_lH_calib = F_mess_calib; + % Data.FromRobot.F_lH_calib(:,[1,2,4,5]) = -F_mess_calib(:,[1,2,4,5]); + else + Data.FromRobot.F_rH_raw_calib = F_mess_calib; + Data.FromRobot.F_rH_calib = F_mess_calib; + end + end + end +elseif strcmp(calib_Fext, 'first') % assume first measured force data point as reference + % calibration of raw data (without correct orientation) + Data.FromRobot.F_lH_raw_calib = Data.FromRobot.F_lH_raw - ... + repmat(Data.FromRobot.F_lH_raw(1,:), length(Data.FromRobot.t), 1); + Data.FromRobot.F_rH_raw_calib = Data.FromRobot.F_rH_raw - ... + repmat(Data.FromRobot.F_rH_raw(1,:), length(Data.FromRobot.t), 1); + + % calibration of rotated data + Data.FromRobot.F_lH_calib = Data.FromRobot.F_lH - ... + repmat(Data.FromRobot.F_lH(1,:), length(Data.FromRobot.t), 1); + Data.FromRobot.F_rH_calib = Data.FromRobot.F_rH - ... + repmat(Data.FromRobot.F_rH(1,:), length(Data.FromRobot.t), 1); +else + error('unknown calibration mode for external forces!'); +end + +%% Output Gains +if isfield(Data.ToRobot, 'ConstGains') +Gains = {'k_q_p', 'k_q_i', 'k_qd_p', 'k_f_p', 'ff_qd', 'ff_qd_d', 'ff_f_d'}; +% print gains to post them in the wiki +fprintf('| | '); +for i = [AS.JI_lArm, AS.JI_rArm] + fprintf('%s |', AS.JN{i}); +end +fprintf('\n'); +for IG = 1:length(Gains) + if ~isfield(Data.ToRobot.ConstGains, Gains{IG}) + continue; % Der Gain verändert sich + end + GainData = Data.ToRobot.ConstGains.(Gains{IG}); + fprintf('| %s | ', Gains{IG}); + for i = 1:size(GainData,2) + fprintf('%1.3f | ', GainData(1,i)); + end + fprintf('\n'); +end + +end +%% Plot joint angles +if plot_q_all +fprintf('printing all joint positions in one plot\n'); +figure(1);set(1, 'Name', 'q', 'NumberTitle', 'off');clf; + +subplot(2,3,1);hold on;grid on; +hdl=plot(Data.FromRobot.t, Data.FromRobot.q(:,AS.JI_lArm)); set(gca, 'ColorOrderIndex', 1) +plot(Data.ToRobot.t, Data.ToRobot.q(:,AS.JI_lArm), '-'); +legend(hdl, AS.JN(AS.JI_lArm), 'interpreter', 'none'); +ylabel('q [rad]'); +xlabel('t [s]'); +title('Left Arm'); + +subplot(2,3,2);hold on;grid on; +hdl=plot(Data.FromRobot.t, Data.FromRobot.q(:,AS.JI_rArm)); set(gca, 'ColorOrderIndex', 1) +plot(Data.ToRobot.t, Data.ToRobot.q(:,AS.JI_rArm), '-'); +legend(hdl, AS.JN(AS.JI_rArm), 'interpreter', 'none'); +ylabel('q [rad]'); +xlabel('t [s]'); +title('Right Arm'); + +subplot(2,3,4);hold on;grid on; +hdl=plot(Data.FromRobot.t, Data.FromRobot.q(:,AS.JI_lLeg)); set(gca, 'ColorOrderIndex', 1) +plot(Data.ToRobot.t, Data.ToRobot.q(:,AS.JI_lLeg), '-'); +legend(hdl, AS.JN(AS.JI_lLeg), 'interpreter', 'none'); +ylabel('q [rad]'); +xlabel('t [s]'); +title('Left Leg'); + +subplot(2,3,5);hold on;grid on; +hdl=plot(Data.FromRobot.t, Data.FromRobot.q(:,AS.JI_rLeg)); set(gca, 'ColorOrderIndex', 1) +plot(Data.ToRobot.t, Data.ToRobot.q(:,AS.JI_rLeg), '-'); +legend(hdl, AS.JN(AS.JI_rLeg), 'interpreter', 'none'); +ylabel('q [rad]'); +xlabel('t [s]'); +title('Right Leg'); + +subplot(2,3,3);hold on;grid on; +hdl=plot(Data.FromRobot.t, Data.FromRobot.q(:,AS.JI_Torso)); set(gca, 'ColorOrderIndex', 1) +plot(Data.ToRobot.t, Data.ToRobot.q(:,AS.JI_Torso), '-'); +legend(hdl, AS.JN(AS.JI_Torso), 'interpreter', 'none'); +ylabel('q [rad]'); +xlabel('t [s]'); +title('Back'); +linkxaxes; +subplot_expand(1,2,3); +xlim(TLim) +end +%% Plot joint velocities +if plot_qD_all +fprintf('printing all joint velocities in one plot\n'); +figure(2);set(2, 'Name', 'qD', 'NumberTitle', 'off'); clf; +subplot(2,3,1);hold on;grid on; +hdl=plot(Data.FromRobot.t, Data.FromRobot.qD(:,AS.JI_lArm)); set(gca, 'ColorOrderIndex', 1) +plot(Data.ToRobot.t, Data.ToRobot.qD(:,AS.JI_lArm), '-'); +legend(hdl, AS.JN(AS.JI_lArm), 'interpreter', 'none'); +ylabel('qD [rad/s]'); +xlabel('t [s]'); +title('Left Arm'); + +subplot(2,3,2);hold on;grid on; +hdl=plot(Data.FromRobot.t, Data.FromRobot.qD(:,AS.JI_rArm)); set(gca, 'ColorOrderIndex', 1) +plot(Data.ToRobot.t, Data.ToRobot.qD(:,AS.JI_rArm), '-'); +legend(hdl, AS.JN(AS.JI_rArm), 'interpreter', 'none'); +ylabel('qD [rad/s]'); +xlabel('t [s]'); +title('Right Arm'); + +subplot(2,3,4);hold on;grid on; +hdl=plot(Data.FromRobot.t, Data.FromRobot.qD(:,AS.JI_lLeg)); set(gca, 'ColorOrderIndex', 1) +plot(Data.ToRobot.t, Data.ToRobot.qD(:,AS.JI_lLeg), '-'); +legend(hdl, AS.JN(AS.JI_lLeg), 'interpreter', 'none'); +ylabel('qD [rad/s]'); +xlabel('t [s]'); +title('Left Leg'); + +subplot(2,3,5);hold on;grid on; +hdl=plot(Data.FromRobot.t, Data.FromRobot.qD(:,AS.JI_rLeg)); set(gca, 'ColorOrderIndex', 1) +plot(Data.ToRobot.t, Data.ToRobot.qD(:,AS.JI_rLeg), '-'); +legend(hdl, AS.JN(AS.JI_rLeg), 'interpreter', 'none'); +ylabel('qD [rad/s]'); +xlabel('t [s]'); +title('Right Leg'); + +subplot(2,3,3);hold on;grid on; +hdl=plot(Data.FromRobot.t, Data.FromRobot.qD(:,AS.JI_Torso)); set(gca, 'ColorOrderIndex', 1) +plot(Data.ToRobot.t, Data.ToRobot.qD(:,AS.JI_Torso), '-'); +legend(hdl, AS.JN(AS.JI_Torso), 'interpreter', 'none'); +ylabel('qD [rad/s]'); +xlabel('t [s]'); +title('Back'); +linkxaxes; +subplot_expand(2,2,3); +xlim(TLim) +end +%% Plot joint torque +if plot_tau_all +fprintf('printing all joint torques in one plot\n'); +figure(3);clf;set(3, 'Name', 'tau', 'NumberTitle', 'off'); clf; +subplot(2,3,1);hold on;grid on; +hdl=plot(Data.FromRobot.t, Data.FromRobot.tau(:,AS.JI_lArm)); +plot(Data.ToRobot.t, Data.ToRobot.tau(:,AS.JI_lArm), '-'); +legend(hdl, AS.JN(AS.JI_lArm), 'interpreter', 'none'); +ylabel('\tau [Nm]'); +xlabel('t [s]'); +title('Left Arm'); + +subplot(2,3,2);hold on;grid on; +hdl=plot(Data.FromRobot.t, Data.FromRobot.tau(:,AS.JI_rArm)); +plot(Data.ToRobot.t, Data.ToRobot.tau(:,AS.JI_rArm), '-'); +legend(hdl, AS.JN(AS.JI_rArm), 'interpreter', 'none'); +ylabel('\tau [Nm]'); +xlabel('t [s]'); +title('Right Arm'); + +subplot(2,3,4);hold on;grid on; +hdl=plot(Data.FromRobot.t, Data.FromRobot.tau(:,AS.JI_lLeg)); +plot(Data.ToRobot.t, Data.ToRobot.tau(:,AS.JI_lLeg), '-'); +legend(hdl, AS.JN(AS.JI_lLeg), 'interpreter', 'none'); +ylabel('\tau [N ?]'); +xlabel('t [s]'); +title('Left Leg'); + +subplot(2,3,5);hold on;grid on; +hdl=plot(Data.FromRobot.t, Data.FromRobot.tau(:,AS.JI_rLeg)); +plot(Data.ToRobot.t, Data.ToRobot.tau(:,AS.JI_rLeg), '-'); +legend(hdl, AS.JN(AS.JI_rLeg), 'interpreter', 'none'); +ylabel('\tau [N ?]'); +xlabel('t [s]'); +title('Right Leg'); + +subplot(2,3,3);hold on;grid on; +hdl=plot(Data.FromRobot.t, Data.FromRobot.tau(:,AS.JI_Torso)); +plot(Data.ToRobot.t, Data.ToRobot.tau(:,AS.JI_Torso), '-'); +legend(hdl, AS.JN(AS.JI_Torso), 'interpreter', 'none'); +ylabel('\tau [N ?]'); +xlabel('t [s]'); +title('Back'); +linkxaxes; +subplot_expand(3,2,3); +xlim(TLim) +end +%% Force/Torque Sensor Data +if plot_FT && isfield(Data.FromRobot, 'F_lH') + % data with correct orientation (hand frame) + fprintf('plotting F/T sensor data\n'); + figure(4);clf;set(4, 'Name', 'F_T_Sensors', 'NumberTitle', 'off'); clf; + subplot(2,2,1);hold on;grid on; + hdl=plot(Data.FromRobot.t, Data.FromRobot.F_lH); + legend(hdl, FT_Names, 'interpreter', 'tex'); + title('left Hand F/T'); + ylabel('F [N], M [Nm]'); + + subplot(2,2,2);hold on;grid on; + hdl=plot(Data.FromRobot.t, Data.FromRobot.F_rH); + legend(hdl, FT_Names, 'interpreter', 'tex'); + title('right Hand F/T'); + ylabel('F [N], M [Nm]'); + + subplot(2,2,3);hold on;grid on; + hdl=plot(Data.FromRobot.t, Data.FromRobot.F_lF); + legend(hdl, FT_Names, 'interpreter', 'tex'); + title('left Foot F/T'); + ylabel('F [N], M [Nm]'); + + subplot(2,2,4);hold on;grid on; + hdl=plot(Data.FromRobot.t, Data.FromRobot.F_rF); + legend(hdl, FT_Names, 'interpreter', 'tex'); + title('right Foot F/T'); + ylabel('F [N], M [Nm]'); + linkxaxes; + subplot_expand(4,2,2); + xlim(TLim) + + % calibrated raw data + figure(5);clf;set(5, 'Name', 'F_T_calib', 'NumberTitle', 'off'); clf; + % raw measured force (wrong orientation) after calibration + subplot(2,2,1);hold on;grid on; + hdl=plot(Data.FromRobot.t, Data.FromRobot.F_lH_raw_calib(:,1:3)); + legend(hdl, FT_Names(1:3), 'interpreter', 'tex'); + title('left Hand F raw calib'); + ylabel('F [N]'); + + subplot(2,2,2);hold on;grid on; + hdl=plot(Data.FromRobot.t, Data.FromRobot.F_lH_raw_calib(:,4:6)); + legend(hdl, FT_Names(4:6), 'interpreter', 'tex'); + title('left Hand M raw calib'); + ylabel('M [Nm]'); + + subplot(2,2,3);hold on;grid on; + hdl=plot(Data.FromRobot.t, Data.FromRobot.F_rH_raw_calib(:,1:3)); + legend(hdl, FT_Names(1:3), 'interpreter', 'tex'); + title('right Hand F raw calib'); + ylabel('F [N]'); + + subplot(2,2,4);hold on;grid on; + hdl=plot(Data.FromRobot.t, Data.FromRobot.F_rH_raw_calib(:,4:6)); + legend(hdl, FT_Names(4:6), 'interpreter', 'tex'); + title('right Hand M raw calib'); + ylabel('M [Nm]'); + linkxaxes; + subplot_expand(5,2,2); + xlim(TLim) +end +%% IMU Data +if plot_IMU +fprintf('plotting IMU sensor data\n'); +figure(8);clf;set(8, 'Name', 'IMU_Sensors', 'NumberTitle', 'off'); clf; +subplot(2,2,1);hold on;grid on; +hdl=plot(Data.FromRobot.t, Data.FromRobot.pelvis_x_r); +legend(hdl, {'quat_x', 'quat_y', 'quat_z', 'quat_w'}, 'interpreter', 'tex'); +title('Pelvis Quaternion Orientation'); +ylabel('[1]'); + +subplot(2,2,2);hold on;grid on; +ori_utorso_angle = NaN(length(Data.FromRobot.t),1); +% Calculate utorso orientation +for i = 1:length(Data.FromRobot.t) + % pelvis quaternion orientation (correct precision errors) + quat_pelvis_corr = Data.FromRobot.pelvis_x_r(i,:)/ norm(Data.FromRobot.pelvis_x_r(i,:)); + R_pelvis = quat2r_mex(quat_pelvis_corr); + T_pelvis_utorso = atlas_T_pelvis_utorso_mex(Data.FromRobot.q(i,:), atlas_version); + R_utorso = R_pelvis * T_pelvis_utorso(1:3,1:3); + + % calculate angle between utorso z-axis and global z-axis + ori_utorso_angle(i) = acos(R_utorso(1:3,3)'*[0;0;1] / (1*1)); +end +hdl=plot(Data.FromRobot.t, ori_utorso_angle*180/pi); +legend(hdl, {'angle_utorso'}, 'interpreter', 'none'); +title('Utorso Angle Orientation'); +ylabel('angle betw. z_{utorso} and z_{world} [deg]'); + +subplot(2,2,3);hold on;grid on; +hdl=plot(Data.FromRobot.t, Data.FromRobot.pelvis_xD_r); +legend(hdl, {'\omega_x', '\omega_y', '\omega_z'}, 'interpreter', 'tex'); +title('Pelvis Angular Velocity'); +ylabel('\omega [rad/s]'); + +subplot(2,2,4);hold on;grid on; +hdl=plot(Data.FromRobot.t, Data.FromRobot.pelvis_xDD_t); +legend(hdl, {'a_x', 'a_y', 'a_z'}, 'interpreter', 'tex'); +title('Pelvis Linear Acceleration'); +ylabel('xDD [m/s^2]'); +linkxaxes; +subplot_expand(8,2,2); +xlim(TLim) +end +%% Plot position, velocity, acceleration and torque for all joint chains +for limb = [1, 2] +for lr = [true, false] + + + %% Init + figoffset = 0; + lrString = 'left'; + ImpCtrlStrct = Data.ToRobot.ImpCtrlGains_left_arm; + if lr == false + figoffset = figoffset + 1; + lrString = 'right'; + ImpCtrlStrct = Data.ToRobot.ImpCtrlGains_right_arm; + end + AS = atlas_const(atlas_version, lr); + if limb == 1 + NJL = AS.NJA; + JI = AS.JI_Arm; + limbString = 'Arm'; + else + NJL = 6; + figoffset = figoffset + 2; + JI = AS.JI_Leg; + limbString = 'Leg'; + end + + %% Calculations + + % calculate torque from external forces + if (plot_tau_ext || plot_stiffness(2-lr)) && limb == 1 + F_0 = NaN(6,1); + tau_ext = NaN(length(Data.FromRobot.t),NJL); + if limb == 1 + if lr == true, F_Mess = Data.FromRobot.F_lH_calib(:, :); + else F_Mess = Data.FromRobot.F_rH_calib(:, :); end + else + if lr == true, F_Mess = Data.FromRobot.F_lF(:, :); + else F_Mess = Data.FromRobot.F_rF(:, :); end + end + for i = 1:length(Data.FromRobot.t) + if limb == 1 + T_0_EE = atlas_arm_fkine_mex(Data.FromRobot.q(i, JI), lr, atlas_version); + else + T_0_EE = atlas_leg_fkine_mex(Data.FromRobot.q(i, JI), lr, atlas_version); + end + F_0(1:3) = t2r(T_0_EE(:,:,end))*(F_Mess(i,1:3))'; + F_0(4:6) = t2r(T_0_EE(:,:,end))*(F_Mess(i,4:6))'; + if limb == 1 + tau_ext(i,:) = atlas_arm_jacobig_mex(Data.FromRobot.q(i, JI), lr, atlas_version)'*F_0; + else + tau_ext(i,:) = atlas_leg_jacobig_mex(Data.FromRobot.q(i, JI), lr, atlas_version)'*F_0; + end + end + Data.FromRobot.tau_ext(:,AS.JI_Arm) = tau_ext; + end + + % Position Error + + % sample data to robot with data from robot times + q_Des_time_meas = interp1(Data.ToRobot.t,Data.ToRobot.q(:,AS.JI_Arm),Data.FromRobot.t,'previous'); + Data.FromRobot.Dq(:,AS.JI_Arm) = Data.FromRobot.q(:,AS.JI_Arm) - q_Des_time_meas; + + %% Joint Position (Arm/Leg) + if plot_q_limb(2-lr + 2*(limb-1)) + fprintf('plotting %s %s position data\n', lrString, limbString); + figure(11+figoffset);set(11+figoffset, 'Name', sprintf('q_%s_%s', lrString, limbString), 'NumberTitle', 'off');clf; + for i = 1:NJL + if NJL == 6, nr = 2; nc = 3; + else nr = 3; nc = 3; end + subplot(nr,nc,i);hold on;grid on; + plot(Data.FromRobot.t, Data.FromRobot.q(:,JI(i))); + plot(Data.ToRobot.t, Data.ToRobot.q(:,JI(i)), '-'); + plot(minmax2(Data.FromRobot.t'), [1,1]*AS.q_min(JI(i)), 'r--'); + plot(minmax2(Data.FromRobot.t'), [1,1]*AS.q_max(JI(i)), 'r--'); + xlim(TLim) + legend({'Ist', 'Soll', 'lim'}, 'interpreter', 'none'); + title(sprintf('%s (q%d) [rad]', AS.JN{JI(i)}, i), 'interpreter', 'none'); + % ylabel(sprintf('q_{%d} [rad]', i)); + xlabel('t [s]'); + end + linkxaxes; + subplot_expand(11+figoffset,nr,nc); + end + %% Joint Velocity (Arm/Leg) + if plot_qD_limb(2-lr + 2*(limb-1)) + fprintf('plotting %s %s velocity data\n', lrString, limbString); + figure(15+figoffset);set(15+figoffset, 'Name', sprintf('qD_%s_%s', lrString, limbString), 'NumberTitle', 'off');clf; + for i = 1:NJL + if NJL == 6, nr = 2; nc = 3; + else nr = 3; nc = 3; end + subplot(nr,nc,i);hold on;grid on; + plot(Data.FromRobot.t, Data.FromRobot.qD(:,JI(i))); + plot(Data.ToRobot.t, Data.ToRobot.qD(:,JI(i)), '-'); + legend({'Ist', 'Soll'}, 'interpreter', 'none'); + title(AS.JN{JI(i)}, 'interpreter', 'none'); + xlim(TLim) + ylabel(sprintf('qD_{%d} [rad/s]', i)); + xlabel('t [s]'); + end + linkxaxes; + subplot_expand(15+figoffset,nr,nc); + end + + %% Joint Acceleration (Arm/Leg) + if plot_qDD_limb(2-lr + 2*(limb-1)) && isfield(Data.FromRobot, 'qDD') + fprintf('plotting %s %s acceleration data\n', lrString, limbString); + figure(21+figoffset);set(21+figoffset, 'Name', sprintf('qDD_%s_%s', lrString, limbString), 'NumberTitle', 'off');clf; + for i = 1:NJL + if NJL == 6, nr = 2; nc = 3; + else nr = 3; nc = 3; end + subplot(nr,nc,i);hold on;grid on; + plot(Data.FromRobot.t, Data.FromRobot.qDD(:,JI(i))); + plot(Data.ToRobot.t, Data.ToRobot.qDD(:,JI(i)), '-'); + legend({'Ist', 'Soll'}, 'interpreter', 'none'); + title(AS.JN{JI(i)}, 'interpreter', 'none'); + xlim(TLim) + ylabel(sprintf('qDD_{%d} [rad/s^2]', i)); + xlabel('t [s]'); + end + linkxaxes; + subplot_expand(21+figoffset,nr, nc); + end + %% Joint Torque (Arm/Leg) + if plot_tau_limb(2-lr + 2*(limb-1)) + fprintf('plotting %s %s effort data\n', lrString, limbString); + % calculate gravity and inverse dynamics + N = length(Data.FromRobot.t); + + % load dynamic base parameters + if limb == 1 + if lr == true + MPV_arm = MPV_lArm_model; + else + MPV_arm = MPV_rArm_model; + end + else + % default values for dynamic parameters + [~, rSges_urdf_ORIG, ~, Iges_urdf_ORIG] = ... + atlas_arm_parameter_urdf(lr, uint8(atlas_version)); + [a_mdh, d_mdh, ~, ~, rSges_mdh_ORIG, m_ORIG,Iges_mdh_ORIG] = atlas_leg_parameter_mdh(lr, atlas_version); + MPV_leg = atlas_leg_convert_par1_MPV(rSges_mdh_ORIG, m_ORIG, Iges_mdh_ORIG, a_mdh, d_mdh, atlas_version); + end + tau_invdyn = NaN(N,NJL); + tau_grav = NaN(N,NJL); + if isfield(Data.FromRobot, 'pelvis_x_r') + Q = Data.FromRobot.q; + QD = Data.FromRobot.qD; + QDD = Data.FromRobot.qDD; + X_r = Data.FromRobot.pelvis_x_r; + fprintf('Calculate inverse dynamics for %d joint angles...', min(N_calc, size(Q,1))); + t1 = tic; + parfor i = 1:min(N_calc, size(Q,1)) + q_Rob = Q(i,:); + qD_Rob = QD(i,:); + qDD_Rob = QDD(i,:); + R_pelvis = quat2r_mex(X_r(i,:)); + if limb == 1 + T_pelvis_utorso = atlas_T_pelvis_utorso_mex(q_Rob, atlas_version); + R_utorso = R_pelvis * T_pelvis_utorso(1:3,1:3); + g0_utorso = R_utorso'*[0;0;-9.81]; + + tau_invdyn(i,:) = atlas_arm_invdyn_fb_plin_minpar_sym_lag_varpar_mex( ... + q_Rob(JI), qD_Rob(JI), qDD_Rob(JI), ... + g0_utorso', MPV_arm, lr, atlas_version); + tau_grav(i,:) = atlas_arm_gravload_plin_minpar_sym_lag_varpar_mex( ... + q_Rob(JI), ... + g0_utorso', MPV_arm, lr, atlas_version); + else + g0_pelvis = R_pelvis'*[0;0;-9.81]; + + tau_invdyn(i,:) = atlas_leg_invdyn_fb_plin_minpar_sym_lag_varpar_mex( ... + q_Rob(JI), qD_Rob(JI), qDD_Rob(JI), ... + g0_pelvis', MPV_leg, lr, atlas_version); + tau_grav(i,:) = atlas_leg_gravload_plin_minpar_sym_lag_varpar_mex( ... + q_Rob(JI), ... + g0_pelvis', MPV_leg, lr, atlas_version); + end + end + fprintf('... finished. %1.1fs; Average %1.3fms\n', toc(t1), 1e3*toc(t1)/N); + end + + figure(25+figoffset);set(25+figoffset, 'Name', sprintf('tau_%s_%s', lrString, limbString), 'NumberTitle', 'off');clf; + for i = 1:NJL + if NJL == 6, nr = 2; nc = 3; + else nr = 3; nc = 3; end + subplot(nr,nc,i);hold on;grid on; + legend_hdl = plot(Data.FromRobot.t, Data.FromRobot.tau(:,JI(i))); + legend_content = {'Ist'}; + if ~isempty(Data.ToRobot.tau) + legend_hdl(end+1) = plot(Data.ToRobot.t, Data.ToRobot.tau(:,JI(i)), '-'); %#ok + legend_content = {legend_content{:}, 'Soll'}; + end + if any(~isnan(tau_invdyn(:,i))) + legend_hdl(end+1) = plot(Data.FromRobot.t, tau_invdyn(:,i)); %#ok + legend_content = {legend_content{:}, 'ID'}; + end + if any(~isnan(tau_grav(:,i))) + legend_hdl(end+1) = plot(Data.FromRobot.t, tau_grav(:,i)); %#ok + legend_content = {legend_content{:}, 'Grav'}; + end + + % observed joint torque + if plot_impctrl(2-lr + 2*(limb-1)) && isfield(Data.FromRobot, 'tau_obs') + legend_hdl(end+1) = plot(Data.FromRobot.t, Data.FromRobot.tau_obs(:,JI(i)), ':'); %#ok + legend_content = {legend_content{:}, 'obs'}; + end + + % external forces joint torque + if plot_tau_ext + legend_hdl(end+1) = plot(Data.FromRobot.t, Data.FromRobot.tau_ext(:,AS.JI_Arm(i)), '.-'); %#ok + legend_content = {legend_content{:}, 'ext'}; + end + + % actuator state joint torque + if plot_actuator_state && isfield(Data.FromRobot, 'tau_as') + legend_hdl(end+1) = plot(Data.FromRobot.t, Data.FromRobot.tau_as(:,JI(i)),':'); %#ok + legend_content = {legend_content{:}, 'as'}; + end + + % raw actuator joint torque + if plot_actuator_raw && isfield(Data.FromRobot, 'tau_ar') + legend_hdl(end+1) = plot(Data.FromRobot.t, Data.FromRobot.tau_ar(:,JI(i)),'--'); %#ok + legend_content = {legend_content{:}, 'ar'}; + end + + % actuator command before the integrator is added + if plot_impctrl(2-lr + 2*(limb-1)) && isfield(Data.ToRobot, 'tau_cmd') + legend_hdl(end+1) = plot(Data.ToRobot.t, Data.ToRobot.tau_cmd(:,JI(i)),'--'); %#ok + legend_content = {legend_content{:}, 'wo_int'}; + end + + % calculated torque from electric motors + if i >=5 && limb == 1 && isfield(Data.FromRobot, 'i_el') && ... + any(~isnan(Data.FromRobot.i_el(:,AS.JI_Arm(i)))) + tau_elec = Data.FromRobot.i_el(:,AS.JI_Arm(i)).* ... + AS.k_motor_elec_all(AS.JI_Arm(i)).*... + AS.gear_ratio_elec_all(AS.JI_Arm(i)); + legend_hdl(end+1) = plot(Data.FromRobot.t, tau_elec); %#ok + legend_content = {legend_content{:}, 'elec'}; + end + + if i == 1 || i == NJL + legend(legend_hdl, legend_content, 'interpreter', 'none'); + end + title(AS.JN{JI(i)}, 'interpreter', 'none'); + ylabel(sprintf('\\tau_{%d} [Nm]', i)); + xlabel('t [s]'); + xlim(TLim) + end + linkxaxes; + subplot_expand(25+figoffset,nr, nc); + end + + %% Plot cartesian and joint angle plot_error + if plot_arm_error(2-lr) && limb == 1 + fprintf('plotting %s %s endpoint error\n', lrString, limbString); + tic; + figure(31+figoffset);clf;set(31+figoffset,'Name',sprintf('Error_%s_Arm', lrString), 'NumberTitle', 'off'); + if ~isempty(Data.ToRobot.t) + % sample data to robot with data from robot times + q_Des_time_meas = interp1(Data.ToRobot.t,Data.ToRobot.q(:,AS.JI_Arm),Data.FromRobot.t,'previous'); + q_e = Data.FromRobot.q(:,AS.JI_Arm) - q_Des_time_meas; + % Plot joint position offset + subplot(2,1,1); + plot(Data.FromRobot.t, q_e); + legend(AS.JN(AS.JI_Arm), 'interpreter', 'none');grid on; + ylabel('\Deltaq [rad]'); + % calculate and plot cartesian error + x_EE_Soll = NaN(length(Data.FromRobot.t), 7); + x_EE_Ist = NaN(length(Data.FromRobot.t), 7); + x_EE_Diff = NaN(length(Data.FromRobot.t), 7); + for i = 1:length(Data.FromRobot.t) + T_c_Soll = atlas_arm_fkine_mex(q_Des_time_meas(i,:), lr, atlas_version); + T_c_Ist = atlas_arm_fkine_mex(Data.FromRobot.q(i,AS.JI_Arm), lr, atlas_version); + % T_EE_Diff = tr2delta(T_c_Soll(:,:,end), T_c_Ist(:,:,end)); + x_EE_Soll(i,:) = tr2quat(T_c_Soll(:,:,end)); + x_EE_Ist(i,:) = tr2quat(T_c_Ist(:,:,end)); + x_EE_Diff(i,1:3) = T_c_Ist(1:3,4,end) - T_c_Soll(1:3,4,end); + % tr2quat(T_c_Soll(:,:,end) / T_c_Ist(:,:,end)); + end + subplot(2,1,2); + plot(Data.FromRobot.t, [1e3*x_EE_Diff(:,1:3), 1e3*sqrt(sum(abs(x_EE_Diff(:,1:3)).^2,2))]); + legend({'x', 'y', 'z', 'norm'}); + ylabel('\Delta x trans [mm]');grid on; + linkxaxes + subplot_expand(31+figoffset, 2, 1); + fprintf('Calculated forward kinematics for %d positions for %s %s. %1.4fs\n', ... + length(Data.FromRobot.t), lrString, limbString,toc); + end + end + + + %% Plot End-Effector velocities + if plot_EE_velo(1+figoffset) + % EE-Geschw. berechnen (Annahme: Basis fest) + XD = NaN(length(Data.FromRobot.t),6); + for i = 1:length(Data.FromRobot.t) + if limb == 1, JG = atlas_arm_jacobig_mex(Data.FromRobot.q(i,JI), lr, atlas_version); + else JG = atlas_leg_jacobig_mex(Data.FromRobot.q(i,JI), lr, atlas_version); end + XD(i,:) = JG * (Data.FromRobot.qD(i,JI)'); + end + XD_Norm = [sqrt(XD(:,1).^2+XD(:,2).^2+XD(:,3).^2), ... % Norm der Geschw. + sqrt(XD(:,4).^2+XD(:,5).^2+XD(:,6).^2)]; % Norm der Winkelgeschw. + + figure(91+figoffset);clf; + subplot(2,2,1); + plot(Data.FromRobot.t, XD(:,1:3)); + ylabel('v_{EE}');grid on; + legend({'v_x', 'v_y', 'v_z'}); + subplot(2,2,2); + plot(Data.FromRobot.t, XD_Norm(:,1)); + ylabel('||v_{EE}||');grid on; + subplot(2,2,3); + plot(Data.FromRobot.t, XD(:,4:6)); + ylabel('\omega_{EE}');grid on; + subplot(2,2,4); + plot(Data.FromRobot.t, XD_Norm(:,2)); + ylabel('||\omega_{EE}||');grid on; + linkxaxes + end + + + %% Plot Collision Detection features + if plot_colldet(2-lr) && limb == 1 && isfield(Data.FromRobot, 'tau_obs') + fprintf('plotting %s %s endpoint error\n', lrString, limbString); + tic; + figure(35+figoffset);clf;set(35+figoffset,'Name',sprintf('CollDet_%s_Arm', lrString), 'NumberTitle', 'off'); + + for i = 1:AS.NJA + if NJL == 6, nr = 2; nc = 3; + else nr = 3; nc = 3; end + subplot(nr,nc,i);hold on;grid on; + + % observer joint torque + legend_hdl(end+1) = plot(Data.FromRobot.t, Data.FromRobot.tau_obs(:,JI(i))); %#ok + legend_content = {legend_content{:}, 'obs'}; + + % threshold for collision detection + stairs(ImpCtrlStrct.t, -10./ImpCtrlStrct.K_cd_o, 'r--'); + legend_hdl(end+1) = stairs(ImpCtrlStrct.t, 10./ImpCtrlStrct.K_cd_o, 'r--'); %#ok + legend_content = {legend_content{:}, 'threshold'}; + + ylabel('tau_{obs} [Nm]'); + xlabel('t [s]'); + title(AS.JN{JI(i)}, 'interpreter', 'none'); + linkxaxes + end + + end +end +end + +%% Plot Electric Motor Characteristics +if plot_elecmot && isfield(Data.FromRobot, 'T_el') + fprintf('plotting electric motor data\n'); + figure(40);clf;set(40,'Name','Elec', 'NumberTitle', 'off'); + for lr = [true, false] + lrString = 'left'; + if lr == false + lrString = 'right'; + end + AS = atlas_const(atlas_version, lr); + + subplot(3,2,sprc2no(3,2,1,2-lr));hold on;grid on; + plot(Data.FromRobot.t, Data.FromRobot.T_el(:,AS.JI_Arm(5:7)) ); + ylabel('T [deg C]'); + legend(AS.JN(AS.JI_Arm(5:7)), 'interpreter', 'none'); + if lr == true + title('left'); + else + title('right'); + end + + subplot(3,2,sprc2no(3,2,2,2-lr));hold on;grid on; + plot(Data.FromRobot.t, Data.FromRobot.i_el(:,AS.JI_Arm(5:7)) ); + ylabel('i [A]'); + + subplot(3,2,sprc2no(3,2,3,2-lr));hold on;grid on; + plot(Data.FromRobot.t, Data.FromRobot.tau(:,AS.JI_Arm(5:7)) ); + ylabel('tau [Nm]'); + xlim(TLim) + end + linkxaxes; + subplot_expand(40,3,2); +end + +%% Plot Hydraulics data +% convert psi to Pa +psi2Pa = 6894.757293168; % Source: http://en.wikipedia.org/wiki/Pounds_per_square_inch +if plot_hydraulics && isfield(Data.FromRobot, 'p_p') + fprintf('plotting hydraulic actuator data\n'); + for lr = [true, false] + figoffset = 0; + lrString = 'left'; + if lr == false + figoffset = figoffset + 1; + lrString = 'right'; + end + figure(41+figoffset);clf;set(41+figoffset,'Name',sprintf('Hydr_%s_Arm',lrString) , 'NumberTitle', 'off'); + AS = atlas_const(atlas_version, lr); + + for i = 1:4 + % Pressure sensors + subplot(2,4,sprc2no(2,4,1,i));hold on;grid on; + title(AS.JN{AS.JI_Arm(i)}, 'interpreter', 'none'); + plot(Data.FromRobot.t, Data.FromRobot.p_p(:, AS.JI_Arm(i))/psi2Pa ); + plot(Data.FromRobot.t, Data.FromRobot.p_n(:, AS.JI_Arm(i))/psi2Pa ); + if i == 1 + ylabel('p [psi]'); + end + % Inlet and supply pressure + if i == 4 && isfield(Data.FromRobot, 'p_I') + plot(Data.FromRobot.t, Data.FromRobot.p_I/psi2Pa ); + plot(Data.FromRobot.t, Data.FromRobot.p_S/psi2Pa ); + legend({'p_{pos}', 'p_{neg}', 'p_{I}', 'p_{S}'}); + end + + % calculated joint torque + r = AS.hydr_r(AS.JI_Arm(i)); + A_1 = AS.hydr_Apos(AS.JI_Arm(i)); + A_2 = AS.hydr_Aneg(AS.JI_Arm(i)); + p_1 = Data.FromRobot.p_p(:, AS.JI_Arm(i)); + p_2 = Data.FromRobot.p_n(:, AS.JI_Arm(i)); + tau_calc = r*(A_1*p_1 - A_2*p_2); + subplot(2,4,sprc2no(2,4,2,i));hold on;grid on; + plot(Data.FromRobot.t, tau_calc ); + plot(Data.FromRobot.t, Data.FromRobot.tau(:,AS.JI_Arm(i)), '--' ); + if i == 1 + ylabel('\tau [Nm]'); + end + if i == 4 + legend({'\tau_{calc}'}); + end + + end + end + linkxaxes; +end + +%% Plot change of impedance controller gains + +firstelement = @(x)(x(1)); + +if any(plot_impctrl) + fprintf('plotting impedance controller data\n'); + for ich = 1:length(chains) + if ich == 1 || ich == 3 + lr = true; + else + lr = false; + end + if ~plot_impctrl(ich) + continue + end + if ~isfield(Data.ToRobot, sprintf('ImpCtrlGains_%s', chains{ich})) + continue; + end + AS = atlas_const(atlas_version, lr); + if ich == 1 || ich == 2 + names = AS.JN(AS.JI_Arm); + else + names = AS.JN(AS.JI_Leg); + end + % remove the chain name from the joint name to access stored parameters + names_red = names; + for i = 1:length(names) + tmp = names{i}; + names_red{i} = tmp(7:end); + end + Strct = Data.ToRobot.(sprintf('ImpCtrlGains_%s', chains{ich})); + if isempty(Strct.t) + continue % no data available + end + figure(51+ich);clf; + set(51+ich, 'Name', sprintf('ImpCtrl_%s', chains{ich}), 'NumberTitle', 'off'); + + % plot stiffness + subplot(2,3,1);hold on;grid on + for i = 1:length(names) + stairs(Strct.t, Strct.(sprintf('K_d_%s', names_red{i})) ); + end + ylabel('Stiffness [Nm/rad]'); + legend(names_red) + title(sprintf('ImpCtrl_%s', chains{ich}), 'interpreter', 'none'); + + % plot damping + subplot(2,3,2);hold on;grid on + for i = 1:length(names) + stairs(Strct.t, Strct.(sprintf('D_%s', names_red{i}))); + end + ylabel('Damping [1]'); + + subplot(2,3,3);hold on;grid on + plot_list = {'K_tau_K', 'K_tau_D', 'K_tau_g', 'K_tau_e'}; + legend_content = {}; + for i = 1:length(plot_list) + if ~isfield(Strct, plot_list{i}), continue; end + stairs(Strct.t, Strct.(plot_list{i})); + legend_content = {legend_content{:}, sprintf('%s (starts %1.1f)', plot_list{i}, firstelement(Strct.(plot_list{i})))}; + end + legend(legend_content, 'interpreter', 'none'); + + % plot feedforward terms + subplot(2,3,4);hold on;grid on + plot_list = {'K_tau_c', 'K_tau_a', 'K_qDD_d', 'K_qD_d', 'K_tau_f'}; + legend_content = {}; + for i = 1:length(plot_list) + stairs(Strct.t, Strct.(plot_list{i})); + legend_content = {legend_content{:}, sprintf('%s (starts %1.1f)', plot_list{i}, firstelement(Strct.(plot_list{i})))}; + end + legend(legend_content, 'interpreter', 'none'); + + % plot observer settings + subplot(2,3,5);hold on;grid on + plot_list = {'K_obs_c', 'K_ext_c', 'K_fri_o', 'K_ext_o', 'K_tau_o', 'K_O'}; + legend_content = {}; + for i = 1:length(plot_list) + stairs(Strct.t, Strct.(plot_list{i})); + legend_content = {legend_content{:}, sprintf('%s (starts %1.1f)', plot_list{i}, firstelement(Strct.(plot_list{i})))}; + end + legend(legend_content, 'interpreter', 'none'); + + % integral gain + subplot(2,3,6);hold on;grid on + legend_content = {}; + for i = 1:length(names) + if isfield(Strct, sprintf('KI_%s', names_red{i})) + stairs(Strct.t, Strct.(sprintf('KI_%s', names_red{i})) ); + legend_content = {legend_content{:}, names_red{i}}; + end + end + legend(legend_content, 'interpreter', 'none'); + ylabel('Integral Gain K_I'); + end + linkxaxes +end + +%% Plot Impedance Controller output +% Calculate Impedance Controller Output with Simulink from Controller Input +for lr = [true, false] + if plot_impctrl_sl(2-lr) + AS = atlas_const(atlas_version, lr); + figoffset = 0; + lrString = 'left'; + if lr == false + figoffset = figoffset + 1; + lrString = 'right'; + end + % Simulink-Modell mit Regler aus Eingangsdaten berechnen + atlas_calc_impctrl_output + + figure(61+figoffset);clf;set(61+figoffset,'Name',sprintf('SL_ImpCtrl_%s_Arm',lrString) , 'NumberTitle', 'off'); + + qD_Des_time_meas = interp1(Data.ToRobot.t,Data.ToRobot.qD(:,AS.JI_Arm),Data.FromRobot.t,'previous'); + dqD = Data.FromRobot.qD(:,AS.JI_Arm) - qD_Des_time_meas; + + % Ergebnisse plotten + for i = 1:AS.NJA + subplot(3,AS.NJA,sprc2no(3,AS.NJA,1,i));hold on;grid on; + % Positionsfehler, + plot(Data.FromRobot.t, Data.FromRobot.Dq(:,AS.JI_Arm(i))); + if i == 1, ylabel('\Delta q [rad]'); end + title( AS.JN{AS.JI_Arm(i)}, 'interpreter', 'none' ); + % Geschwindigkeitsfehler + subplot(3,AS.NJA,sprc2no(3,AS.NJA,2,i));hold on;grid on; + plot(Data.FromRobot.t, dqD(:,i)); + if i == 1, ylabel('\Delta qD [rad/s]'); end + % Drehmoment + subplot(3,AS.NJA,sprc2no(3,AS.NJA,3,i));hold on;grid on; + plot(out_t, out_tau_Soll(:,i)); + plot(Data.ToRobot.t, Data.ToRobot.tau(:,AS.JI_Arm(i))); + if i == 1, + ylabel('\tau [Nm]'); + legend({'Simulink', 'ToRobot'}) + end + end + linkxaxes + + % compare observer data with saved observer data + figure(65+figoffset);clf;set(65+figoffset,'Name',sprintf('SL_ImpCtrlObs_%s_Arm',lrString) , 'NumberTitle', 'off'); + for i = 1:AS.NJA + subplot(3,3,i);hold on;grid on; + title( AS.JN{AS.JI_Arm(i)}, 'interpreter', 'none' ); + ylabel('\tau_{obs} [Nm] (observer)'); + + % observer data from experiment + plot(Data.FromRobot.t, Data.FromRobot.tau_obs(:,AS.JI_Arm(:,i))); + + % observer data from simulink based on other measured data + plot(out_t, out_tau_obs(:,i), '--'); + + legend({'experiment', 'simulink'}); + end + linkxaxes + + % only compare impedance controller torque without observer + figure(71+figoffset);clf;set(71+figoffset,'Name',sprintf('SL_without_obs_%s_Arm',lrString) , 'NumberTitle', 'off'); + for i = 1:AS.NJA + subplot(3,AS.NJA,sprc2no(3,AS.NJA,1,i));hold on;grid on; + % Positionsfehler, + plot(Data.FromRobot.t, Data.FromRobot.Dq(:,AS.JI_Arm(i))); + if i == 1, ylabel('\Delta q [rad]'); end + title( AS.JN{AS.JI_Arm(i)}, 'interpreter', 'none' ); + % Geschwindigkeitsfehler + subplot(3,AS.NJA,sprc2no(3,AS.NJA,2,i));hold on;grid on; + plot(Data.FromRobot.t, dqD(:,i)); + if i == 1, ylabel('\Delta qD [rad/s]'); end + % Drehmoment + subplot(3,AS.NJA,sprc2no(3,AS.NJA,3,i));hold on;grid on; + plot(out_t, out_tau_Soll_wo_obs(:,i)); + plot(Data.ToRobot.t, Data.ToRobot.tau(:,AS.JI_Arm(i))); + if i == 1, + ylabel('\tau [Nm] (w/o observer)'); + legend({'Simulink', 'ToRobot'}) + end + end + linkxaxes + end +end + +%% Plot Stiffness +% Calculate cartesian stiffness +for lr = [true, false] + if lr == true + F_mess = Data.FromRobot.F_lH; + else + F_mess = Data.FromRobot.F_rH; + end + % Sensoren driften ziemlich stark. Ersten Datenwert als Referenzmessung + F_mess = F_mess - repmat(F_mess(1,:), size(F_mess,1),1); + + + AS = atlas_const(atlas_version, lr); + if plot_stiffness(2-lr) + % calculate desired cartesian stiffness + Strct = Data.ToRobot.(sprintf('ImpCtrlGains_%s', chains{2-lr})); + + K_d = diag([Strct.K_d_shz(1); Strct.K_d_shx(1); Strct.K_d_ely(1); Strct.K_d_elx(1); Strct.K_d_wry(1); Strct.K_d_wrx(1); Strct.K_d_wry2(1)]); + Kx_theo = NaN(length(Data.FromRobot.t), 3); + for i = 1:length(Data.FromRobot.t) + J = atlas_arm_jacobig_mex(Data.FromRobot.q(i, AS.JI_Arm), ... + lr, atlas_version); + % cartesian stiffness + % [1], S. 59 + Kx = inv(J * (K_d \ (J'))); + Kx_theo(i,:) = Kx(sub2ind(size(Kx), [1 2 3], [1 2 3])); + end + + % calculate experimental stiffness + Kx_exp = NaN(length(Data.FromRobot.t), 3); + q_Des_time_meas = interp1(Data.ToRobot.t,Data.ToRobot.q(:,AS.JI_Arm),Data.FromRobot.t,'previous'); + F_0 = NaN(length(Data.FromRobot.t), 3); + Dx = NaN(length(Data.FromRobot.t), 3); + for i = 1:length(Data.FromRobot.t) + T_0_EE = atlas_arm_fkine_mex(Data.FromRobot.q(i, AS.JI_Arm), ... + lr, atlas_version); + x_EE = tr2quat_mex(T_0_EE(:,:,end)); + + T_0_EE_d = atlas_arm_fkine_mex(q_Des_time_meas(i, :), ... + lr, atlas_version); + x_EE_d = tr2quat_mex(T_0_EE_d(:,:,end)); + Dx(i,:) = x_EE(1:3) - x_EE_d(1:3); + F_0(i,:) = t2r(T_0_EE(:,:,end))*(F_mess(i,1:3))'; + % TODO: Hier wurden keine Kopplungen zwischen den Achsen + % berücksichtigt. + % Die somit experimentell bestimmte Steifigkeit ist nicht der + % korrekte Eintrag in der Steifigkeitsmatrix! + Kx_exp(i,:) = F_0(i,1:3) ./ (Dx(i,:)); + end + + xyz = {'x', 'y', 'z'}; + figure(73+figoffset);clf;set(73+figoffset,'Name',sprintf('CartStiff_%s_Arm',lrString) , 'NumberTitle', 'off'); + for i = 1:3 + subplot(3,3,sprc2no(3,3,i,1));hold all; grid on; + plot(Data.FromRobot.t, 1e3*Dx(:,i)); + ylabel(sprintf('\\Delta %s [mm]', xyz{i})); + + subplot(3,3,sprc2no(3,3,i,2));hold all; grid on; + plot(Data.FromRobot.t, F_0(:,i)); + ylabel(sprintf('F_{%s} [N]', xyz{i})); + + subplot(3,3,sprc2no(3,3,i,3));hold all; grid on; + plot(Data.FromRobot.t, Kx_exp(:,i)/1e3); + plot(Data.FromRobot.t, Kx_theo(:,i)/1e3); + legend({'Mess', 'Soll.'}); + + ylabel(sprintf('K_{%s%s} [N/mm]', xyz{i}, xyz{i})); + % ylim(minmax2(Kx_theo(:,i)')); + end + linkxaxes + + %% Joint Stiffness + figure(75+figoffset);clf;set(75+figoffset,'Name',sprintf('JointStiff_%s_Arm',lrString) , 'NumberTitle', 'off'); + for i = 1:AS.NJA + subplot(3,7,sprc2no(3,7,1,i));hold all; grid on; + plot(Data.FromRobot.t, Data.FromRobot.Dq(:,AS.JI_Arm(i))); + ylabel(sprintf('\\Delta q_%d [rad]', i)); + + subplot(3,7,sprc2no(3,7,2,i));hold all; grid on; + plot(Data.FromRobot.t, Data.FromRobot.tau_ext(:,AS.JI_Arm(i))); + ylabel(sprintf('\\tau_{ext,%d} [Nm]', i)); + + subplot(3,7,sprc2no(3,7,3,i));hold all; grid on; + Kq_i_exp = Data.FromRobot.tau_ext(:,AS.JI_Arm(i)) ./ Data.FromRobot.Dq(:,AS.JI_Arm(i)); + plot(Data.FromRobot.t, Kq_i_exp); + plot(minmax2(Data.FromRobot.t'), K_d(i,i)*[1,1]); + legend({'Mess', 'Soll.'}); + + ylabel(sprintf('K_{q%d} [Nm/rad]',i)); + % ylim(minmax2(Kx_theo(:,i)')); + end + linkxaxes + + + end +end +%% Plot Robot +if plot_robot +figure(81);clf;set(81, 'Name', 'Rob_t_end', 'NumberTitle', 'off'); +hold on; grid on;axis equal;view(3);set(81, 'Renderer','OpenGL') +I = 1; +q = Data.FromRobot.q(I,:); +T_pelvis = quat2tr([0,0,0,Data.FromRobot.pelvis_x_r(I,:)]); +atlas_plot_robot(q, atlas_version, 81, T_pelvis) +atlas_plot_frames(q, [AS.LI_rArm, AS.LI_lArm], atlas_version, T_pelvis); +%subtitle(filename); + +figure(80);clf;set(80, 'Name', 'Rob_t0', 'NumberTitle', 'off'); +hold on; grid on;axis equal;view(3);set(80, 'Renderer','OpenGL') +I = size(Data.FromRobot.t,1)-1; +q = Data.FromRobot.q(I,:); +T_pelvis = quat2tr([0,0,0,Data.FromRobot.pelvis_x_r(I,:)]); +atlas_plot_robot(q, atlas_version, 80, T_pelvis) +atlas_plot_frames(q, [AS.LI_rArm, AS.LI_lArm], atlas_version, T_pelvis); +%subtitle(filename); + + +for ff = 5:6 + figure(ff); + % Insert Floor + p0 = [0 0 0]; + v1 = [1 0 0]; + v2 = [0 1 0]; + plane = [p0 v1 v2]; + + drawPlane3d(plane, 'FaceColor', [0.6,0.6,0.6], 'FaceAlpha', 0.3) + + % change view + %view([90 0]) % YZ-View + %view([0 90]) % XY-View + view([0 0]) % XZ-View +end +end +%% Save Figures +dockall +if save_plot +eval_path = [eval_path, sprintf('_eval_%s', datestr(now, 'yyyymmdd_HHMM'))]; %#ok +if ~exist(eval_path, 'file') + mkdir(eval_path); +end +if strcmp(mode, 'single') + [~,basename] = fileparts(filename); +else + basename = 'evaluation_compilation'; +end +tic; +Bilder_Speichern(eval_path, {'fig', 'png'}, basename); +fprintf('Saved Figures to %s. Time: %1.1fs.\n', eval_path, toc); +end +end \ No newline at end of file diff --git a/robot_model/atlas_joint_impctrl_sqrt_damping_test_settings_default.m b/robot_model/atlas_joint_impctrl_sqrt_damping_test_settings_default.m new file mode 100644 index 0000000..ae8784f --- /dev/null +++ b/robot_model/atlas_joint_impctrl_sqrt_damping_test_settings_default.m @@ -0,0 +1,157 @@ +% Settings to start the Atlas Arm joint impedance controller +% called by atlas_joint_impctrl_sqrt_damping_test_start.m + +% Jonathan Vorndamme, vorndamme@irt.uni-hannover.de, 2015-01 +% Moritz Schappler, schappler@irt.uni-hannover.de, 2015-09 +% (c) Institut für Regelungstechnik, Universität Hannover + +%% Init + +lrStrings = {'left', 'right'}; + +AS=atlas_const(atlas_version, lr); +if atlas_limb == 1 + q_r=0.5*(AS.q_min(AS.JI_rArm)+AS.q_max(AS.JI_rArm)); + q_l=0.5*(AS.q_min(AS.JI_lArm)+AS.q_max(AS.JI_lArm)); + NJL = AS.NJA; + JI = AS.JI_Arm; + % TODO: Simulink-Modell an Arm v5 umbenennen + sl_Modellname = 'atlas_joint_impctrl_sqrt_damping_test'; + atlas_arm_lr = lr; +else + q_r=0.5*(AS.q_min(AS.JI_rLeg)+AS.q_max(AS.JI_rLeg)); + q_l=0.5*(AS.q_min(AS.JI_lLeg)+AS.q_max(AS.JI_lLeg)); + NJL = AS.NJL; + JI = AS.JI_Leg; + sl_Modellname = 'atlas5_leg_joint_impctrl_sqrt_damping_test'; + atlas_leg_lr = lr; +end + +%% Soll-Trajektorie +q0=q_l; +qD0 = zeros(1,NJL)'; + +q_start = q0'; +q_end = q_start; +q_end(2) = q_start(2)+pi/2; %Drehe q2 um 90° (seitlich ausgestreckt) +% C3-stetige Trapez-Trajektorie fahren +vmax = 2*ones(1,NJL); +amax = 10*ones(1,NJL); +jmax = 100*ones(1,NJL); +zmax = [ (q0(2)+pi/2) ; 2; 10; 100]; + +[~, ~, w_t, w_Q] = traj_trapezN( [q_start; zeros(2,NJL)], ... + [q_end; zeros(2,NJL)], [q_end; vmax; amax; jmax], 1e-3, false); +qsollDaten.q = NaN(length(w_t), NJL); +qsollDaten.qD = NaN(length(w_t), NJL); +qsollDaten.qDD = NaN(length(w_t), NJL); +for i = 1:NJL + qsollDaten.q(:,i) = w_Q(:,1,i); + qsollDaten.qD(:,i) = w_Q(:,2,i); + qsollDaten.qDD(:,i) = w_Q(:,3,i); +end + +qsollDaten.t = w_t; % Zeitbasis ist für alle Achsen gleich. Daher hier keine Anpassung notwendig + +%% Externe Kraft +t_Fext = [0;1;4]; +F_ext = [[0;100;0], zeros(3,5)]; + +%% Simulink-Eingangsdaten +simin_q_soll = struct('time', qsollDaten.t, ... + 'signals', struct('values', qsollDaten.q, 'dimensions', NJL), ... + 'name', 'q_soll'); + +simin_qD_soll = struct('time', qsollDaten.t, ... + 'signals', struct('values', qsollDaten.qD, 'dimensions', NJL), ... + 'name', 'qD_soll'); + +simin_qDD_soll = struct('time', qsollDaten.t, ... + 'signals', struct('values', qsollDaten.qDD, 'dimensions', NJL), ... + 'name', 'qD_soll'); + +simin_F0_ext = struct('time', t_Fext, ... + 'signals', struct('values', F_ext, 'dimensions', 6), ... + 'name', 'F0_ext'); + +%% model parameters +if atlas_limb == 1 + [a_mdh, d_mdh, ~, ~, rSges_mdh_ORIG, m_ORIG,Iges_mdh_ORIG] = atlas_arm_parameter_mdh(atlas_arm_lr, atlas_version); + MPV_ORIG = atlas_arm_convert_par1_MPV(rSges_mdh_ORIG, m_ORIG, Iges_mdh_ORIG, a_mdh, d_mdh, atlas_version); + % Zusatzlast: 1kg mit 100mm Hebelarm, damit Trägheit im Dynamikmodell + % höher wird. + MPV_payload = atlas5_arm_FT_payload_MPV(1, [.1,.1,.1]', [0.1, 0, 0, 0.1, 0, 0.1]', true); + MPV_arm_plant=MPV_ORIG+MPV_payload; % MPV for simulated plant + MPV_arm_model=MPV_ORIG+MPV_payload;% MPV for calculating the gravity model + MPV_arm_damp=MPV_ORIG+MPV_payload; % MPV for calculating the inertia matrix (positive definite) + % set noise levels for simulated measurements + q_noise = 0.01; + qD_noise = 0.01; + tau_noise = 0.5; + F_ext_noise = 3; + g_noise = 0.001; + % set noise seeds for measurement noises + q_noise_seed = 0; + qD_noise_seed = 0; + tau_noise_seed = 0; + F_ext_noise_seed = 0; + g_noise_seed = 0; + % set noise switches for measurement noises (1=on, 0=off) + q_noise_switch = 0; + qD_noise_switch = 0; + tau_noise_switch = 0; + F_ext_noise_switch = 0; + g_noise_switch = 0; +else + [a_mdh, d_mdh, ~, ~, rSges_mdh_ORIG, m_ORIG,Iges_mdh_ORIG] = atlas_leg_parameter_mdh(atlas_leg_lr, atlas_version); + MPV_ORIG = atlas_leg_convert_par1_MPV(rSges_mdh_ORIG, m_ORIG, Iges_mdh_ORIG, a_mdh, d_mdh, atlas_version); + MPV_leg_plant=MPV_ORIG; % MPV for simulated plant + MPV_leg_model=MPV_ORIG;% MPV for calculating the gravity model + MPV_leg_damp=MPV_ORIG; % MPV for calculating the inertia matrix (positive definite) +end + +d = 0.2*ones(NJL,1); +muC = 8*ones(NJL,1); + +% controller parameters and gains +K_d = 150*eye(NJL); +D = 0.7*eye(NJL); +K_O = 5*eye(NJL); +T = 0.001; +T1 = 0; +K_tau_g = 1; +K_tau_c = 1; +K_tau_K = 1; +K_tau_D = 1; +K_tau_a = 1; +K_tau_f = 0; +K_tau_e = 0; +K_tau_o = 0; +K_ext_c = 0; +K_obs_c = 0; +K_fri_o = 1; +K_ext_o = 1; +K_qD_d = 1; +K_qDD_d = 1; +tau_c = muC - 4*ones(NJL,1); +B = d - 0.1*ones(NJL,1); +qD_th = 0.05*ones(NJL,1); +tau_th = 0.02*ones(NJL,1); + +% Filter für Ein- und Ausgänge des Reglers +T1_filter_input = 0; +T1_filter_output = 0; +%% Configure Model + +load_system(sl_Modellname) +configSet = getActiveConfigSet(sl_Modellname); +set_param(configSet, 'Solver', 'ode4'); +set_param(configSet, 'FixedStep', '1e-6'); + +%% Define Inputs +simin_tau_ext = struct('time', 0, ... + 'signals', struct('values', zeros(1,NJL), 'dimensions', NJL), ... + 'name', 'tau_ext'); +simin_tau_m = struct('time', 0, ... + 'signals', struct('values', zeros(1,NJL), 'dimensions', NJL), ... + 'name', 'tau_m'); diff --git a/robot_model/atlas_leg_convert_par1_MPV.m b/robot_model/atlas_leg_convert_par1_MPV.m new file mode 100644 index 0000000..e045601 --- /dev/null +++ b/robot_model/atlas_leg_convert_par1_MPV.m @@ -0,0 +1,112 @@ +% Return the minimum parameter vector for Atlas Legs + +% Moritz Schappler, schappler@irt.uni-hannover.de, 2015-03 +% (c) Institut für Regelungstechnik, Universität Hannover + +function MPV = atlas_leg_convert_par1_MPV(rSges_num_mdh, m_num_mdh, Iges_num_mdh, a_mdh, d_mdh, version) + +%% Init +assert(isa(version,'uint8') && all(size(version) == [1 1]), ... + 'version number has to be [1x1] uint8'); + +d2 = d_mdh(2); +d3 = d_mdh(3); + +a2 = a_mdh(2); +a3 = a_mdh(3); +a4 = a_mdh(4); +a5 = a_mdh(5); +a6 = a_mdh(6); + +% Convert to Parameterset 2 +% Gleicher Funktionsaufruf wie für den Arm +[mrSges_num_mdh, Ifges_num_mdh] = atlas_arm_convert_mdh_par1_par2(rSges_num_mdh, Iges_num_mdh, m_num_mdh); + + +% Mass +M1 = m_num_mdh(1); +M2 = m_num_mdh(2); +M3 = m_num_mdh(3); +M4 = m_num_mdh(4); +M5 = m_num_mdh(5); +M6 = m_num_mdh(6); + +% Erstes Moment +MX1 = mrSges_num_mdh(1,1); +MY1 = mrSges_num_mdh(1,2); +MZ1 = mrSges_num_mdh(1,3); +MX2 = mrSges_num_mdh(2,1); +MY2 = mrSges_num_mdh(2,2); +MZ2 = mrSges_num_mdh(2,3); +MX3 = mrSges_num_mdh(3,1); +MY3 = mrSges_num_mdh(3,2); +MZ3 = mrSges_num_mdh(3,3); +MX4 = mrSges_num_mdh(4,1); +MY4 = mrSges_num_mdh(4,2); +MZ4 = mrSges_num_mdh(4,3); +MX5 = mrSges_num_mdh(5,1); +MY5 = mrSges_num_mdh(5,2); +MZ5 = mrSges_num_mdh(5,3); +MX6 = mrSges_num_mdh(6,1); +MY6 = mrSges_num_mdh(6,2); +MZ6 = mrSges_num_mdh(6,3); + +% Inertia +XX1 = Ifges_num_mdh(1,1); +XY1 = Ifges_num_mdh(1,4); +XZ1 = Ifges_num_mdh(1,5); +YY1 = Ifges_num_mdh(1,2); +YZ1 = Ifges_num_mdh(1,6); +ZZ1 = Ifges_num_mdh(1,3); +XX2 = Ifges_num_mdh(2,1); +XY2 = Ifges_num_mdh(2,4); +XZ2 = Ifges_num_mdh(2,5); +YY2 = Ifges_num_mdh(2,2); +YZ2 = Ifges_num_mdh(2,6); +ZZ2 = Ifges_num_mdh(2,3); +XX3 = Ifges_num_mdh(3,1); +XY3 = Ifges_num_mdh(3,4); +XZ3 = Ifges_num_mdh(3,5); +YY3 = Ifges_num_mdh(3,2); +YZ3 = Ifges_num_mdh(3,6); +ZZ3 = Ifges_num_mdh(3,3); +XX4 = Ifges_num_mdh(4,1); +XY4 = Ifges_num_mdh(4,4); +XZ4 = Ifges_num_mdh(4,5); +YY4 = Ifges_num_mdh(4,2); +YZ4 = Ifges_num_mdh(4,6); +ZZ4 = Ifges_num_mdh(4,3); +XX5 = Ifges_num_mdh(5,1); +XY5 = Ifges_num_mdh(5,4); +XZ5 = Ifges_num_mdh(5,5); +YY5 = Ifges_num_mdh(5,2); +YZ5 = Ifges_num_mdh(5,6); +ZZ5 = Ifges_num_mdh(5,3); +XX6 = Ifges_num_mdh(6,1); +XY6 = Ifges_num_mdh(6,4); +XZ6 = Ifges_num_mdh(6,5); +YY6 = Ifges_num_mdh(6,2); +YZ6 = Ifges_num_mdh(6,6); +ZZ6 = Ifges_num_mdh(6,3); + +%% Parameter +if version == 3 || version == 4 || version == 5 + % Quelle: codeexport/atlas4_leg_minimal_parameter_vector.m + t8 = M5 + M6; + t7 = M4 + t8; + t4 = (M3 + t7); + t14 = MZ4 + MZ5; + t6 = (MZ3 + t14); + t19 = d3 * t4 + t6; + t18 = (d2 * (M2 + t4)); + t3 = a4 ^ 2 * t7; + t16 = (-YY3 - t3); + t5 = a5 ^ 2 * t8; + t15 = (-YY4 - t5); + t13 = 2 * d3 * t6 + YY5 - t15 - t16; + t12 = (a3 ^ 2); + t9 = d3 ^ 2; + MPV = [t12 * t4 + YY2 + ZZ1 + (2 * MZ2 + t18) * d2; MX1; MY1 - MZ2 - t18; XX2 - YY2 + (-t12 + t9) * t4 + t13; t19 * a3 + XY2; XZ2; YZ2; ZZ2 + (t9 + t12) * t4 + t13; a3 * t4 + MX2; MY2 - t19; XX3 + t16; XY3; -a4 * t14 + XZ3; YZ3; ZZ3 + t3; a4 * t7 + MX3; MY3; XX4 + t15; XY4; -MZ5 * a5 + XZ4; YZ4; ZZ4 + t5; a5 * t8 + MX4; MY4; XX5 + YY6 - YY5; XY5; XZ5; YZ5; ZZ5 + YY6; MX5; MY5 + MZ6; XX6 - YY6; XY6; XZ6; YZ6; ZZ6; MX6; MY6;]; +else + error('Version %d not implemented yet', version); +end \ No newline at end of file diff --git a/robot_model/atlas_leg_fkine.m b/robot_model/atlas_leg_fkine.m new file mode 100644 index 0000000..c5a3a82 --- /dev/null +++ b/robot_model/atlas_leg_fkine.m @@ -0,0 +1,47 @@ +% Calculate Forward Kinematics for Atlas Robot Leg (all versions) +% +% Input: +% q [1x6] +% Joint Angles [rad] +% lr [1x1 logical] +% true for left, false for right +% version [1x1 uint8] +% Version of the robot (e.g. 3 or 4) +% +% Output: +% T_c_urdf [4x4x7] +% homogenious transformation matrices for each body frame +% 1: pelvis -> pelvis +% 2: pelvis -> uglut +% 3: pelvis -> lglut +% 4: pelvis -> uleg +% 5: pelvis -> lleg +% 6: pelvis -> talus +% 7: pelvis -> foot +% +% Sources: +% [1] atlas_v4.urdf + +% Moritz Schappler, schappler@irt.uni-hannover.de, 2015-01 +% (c) Institut für Regelungstechnik, Leibniz Universität Hannover + + +function T_c_urdf = atlas_leg_fkine(q, lr, version) +%% Init +%#codegen +% Coder Information +assert(isa(q,'double') && isreal(q) && all(size(q) == [1 6]), ... + 'Joint angles q have to be [1x6] double'); +assert(isa(lr,'logical') && all(size(lr) == [1 1]), ... + 'Left/Right flag has to be [1x1] logical'); +assert(isa(version,'uint8') && all(size(version) == [1 1]), ... + 'version number has to be [1x1] uint8'); + +%% Calculation +if version == 3 + T_c_urdf = atlas3_leg_fkine_num(q, lr); +elseif version == 4 || version == 5 + T_c_urdf = atlas4_leg_fkine_num(q, lr); +else + error('Version %d not implemented yet', version); +end \ No newline at end of file diff --git a/robot_model/atlas_leg_parameter_mdh.m b/robot_model/atlas_leg_parameter_mdh.m new file mode 100644 index 0000000..8162710 --- /dev/null +++ b/robot_model/atlas_leg_parameter_mdh.m @@ -0,0 +1,43 @@ +% Return MDH Parameter of the Atlas Robot Leg (all versions) +% +% Input: +% lr +% true for left, false for right +% version +% 3, 4 or 5 +% +% Output: N joints +% a_mdh, d_mdh, alpha_mdh, q_offset_mdh +% Numeric Values of Kinematic Parameters, MDH-Notation +% rSges_num [Nx3] +% Center of Gravity of all indepedent bodies (arm only) in urdf frames +% m_num [Nx1] +% masses of all indepedent bodies (arm only) +% Iges_num [Nx6] +% inertia of all indepedent bodies (arm only) +% rows: bodies +% columns: inertia tensor entries. Order: xx, yy, zz, xy, xz, yz +% +% Sources: +% [1] [KhalilKle1986] + +% Moritz Schappler, schappler@irt.uni-hannover.de, 2014-11 +% (c) Institut für Regelungstechnik, Leibniz Universität Hannover + +function [a_mdh, d_mdh, alpha_mdh, q_offset_mdh, ... + rSges_num_mdh, m_num_mdh, Iges_num_mdh] = atlas_leg_parameter_mdh(lr, version) + +assert(isa(lr,'logical') && all(size(lr) == [1 1]), ... + 'Left/Right flag has to be [1x1] logical'); +assert(isa(version,'uint8') && all(size(version) == [1 1]), ... + 'version to be [1x1] uint8'); +%% URDF Parameter +if version == 3 + [a_mdh, d_mdh, alpha_mdh, q_offset_mdh, ... + rSges_num_mdh, m_num_mdh, Iges_num_mdh] = atlas3_leg_parameter_mdh(lr); +elseif version == 4 || version == 5 + [a_mdh, d_mdh, alpha_mdh, q_offset_mdh, ... + rSges_num_mdh, m_num_mdh, Iges_num_mdh] = atlas4_leg_parameter_mdh(lr); +else + error('Version %d not implemented', version); +end diff --git a/robot_model/atlas_plot_arm_link_stl.m b/robot_model/atlas_plot_arm_link_stl.m new file mode 100644 index 0000000..7fbc375 --- /dev/null +++ b/robot_model/atlas_plot_arm_link_stl.m @@ -0,0 +1,109 @@ +% Plot one arm link of the Atlas model with STL files from drcsim +% +% Input: +% j +% Number of Robot Arm Segment +% lr [1x1 logical] +% true for left, false for right +% version [1x1 uint8] +% Atlas Model Version number +% T_b_urdf +% Body frame in urdf coordinates + +% Output: +% hdl +% handle to the created patch object +% +% Sources: +% [1] Atlas Simulator STL files +% [2] atlas_v4.urdf +% [3] atlas_v5.urdf +% +% TODO: Fix Position of Atlas v4 Arm segments + +% Moritz Schappler, schappler@irt.uni-hannover.de, 2014-11 +% (c) Institut für Regelungstechnik, Universität Hannover + + +function hdl = atlas_plot_arm_link_stl(j, lr, version, T_b_urdf) + +%% Init +assert(isa(lr,'logical') && all(size(lr) == [1 1]), ... + 'Left/Right flag has to be [1x1] logical'); +assert(isa(version,'uint8') && all(size(version) == [1 1]), ... + 'version number has to be [1x1] uint8'); + +STLpath = fileparts(which('atlas_stl_location')); +AS = atlas_const(version, lr); +%% Assemble Filename +if version == 3 % the same STL files for both versions + STLpath = fullfile(STLpath, 'meshes_v3'); +elseif version == 4 + STLpath = fullfile(STLpath, 'meshes_unplugged'); +elseif version == 5 + if j <= 3 + STLpath = fullfile(STLpath, 'meshes_unplugged'); + end + if j > 3 + % Der Unterarm sieht anders aus. Die STL-Dateien in meshes_unplugged + % sind dafür geändert worden. Diese sind hier in den Ordner meshes_v5 + % umgezogen. + STLpath = fullfile(STLpath, 'meshes_v5'); + end +else + error('Version %d not implemented yet', version); +end + +if version == 5 + AS = atlas_const(4, lr); %TODO KLÄREN OB HIER FÜNF STEHEN SOLL + % See [3], for ufarm, lfarm, hand + % number | name | STL name + % 1 | l_clav | l_clav + % 2 | l_scap | l_scap + % 3 | l_uarm | l_uarm + % 4 | l_larm | l_larm.dae + % 5 | l_ufarm | l_farm + % 6 | l_lfarm | l_hand.stl + % 7 | l_hand | / + if lr + T_c_urdf_l_new_old = atlas5_simple_shapes_stf_plot_transformation(); + T_b_urdf = T_b_urdf * T_c_urdf_l_new_old(:,:,j); + end + if j == 7 + hdl = NaN; + return; % take meshes from atlas v4 + end +end + +filename = [AS.LN{AS.LI_Arm(j)}, '.stl']; +%% Move origin of STL +% if version == 4 && j == 1 +% % Atlas v4 has the same STL files but different position +% if lr == true +% T_b_urdf = T_b_urdf*transl([0; -0.048; -0.45]); % see [2], +% else +% T_b_urdf = T_b_urdf*transl([0; 0.048; -0.45]); % see [2], +% end +% end + +%% STL Operation +% read STL + +[v, f, n, c, ~] = stlread(fullfile(STLpath, filename), 0); + +% Move and rotate to link reference frame +for i = 1:size(n,1) + n(i,:) = (T_b_urdf(1:3,1:3)*n(i,:)')'; +end +for i = 1:size(v,1) + v(i,:) = (eye(3,4)*T_b_urdf*[v(i,:)';1])'; +end + +%% Plot +% Define colors +Arm_Colors = {'r', 'g', 'b', 'c', 'm', 'y', 'k'}; + +% draw STL +hdl = patch('Faces', f, 'Vertices', v,'FaceVertexCData',c, ... + 'FaceColor', 'k', 'FaceAlpha', 0.53, ... + 'EdgeColor', Arm_Colors{j}, 'EdgeAlpha', 0.54); \ No newline at end of file diff --git a/robot_model/atlas_plot_arm_stl.m b/robot_model/atlas_plot_arm_stl.m new file mode 100644 index 0000000..673481e --- /dev/null +++ b/robot_model/atlas_plot_arm_stl.m @@ -0,0 +1,34 @@ +% Plot the complete Atlas arm model with STL files from drcsim +% +% Input: +% T_c_urdf [4x4x11] +% Body frames in urdf coordinates (from atlas_dirkin_urdf function) +% lr [1x1 logical] +% true for left, false for right +% version [1x1 uint8] +% Atlas Model Version number + +% Output: +% hdl +% handle to the created patch object +% +% Sources: +% [1] Atlas Simulator STL files + +% Moritz Schappler, schappler@irt.uni-hannover.de, 2014-11 +% (c) Institut für Regelungstechnik, Universität Hannover + +function hdl = atlas_plot_arm_stl(T_c_urdf, lr, version) + +assert(isa(lr,'logical') && all(size(lr) == [1 1]), ... + 'Left/Right flag has to be [1x1] logical'); +assert(isa(version,'uint8') && all(size(version) == [1 1]), ... + 'version number has to be [1x1] uint8'); + +hdl = NaN(7,1); +for j = 1:6 + hdl(j) = atlas_plot_arm_link_stl(j, lr, version, T_c_urdf(:,:,j+1)); +end +xlabel('x [m]'); +ylabel('y [m]'); +zlabel('z [m]'); \ No newline at end of file diff --git a/robot_model/atlas_plot_frames.m b/robot_model/atlas_plot_frames.m new file mode 100644 index 0000000..bfa9e38 --- /dev/null +++ b/robot_model/atlas_plot_frames.m @@ -0,0 +1,78 @@ +% Plot Atlas arm with all frames +% +% Input: +% q +% joint angles +% LI +% Indices of the body frames to plot (see atlas_const) +% version [1x1 uint8] +% Atlas Model Version number +% T_pelvis [4x4] +% Transformation Matrix to Pelvis + +% Moritz Schappler, schappler@irt.uni-hannover.de, 2014-11 +% (c) Institut für Regelungstechnik, Universität Hannover + +function atlas_plot_frames(q, LI, version, T_pelvis) + +AS = atlas_const(version); + +%% Calculate Kinematics +T_torso_c_urdf = atlas_torso_fkine(q(AS.JI_Torso), version); + +T_legL_c_urdf = atlas_leg_fkine(q(AS.JI_lLeg), true, version); +T_legR_c_urdf = atlas_leg_fkine(q(AS.JI_rLeg), false, version); + +T_armL_c_urdf = atlas_arm_fkine(q(AS.JI_lArm), true, version); +T_armR_c_urdf = atlas_arm_fkine(q(AS.JI_rArm), false, version); + + +%% Assemble Kinematics for full Humanoid +% Consider given T_pelvis +for i = 1:size(T_torso_c_urdf,3) + T_torso_c_urdf(:,:,i) = T_pelvis * T_torso_c_urdf(:,:,i); +end + +% Leg Transformations start at pelvis +for i = 1:7 + T_legL_c_urdf(:,:,i) = T_pelvis * T_legL_c_urdf(:,:,i); + T_legR_c_urdf(:,:,i) = T_pelvis * T_legR_c_urdf(:,:,i); +end + +% Arm Transformations start at utorso +% pelvis-> utorso +for i = 1:size(T_armL_c_urdf,3) + T_armL_c_urdf(:,:,i) = T_torso_c_urdf(:,:,4) * T_armL_c_urdf(:,:,i); + T_armR_c_urdf(:,:,i) = T_torso_c_urdf(:,:,4) * T_armR_c_urdf(:,:,i); +end + +%% Plot Frames + +for i = LI + % left Arm + name = strrep(AS.LN{i}, '_', '\\_'); + if any(i==AS.LI_lArm) + SegmentNr = i-AS.LI_lArm(1)+1; + trplot(T_armL_c_urdf(:,:,SegmentNr+1), 'frame', name, 'arrow', 'rgb', 'length', 0.3) + end + % right Arm + if any(i==AS.LI_rArm) + SegmentNr = i-AS.LI_rArm(1)+1; + trplot(T_armR_c_urdf(:,:,SegmentNr+1), 'frame', name, 'arrow', 'rgb', 'length', 0.3) + end + % left Leg + if any(i==AS.LI_lLeg) + SegmentNr = i-AS.LI_lLeg(1)+1; + trplot(T_legL_c_urdf(:,:,SegmentNr+1), 'frame', name, 'arrow', 'rgb', 'length', 0.3) + end + % right Leg + if any(i==AS.LI_rLeg) + SegmentNr = i-AS.LI_rLeg(1)+1; + trplot(T_legR_c_urdf(:,:,SegmentNr+1), 'frame', name, 'arrow', 'rgb', 'length', 0.3) + end + if any(i==AS.LI_Torso) + SegmentNr = i-AS.LI_Torso(1)+1; + trplot(T_torso_c_urdf(:,:,SegmentNr), 'frame', name, 'arrow', 'rgb', 'length', 0.3) + end + % text_opts', {'interpreter', 'none'} +end diff --git a/robot_model/atlas_plot_leg_link_stl.m b/robot_model/atlas_plot_leg_link_stl.m new file mode 100644 index 0000000..9296efc --- /dev/null +++ b/robot_model/atlas_plot_leg_link_stl.m @@ -0,0 +1,59 @@ +% Plot one leg link of the Atlas model with STL files from drcsim +% +% Input: +% j +% Number of Robot Leg Segment +% lr +% true = left, false = right +% version [1x1 uint8] +% Atlas Model Version number +% T_b_urdf +% Body frame in urdf coordinates +% +% Output: +% hdl +% handle to the created patch object +% +% Sources: +% [1] Atlas Simulator STL files + +% Moritz Schappler, schappler@irt.uni-hannover.de, 2014-11 +% (c) Institut für Regelungstechnik, Universität Hannover + + +function hdl = atlas_plot_leg_link_stl(j, lr, version, T_b_urdf) + +%% Init +STLpath = fileparts(which('atlas_stl_location')); + +AS = atlas_const(version, lr); +%% Assemble Filename +if version == 3 % the same STL files for both versions + STLpath = fullfile(STLpath, 'meshes_v3'); +elseif version == 4 || version == 5 + STLpath = fullfile(STLpath, 'meshes_unplugged'); +else + error('Version %d not implemented yet', version); +end + +filename = [AS.LN{AS.LI_Leg(j)}, '.stl']; + +%% read STL +[v, f, n, c, ~] = stlread(fullfile(STLpath, filename), 0); + +%% Move and rotate to link reference frame +for i = 1:size(n,1) + n(i,:) = (T_b_urdf(1:3,1:3)*n(i,:)')'; +end +for i = 1:size(v,1) + v(i,:) = (eye(3,4)*T_b_urdf*[v(i,:)';1])'; +end + +%% Plot +% Define colors +Arm_Colors = {'r', 'g', 'b', 'c', 'm', 'y', 'k'}; + +% draw STL +hdl = patch('Faces', f, 'Vertices', v,'FaceVertexCData',c, ... + 'FaceColor', 'k', 'FaceAlpha', 0.53, ... + 'EdgeColor', Arm_Colors{j}, 'EdgeAlpha', 0.54); \ No newline at end of file diff --git a/robot_model/atlas_plot_leg_stl.m b/robot_model/atlas_plot_leg_stl.m new file mode 100644 index 0000000..dd1ced7 --- /dev/null +++ b/robot_model/atlas_plot_leg_stl.m @@ -0,0 +1,26 @@ +% Plot the complete Atlas leg model with STL files from drcsim +% +% Input: +% T_c_urdf [4x4x11] +% Body frames in urdf coordinates (from atlas_dirkin_urdf function) +% lr +% true = left, false = right +% version [1x1 uint8] +% Atlas Model Version number +% +% Output: +% hdl +% handle to the created patch object +% +% Sources: +% [1] Baxter Simulator STL files + +% Moritz Schappler, schappler@irt.uni-hannover.de, 2014-11 +% (c) Institut für Regelungstechnik, Universität Hannover + +function hdl = atlas_plot_leg_stl(T_c_urdf, lr, version) + +hdl = NaN(6,1); +for j = 1:6 + hdl(j) = atlas_plot_leg_link_stl(j, lr, version, T_c_urdf(:,:,j+1)); +end \ No newline at end of file diff --git a/robot_model/atlas_plot_robot.m b/robot_model/atlas_plot_robot.m new file mode 100644 index 0000000..18a16d8 --- /dev/null +++ b/robot_model/atlas_plot_robot.m @@ -0,0 +1,86 @@ +% Plot Atlas arm CAD Models +% +% Input: +% q [1x28] +% joint angles [rad] +% Order: See data/atlas_const.m +% version +% Atlas Model Version +% fignr +% Figure Handle to plot in +% T_pelvis +% Transformation Matrix to Pelvis +% subplotInf +% information for subplot [row x col x number], +% Source: +% [1] Atlas Message Format from DRCSim +% https://bitbucket.org/osrf/drcsim/src/c028afcf24728fb5bfbe57a9f3648c23ab711b39/atlas_msgs/msg/AtlasState.msg?at=default + +% Moritz Schappler, schappler@irt.uni-hannover.de, 2014-11 +% (c) Institut für Regelungstechnik, Universität Hannover + +function hdl = atlas_plot_robot(q, version, fignr, T_pelvis,subplotInf) + +AS = atlas_const(version); +hdl = NaN(AS.NJ+1,1); +%% Set Default Input +if nargin == 0 + q = zeros(1,AS.NJ); +end + +if nargin < 2 + version = 3; +end +if nargin < 3 + figure(1);set(1, 'Name', '5:Frame', 'NumberTitle', 'off'); + hold on; grid on;axis equal;view(3);set(1, 'Renderer','OpenGL') +else + figure(fignr); +end + +if nargin < 4 + T_pelvis = eye(4); +end + +if nargin < 5 + % no subplot +else + subplot(subplotInf); +end + +%% Calculate Kinematics +T_torso_c_urdf = atlas_torso_fkine(q(AS.JI_Torso), version); + +T_legL_c_urdf = atlas_leg_fkine(q(AS.JI_lLeg), true, version); +T_legR_c_urdf = atlas_leg_fkine(q(AS.JI_rLeg), false, version); + +T_armL_c_urdf = atlas_arm_fkine(q(AS.JI_lArm), true, version); +T_armR_c_urdf = atlas_arm_fkine(q(AS.JI_rArm), false, version); + +%% Assemble Kinematics for full Humanoid +% Consider given T_pelvis +for i = 1:size(T_torso_c_urdf,3) + T_torso_c_urdf(:,:,i) = T_pelvis * T_torso_c_urdf(:,:,i); +end + +% Leg Transformations start at pelvis +for i = 1:size(T_legL_c_urdf,3) + T_legL_c_urdf(:,:,i) = T_pelvis * T_legL_c_urdf(:,:,i); + T_legR_c_urdf(:,:,i) = T_pelvis * T_legR_c_urdf(:,:,i); +end + +% Arm Transformations start at utorso +% pelvis-> utorso +for i = 1:size(T_armL_c_urdf,3) + T_armL_c_urdf(:,:,i) = T_torso_c_urdf(:,:,4) * T_armL_c_urdf(:,:,i); + T_armR_c_urdf(:,:,i) = T_torso_c_urdf(:,:,4) * T_armR_c_urdf(:,:,i); +end + +%% Plot +hdl(AS.LI_Torso)=atlas_plot_torso_stl(T_torso_c_urdf, version); + +hdl(AS.LI_lLeg)=atlas_plot_leg_stl(T_legL_c_urdf, true, version); +hdl(AS.LI_rLeg)=atlas_plot_leg_stl(T_legR_c_urdf, false, version); + +hdl(AS.LI_lArm)=atlas_plot_arm_stl(T_armL_c_urdf, true, version); +hdl(AS.LI_rArm)=atlas_plot_arm_stl(T_armR_c_urdf, false, version); diff --git a/robot_model/atlas_plot_torso_link_stl.m b/robot_model/atlas_plot_torso_link_stl.m new file mode 100644 index 0000000..24d883b --- /dev/null +++ b/robot_model/atlas_plot_torso_link_stl.m @@ -0,0 +1,53 @@ +% Plot one torso link of the Atlas model with STL files from drcsim +% +% Input: +% j +% Number of Robot Body +% version +% Atlas Model Version +% T_b_urdf +% Body frame in urdf coordinates +% +% Output: +% hdl +% handle to the created patch object +% +% Sources: +% [1] Atlas Simulator STL files + +% Moritz Schappler, schappler@irt.uni-hannover.de, 2014-11 +% (c) Institut für Regelungstechnik, Universität Hannover + + +function hdl = atlas_plot_torso_link_stl(j, version, T_b_urdf) + +%% Init + +STLpath = fileparts(which('atlas_stl_location')); +AS = atlas_const(version); + +%% Assemble Filename +if version == 3 % the same STL files for both versions + STLpath = fullfile(STLpath, 'meshes_v3'); +elseif version == 4 || version == 5 + STLpath = fullfile(STLpath, 'meshes_unplugged'); +else + error('Version %d not implemented yet', version); +end +filename = [AS.LN{AS.LI_Torso(j)}, '.stl']; + +%% read STL +[version, f, n, c, ~] = stlread(fullfile(STLpath, filename), 0); + +%% Move and rotate to link reference frame +for i = 1:size(n,1) + n(i,:) = (T_b_urdf(1:3,1:3)*n(i,:)')'; +end +for i = 1:size(version,1) + version(i,:) = (eye(3,4)*T_b_urdf*[version(i,:)';1])'; +end + +% draw STL (grey color for torso) +hdl = patch('Faces', f, 'Vertices', version,'FaceVertexCData',c, ... + 'FaceColor', [0.5, 0.5, 0.5], 'FaceAlpha', 0.53, ... + 'EdgeColor', [0.2, 0.2, 0.2], 'EdgeAlpha', 0.54); \ No newline at end of file diff --git a/robot_model/atlas_plot_torso_stl.m b/robot_model/atlas_plot_torso_stl.m new file mode 100644 index 0000000..8c627e8 --- /dev/null +++ b/robot_model/atlas_plot_torso_stl.m @@ -0,0 +1,24 @@ +% Plot the complete Atlas arm model with STL files from drcsim +% +% Input: +% T_c_urdf [4x4x11] +% Body frames in urdf coordinates (from atlas_dirkin_urdf function) +% version [1x1 uint8] +% Atlas Model Version number +% +% Output: +% hdl +% handle to the created patch object +% +% Sources: +% [1] Atlas Simulator STL files + +% Moritz Schappler, schappler@irt.uni-hannover.de, 2014-11 +% (c) Institut für Regelungstechnik, Universität Hannover + +function hdl = atlas_plot_torso_stl(T_c_urdf, version) + +hdl = NaN(5,1); +for j = 1:5 + hdl(j) = atlas_plot_torso_link_stl(j, version, T_c_urdf(:,:,j)); +end \ No newline at end of file diff --git a/robot_model/atlas_torso_fkine.m b/robot_model/atlas_torso_fkine.m new file mode 100644 index 0000000..184093f --- /dev/null +++ b/robot_model/atlas_torso_fkine.m @@ -0,0 +1,68 @@ +% Calculate Forward Kinematics for Atlas Robot Torso (all versions) +% +% Input: +% q [1x4] +% Joint Angles [rad] +% version [1x1 uint8] +% Version of the robot (e.g. 3 or 4) +% +% Output: +% T_c_urdf [4x4x5] +% homogenious transformation matrices for each body frame +% 1: pelvis -> pelvis +% 2: pelvis -> ltorso +% 3: pelvis -> mtorso +% 4: pelvis -> utorso +% 5: pelvis -> head +% +% Sources: +% [1] atlas_v3.urdf + +% Moritz Schappler, schappler@irt.uni-hannover.de, 2015-01 +% (c) Institut für Regelungstechnik, Leibniz Universität Hannover + + +function T_c_urdf = atlas_torso_fkine(q, version) +%% Init +%#codegen +% Coder Information +assert(isa(q,'double') && isreal(q) && all(size(q) == [1 4]), ... + 'Joint angles q have to be [1x4] double'); +assert(isa(version,'uint8') && all(size(version) == [1 1]), ... + 'version number has to be [1x1] uint8'); + +%% Parameters +p_num = atlas_torso_parameter_urdf(version); + +%% Frame to Frame Transformations +T_urdf = NaN(4,4,4); + +% T_urdf: Overview over the indices +% 1 back_bkz: pelvis -> ltorso +% 2 back_bky: ltorso -> mtorso +% 3 back_bkx: mtorso -> utorso +% 4 neck_ry: utorso -> head + + +% 1 back_bkz: pelvis -> ltorso +T_urdf(:,:,1) = transl([p_num(1), 0, 0]) * trotz(q(1)); + +% 2 back_bky: ltorso -> mtorso +T_urdf(:,:,2) = transl([0, 0, p_num(2)]) * troty(q(2)); + +% 3 back_bkx: mtorso -> utorso +T_urdf(:,:,3) = transl([0, 0, p_num(3)]) * trotx(q(3)); + +% 4 neck_ry: utorso -> head +T_urdf(:,:,4) = transl([p_num(4), 0, p_num(5)]) * troty(q(4)); + + +%% Kumulierte Transformationsmatrizen +T_c_urdf = NaN(4,4,5); +T_c_urdf(:,:,1) = eye(4); + +for j = 2:5 + T_c_urdf(:,:,j) = T_c_urdf(:,:,j-1) * T_urdf(:,:,j-1); +end + +end diff --git a/robot_model/atlas_torso_parameter_urdf.m b/robot_model/atlas_torso_parameter_urdf.m new file mode 100644 index 0000000..c82c463 --- /dev/null +++ b/robot_model/atlas_torso_parameter_urdf.m @@ -0,0 +1,37 @@ +% Return Parameter of the Atlas Robot (all versions) (hard coded) +% +% Input: +% +% Output: +% p_num [1x5] +% Numeric Values of Kinematic Parameters +% rSges_num [5x3] +% Center of Gravity of all independent bodies (torso only) in urdf frames +% m_num [5x1] +% masses of all independent bodies (torso only) +% Iges_num [5x6] +% inertia of all independent bodies (torso only) +% rows: bodies +% columns: inertia tensor entries. Order: xx, yy, zz, xy, xz, yz +% +% Sources: +% [1] atlas_v3.urdf + +% Moritz Schappler, schappler@irt.uni-hannover.de, 2014-11 +% (c) Institut für Regelungstechnik, Leibniz Universität Hannover + +function [p_num, rSges_num, m_num, Iges_num] = atlas_torso_parameter_urdf(version) + +assert(isa(version,'uint8') && all(size(version) == [1 1]), ... + 'version to be [1x1] uint8'); + +%% URDF Parameter +if version == 3 + [p_num, rSges_num, m_num, Iges_num] = atlas3_torso_parameter_urdf(); +elseif version == 4 + [p_num, rSges_num, m_num, Iges_num] = atlas4_torso_parameter_urdf(); +elseif version == 5 + [p_num, rSges_num, m_num, Iges_num] = atlas5_torso_parameter_urdf(); +else + error('Version %d not implemented', version); +end \ No newline at end of file diff --git a/run_all_simulation_scripts.m b/run_all_simulation_scripts.m new file mode 100644 index 0000000..e3b763d --- /dev/null +++ b/run_all_simulation_scripts.m @@ -0,0 +1,18 @@ +% Run all scripts which reproduce the simulation figures in this repository + +% Moritz Schappler, schappler@irt.uni-hannover.de, 2020-12 +% (C) Institut für Regelungstechnik, Leibniz Universität Hannover + +clear +clc +close all + +tb_path = fileparts(which('drc_paper_path_init.m')); +sim_path = fullfile(tb_path, 'paper', 'simulations'); +run(fullfile(sim_path, 'atlas_joint_impctrl_sqrt_damping_test_extforce_comp.m')); +tb_path = fileparts(which('drc_paper_path_init.m')); +sim_path = fullfile(tb_path, 'paper', 'simulations'); +run(fullfile(sim_path, 'atlas_joint_impctrl_sqrt_damping_test_extforce_noise.m')); +tb_path = fileparts(which('drc_paper_path_init.m')); +sim_path = fullfile(tb_path, 'paper', 'simulations'); +run(fullfile(sim_path, 'atlas_joint_impctrl_sqrt_damping_test_extforce_noise_plot.m')); \ No newline at end of file diff --git a/simulink/atlas_dynamic_library.mdl b/simulink/atlas_dynamic_library.mdl new file mode 100644 index 0000000..583f428 --- /dev/null +++ b/simulink/atlas_dynamic_library.mdl @@ -0,0 +1,22619 @@ +Library { + Name "atlas_dynamic_library" + Version 8.4 + MdlSubVersion 0 + SavedCharacterEncoding "UTF-8" + LibraryType "BlockLibrary" + ScopeRefreshTime 0.035000 + OverrideScopeRefreshTime on + DisableAllScopes off + FPTRunName "Run 1" + MaxMDLFileLineLength 120 + Object { + $PropName "BdWindowsInfo" + $ObjectID 1 + $ClassName "Simulink.BDWindowsInfo" + Object { + $PropName "WindowsInfo" + $ObjectID 2 + $ClassName "Simulink.WindowInfo" + IsActive [1] + Location [65.0, 30.0, 1855.0, 1056.0] + Object { + $PropName "ModelBrowserInfo" + $ObjectID 3 + $ClassName "Simulink.ModelBrowserInfo" + Visible [0] + DockPosition "Left" + Width [50] + Height [50] + Filter [59] + } + Object { + $PropName "ExplorerBarInfo" + $ObjectID 4 + $ClassName "Simulink.ExplorerBarInfo" + Visible [1] + } + Object { + $PropName "EditorsInfo" + $ObjectID 5 + $ClassName "Simulink.EditorInfo" + IsActive [1] + ViewObjType "SimulinkSubsys" + LoadSaveID "422" + Extents [1793.0, 833.0] + ZoomFactor [1.0] + Offset [0.0, 0.0] + } + } + } + Created "Mon Oct 20 14:12:47 2014" + Creator "schappler" + UpdateHistory "UpdateHistoryNever" + ModifiedByFormat "%" + LastModifiedBy "vorndamme" + ModifiedDateFormat "%" + LastModifiedDate "Mon May 04 23:12:13 2015" + RTWModifiedTimeStamp 352681913 + ModelVersionFormat "1.%" + ConfigurationManager "none" + SampleTimeColors off + SampleTimeAnnotations off + LibraryLinkDisplay "all" + WideLines off + ShowLineDimensions off + ShowPortDataTypes off + ShowDesignRanges off + ShowLoopsOnError on + IgnoreBidirectionalLines off + ShowStorageClass off + ShowTestPointIcons on + ShowSignalResolutionIcons on + ShowViewerIcons on + SortedOrder off + ExecutionContextIcon off + ShowLinearizationAnnotations on + ShowMarkup on + BlockNameDataTip off + BlockParametersDataTip off + BlockDescriptionStringDataTip off + ToolBar on + StatusBar on + BrowserShowLibraryLinks on + BrowserLookUnderMasks on + SimulationMode "normal" + PauseTimes "5" + NumberOfSteps 1 + SnapshotBufferSize 10 + SnapshotInterval 10 + NumberOfLastSnapshots 0 + LinearizationMsg "none" + Profile off + ParamWorkspaceSource "MATLABWorkspace" + RecordCoverage off + CovSaveName "covdata" + CovMetricSettings "dw" + CovNameIncrementing off + CovHtmlReporting on + CovForceBlockReductionOff on + CovEnableCumulative on + covSaveCumulativeToWorkspaceVar on + CovSaveSingleToWorkspaceVar on + CovCumulativeReport off + CovReportOnPause on + CovModelRefEnable "Off" + CovExternalEMLEnable off + CovSFcnEnable off + CovBoundaryAbsTol 0.000010 + CovBoundaryRelTol 0.010000 + CovUseTimeInterval off + CovStartTime 0 + CovStopTime 0 + ExtModeBatchMode off + ExtModeEnableFloating on + ExtModeTrigType "manual" + ExtModeTrigMode "normal" + ExtModeTrigPort "1" + ExtModeTrigElement "any" + ExtModeTrigDuration 1000 + ExtModeTrigDurationFloating "auto" + ExtModeTrigHoldOff 0 + ExtModeTrigDelay 0 + ExtModeTrigDirection "rising" + ExtModeTrigLevel 0 + ExtModeArchiveMode "off" + ExtModeAutoIncOneShot off + ExtModeIncDirWhenArm off + ExtModeAddSuffixToVar off + ExtModeWriteAllDataToWs off + ExtModeArmWhenConnect on + ExtModeSkipDownloadWhenConnect off + ExtModeLogAll on + ExtModeAutoUpdateStatusClock on + ShowModelReferenceBlockVersion off + ShowModelReferenceBlockIO off + Array { + Type "Handle" + Dimension 1 + Simulink.ConfigSet { + $ObjectID 6 + Version "1.14.3" + Array { + Type "Handle" + Dimension 8 + Simulink.SolverCC { + $ObjectID 7 + Version "1.14.3" + StartTime "0.0" + StopTime "10.0" + AbsTol "auto" + FixedStep "auto" + InitialStep "auto" + MaxNumMinSteps "-1" + MaxOrder 5 + ZcThreshold "auto" + ConsecutiveZCsStepRelTol "10*128*eps" + MaxConsecutiveZCs "1000" + ExtrapolationOrder 4 + NumberNewtonIterations 1 + MaxStep "auto" + MinStep "auto" + MaxConsecutiveMinStep "1" + RelTol "1e-3" + SolverMode "Auto" + EnableConcurrentExecution off + ConcurrentTasks off + Solver "ode45" + SolverName "ode45" + SolverJacobianMethodControl "auto" + ShapePreserveControl "DisableAll" + ZeroCrossControl "UseLocalSettings" + ZeroCrossAlgorithm "Nonadaptive" + AlgebraicLoopSolver "TrustRegion" + SolverResetMethod "Fast" + PositivePriorityOrder off + AutoInsertRateTranBlk off + SampleTimeConstraint "Unconstrained" + InsertRTBMode "Whenever possible" + } + Simulink.DataIOCC { + $ObjectID 8 + Version "1.14.3" + Decimation "1" + ExternalInput "[t, u]" + FinalStateName "xFinal" + InitialState "xInitial" + LimitDataPoints on + MaxDataPoints "1000" + LoadExternalInput off + LoadInitialState off + SaveFinalState off + SaveCompleteFinalSimState off + SaveFormat "Array" + SignalLoggingSaveFormat "Dataset" + SaveOutput on + SaveState off + SignalLogging on + DSMLogging on + InspectSignalLogs off + VisualizeSimOutput on + SaveTime on + ReturnWorkspaceOutputs off + StateSaveName "xout" + TimeSaveName "tout" + OutputSaveName "yout" + SignalLoggingName "logsout" + DSMLoggingName "dsmout" + OutputOption "RefineOutputTimes" + OutputTimes "[]" + ReturnWorkspaceOutputsName "out" + Refine "1" + } + Simulink.OptimizationCC { + $ObjectID 9 + Version "1.14.3" + Array { + Type "Cell" + Dimension 8 + Cell "BooleansAsBitfields" + Cell "PassReuseOutputArgsAs" + Cell "PassReuseOutputArgsThreshold" + Cell "ZeroExternalMemoryAtStartup" + Cell "ZeroInternalMemoryAtStartup" + Cell "OptimizeModelRefInitCode" + Cell "NoFixptDivByZeroProtection" + Cell "UseSpecifiedMinMax" + PropName "DisabledProps" + } + BlockReduction on + BooleanDataType on + ConditionallyExecuteInputs on + InlineParams off + UseDivisionForNetSlopeComputation "Off" + UseFloatMulNetSlope off + DefaultUnderspecifiedDataType "double" + UseSpecifiedMinMax off + InlineInvariantSignals off + OptimizeBlockIOStorage on + BufferReuse on + EnhancedBackFolding off + CachingGlobalReferences off + GlobalBufferReuse on + StrengthReduction off + ExpressionFolding on + BooleansAsBitfields off + BitfieldContainerType "uint_T" + EnableMemcpy on + MemcpyThreshold 64 + PassReuseOutputArgsAs "Structure reference" + ExpressionDepthLimit 128 + FoldNonRolledExpr on + LocalBlockOutputs on + RollThreshold 5 + SystemCodeInlineAuto off + StateBitsets off + DataBitsets off + ActiveStateOutputEnumStorageType "Native Integer" + UseTempVars off + ZeroExternalMemoryAtStartup on + ZeroInternalMemoryAtStartup on + InitFltsAndDblsToZero off + NoFixptDivByZeroProtection off + EfficientFloat2IntCast off + EfficientMapNaN2IntZero on + OptimizeModelRefInitCode off + LifeSpan "inf" + MaxStackSize "Inherit from target" + BufferReusableBoundary on + SimCompilerOptimization "Off" + AccelVerboseBuild off + ParallelExecutionInRapidAccelerator on + } + Simulink.DebuggingCC { + $ObjectID 10 + Version "1.14.3" + RTPrefix "error" + ConsistencyChecking "none" + ArrayBoundsChecking "none" + SignalInfNanChecking "none" + SignalRangeChecking "none" + ReadBeforeWriteMsg "UseLocalSettings" + WriteAfterWriteMsg "UseLocalSettings" + WriteAfterReadMsg "UseLocalSettings" + AlgebraicLoopMsg "warning" + ArtificialAlgebraicLoopMsg "warning" + SaveWithDisabledLinksMsg "warning" + SaveWithParameterizedLinksMsg "warning" + CheckSSInitialOutputMsg on + UnderspecifiedInitializationDetection "Simplified" + MergeDetectMultiDrivingBlocksExec "error" + CheckExecutionContextPreStartOutputMsg off + CheckExecutionContextRuntimeOutputMsg off + SignalResolutionControl "UseLocalSettings" + BlockPriorityViolationMsg "warning" + MinStepSizeMsg "warning" + TimeAdjustmentMsg "none" + MaxConsecutiveZCsMsg "error" + MaskedZcDiagnostic "warning" + IgnoredZcDiagnostic "warning" + SolverPrmCheckMsg "warning" + InheritedTsInSrcMsg "warning" + DiscreteInheritContinuousMsg "warning" + MultiTaskDSMMsg "error" + MultiTaskCondExecSysMsg "error" + MultiTaskRateTransMsg "error" + SingleTaskRateTransMsg "none" + TasksWithSamePriorityMsg "warning" + SigSpecEnsureSampleTimeMsg "warning" + CheckMatrixSingularityMsg "none" + IntegerOverflowMsg "warning" + Int32ToFloatConvMsg "warning" + ParameterDowncastMsg "error" + ParameterOverflowMsg "error" + ParameterUnderflowMsg "none" + ParameterPrecisionLossMsg "warning" + ParameterTunabilityLossMsg "warning" + FixptConstUnderflowMsg "none" + FixptConstOverflowMsg "none" + FixptConstPrecisionLossMsg "none" + UnderSpecifiedDataTypeMsg "none" + UnnecessaryDatatypeConvMsg "none" + VectorMatrixConversionMsg "none" + InvalidFcnCallConnMsg "error" + FcnCallInpInsideContextMsg "EnableAllAsError" + SignalLabelMismatchMsg "none" + UnconnectedInputMsg "warning" + UnconnectedOutputMsg "warning" + UnconnectedLineMsg "warning" + SFcnCompatibilityMsg "none" + FrameProcessingCompatibilityMsg "warning" + UniqueDataStoreMsg "none" + BusObjectLabelMismatch "warning" + RootOutportRequireBusObject "warning" + AssertControl "UseLocalSettings" + EnableOverflowDetection off + ModelReferenceIOMsg "none" + ModelReferenceMultiInstanceNormalModeStructChecksumCheck "error" + ModelReferenceVersionMismatchMessage "none" + ModelReferenceIOMismatchMessage "none" + ModelReferenceCSMismatchMessage "none" + UnknownTsInhSupMsg "warning" + ModelReferenceDataLoggingMessage "warning" + ModelReferenceSymbolNameMessage "warning" + ModelReferenceExtraNoncontSigs "error" + StateNameClashWarn "none" + SimStateInterfaceChecksumMismatchMsg "warning" + SimStateOlderReleaseMsg "error" + InitInArrayFormatMsg "warning" + StrictBusMsg "ErrorLevel1" + BusNameAdapt "WarnAndRepair" + NonBusSignalsTreatedAsBus "none" + LoggingUnavailableSignals "error" + BlockIODiagnostic "none" + SFUnusedDataAndEventsDiag "warning" + SFUnexpectedBacktrackingDiag "warning" + SFInvalidInputDataAccessInChartInitDiag "warning" + SFNoUnconditionalDefaultTransitionDiag "warning" + SFTransitionOutsideNaturalParentDiag "warning" + SFUnconditionalTransitionShadowingDiag "warning" + SFUndirectedBroadcastEventsDiag "warning" + SFTransitionActionBeforeConditionDiag "warning" + IntegerSaturationMsg "warning" + } + Simulink.HardwareCC { + $ObjectID 11 + Version "1.14.3" + ProdBitPerChar 8 + ProdBitPerShort 16 + ProdBitPerInt 32 + ProdBitPerLong 32 + ProdBitPerLongLong 64 + ProdBitPerFloat 32 + ProdBitPerDouble 64 + ProdBitPerPointer 32 + ProdLargestAtomicInteger "Char" + ProdLargestAtomicFloat "None" + ProdIntDivRoundTo "Undefined" + ProdEndianess "Unspecified" + ProdWordSize 32 + ProdShiftRightIntArith on + ProdLongLongMode off + ProdHWDeviceType "32-bit Generic" + TargetBitPerChar 8 + TargetBitPerShort 16 + TargetBitPerInt 32 + TargetBitPerLong 32 + TargetBitPerLongLong 64 + TargetBitPerFloat 32 + TargetBitPerDouble 64 + TargetBitPerPointer 32 + TargetLargestAtomicInteger "Char" + TargetLargestAtomicFloat "None" + TargetShiftRightIntArith on + TargetLongLongMode off + TargetIntDivRoundTo "Undefined" + TargetEndianess "Unspecified" + TargetWordSize 32 + TargetTypeEmulationWarnSuppressLevel 0 + TargetPreprocMaxBitsSint 32 + TargetPreprocMaxBitsUint 32 + TargetHWDeviceType "Specified" + TargetUnknown off + ProdEqTarget on + } + Simulink.ModelReferenceCC { + $ObjectID 12 + Version "1.14.3" + UpdateModelReferenceTargets "IfOutOfDateOrStructuralChange" + CheckModelReferenceTargetMessage "error" + EnableParallelModelReferenceBuilds off + ParallelModelReferenceErrorOnInvalidPool on + ParallelModelReferenceMATLABWorkerInit "None" + ModelReferenceNumInstancesAllowed "Multi" + PropagateVarSize "Infer from blocks in model" + ModelReferencePassRootInputsByReference on + ModelReferenceMinAlgLoopOccurrences off + PropagateSignalLabelsOutOfModel off + SupportModelReferenceSimTargetCustomCode off + } + Simulink.SFSimCC { + $ObjectID 13 + Version "1.14.3" + SFSimEnableDebug on + SFSimOverflowDetection on + SFSimEcho on + SimBlas on + SimCtrlC on + SimExtrinsic on + SimIntegrity on + SimUseLocalCustomCode off + SimParseCustomCode on + SimBuildMode "sf_incremental_build" + SimGenImportedTypeDefs off + } + Simulink.RTWCC { + $BackupClass "Simulink.RTWCC" + $ObjectID 14 + Version "1.14.3" + Array { + Type "Cell" + Dimension 15 + Cell "IncludeHyperlinkInReport" + Cell "GenerateTraceInfo" + Cell "GenerateTraceReport" + Cell "GenerateTraceReportSl" + Cell "GenerateTraceReportSf" + Cell "GenerateTraceReportEml" + Cell "PortableWordSizes" + Cell "GenerateWebview" + Cell "GenerateCodeMetricsReport" + Cell "GenerateCodeReplacementReport" + Cell "GenerateErtSFunction" + Cell "CreateSILPILBlock" + Cell "CodeExecutionProfiling" + Cell "CodeProfilingSaveOptions" + Cell "CodeProfilingInstrumentation" + PropName "DisabledProps" + } + SystemTargetFile "grt.tlc" + TLCOptions "" + GenCodeOnly off + MakeCommand "make_rtw" + GenerateMakefile on + PackageGeneratedCodeAndArtifacts off + PackageName "" + TemplateMakefile "grt_default_tmf" + PostCodeGenCommand "" + Description "" + GenerateReport off + SaveLog off + RTWVerbose on + RetainRTWFile off + ProfileTLC off + TLCDebug off + TLCCoverage off + TLCAssert off + ProcessScriptMode "Default" + ConfigurationMode "Optimized" + ProcessScript "" + ConfigurationScript "" + ConfigAtBuild off + RTWUseLocalCustomCode off + RTWUseSimCustomCode off + CustomSourceCode "" + CustomHeaderCode "" + CustomInclude "" + CustomSource "" + CustomLibrary "" + CustomInitializer "" + CustomTerminator "" + Toolchain "Automatically locate an installed toolchain" + BuildConfiguration "Faster Builds" + IncludeHyperlinkInReport off + LaunchReport off + PortableWordSizes off + CreateSILPILBlock "None" + CodeExecutionProfiling off + CodeExecutionProfileVariable "executionProfile" + CodeProfilingSaveOptions "SummaryOnly" + CodeProfilingInstrumentation off + SILDebugging off + TargetLang "C" + IncludeBusHierarchyInRTWFileBlockHierarchyMap off + IncludeERTFirstTime off + GenerateTraceInfo off + GenerateTraceReport off + GenerateTraceReportSl off + GenerateTraceReportSf off + GenerateTraceReportEml off + GenerateCodeInfo off + GenerateWebview off + GenerateCodeMetricsReport off + GenerateCodeReplacementReport off + RTWCompilerOptimization "Off" + RTWCustomCompilerOptimizations "" + CheckMdlBeforeBuild "Off" + CustomRebuildMode "OnUpdate" + DataInitializer "" + SharedConstantsCachingThreshold 1024 + Array { + Type "Handle" + Dimension 2 + Simulink.CodeAppCC { + $ObjectID 15 + Version "1.14.3" + Array { + Type "Cell" + Dimension 23 + Cell "IgnoreCustomStorageClasses" + Cell "IgnoreTestpoints" + Cell "InsertBlockDesc" + Cell "InsertPolySpaceComments" + Cell "SFDataObjDesc" + Cell "MATLABFcnDesc" + Cell "SimulinkDataObjDesc" + Cell "DefineNamingRule" + Cell "SignalNamingRule" + Cell "ParamNamingRule" + Cell "InternalIdentifier" + Cell "InlinedPrmAccess" + Cell "CustomSymbolStr" + Cell "CustomSymbolStrGlobalVar" + Cell "CustomSymbolStrType" + Cell "CustomSymbolStrField" + Cell "CustomSymbolStrFcn" + Cell "CustomSymbolStrFcnArg" + Cell "CustomSymbolStrBlkIO" + Cell "CustomSymbolStrTmpVar" + Cell "CustomSymbolStrMacro" + Cell "CustomSymbolStrUtil" + Cell "ReqsInCode" + PropName "DisabledProps" + } + ForceParamTrailComments off + GenerateComments on + CommentStyle "Auto" + IgnoreCustomStorageClasses on + IgnoreTestpoints off + IncHierarchyInIds off + MaxIdLength 31 + PreserveName off + PreserveNameWithParent off + ShowEliminatedStatement off + OperatorAnnotations off + IncAutoGenComments off + SimulinkDataObjDesc off + SFDataObjDesc off + MATLABFcnDesc off + IncDataTypeInIds off + MangleLength 1 + CustomSymbolStrGlobalVar "$R$N$M" + CustomSymbolStrType "$N$R$M_T" + CustomSymbolStrField "$N$M" + CustomSymbolStrFcn "$R$N$M$F" + CustomSymbolStrFcnArg "rt$I$N$M" + CustomSymbolStrBlkIO "rtb_$N$M" + CustomSymbolStrTmpVar "$N$M" + CustomSymbolStrMacro "$R$N$M" + CustomSymbolStrUtil "$N$C" + DefineNamingRule "None" + ParamNamingRule "None" + SignalNamingRule "None" + InsertBlockDesc off + InsertPolySpaceComments off + SimulinkBlockComments on + MATLABSourceComments off + EnableCustomComments off + InternalIdentifier "Shortened" + InlinedPrmAccess "Literals" + ReqsInCode off + UseSimReservedNames off + } + Simulink.GRTTargetCC { + $BackupClass "Simulink.TargetCC" + $ObjectID 16 + Version "1.14.3" + Array { + Type "Cell" + Dimension 13 + Cell "GeneratePreprocessorConditionals" + Cell "IncludeMdlTerminateFcn" + Cell "SupportNonInlinedSFcns" + Cell "SuppressErrorStatus" + Cell "ERTCustomFileBanners" + Cell "GenerateSampleERTMain" + Cell "GenerateTestInterfaces" + Cell "ModelStepFunctionPrototypeControlCompliant" + Cell "GenerateAllocFcn" + Cell "PurelyIntegerCode" + Cell "SupportComplex" + Cell "SupportAbsoluteTime" + Cell "SupportContinuousTime" + PropName "DisabledProps" + } + TargetFcnLib "ansi_tfl_table_tmw.mat" + TargetLibSuffix "" + TargetPreCompLibLocation "" + GenFloatMathFcnCalls "NOT IN USE" + TargetLangStandard "C89/C90 (ANSI)" + CodeReplacementLibrary "None" + UtilityFuncGeneration "Auto" + ERTMultiwordTypeDef "System defined" + ERTMultiwordLength 256 + MultiwordLength 2048 + GenerateFullHeader on + GenerateSampleERTMain off + GenerateTestInterfaces off + ModelReferenceCompliant on + ParMdlRefBuildCompliant on + CompOptLevelCompliant on + ConcurrentExecutionCompliant on + IncludeMdlTerminateFcn on + GeneratePreprocessorConditionals "Disable all" + CombineOutputUpdateFcns on + CombineSignalStateStructs off + SuppressErrorStatus off + ERTFirstTimeCompliant off + IncludeFileDelimiter "Auto" + ERTCustomFileBanners off + SupportAbsoluteTime on + LogVarNameModifier "rt_" + MatFileLogging on + MultiInstanceERTCode off + CodeInterfacePackaging "Nonreusable function" + SupportNonFinite on + SupportComplex on + PurelyIntegerCode off + SupportContinuousTime on + SupportNonInlinedSFcns on + SupportVariableSizeSignals off + EnableShiftOperators on + ParenthesesLevel "Nominal" + CastingMode "Nominal" + MATLABClassNameForMDSCustomization "Simulink.SoftwareTarget.GRTCustomization" + ModelStepFunctionPrototypeControlCompliant off + CPPClassGenCompliant on + AutosarCompliant off + GRTInterface off + GenerateAllocFcn off + GenerateSharedConstants on + UseMalloc off + ExtMode off + ExtModeStaticAlloc off + ExtModeTesting off + ExtModeStaticAllocSize 1000000 + ExtModeTransport 0 + ExtModeMexFile "ext_comm" + ExtModeIntrfLevel "Level1" + RTWCAPISignals off + RTWCAPIParams off + RTWCAPIStates off + RTWCAPIRootIO off + GenerateASAP2 off + MultiInstanceErrorCode "Error" + } + PropName "Components" + } + } + PropName "Components" + } + Name "Configuration" + CurrentDlgPage "Solver" + ConfigPrmDlgPosition [ 1380, 220, 2460, 860 ] + } + PropName "ConfigurationSets" + } + ExplicitPartitioning off + BlockDefaults { + ForegroundColor "black" + BackgroundColor "white" + DropShadow off + NamePlacement "normal" + FontName "Helvetica" + FontSize 10 + FontWeight "normal" + FontAngle "normal" + ShowName on + BlockRotation 0 + BlockMirror off + } + AnnotationDefaults { + HorizontalAlignment "center" + VerticalAlignment "middle" + ForegroundColor "black" + BackgroundColor "white" + DropShadow off + FontName "Helvetica" + FontSize 10 + FontWeight "normal" + FontAngle "normal" + UseDisplayTextAsClickCallback off + } + LineDefaults { + FontName "Helvetica" + FontSize 9 + FontWeight "normal" + FontAngle "normal" + } + MaskDefaults { + SelfModifiable "off" + IconFrame "on" + IconOpaque "on" + RunInitForIconRedraw "off" + IconRotate "none" + PortRotate "default" + IconUnits "autoscale" + } + MaskParameterDefaults { + Evaluate "on" + Tunable "on" + NeverSave "off" + Internal "off" + ReadOnly "off" + Enabled "on" + Visible "on" + ToolTip "on" + } + BlockParameterDefaults { + Block { + BlockType Demux + Outputs "4" + DisplayOption "none" + BusSelectionMode off + } + Block { + BlockType Inport + Port "1" + OutputFunctionCall off + OutMin "[]" + OutMax "[]" + OutDataTypeStr "Inherit: auto" + LockScale off + BusOutputAsStruct off + PortDimensions "-1" + VarSizeSig "Inherit" + SampleTime "-1" + SignalType "auto" + SamplingMode "auto" + LatchByDelayingOutsideSignal off + LatchInputForFeedbackSignals off + Interpolate on + } + Block { + BlockType Integrator + ExternalReset "none" + InitialConditionSource "internal" + InitialCondition "0" + LimitOutput off + UpperSaturationLimit "inf" + LowerSaturationLimit "-inf" + ShowSaturationPort off + ShowStatePort off + AbsoluteTolerance "auto" + IgnoreLimit off + ZeroCross on + ContinuousStateAttributes "''" + } + Block { + BlockType Outport + Port "1" + OutMin "[]" + OutMax "[]" + OutDataTypeStr "Inherit: auto" + LockScale off + BusOutputAsStruct off + PortDimensions "-1" + VarSizeSig "Inherit" + SampleTime "-1" + SignalType "auto" + SamplingMode "auto" + SourceOfInitialOutputValue "Dialog" + OutputWhenDisabled "held" + InitialOutput "[]" + } + Block { + BlockType S-Function + FunctionName "system" + SFunctionModules "''" + PortCounts "[]" + SFunctionDeploymentMode off + } + Block { + BlockType SubSystem + ShowPortLabels "FromPortIcon" + Permissions "ReadWrite" + PermitHierarchicalResolution "All" + TreatAsAtomicUnit off + MinAlgLoopOccurrences off + PropExecContextOutsideSubsystem off + CheckFcnCallInpInsideContextMsg off + SystemSampleTime "-1" + RTWSystemCode "Auto" + RTWFcnNameOpts "Auto" + RTWFileNameOpts "Auto" + FunctionInterfaceSpec "void_void" + FunctionWithSeparateData off + RTWMemSecFuncInitTerm "Inherit from model" + RTWMemSecFuncExecute "Inherit from model" + RTWMemSecDataConstants "Inherit from model" + RTWMemSecDataInternal "Inherit from model" + RTWMemSecDataParameters "Inherit from model" + SimViewingDevice off + DataTypeOverride "UseLocalSettings" + DataTypeOverrideAppliesTo "AllNumericTypes" + MinMaxOverflowLogging "UseLocalSettings" + Opaque off + MaskHideContents off + SFBlockType "NONE" + Variant off + GeneratePreprocessorConditionals off + ContentPreviewEnabled off + } + Block { + BlockType Sum + IconShape "rectangular" + Inputs "++" + CollapseMode "All dimensions" + CollapseDim "1" + InputSameDT on + AccumDataTypeStr "Inherit: Inherit via internal rule" + OutMin "[]" + OutMax "[]" + OutDataTypeStr "Inherit: Same as first input" + LockScale off + RndMeth "Floor" + SaturateOnIntegerOverflow on + SampleTime "-1" + } + Block { + BlockType Terminator + } + } + System { + Name "atlas_dynamic_library" + Location [65, 30, 1920, 1086] + Open off + ModelBrowserVisibility off + ModelBrowserWidth 200 + ScreenColor "white" + PaperOrientation "landscape" + PaperPositionMode "auto" + PaperType "A4" + PaperUnits "centimeters" + TiledPaperMargins [1.270000, 1.270000, 1.270000, 1.270000] + TiledPageScale 1 + ShowPageBoundaries off + ZoomFactor "100" + ReportName "simulink-default.rpt" + SIDHighWatermark "447" + Block { + BlockType SubSystem + Name "atlas3_arm_coriolis_vec" + SID "135" + Ports [2, 1] + Position [585, 77, 655, 128] + ZOrder 104 + TreatAsAtomicUnit on + RequestExecContextInheritance off + System { + Name "atlas3_arm_coriolis_vec" + Location [1411, 24, 2646, 1024] + Open off + ModelBrowserVisibility off + ModelBrowserWidth 200 + ScreenColor "white" + PaperOrientation "landscape" + PaperPositionMode "auto" + PaperType "A4" + PaperUnits "centimeters" + TiledPaperMargins [1.270000, 1.270000, 1.270000, 1.270000] + TiledPageScale 1 + ShowPageBoundaries off + ZoomFactor "100" + Block { + BlockType Inport + Name "q" + SID "136" + Position [20, 33, 50, 47] + ZOrder 101 + IconDisplay "Port number" + } + Block { + BlockType Inport + Name "qD" + SID "137" + Position [20, 68, 50, 82] + ZOrder 102 + Port "2" + IconDisplay "Port number" + } + Block { + BlockType SubSystem + Name "mFcn_c" + SID "127" + Ports [2, 1] + Position [70, 23, 140, 92] + ZOrder 100 + LibraryVersion "1.110" + ErrorFcn "Stateflow.Translate.translate" + PermitHierarchicalResolution "ExplicitOnly" + TreatAsAtomicUnit on + RequestExecContextInheritance off + SFBlockType "MATLAB Function" + System { + Name "mFcn_c" + Location [223, 338, 826, 833] + Open off + ModelBrowserVisibility off + ModelBrowserWidth 200 + ScreenColor "white" + PaperOrientation "landscape" + PaperPositionMode "auto" + PaperType "A4" + PaperUnits "centimeters" + TiledPaperMargins [1.270000, 1.270000, 1.270000, 1.270000] + TiledPageScale 1 + ShowPageBoundaries off + ZoomFactor "100" + SIDHighWatermark "51" + Block { + BlockType Inport + Name "q" + SID "127::1" + Position [20, 101, 40, 119] + ZOrder -1 + IconDisplay "Port number" + } + Block { + BlockType Inport + Name "qD" + SID "127::21" + Position [20, 136, 40, 154] + ZOrder 7 + Port "2" + IconDisplay "Port number" + } + Block { + BlockType Demux + Name " Demux " + SID "127::50" + Ports [1, 1] + Position [270, 230, 320, 270] + ZOrder 18 + Outputs "1" + } + Block { + BlockType S-Function + Name " SFunction " + SID "127::49" + Tag "Stateflow S-Function atlas_dynamic_library 21" + Ports [2, 2] + Position [180, 100, 230, 160] + ZOrder 17 + FunctionName "sf_sfun" + Parameters "atlas_arm_lr" + PortCounts "[2 2]" + EnableBusSupport off + Port { + PortNumber 2 + Name "tau_c" + RTWStorageClass "Auto" + DataLoggingNameMode "SignalName" + } + } + Block { + BlockType Terminator + Name " Terminator " + SID "127::51" + Position [460, 241, 480, 259] + ZOrder 19 + } + Block { + BlockType Outport + Name "tau_c" + SID "127::27" + Position [460, 101, 480, 119] + ZOrder 13 + IconDisplay "Port number" + } + Line { + ZOrder 6 + SrcBlock "q" + SrcPort 1 + Points [120, 0] + DstBlock " SFunction " + DstPort 1 + } + Line { + ZOrder 7 + SrcBlock "qD" + SrcPort 1 + DstBlock " SFunction " + DstPort 2 + } + Line { + Name "tau_c" + ZOrder 8 + Labels [0, 0] + SrcBlock " SFunction " + SrcPort 2 + DstBlock "tau_c" + DstPort 1 + } + Line { + ZOrder 9 + SrcBlock " Demux " + SrcPort 1 + DstBlock " Terminator " + DstPort 1 + } + Line { + ZOrder 10 + SrcBlock " SFunction " + SrcPort 1 + DstBlock " Demux " + DstPort 1 + } + } + } + Block { + BlockType Outport + Name "tau_c" + SID "138" + Position [160, 53, 190, 67] + ZOrder 103 + IconDisplay "Port number" + } + Line { + ZOrder 11 + SrcBlock "mFcn_c" + SrcPort 1 + DstBlock "tau_c" + DstPort 1 + } + Line { + ZOrder 10 + SrcBlock "qD" + SrcPort 1 + DstBlock "mFcn_c" + DstPort 2 + } + Line { + ZOrder 9 + SrcBlock "q" + SrcPort 1 + DstBlock "mFcn_c" + DstPort 1 + } + } + } + Block { + BlockType SubSystem + Name "atlas3_arm_energy" + SID "147" + Ports [2, 2] + Position [475, 78, 545, 127] + ZOrder 108 + TreatAsAtomicUnit on + RequestExecContextInheritance off + System { + Name "atlas3_arm_energy" + Location [960, 0, 1920, 1160] + Open off + ModelBrowserVisibility off + ModelBrowserWidth 200 + ScreenColor "white" + PaperOrientation "landscape" + PaperPositionMode "auto" + PaperType "A4" + PaperUnits "centimeters" + TiledPaperMargins [1.270000, 1.270000, 1.270000, 1.270000] + TiledPageScale 1 + ShowPageBoundaries off + ZoomFactor "100" + Block { + BlockType Inport + Name "q" + SID "148" + Position [20, 33, 50, 47] + ZOrder 86 + IconDisplay "Port number" + } + Block { + BlockType Inport + Name "qD" + SID "149" + Position [20, 63, 50, 77] + ZOrder 87 + Port "2" + IconDisplay "Port number" + } + Block { + BlockType SubSystem + Name "atlas3_arm_energy_fb" + SID "81" + Ports [2, 2] + Position [70, 23, 140, 87] + ZOrder 85 + NamePlacement "alternate" + LibraryVersion "1.32" + ErrorFcn "Stateflow.Translate.translate" + PermitHierarchicalResolution "ExplicitOnly" + TreatAsAtomicUnit on + RequestExecContextInheritance off + SFBlockType "MATLAB Function" + Object { + $PropName "MaskObject" + $ObjectID 17 + $ClassName "Simulink.Mask" + Initialization "if edit_lr == 1\n atlas_arm_lr = true; % left\nelse\n atlas_arm_lr = false; % right\nend\n" + Object { + $PropName "Parameters" + $ObjectID 18 + $ClassName "Simulink.MaskParameter" + Type "edit" + Name "edit_lr" + Prompt "Arm (left = true, right = false)" + Value "atlas_arm_lr" + } + } + System { + Name "atlas3_arm_energy_fb" + Location [223, 338, 826, 833] + Open off + ModelBrowserVisibility off + ModelBrowserWidth 200 + ScreenColor "white" + PaperOrientation "landscape" + PaperPositionMode "auto" + PaperType "A4" + PaperUnits "centimeters" + TiledPaperMargins [1.270000, 1.270000, 1.270000, 1.270000] + TiledPageScale 1 + ShowPageBoundaries off + ZoomFactor "100" + SIDHighWatermark "66" + Block { + BlockType Inport + Name "q" + SID "81::1" + Position [20, 101, 40, 119] + ZOrder -1 + IconDisplay "Port number" + } + Block { + BlockType Inport + Name "qD" + SID "81::21" + Position [20, 136, 40, 154] + ZOrder 7 + Port "2" + IconDisplay "Port number" + } + Block { + BlockType Demux + Name " Demux " + SID "81::37" + Ports [1, 1] + Position [270, 230, 320, 270] + ZOrder 13 + Outputs "1" + } + Block { + BlockType S-Function + Name " SFunction " + SID "81::36" + Tag "Stateflow S-Function atlas_dynamic_library 6" + Ports [2, 3] + Position [180, 100, 230, 180] + ZOrder 12 + FunctionName "sf_sfun" + Parameters "atlas_arm_lr" + PortCounts "[2 3]" + EnableBusSupport off + Port { + PortNumber 2 + Name "T" + RTWStorageClass "Auto" + DataLoggingNameMode "SignalName" + } + Port { + PortNumber 3 + Name "U" + RTWStorageClass "Auto" + DataLoggingNameMode "SignalName" + } + } + Block { + BlockType Terminator + Name " Terminator " + SID "81::38" + Position [460, 241, 480, 259] + ZOrder 14 + } + Block { + BlockType Outport + Name "T" + SID "81::5" + Position [460, 101, 480, 119] + ZOrder -5 + IconDisplay "Port number" + } + Block { + BlockType Outport + Name "U" + SID "81::25" + Position [460, 136, 480, 154] + ZOrder 11 + Port "2" + IconDisplay "Port number" + } + Line { + ZOrder 46 + SrcBlock "q" + SrcPort 1 + Points [120, 0] + DstBlock " SFunction " + DstPort 1 + } + Line { + ZOrder 47 + SrcBlock "qD" + SrcPort 1 + DstBlock " SFunction " + DstPort 2 + } + Line { + Name "T" + ZOrder 48 + Labels [0, 0] + SrcBlock " SFunction " + SrcPort 2 + DstBlock "T" + DstPort 1 + } + Line { + Name "U" + ZOrder 49 + Labels [0, 0] + SrcBlock " SFunction " + SrcPort 3 + DstBlock "U" + DstPort 1 + } + Line { + ZOrder 50 + SrcBlock " Demux " + SrcPort 1 + DstBlock " Terminator " + DstPort 1 + } + Line { + ZOrder 51 + SrcBlock " SFunction " + SrcPort 1 + DstBlock " Demux " + DstPort 1 + } + } + } + Block { + BlockType Outport + Name "T" + SID "150" + Position [160, 33, 190, 47] + ZOrder 88 + IconDisplay "Port number" + } + Block { + BlockType Outport + Name "U" + SID "151" + Position [160, 63, 190, 77] + ZOrder 89 + Port "2" + IconDisplay "Port number" + } + Line { + ZOrder 18 + SrcBlock "q" + SrcPort 1 + DstBlock "atlas3_arm_energy_fb" + DstPort 1 + } + Line { + ZOrder 19 + SrcBlock "qD" + SrcPort 1 + DstBlock "atlas3_arm_energy_fb" + DstPort 2 + } + Line { + ZOrder 21 + SrcBlock "atlas3_arm_energy_fb" + SrcPort 2 + DstBlock "U" + DstPort 1 + } + Line { + ZOrder 20 + SrcBlock "atlas3_arm_energy_fb" + SrcPort 1 + DstBlock "T" + DstPort 1 + } + } + } + Block { + BlockType SubSystem + Name "atlas3_arm_fordyn_rj_damping" + SID "28" + Ports [3, 3] + Position [110, 77, 280, 153] + ZOrder 61 + RequestExecContextInheritance off + Object { + $PropName "MaskObject" + $ObjectID 19 + $ClassName "Simulink.Mask" + Array { + Type "Simulink.MaskParameter" + Dimension 5 + Object { + $ObjectID 20 + Type "edit" + Name "q0" + Prompt "q0 (initial pose)" + Value "q0" + } + Object { + $ObjectID 21 + Type "edit" + Name "qD0" + Prompt "qD0 (initial velocity)" + Value "qD0" + } + Object { + $ObjectID 22 + Type "edit" + Name "d" + Prompt "d (viscous friction)" + Value "d" + } + Object { + $ObjectID 23 + Type "edit" + Name "muC" + Prompt "muC (coulomb friction)" + Value "muC" + } + Object { + $ObjectID 24 + Type "edit" + Name "atlas_arm_lr" + Prompt "atlas_arm_lr (Arm: left = true, right = false)" + Value "atlas_arm_lr" + } + PropName "Parameters" + } + Array { + Type "Simulink.dialog.Group" + Dimension 2 + Object { + $ObjectID 25 + Prompt "%" + Object { + $PropName "DialogControls" + $ObjectID 26 + $ClassName "Simulink.dialog.Text" + Prompt "%" + Name "DescTextVar" + } + Name "DescGroupVar" + } + Object { + $ObjectID 27 + Prompt "Robot Parameters" + Array { + Type "Simulink.dialog.parameter.Edit" + Dimension 5 + Object { + $ObjectID 28 + Name "q0" + } + Object { + $ObjectID 29 + Name "qD0" + } + Object { + $ObjectID 30 + Name "d" + } + Object { + $ObjectID 31 + Name "muC" + } + Object { + $ObjectID 32 + Name "atlas_arm_lr" + } + PropName "DialogControls" + } + Name "ParameterGroupVar" + } + PropName "DialogControls" + } + } + System { + Name "atlas3_arm_fordyn_rj_damping" + Location [960, 0, 1920, 1160] + Open off + ModelBrowserVisibility off + ModelBrowserWidth 200 + ScreenColor "white" + PaperOrientation "landscape" + PaperPositionMode "auto" + PaperType "A4" + PaperUnits "centimeters" + TiledPaperMargins [1.270000, 1.270000, 1.270000, 1.270000] + TiledPageScale 1 + ShowPageBoundaries off + ZoomFactor "100" + Block { + BlockType Inport + Name "tau_ext\n" + SID "29" + Position [70, 233, 100, 247] + ZOrder 61 + IconDisplay "Port number" + } + Block { + BlockType Inport + Name "tau_m" + SID "30" + Position [70, 448, 100, 462] + ZOrder 62 + Port "2" + IconDisplay "Port number" + Port { + PortNumber 1 + Name "tau_m" + RTWStorageClass "Auto" + DataLogging on + DataLoggingNameMode "SignalName" + } + } + Block { + BlockType Inport + Name "g" + SID "206" + Position [695, 398, 725, 412] + ZOrder 125 + BlockMirror on + Port "3" + IconDisplay "Port number" + } + Block { + BlockType Integrator + Name "Integrator" + SID "5" + Ports [1, 1] + Position [335, 85, 365, 115] + ZOrder 36 + InitialCondition "qD0" + Port { + PortNumber 1 + Name "qD" + RTWStorageClass "Auto" + DataLogging on + DataLoggingNameMode "SignalName" + } + } + Block { + BlockType Integrator + Name "Integrator1" + SID "6" + Ports [1, 1] + Position [445, 84, 475, 116] + ZOrder 37 + InitialCondition "q0" + Port { + PortNumber 1 + Name "q" + RTWStorageClass "Auto" + DataLogging on + DataLoggingNameMode "SignalName" + } + } + Block { + BlockType Sum + Name "Sum2" + SID "13" + Ports [2, 1] + Position [180, 385, 200, 405] + ZOrder 45 + BlockRotation 270 + ShowName off + IconShape "round" + Inputs "|+-" + InputSameDT off + OutDataTypeStr "Inherit: Inherit via internal rule" + SaturateOnIntegerOverflow off + } + Block { + BlockType Sum + Name "Sum3" + SID "14" + Ports [3, 1] + Position [180, 230, 200, 250] + ZOrder 46 + BlockRotation 270 + ShowName off + IconShape "round" + Inputs "++-" + InputSameDT off + OutDataTypeStr "Inherit: Inherit via internal rule" + SaturateOnIntegerOverflow off + Port { + PortNumber 1 + Name "tau_acc" + RTWStorageClass "Auto" + DataLogging on + DataLoggingNameMode "SignalName" + } + } + Block { + BlockType Sum + Name "Sum4" + SID "15" + Ports [2, 1] + Position [180, 305, 200, 325] + ZOrder 52 + BlockRotation 270 + ShowName off + IconShape "round" + Inputs "|+-" + InputSameDT off + OutDataTypeStr "Inherit: Inherit via internal rule" + SaturateOnIntegerOverflow off + } + Block { + BlockType Reference + Name "atlas3_arm_coriolis_vec" + SID "152" + Ports [2, 1] + Position [285, 212, 355, 263] + ZOrder 105 + BlockMirror on + LibraryVersion "1.201" + SourceBlock "atlas_dynamic_library/atlas3_arm_coriolis_vec" + SourceType "SubSystem" + ContentPreviewEnabled off + Port { + PortNumber 1 + Name "tau_c" + RTWStorageClass "Auto" + DataLoggingNameMode "SignalName" + } + } + Block { + BlockType Reference + Name "atlas3_arm_gravload" + SID "153" + Ports [2, 1] + Position [285, 367, 355, 418] + ZOrder 106 + BlockMirror on + LibraryVersion "1.201" + SourceBlock "atlas_dynamic_library/atlas3_arm_gravload" + SourceType "SubSystem" + ContentPreviewEnabled off + Port { + PortNumber 1 + Name "tau_g" + RTWStorageClass "Auto" + DataLoggingNameMode "SignalName" + } + } + Block { + BlockType Reference + Name "atlas3_arm_inertia" + SID "154" + Ports [1, 1] + Position [90, 60, 160, 110] + ZOrder 107 + LibraryVersion "1.201" + SourceBlock "atlas_dynamic_library/atlas3_arm_inertia" + SourceType "SubSystem" + ContentPreviewEnabled off + } + Block { + BlockType Reference + Name "atlas_friction_model" + SID "243" + Ports [1, 1] + Position [285, 291, 355, 339] + ZOrder 132 + BlockMirror on + LibraryVersion "1.201" + SourceBlock "atlas_dynamic_library/atlas_friction_model" + SourceType "" + ContentPreviewEnabled off + muC "muC" + d "d" + Port { + PortNumber 1 + Name "tau_fr" + PropagatedSignals "tau_reib" + RTWStorageClass "Auto" + DataLoggingNameMode "SignalName" + } + } + Block { + BlockType SubSystem + Name "mFcn_Minv" + SID "19" + Ports [2, 1] + Position [210, 71, 295, 124] + ZOrder 35 + LibraryVersion "1.32" + ErrorFcn "Stateflow.Translate.translate" + PermitHierarchicalResolution "ExplicitOnly" + TreatAsAtomicUnit on + RequestExecContextInheritance off + SFBlockType "MATLAB Function" + Port { + PortNumber 1 + Name "qDD" + PropagatedSignals "q_ddot" + RTWStorageClass "Auto" + DataLogging on + DataLoggingNameMode "SignalName" + } + System { + Name "mFcn_Minv" + Location [223, 338, 826, 833] + Open off + ModelBrowserVisibility off + ModelBrowserWidth 200 + ScreenColor "white" + PaperOrientation "landscape" + PaperPositionMode "auto" + PaperType "A4" + PaperUnits "centimeters" + TiledPaperMargins [1.270000, 1.270000, 1.270000, 1.270000] + TiledPageScale 1 + ShowPageBoundaries off + ZoomFactor "100" + SIDHighWatermark "45" + Block { + BlockType Inport + Name "M" + SID "19::1" + Position [20, 101, 40, 119] + ZOrder -1 + IconDisplay "Port number" + } + Block { + BlockType Inport + Name "tau" + SID "19::21" + Position [20, 136, 40, 154] + ZOrder 7 + Port "2" + IconDisplay "Port number" + } + Block { + BlockType Demux + Name " Demux " + SID "19::38" + Ports [1, 1] + Position [270, 230, 320, 270] + ZOrder 12 + Outputs "1" + } + Block { + BlockType S-Function + Name " SFunction " + SID "19::37" + Tag "Stateflow S-Function atlas_dynamic_library 1" + Ports [2, 2] + Position [180, 100, 230, 160] + ZOrder 11 + FunctionName "sf_sfun" + PortCounts "[2 2]" + EnableBusSupport off + Port { + PortNumber 2 + Name "q_ddot" + RTWStorageClass "Auto" + DataLoggingNameMode "SignalName" + } + } + Block { + BlockType Terminator + Name " Terminator " + SID "19::39" + Position [460, 241, 480, 259] + ZOrder 13 + } + Block { + BlockType Outport + Name "q_ddot" + SID "19::5" + Position [460, 101, 480, 119] + ZOrder -5 + IconDisplay "Port number" + } + Line { + ZOrder 6 + SrcBlock "M" + SrcPort 1 + Points [120, 0] + DstBlock " SFunction " + DstPort 1 + } + Line { + ZOrder 7 + SrcBlock "tau" + SrcPort 1 + DstBlock " SFunction " + DstPort 2 + } + Line { + Name "q_ddot" + ZOrder 8 + Labels [0, 0] + SrcBlock " SFunction " + SrcPort 2 + DstBlock "q_ddot" + DstPort 1 + } + Line { + ZOrder 9 + SrcBlock " Demux " + SrcPort 1 + DstBlock " Terminator " + DstPort 1 + } + Line { + ZOrder 10 + SrcBlock " SFunction " + SrcPort 1 + DstBlock " Demux " + DstPort 1 + } + } + } + Block { + BlockType Outport + Name "q" + SID "31" + Position [695, 93, 725, 107] + ZOrder 63 + IconDisplay "Port number" + } + Block { + BlockType Outport + Name "qD" + SID "32" + Position [695, 148, 725, 162] + ZOrder 64 + Port "2" + IconDisplay "Port number" + } + Block { + BlockType Outport + Name "qDD" + SID "33" + Position [695, 48, 725, 62] + ZOrder 65 + Port "3" + IconDisplay "Port number" + } + Line { + Name "tau_g" + ZOrder 97 + Labels [0, 0] + SrcBlock "atlas3_arm_gravload" + SrcPort 1 + DstBlock "Sum2" + DstPort 2 + } + Line { + Name "q" + ZOrder 23 + Labels [-1, 0] + SrcBlock "Integrator1" + SrcPort 1 + Points [65, 0] + Branch { + ZOrder 98 + Labels [2, 1] + Points [0, -64; -470, 0] + DstBlock "atlas3_arm_inertia" + DstPort 1 + } + Branch { + ZOrder 94 + Labels [0, 1] + Points [0, 125] + DstBlock "atlas3_arm_coriolis_vec" + DstPort 1 + } + Branch { + ZOrder 19 + Labels [1, 1] + Points [67, 0] + Branch { + ZOrder 124 + Labels [1, 0] + Points [0, 280] + DstBlock "atlas3_arm_gravload" + DstPort 1 + } + Branch { + ZOrder 72 + Labels [1, 1] + DstBlock "q" + DstPort 1 + } + } + } + Line { + ZOrder 29 + SrcBlock "Sum2" + SrcPort 1 + DstBlock "Sum4" + DstPort 1 + } + Line { + Name "qDD" + ZOrder 31 + Labels [0, 0] + SrcBlock "mFcn_Minv" + SrcPort 1 + Points [13, 0] + Branch { + ZOrder 74 + Points [0, -45] + DstBlock "qDD" + DstPort 1 + } + Branch { + ZOrder 42 + DstBlock "Integrator" + DstPort 1 + } + } + Line { + ZOrder 30 + SrcBlock "Sum4" + SrcPort 1 + DstBlock "Sum3" + DstPort 2 + } + Line { + Name "tau_c" + ZOrder 95 + Labels [-1, 0] + SrcBlock "atlas3_arm_coriolis_vec" + SrcPort 1 + DstBlock "Sum3" + DstPort 3 + } + Line { + Name "tau_fr" + ZOrder 145 + Labels [0, 0] + SrcBlock "atlas_friction_model" + SrcPort 1 + DstBlock "Sum4" + DstPort 2 + } + Line { + ZOrder 70 + SrcBlock "tau_ext\n" + SrcPort 1 + DstBlock "Sum3" + DstPort 1 + } + Line { + Name "tau_m" + ZOrder 71 + Labels [0, 0] + SrcBlock "tau_m" + SrcPort 1 + Points [85, 0] + DstBlock "Sum2" + DstPort 1 + } + Line { + Name "qD" + ZOrder 12 + Labels [1, 1] + SrcBlock "Integrator" + SrcPort 1 + Points [32, 0] + Branch { + ZOrder 41 + Points [0, 55] + Branch { + ZOrder 73 + DstBlock "qD" + DstPort 1 + } + Branch { + ZOrder 8 + Labels [1, 1; -1, 0] + Points [0, 95] + Branch { + ZOrder 146 + Points [0, 65] + DstBlock "atlas_friction_model" + DstPort 1 + } + Branch { + ZOrder 93 + DstBlock "atlas3_arm_coriolis_vec" + DstPort 2 + } + } + } + Branch { + ZOrder 5 + Labels [1, 1] + DstBlock "Integrator1" + DstPort 1 + } + } + Line { + Name "tau_acc" + ZOrder 28 + Labels [0, 0] + SrcBlock "Sum3" + SrcPort 1 + Points [0, -115] + DstBlock "mFcn_Minv" + DstPort 2 + } + Line { + ZOrder 99 + SrcBlock "atlas3_arm_inertia" + SrcPort 1 + DstBlock "mFcn_Minv" + DstPort 1 + } + Line { + ZOrder 122 + SrcBlock "g" + SrcPort 1 + DstBlock "atlas3_arm_gravload" + DstPort 2 + } + } + } + Block { + BlockType SubSystem + Name "atlas3_arm_gravload" + SID "132" + Ports [2, 1] + Position [475, 157, 545, 208] + ZOrder 103 + TreatAsAtomicUnit on + RequestExecContextInheritance off + System { + Name "atlas3_arm_gravload" + Location [960, 65, 1920, 1080] + Open off + ModelBrowserVisibility off + ModelBrowserWidth 200 + ScreenColor "white" + PaperOrientation "landscape" + PaperPositionMode "auto" + PaperType "A4" + PaperUnits "centimeters" + TiledPaperMargins [1.270000, 1.270000, 1.270000, 1.270000] + TiledPageScale 1 + ShowPageBoundaries off + ZoomFactor "100" + Block { + BlockType Inport + Name "q" + SID "133" + Position [15, 33, 45, 47] + ZOrder 102 + IconDisplay "Port number" + } + Block { + BlockType Inport + Name "g" + SID "203" + Position [15, 58, 45, 72] + ZOrder 104 + Port "2" + IconDisplay "Port number" + } + Block { + BlockType SubSystem + Name "mFcn_g" + SID "128" + Ports [2, 1] + Position [70, 26, 140, 79] + ZOrder 101 + LibraryVersion "1.110" + ErrorFcn "Stateflow.Translate.translate" + PermitHierarchicalResolution "ExplicitOnly" + TreatAsAtomicUnit on + RequestExecContextInheritance off + SFBlockType "MATLAB Function" + System { + Name "mFcn_g" + Location [223, 338, 826, 833] + Open off + ModelBrowserVisibility off + ModelBrowserWidth 200 + ScreenColor "white" + PaperOrientation "landscape" + PaperPositionMode "auto" + PaperType "A4" + PaperUnits "centimeters" + TiledPaperMargins [1.270000, 1.270000, 1.270000, 1.270000] + TiledPageScale 1 + ShowPageBoundaries off + ZoomFactor "100" + SIDHighWatermark "48" + Block { + BlockType Inport + Name "q" + SID "128::1" + Position [20, 101, 40, 119] + ZOrder -1 + IconDisplay "Port number" + } + Block { + BlockType Inport + Name "g" + SID "128::48" + Position [20, 136, 40, 154] + ZOrder 16 + Port "2" + IconDisplay "Port number" + } + Block { + BlockType Demux + Name " Demux " + SID "128::46" + Ports [1, 1] + Position [270, 230, 320, 270] + ZOrder 14 + Outputs "1" + } + Block { + BlockType S-Function + Name " SFunction " + SID "128::45" + Tag "Stateflow S-Function atlas_dynamic_library 22" + Ports [2, 2] + Position [180, 100, 230, 160] + ZOrder 13 + FunctionName "sf_sfun" + Parameters "atlas_arm_lr" + PortCounts "[2 2]" + EnableBusSupport off + Port { + PortNumber 2 + Name "tau_g" + RTWStorageClass "Auto" + DataLoggingNameMode "SignalName" + } + } + Block { + BlockType Terminator + Name " Terminator " + SID "128::47" + Position [460, 241, 480, 259] + ZOrder 15 + } + Block { + BlockType Outport + Name "tau_g" + SID "128::5" + Position [460, 101, 480, 119] + ZOrder -5 + IconDisplay "Port number" + } + Line { + ZOrder 9 + SrcBlock "q" + SrcPort 1 + DstBlock " SFunction " + DstPort 1 + } + Line { + ZOrder 10 + SrcBlock "g" + SrcPort 1 + DstBlock " SFunction " + DstPort 2 + } + Line { + Name "tau_g" + ZOrder 11 + Labels [0, 0] + SrcBlock " SFunction " + SrcPort 2 + DstBlock "tau_g" + DstPort 1 + } + Line { + ZOrder 12 + SrcBlock " Demux " + SrcPort 1 + DstBlock " Terminator " + DstPort 1 + } + Line { + ZOrder 13 + SrcBlock " SFunction " + SrcPort 1 + DstBlock " Demux " + DstPort 1 + } + } + } + Block { + BlockType Outport + Name "tau_g" + SID "134" + Position [160, 48, 190, 62] + ZOrder 103 + IconDisplay "Port number" + } + Line { + ZOrder 6 + SrcBlock "q" + SrcPort 1 + DstBlock "mFcn_g" + DstPort 1 + } + Line { + ZOrder 7 + SrcBlock "mFcn_g" + SrcPort 1 + DstBlock "tau_g" + DstPort 1 + } + Line { + ZOrder 8 + SrcBlock "g" + SrcPort 1 + DstBlock "mFcn_g" + DstPort 2 + } + } + } + Block { + BlockType SubSystem + Name "atlas3_arm_inertia" + SID "129" + Ports [1, 1] + Position [585, 155, 655, 205] + ZOrder 102 + TreatAsAtomicUnit on + RequestExecContextInheritance off + System { + Name "atlas3_arm_inertia" + Location [960, 0, 1920, 1160] + Open off + ModelBrowserVisibility off + ModelBrowserWidth 200 + ScreenColor "white" + PaperOrientation "landscape" + PaperPositionMode "auto" + PaperType "A4" + PaperUnits "centimeters" + TiledPaperMargins [1.270000, 1.270000, 1.270000, 1.270000] + TiledPageScale 1 + ShowPageBoundaries off + ZoomFactor "100" + Block { + BlockType Inport + Name "q" + SID "130" + Position [20, 43, 50, 57] + ZOrder 100 + IconDisplay "Port number" + } + Block { + BlockType SubSystem + Name "mFcn_M" + SID "126" + Ports [1, 1] + Position [70, 24, 140, 76] + ZOrder 99 + LibraryVersion "1.110" + ErrorFcn "Stateflow.Translate.translate" + PermitHierarchicalResolution "ExplicitOnly" + TreatAsAtomicUnit on + RequestExecContextInheritance off + SFBlockType "MATLAB Function" + System { + Name "mFcn_M" + Location [223, 338, 826, 833] + Open off + ModelBrowserVisibility off + ModelBrowserWidth 200 + ScreenColor "white" + PaperOrientation "landscape" + PaperPositionMode "auto" + PaperType "A4" + PaperUnits "centimeters" + TiledPaperMargins [1.270000, 1.270000, 1.270000, 1.270000] + TiledPageScale 1 + ShowPageBoundaries off + ZoomFactor "100" + SIDHighWatermark "47" + Block { + BlockType Inport + Name "q" + SID "126::1" + Position [20, 101, 40, 119] + ZOrder -1 + IconDisplay "Port number" + } + Block { + BlockType Demux + Name " Demux " + SID "126::46" + Ports [1, 1] + Position [270, 230, 320, 270] + ZOrder 14 + Outputs "1" + } + Block { + BlockType S-Function + Name " SFunction " + SID "126::45" + Tag "Stateflow S-Function atlas_dynamic_library 20" + Ports [1, 2] + Position [180, 100, 230, 160] + ZOrder 13 + FunctionName "sf_sfun" + Parameters "atlas_arm_lr" + PortCounts "[1 2]" + EnableBusSupport off + Port { + PortNumber 2 + Name "M" + RTWStorageClass "Auto" + DataLoggingNameMode "SignalName" + } + } + Block { + BlockType Terminator + Name " Terminator " + SID "126::47" + Position [460, 241, 480, 259] + ZOrder 15 + } + Block { + BlockType Outport + Name "M" + SID "126::5" + Position [460, 101, 480, 119] + ZOrder -5 + IconDisplay "Port number" + } + Line { + ZOrder 5 + SrcBlock "q" + SrcPort 1 + DstBlock " SFunction " + DstPort 1 + } + Line { + Name "M" + ZOrder 6 + Labels [0, 0] + SrcBlock " SFunction " + SrcPort 2 + DstBlock "M" + DstPort 1 + } + Line { + ZOrder 7 + SrcBlock " Demux " + SrcPort 1 + DstBlock " Terminator " + DstPort 1 + } + Line { + ZOrder 8 + SrcBlock " SFunction " + SrcPort 1 + DstBlock " Demux " + DstPort 1 + } + } + } + Block { + BlockType Outport + Name "M" + SID "131" + Position [160, 43, 190, 57] + ZOrder 101 + IconDisplay "Port number" + } + Line { + ZOrder 4 + SrcBlock "q" + SrcPort 1 + DstBlock "mFcn_M" + DstPort 1 + } + Line { + ZOrder 5 + SrcBlock "mFcn_M" + SrcPort 1 + DstBlock "M" + DstPort 1 + } + } + } + Block { + BlockType SubSystem + Name "atlas3_arm_jacobig" + SID "140" + Ports [1, 1] + Position [370, 155, 440, 205] + ZOrder 106 + TreatAsAtomicUnit on + RequestExecContextInheritance off + System { + Name "atlas3_arm_jacobig" + Location [960, 0, 1920, 1160] + Open off + ModelBrowserVisibility off + ModelBrowserWidth 200 + ScreenColor "white" + PaperOrientation "landscape" + PaperPositionMode "auto" + PaperType "A4" + PaperUnits "centimeters" + TiledPaperMargins [1.270000, 1.270000, 1.270000, 1.270000] + TiledPageScale 1 + ShowPageBoundaries off + ZoomFactor "100" + Block { + BlockType Inport + Name "q" + SID "141" + Position [20, 38, 50, 52] + ZOrder 88 + IconDisplay "Port number" + } + Block { + BlockType SubSystem + Name "atlas3_arm_jacobig" + SID "83" + Ports [1, 1] + Position [70, 20, 140, 70] + ZOrder 87 + NamePlacement "alternate" + LibraryVersion "1.72" + ErrorFcn "Stateflow.Translate.translate" + PermitHierarchicalResolution "ExplicitOnly" + TreatAsAtomicUnit on + RequestExecContextInheritance off + SFBlockType "MATLAB Function" + Object { + $PropName "MaskObject" + $ObjectID 33 + $ClassName "Simulink.Mask" + Initialization "if edit_lr == 1\n atlas_arm_lr = true; % left\nelse\n atlas_arm_lr = false; % right\nend\n" + Object { + $PropName "Parameters" + $ObjectID 34 + $ClassName "Simulink.MaskParameter" + Type "edit" + Name "edit_lr" + Prompt "Arm (left = true, right = false)" + Value "atlas_arm_lr" + } + } + System { + Name "atlas3_arm_jacobig" + Location [223, 338, 826, 833] + Open off + ModelBrowserVisibility off + ModelBrowserWidth 200 + ScreenColor "white" + PaperOrientation "landscape" + PaperPositionMode "auto" + PaperType "A4" + PaperUnits "centimeters" + TiledPaperMargins [1.270000, 1.270000, 1.270000, 1.270000] + TiledPageScale 1 + ShowPageBoundaries off + ZoomFactor "100" + SIDHighWatermark "51" + Block { + BlockType Inport + Name "q" + SID "83::1" + Position [20, 101, 40, 119] + ZOrder -1 + IconDisplay "Port number" + } + Block { + BlockType Demux + Name " Demux " + SID "83::50" + Ports [1, 1] + Position [270, 230, 320, 270] + ZOrder 19 + Outputs "1" + } + Block { + BlockType S-Function + Name " SFunction " + SID "83::49" + Tag "Stateflow S-Function atlas_dynamic_library 7" + Ports [1, 2] + Position [180, 100, 230, 160] + ZOrder 18 + FunctionName "sf_sfun" + Parameters "atlas_arm_lr" + PortCounts "[1 2]" + EnableBusSupport off + Port { + PortNumber 2 + Name "JG" + RTWStorageClass "Auto" + DataLoggingNameMode "SignalName" + } + } + Block { + BlockType Terminator + Name " Terminator " + SID "83::51" + Position [460, 241, 480, 259] + ZOrder 20 + } + Block { + BlockType Outport + Name "JG" + SID "83::5" + Position [460, 101, 480, 119] + ZOrder -5 + IconDisplay "Port number" + } + Line { + ZOrder 11 + SrcBlock "q" + SrcPort 1 + DstBlock " SFunction " + DstPort 1 + } + Line { + Name "JG" + ZOrder 12 + Labels [0, 0] + SrcBlock " SFunction " + SrcPort 2 + DstBlock "JG" + DstPort 1 + } + Line { + ZOrder 13 + SrcBlock " Demux " + SrcPort 1 + DstBlock " Terminator " + DstPort 1 + } + Line { + ZOrder 14 + SrcBlock " SFunction " + SrcPort 1 + DstBlock " Demux " + DstPort 1 + } + } + } + Block { + BlockType Outport + Name "JG" + SID "142" + Position [160, 38, 190, 52] + ZOrder 89 + IconDisplay "Port number" + } + Line { + ZOrder 12 + SrcBlock "atlas3_arm_jacobig" + SrcPort 1 + DstBlock "JG" + DstPort 1 + } + Line { + ZOrder 11 + SrcBlock "q" + SrcPort 1 + DstBlock "atlas3_arm_jacobig" + DstPort 1 + } + } + } + Block { + BlockType SubSystem + Name "atlas4_arm_coriolis_vec" + SID "164" + Ports [2, 1] + Position [970, 87, 1040, 138] + ZOrder 114 + TreatAsAtomicUnit on + RequestExecContextInheritance off + System { + Name "atlas4_arm_coriolis_vec" + Location [960, 0, 1920, 1160] + Open off + ModelBrowserVisibility off + ModelBrowserWidth 200 + ScreenColor "white" + PaperOrientation "landscape" + PaperPositionMode "auto" + PaperType "A4" + PaperUnits "centimeters" + TiledPaperMargins [1.270000, 1.270000, 1.270000, 1.270000] + TiledPageScale 1 + ShowPageBoundaries off + ZoomFactor "100" + Block { + BlockType Inport + Name "q" + SID "165" + Position [20, 33, 50, 47] + ZOrder 111 + IconDisplay "Port number" + } + Block { + BlockType Inport + Name "qD" + SID "166" + Position [20, 63, 50, 77] + ZOrder 112 + Port "2" + IconDisplay "Port number" + } + Block { + BlockType SubSystem + Name "mFcn_c" + SID "156" + Ports [2, 1] + Position [70, 25, 140, 85] + ZOrder 110 + LibraryVersion "1.118" + ErrorFcn "Stateflow.Translate.translate" + PermitHierarchicalResolution "ExplicitOnly" + TreatAsAtomicUnit on + RequestExecContextInheritance off + SFBlockType "MATLAB Function" + System { + Name "mFcn_c" + Location [223, 338, 826, 833] + Open off + ModelBrowserVisibility off + ModelBrowserWidth 200 + ScreenColor "white" + PaperOrientation "landscape" + PaperPositionMode "auto" + PaperType "A4" + PaperUnits "centimeters" + TiledPaperMargins [1.270000, 1.270000, 1.270000, 1.270000] + TiledPageScale 1 + ShowPageBoundaries off + ZoomFactor "100" + SIDHighWatermark "54" + Block { + BlockType Inport + Name "q" + SID "156::1" + Position [20, 101, 40, 119] + ZOrder -1 + IconDisplay "Port number" + } + Block { + BlockType Inport + Name "qD" + SID "156::21" + Position [20, 136, 40, 154] + ZOrder 7 + Port "2" + IconDisplay "Port number" + } + Block { + BlockType Demux + Name " Demux " + SID "156::53" + Ports [1, 1] + Position [270, 230, 320, 270] + ZOrder 21 + Outputs "1" + } + Block { + BlockType S-Function + Name " SFunction " + SID "156::52" + Tag "Stateflow S-Function atlas_dynamic_library 3" + Ports [2, 2] + Position [180, 100, 230, 160] + ZOrder 20 + FunctionName "sf_sfun" + Parameters "atlas_arm_lr" + PortCounts "[2 2]" + EnableBusSupport off + Port { + PortNumber 2 + Name "tau_c" + RTWStorageClass "Auto" + DataLoggingNameMode "SignalName" + } + } + Block { + BlockType Terminator + Name " Terminator " + SID "156::54" + Position [460, 241, 480, 259] + ZOrder 22 + } + Block { + BlockType Outport + Name "tau_c" + SID "156::27" + Position [460, 101, 480, 119] + ZOrder 13 + IconDisplay "Port number" + } + Line { + ZOrder 6 + SrcBlock "q" + SrcPort 1 + Points [120, 0] + DstBlock " SFunction " + DstPort 1 + } + Line { + ZOrder 7 + SrcBlock "qD" + SrcPort 1 + DstBlock " SFunction " + DstPort 2 + } + Line { + Name "tau_c" + ZOrder 8 + Labels [0, 0] + SrcBlock " SFunction " + SrcPort 2 + DstBlock "tau_c" + DstPort 1 + } + Line { + ZOrder 9 + SrcBlock " Demux " + SrcPort 1 + DstBlock " Terminator " + DstPort 1 + } + Line { + ZOrder 10 + SrcBlock " SFunction " + SrcPort 1 + DstBlock " Demux " + DstPort 1 + } + } + } + Block { + BlockType Outport + Name "tau_c" + SID "167" + Position [160, 48, 190, 62] + ZOrder 113 + IconDisplay "Port number" + } + Line { + ZOrder 29 + SrcBlock "mFcn_c" + SrcPort 1 + DstBlock "tau_c" + DstPort 1 + } + Line { + ZOrder 27 + SrcBlock "q" + SrcPort 1 + DstBlock "mFcn_c" + DstPort 1 + } + Line { + ZOrder 28 + SrcBlock "qD" + SrcPort 1 + DstBlock "mFcn_c" + DstPort 2 + } + } + } + Block { + BlockType SubSystem + Name "atlas4_arm_fordyn_rj_damping" + SID "84" + Ports [3, 3] + Position [710, 77, 880, 153] + ZOrder 88 + RequestExecContextInheritance off + Object { + $PropName "MaskObject" + $ObjectID 35 + $ClassName "Simulink.Mask" + Array { + Type "Simulink.MaskParameter" + Dimension 5 + Object { + $ObjectID 36 + Type "edit" + Name "q0" + Prompt "q0 (initial pose)" + Value "q0" + } + Object { + $ObjectID 37 + Type "edit" + Name "qD0" + Prompt "qD0 (initial velocity)" + Value "qD0" + } + Object { + $ObjectID 38 + Type "edit" + Name "d" + Prompt "d (viscous friction)" + Value "d" + } + Object { + $ObjectID 39 + Type "edit" + Name "muC" + Prompt "muC (coulomb friction)" + Value "muC" + } + Object { + $ObjectID 40 + Type "edit" + Name "atlas_arm_lr" + Prompt "atlas_arm_lr (Arm: left = true, right = false)" + Value "atlas_arm_lr" + } + PropName "Parameters" + } + Array { + Type "Simulink.dialog.Group" + Dimension 2 + Object { + $ObjectID 41 + Prompt "%" + Object { + $PropName "DialogControls" + $ObjectID 42 + $ClassName "Simulink.dialog.Text" + Prompt "%" + Name "DescTextVar" + } + Name "DescGroupVar" + } + Object { + $ObjectID 43 + Prompt "Robot Parameters" + Array { + Type "Simulink.dialog.parameter.Edit" + Dimension 5 + Object { + $ObjectID 44 + Name "q0" + } + Object { + $ObjectID 45 + Name "qD0" + } + Object { + $ObjectID 46 + Name "d" + } + Object { + $ObjectID 47 + Name "muC" + } + Object { + $ObjectID 48 + Name "atlas_arm_lr" + } + PropName "DialogControls" + } + Name "ParameterGroupVar" + } + PropName "DialogControls" + } + } + System { + Name "atlas4_arm_fordyn_rj_damping" + Location [273, 52, 1442, 1080] + Open off + ModelBrowserVisibility off + ModelBrowserWidth 200 + ScreenColor "white" + PaperOrientation "landscape" + PaperPositionMode "auto" + PaperType "A4" + PaperUnits "centimeters" + TiledPaperMargins [1.270000, 1.270000, 1.270000, 1.270000] + TiledPageScale 1 + ShowPageBoundaries off + ZoomFactor "100" + Block { + BlockType Inport + Name "tau_ext\n" + SID "85" + Position [70, 233, 100, 247] + ZOrder 61 + IconDisplay "Port number" + } + Block { + BlockType Inport + Name "tau_m" + SID "86" + Position [70, 448, 100, 462] + ZOrder 62 + Port "2" + IconDisplay "Port number" + Port { + PortNumber 1 + Name "tau_m" + RTWStorageClass "Auto" + DataLogging on + DataLoggingNameMode "SignalName" + } + } + Block { + BlockType Inport + Name "g" + SID "205" + Position [695, 398, 725, 412] + ZOrder 125 + BlockMirror on + Port "3" + IconDisplay "Port number" + } + Block { + BlockType Integrator + Name "Integrator" + SID "88" + Ports [1, 1] + Position [335, 85, 365, 115] + ZOrder 36 + InitialCondition "qD0" + Port { + PortNumber 1 + Name "qD" + RTWStorageClass "Auto" + DataLogging on + DataLoggingNameMode "SignalName" + } + } + Block { + BlockType Integrator + Name "Integrator1" + SID "89" + Ports [1, 1] + Position [445, 84, 475, 116] + ZOrder 37 + InitialCondition "q0" + Port { + PortNumber 1 + Name "q" + RTWStorageClass "Auto" + DataLogging on + DataLoggingNameMode "SignalName" + } + } + Block { + BlockType Sum + Name "Sum2" + SID "90" + Ports [2, 1] + Position [180, 385, 200, 405] + ZOrder 45 + BlockRotation 270 + ShowName off + IconShape "round" + Inputs "|+-" + InputSameDT off + OutDataTypeStr "Inherit: Inherit via internal rule" + SaturateOnIntegerOverflow off + } + Block { + BlockType Sum + Name "Sum3" + SID "91" + Ports [3, 1] + Position [180, 230, 200, 250] + ZOrder 46 + BlockRotation 270 + ShowName off + IconShape "round" + Inputs "++-" + InputSameDT off + OutDataTypeStr "Inherit: Inherit via internal rule" + SaturateOnIntegerOverflow off + Port { + PortNumber 1 + Name "tau_acc" + RTWStorageClass "Auto" + DataLogging on + DataLoggingNameMode "SignalName" + } + } + Block { + BlockType Sum + Name "Sum4" + SID "92" + Ports [2, 1] + Position [180, 305, 200, 325] + ZOrder 52 + BlockRotation 270 + ShowName off + IconShape "round" + Inputs "|+-" + InputSameDT off + OutDataTypeStr "Inherit: Inherit via internal rule" + SaturateOnIntegerOverflow off + } + Block { + BlockType Reference + Name "atlas4_arm_coriolis_vec" + SID "168" + Ports [2, 1] + Position [285, 214, 355, 261] + ZOrder 117 + BlockMirror on + LibraryVersion "1.204" + SourceBlock "atlas_dynamic_library/atlas4_arm_coriolis_vec" + SourceType "SubSystem" + ContentPreviewEnabled off + Port { + PortNumber 1 + Name "tau_c" + RTWStorageClass "Auto" + DataLoggingNameMode "SignalName" + } + } + Block { + BlockType Reference + Name "atlas4_arm_gravload" + SID "169" + Ports [2, 1] + Position [285, 367, 355, 418] + ZOrder 116 + BlockMirror on + LibraryVersion "1.204" + SourceBlock "atlas_dynamic_library/atlas4_arm_gravload" + SourceType "SubSystem" + ContentPreviewEnabled off + Port { + PortNumber 1 + Name "tau_g" + RTWStorageClass "Auto" + DataLoggingNameMode "SignalName" + } + } + Block { + BlockType Reference + Name "atlas4_arm_inertia" + SID "170" + Ports [1, 1] + Position [90, 60, 160, 110] + ZOrder 115 + LibraryVersion "1.204" + SourceBlock "atlas_dynamic_library/atlas4_arm_inertia" + SourceType "SubSystem" + ContentPreviewEnabled off + } + Block { + BlockType Reference + Name "atlas_friction_model" + SID "242" + Ports [1, 1] + Position [285, 291, 355, 339] + ZOrder 132 + BlockMirror on + LibraryVersion "1.204" + SourceBlock "atlas_dynamic_library/atlas_friction_model" + SourceType "" + ContentPreviewEnabled off + muC "muC" + d "d" + Port { + PortNumber 1 + Name "tau_fr" + PropagatedSignals "tau_reib" + RTWStorageClass "Auto" + DataLoggingNameMode "SignalName" + } + } + Block { + BlockType SubSystem + Name "mFcn_Minv" + SID "94" + Ports [2, 1] + Position [210, 71, 295, 124] + ZOrder 35 + LibraryVersion "1.32" + ErrorFcn "Stateflow.Translate.translate" + PermitHierarchicalResolution "ExplicitOnly" + TreatAsAtomicUnit on + RequestExecContextInheritance off + SFBlockType "MATLAB Function" + Port { + PortNumber 1 + Name "qDD" + PropagatedSignals "q_ddot" + RTWStorageClass "Auto" + DataLogging on + DataLoggingNameMode "SignalName" + } + System { + Name "mFcn_Minv" + Location [223, 338, 826, 833] + Open off + ModelBrowserVisibility off + ModelBrowserWidth 200 + ScreenColor "white" + PaperOrientation "landscape" + PaperPositionMode "auto" + PaperType "A4" + PaperUnits "centimeters" + TiledPaperMargins [1.270000, 1.270000, 1.270000, 1.270000] + TiledPageScale 1 + ShowPageBoundaries off + ZoomFactor "100" + SIDHighWatermark "48" + Block { + BlockType Inport + Name "M" + SID "94::1" + Position [20, 101, 40, 119] + ZOrder -1 + IconDisplay "Port number" + } + Block { + BlockType Inport + Name "tau" + SID "94::21" + Position [20, 136, 40, 154] + ZOrder 7 + Port "2" + IconDisplay "Port number" + } + Block { + BlockType Demux + Name " Demux " + SID "94::47" + Ports [1, 1] + Position [270, 230, 320, 270] + ZOrder 15 + Outputs "1" + } + Block { + BlockType S-Function + Name " SFunction " + SID "94::46" + Tag "Stateflow S-Function atlas_dynamic_library 9" + Ports [2, 2] + Position [180, 100, 230, 160] + ZOrder 14 + FunctionName "sf_sfun" + PortCounts "[2 2]" + EnableBusSupport off + Port { + PortNumber 2 + Name "q_ddot" + RTWStorageClass "Auto" + DataLoggingNameMode "SignalName" + } + } + Block { + BlockType Terminator + Name " Terminator " + SID "94::48" + Position [460, 241, 480, 259] + ZOrder 16 + } + Block { + BlockType Outport + Name "q_ddot" + SID "94::5" + Position [460, 101, 480, 119] + ZOrder -5 + IconDisplay "Port number" + } + Line { + ZOrder 6 + SrcBlock "M" + SrcPort 1 + Points [120, 0] + DstBlock " SFunction " + DstPort 1 + } + Line { + ZOrder 7 + SrcBlock "tau" + SrcPort 1 + DstBlock " SFunction " + DstPort 2 + } + Line { + Name "q_ddot" + ZOrder 8 + Labels [0, 0] + SrcBlock " SFunction " + SrcPort 2 + DstBlock "q_ddot" + DstPort 1 + } + Line { + ZOrder 9 + SrcBlock " Demux " + SrcPort 1 + DstBlock " Terminator " + DstPort 1 + } + Line { + ZOrder 10 + SrcBlock " SFunction " + SrcPort 1 + DstBlock " Demux " + DstPort 1 + } + } + } + Block { + BlockType Outport + Name "q" + SID "97" + Position [695, 93, 725, 107] + ZOrder 63 + IconDisplay "Port number" + } + Block { + BlockType Outport + Name "qD" + SID "98" + Position [695, 148, 725, 162] + ZOrder 64 + Port "2" + IconDisplay "Port number" + } + Block { + BlockType Outport + Name "qDD" + SID "99" + Position [695, 48, 725, 62] + ZOrder 65 + Port "3" + IconDisplay "Port number" + } + Line { + Name "tau_g" + ZOrder 26 + Labels [0, 0] + SrcBlock "atlas4_arm_gravload" + SrcPort 1 + DstBlock "Sum2" + DstPort 2 + } + Line { + Name "q" + ZOrder 2 + Labels [-1, 0] + SrcBlock "Integrator1" + SrcPort 1 + Points [65, 0] + Branch { + ZOrder 32 + Labels [2, 1] + Points [0, -64; -470, 0] + DstBlock "atlas4_arm_inertia" + DstPort 1 + } + Branch { + ZOrder 29 + Labels [0, 1] + Points [0, 125] + DstBlock "atlas4_arm_coriolis_vec" + DstPort 1 + } + Branch { + ZOrder 4 + Labels [1, 1] + Points [67, 0] + Branch { + ZOrder 57 + Labels [1, 0] + Points [0, 280] + DstBlock "atlas4_arm_gravload" + DstPort 1 + } + Branch { + ZOrder 5 + Labels [1, 1] + DstBlock "q" + DstPort 1 + } + } + } + Line { + ZOrder 8 + SrcBlock "Sum2" + SrcPort 1 + DstBlock "Sum4" + DstPort 1 + } + Line { + Name "qDD" + ZOrder 9 + Labels [0, 0] + SrcBlock "mFcn_Minv" + SrcPort 1 + Points [13, 0] + Branch { + ZOrder 10 + Points [0, -45] + DstBlock "qDD" + DstPort 1 + } + Branch { + ZOrder 11 + DstBlock "Integrator" + DstPort 1 + } + } + Line { + ZOrder 12 + SrcBlock "Sum4" + SrcPort 1 + DstBlock "Sum3" + DstPort 2 + } + Line { + Name "tau_c" + ZOrder 30 + Labels [-1, 0] + SrcBlock "atlas4_arm_coriolis_vec" + SrcPort 1 + DstBlock "Sum3" + DstPort 3 + } + Line { + Name "tau_fr" + ZOrder 79 + Labels [0, 0] + SrcBlock "atlas_friction_model" + SrcPort 1 + DstBlock "Sum4" + DstPort 2 + } + Line { + ZOrder 15 + SrcBlock "tau_ext\n" + SrcPort 1 + DstBlock "Sum3" + DstPort 1 + } + Line { + Name "tau_m" + ZOrder 16 + Labels [0, 0] + SrcBlock "tau_m" + SrcPort 1 + Points [85, 0] + DstBlock "Sum2" + DstPort 1 + } + Line { + Name "qD" + ZOrder 17 + Labels [1, 1] + SrcBlock "Integrator" + SrcPort 1 + Points [32, 0] + Branch { + ZOrder 18 + Points [0, 55] + Branch { + ZOrder 19 + DstBlock "qD" + DstPort 1 + } + Branch { + ZOrder 20 + Labels [1, 1; -1, 0] + Points [0, 95] + Branch { + ZOrder 78 + Points [0, 65] + DstBlock "atlas_friction_model" + DstPort 1 + } + Branch { + ZOrder 28 + DstBlock "atlas4_arm_coriolis_vec" + DstPort 2 + } + } + } + Branch { + ZOrder 23 + Labels [1, 1] + DstBlock "Integrator1" + DstPort 1 + } + } + Line { + Name "tau_acc" + ZOrder 24 + Labels [0, 0] + SrcBlock "Sum3" + SrcPort 1 + Points [0, -115] + DstBlock "mFcn_Minv" + DstPort 2 + } + Line { + ZOrder 31 + SrcBlock "atlas4_arm_inertia" + SrcPort 1 + DstBlock "mFcn_Minv" + DstPort 1 + } + Line { + ZOrder 55 + SrcBlock "g" + SrcPort 1 + DstBlock "atlas4_arm_gravload" + DstPort 2 + } + } + } + Block { + BlockType SubSystem + Name "atlas4_arm_gravload" + SID "161" + Ports [2, 1] + Position [1075, 87, 1145, 138] + ZOrder 113 + TreatAsAtomicUnit on + RequestExecContextInheritance off + System { + Name "atlas4_arm_gravload" + Location [976, 17, 1932, 1093] + Open off + ModelBrowserVisibility off + ModelBrowserWidth 200 + ScreenColor "white" + PaperOrientation "landscape" + PaperPositionMode "auto" + PaperType "A4" + PaperUnits "centimeters" + TiledPaperMargins [1.270000, 1.270000, 1.270000, 1.270000] + TiledPageScale 1 + ShowPageBoundaries off + ZoomFactor "100" + Block { + BlockType Inport + Name "q" + SID "162" + Position [20, 33, 50, 47] + ZOrder 112 + IconDisplay "Port number" + } + Block { + BlockType Inport + Name "g" + SID "202" + Position [20, 58, 50, 72] + ZOrder 114 + Port "2" + IconDisplay "Port number" + } + Block { + BlockType SubSystem + Name "mFcn_g" + SID "157" + Ports [2, 1] + Position [70, 26, 140, 79] + ZOrder 111 + LibraryVersion "1.118" + ErrorFcn "Stateflow.Translate.translate" + PermitHierarchicalResolution "ExplicitOnly" + TreatAsAtomicUnit on + RequestExecContextInheritance off + SFBlockType "MATLAB Function" + System { + Name "mFcn_g" + Location [223, 338, 826, 833] + Open off + ModelBrowserVisibility off + ModelBrowserWidth 200 + ScreenColor "white" + PaperOrientation "landscape" + PaperPositionMode "auto" + PaperType "A4" + PaperUnits "centimeters" + TiledPaperMargins [1.270000, 1.270000, 1.270000, 1.270000] + TiledPageScale 1 + ShowPageBoundaries off + ZoomFactor "100" + SIDHighWatermark "51" + Block { + BlockType Inport + Name "q" + SID "157::1" + Position [20, 101, 40, 119] + ZOrder -1 + IconDisplay "Port number" + } + Block { + BlockType Inport + Name "g" + SID "157::51" + Position [20, 136, 40, 154] + ZOrder 19 + Port "2" + IconDisplay "Port number" + } + Block { + BlockType Demux + Name " Demux " + SID "157::49" + Ports [1, 1] + Position [270, 230, 320, 270] + ZOrder 17 + Outputs "1" + } + Block { + BlockType S-Function + Name " SFunction " + SID "157::48" + Tag "Stateflow S-Function atlas_dynamic_library 4" + Ports [2, 2] + Position [180, 100, 230, 160] + ZOrder 16 + FunctionName "sf_sfun" + Parameters "atlas_arm_lr" + PortCounts "[2 2]" + EnableBusSupport off + Port { + PortNumber 2 + Name "tau_g" + RTWStorageClass "Auto" + DataLoggingNameMode "SignalName" + } + } + Block { + BlockType Terminator + Name " Terminator " + SID "157::50" + Position [460, 241, 480, 259] + ZOrder 18 + } + Block { + BlockType Outport + Name "tau_g" + SID "157::5" + Position [460, 101, 480, 119] + ZOrder -5 + IconDisplay "Port number" + } + Line { + ZOrder 9 + SrcBlock "q" + SrcPort 1 + DstBlock " SFunction " + DstPort 1 + } + Line { + ZOrder 10 + SrcBlock "g" + SrcPort 1 + DstBlock " SFunction " + DstPort 2 + } + Line { + Name "tau_g" + ZOrder 11 + Labels [0, 0] + SrcBlock " SFunction " + SrcPort 2 + DstBlock "tau_g" + DstPort 1 + } + Line { + ZOrder 12 + SrcBlock " Demux " + SrcPort 1 + DstBlock " Terminator " + DstPort 1 + } + Line { + ZOrder 13 + SrcBlock " SFunction " + SrcPort 1 + DstBlock " Demux " + DstPort 1 + } + } + } + Block { + BlockType Outport + Name "tau_g" + SID "163" + Position [175, 48, 205, 62] + ZOrder 113 + IconDisplay "Port number" + } + Line { + ZOrder 25 + SrcBlock "mFcn_g" + SrcPort 1 + DstBlock "tau_g" + DstPort 1 + } + Line { + ZOrder 24 + SrcBlock "q" + SrcPort 1 + DstBlock "mFcn_g" + DstPort 1 + } + Line { + ZOrder 27 + SrcBlock "g" + SrcPort 1 + DstBlock "mFcn_g" + DstPort 2 + } + } + } + Block { + BlockType SubSystem + Name "atlas4_arm_inertia" + SID "158" + Ports [1, 1] + Position [1185, 90, 1255, 140] + ZOrder 112 + TreatAsAtomicUnit on + RequestExecContextInheritance off + System { + Name "atlas4_arm_inertia" + Location [960, 0, 1920, 1160] + Open off + ModelBrowserVisibility off + ModelBrowserWidth 200 + ScreenColor "white" + PaperOrientation "landscape" + PaperPositionMode "auto" + PaperType "A4" + PaperUnits "centimeters" + TiledPaperMargins [1.270000, 1.270000, 1.270000, 1.270000] + TiledPageScale 1 + ShowPageBoundaries off + ZoomFactor "100" + Block { + BlockType Inport + Name "q" + SID "159" + Position [20, 43, 50, 57] + ZOrder 110 + IconDisplay "Port number" + } + Block { + BlockType SubSystem + Name "mFcn_M" + SID "155" + Ports [1, 1] + Position [70, 24, 140, 76] + ZOrder 109 + LibraryVersion "1.118" + ErrorFcn "Stateflow.Translate.translate" + PermitHierarchicalResolution "ExplicitOnly" + TreatAsAtomicUnit on + RequestExecContextInheritance off + SFBlockType "MATLAB Function" + System { + Name "mFcn_M" + Location [223, 338, 826, 833] + Open off + ModelBrowserVisibility off + ModelBrowserWidth 200 + ScreenColor "white" + PaperOrientation "landscape" + PaperPositionMode "auto" + PaperType "A4" + PaperUnits "centimeters" + TiledPaperMargins [1.270000, 1.270000, 1.270000, 1.270000] + TiledPageScale 1 + ShowPageBoundaries off + ZoomFactor "100" + SIDHighWatermark "50" + Block { + BlockType Inport + Name "q" + SID "155::1" + Position [20, 101, 40, 119] + ZOrder -1 + IconDisplay "Port number" + } + Block { + BlockType Demux + Name " Demux " + SID "155::49" + Ports [1, 1] + Position [270, 230, 320, 270] + ZOrder 17 + Outputs "1" + } + Block { + BlockType S-Function + Name " SFunction " + SID "155::48" + Tag "Stateflow S-Function atlas_dynamic_library 2" + Ports [1, 2] + Position [180, 100, 230, 160] + ZOrder 16 + FunctionName "sf_sfun" + Parameters "atlas_arm_lr" + PortCounts "[1 2]" + EnableBusSupport off + Port { + PortNumber 2 + Name "M" + RTWStorageClass "Auto" + DataLoggingNameMode "SignalName" + } + } + Block { + BlockType Terminator + Name " Terminator " + SID "155::50" + Position [460, 241, 480, 259] + ZOrder 18 + } + Block { + BlockType Outport + Name "M" + SID "155::5" + Position [460, 101, 480, 119] + ZOrder -5 + IconDisplay "Port number" + } + Line { + ZOrder 5 + SrcBlock "q" + SrcPort 1 + DstBlock " SFunction " + DstPort 1 + } + Line { + Name "M" + ZOrder 6 + Labels [0, 0] + SrcBlock " SFunction " + SrcPort 2 + DstBlock "M" + DstPort 1 + } + Line { + ZOrder 7 + SrcBlock " Demux " + SrcPort 1 + DstBlock " Terminator " + DstPort 1 + } + Line { + ZOrder 8 + SrcBlock " SFunction " + SrcPort 1 + DstBlock " Demux " + DstPort 1 + } + } + } + Block { + BlockType Outport + Name "M" + SID "160" + Position [160, 43, 190, 57] + ZOrder 111 + IconDisplay "Port number" + } + Line { + ZOrder 22 + SrcBlock "q" + SrcPort 1 + DstBlock "mFcn_M" + DstPort 1 + } + Line { + ZOrder 23 + SrcBlock "mFcn_M" + SrcPort 1 + DstBlock "M" + DstPort 1 + } + } + } + Block { + BlockType SubSystem + Name "atlas5_arm_coriolis_vec" + SID "276" + Ports [2, 1] + Position [585, 472, 655, 523] + ZOrder 230 + TreatAsAtomicUnit on + RequestExecContextInheritance off + System { + Name "atlas5_arm_coriolis_vec" + Location [-10, -14, 1930, 1090] + Open off + ModelBrowserVisibility off + ModelBrowserWidth 200 + ScreenColor "white" + PaperOrientation "landscape" + PaperPositionMode "auto" + PaperType "A4" + PaperUnits "centimeters" + TiledPaperMargins [1.270000, 1.270000, 1.270000, 1.270000] + TiledPageScale 1 + ShowPageBoundaries off + ZoomFactor "100" + Block { + BlockType Inport + Name "q" + SID "314" + Position [20, 33, 50, 47] + ZOrder 101 + IconDisplay "Port number" + } + Block { + BlockType Inport + Name "qD" + SID "315" + Position [20, 68, 50, 82] + ZOrder 102 + Port "2" + IconDisplay "Port number" + } + Block { + BlockType SubSystem + Name "mFcn_c" + SID "316" + Ports [2, 1] + Position [70, 23, 140, 92] + ZOrder 100 + LibraryVersion "1.110" + ErrorFcn "Stateflow.Translate.translate" + PermitHierarchicalResolution "ExplicitOnly" + TreatAsAtomicUnit on + RequestExecContextInheritance off + SFBlockType "MATLAB Function" + System { + Name "mFcn_c" + Location [223, 338, 826, 833] + Open off + ModelBrowserVisibility off + ModelBrowserWidth 200 + ScreenColor "white" + PaperOrientation "landscape" + PaperPositionMode "auto" + PaperType "A4" + PaperUnits "centimeters" + TiledPaperMargins [1.270000, 1.270000, 1.270000, 1.270000] + TiledPageScale 1 + ShowPageBoundaries off + ZoomFactor "100" + SIDHighWatermark "57" + Block { + BlockType Inport + Name "q" + SID "316::1" + Position [20, 101, 40, 119] + ZOrder -1 + IconDisplay "Port number" + } + Block { + BlockType Inport + Name "qD" + SID "316::21" + Position [20, 136, 40, 154] + ZOrder 7 + Port "2" + IconDisplay "Port number" + } + Block { + BlockType Demux + Name " Demux " + SID "316::56" + Ports [1, 1] + Position [270, 230, 320, 270] + ZOrder 24 + Outputs "1" + } + Block { + BlockType S-Function + Name " SFunction " + SID "316::55" + Tag "Stateflow S-Function atlas_dynamic_library 30" + Ports [2, 2] + Position [180, 100, 230, 160] + ZOrder 23 + FunctionName "sf_sfun" + Parameters "atlas_arm_lr" + PortCounts "[2 2]" + EnableBusSupport off + Port { + PortNumber 2 + Name "tau_c" + RTWStorageClass "Auto" + DataLoggingNameMode "SignalName" + } + } + Block { + BlockType Terminator + Name " Terminator " + SID "316::57" + Position [460, 241, 480, 259] + ZOrder 25 + } + Block { + BlockType Outport + Name "tau_c" + SID "316::27" + Position [460, 101, 480, 119] + ZOrder 13 + IconDisplay "Port number" + } + Line { + ZOrder 6 + SrcBlock "q" + SrcPort 1 + Points [120, 0] + DstBlock " SFunction " + DstPort 1 + } + Line { + ZOrder 7 + SrcBlock "qD" + SrcPort 1 + DstBlock " SFunction " + DstPort 2 + } + Line { + Name "tau_c" + ZOrder 8 + Labels [0, 0] + SrcBlock " SFunction " + SrcPort 2 + DstBlock "tau_c" + DstPort 1 + } + Line { + ZOrder 9 + SrcBlock " Demux " + SrcPort 1 + DstBlock " Terminator " + DstPort 1 + } + Line { + ZOrder 10 + SrcBlock " SFunction " + SrcPort 1 + DstBlock " Demux " + DstPort 1 + } + } + } + Block { + BlockType Outport + Name "tau_c" + SID "317" + Position [160, 53, 190, 67] + ZOrder 103 + IconDisplay "Port number" + } + Line { + ZOrder 1 + SrcBlock "mFcn_c" + SrcPort 1 + DstBlock "tau_c" + DstPort 1 + } + Line { + ZOrder 2 + SrcBlock "qD" + SrcPort 1 + DstBlock "mFcn_c" + DstPort 2 + } + Line { + ZOrder 3 + SrcBlock "q" + SrcPort 1 + DstBlock "mFcn_c" + DstPort 1 + } + } + } + Block { + BlockType SubSystem + Name "atlas5_arm_coriolis_vec_minvarpar" + SID "277" + Ports [2, 1] + Position [880, 477, 950, 528] + ZOrder 236 + TreatAsAtomicUnit on + RequestExecContextInheritance off + Object { + $PropName "MaskObject" + $ObjectID 49 + $ClassName "Simulink.Mask" + Array { + Type "Simulink.MaskParameter" + Dimension 2 + Object { + $ObjectID 50 + Type "edit" + Name "atlas_arm_lr" + Prompt "atlas_arm_lr (left = true, right = false)" + Value "atlas_arm_lr" + } + Object { + $ObjectID 51 + Type "edit" + Name "MPV" + Prompt "MPV (vector of minimal parameters)" + Value "MPV" + } + PropName "Parameters" + } + } + System { + Name "atlas5_arm_coriolis_vec_minvarpar" + Location [266, 65, 1226, 1225] + Open off + ModelBrowserVisibility off + ModelBrowserWidth 200 + ScreenColor "white" + PaperOrientation "landscape" + PaperPositionMode "auto" + PaperType "A4" + PaperUnits "centimeters" + TiledPaperMargins [1.270000, 1.270000, 1.270000, 1.270000] + TiledPageScale 1 + ShowPageBoundaries off + ZoomFactor "100" + Block { + BlockType Inport + Name "q" + SID "297" + Position [20, 33, 50, 47] + ZOrder 117 + IconDisplay "Port number" + } + Block { + BlockType Inport + Name "qD" + SID "298" + Position [20, 63, 50, 77] + ZOrder 118 + Port "2" + IconDisplay "Port number" + } + Block { + BlockType SubSystem + Name "mFcn_c" + SID "299" + Ports [2, 1] + Position [70, 24, 140, 86] + ZOrder 116 + LibraryVersion "1.124" + ErrorFcn "Stateflow.Translate.translate" + PermitHierarchicalResolution "ExplicitOnly" + TreatAsAtomicUnit on + RequestExecContextInheritance off + SFBlockType "MATLAB Function" + System { + Name "mFcn_c" + Location [223, 338, 826, 833] + Open off + ModelBrowserVisibility off + ModelBrowserWidth 200 + ScreenColor "white" + PaperOrientation "landscape" + PaperPositionMode "auto" + PaperType "A4" + PaperUnits "centimeters" + TiledPaperMargins [1.270000, 1.270000, 1.270000, 1.270000] + TiledPageScale 1 + ShowPageBoundaries off + ZoomFactor "100" + SIDHighWatermark "134" + Block { + BlockType Inport + Name "q" + SID "299::1" + Position [20, 101, 40, 119] + ZOrder -1 + IconDisplay "Port number" + } + Block { + BlockType Inport + Name "qD" + SID "299::21" + Position [20, 136, 40, 154] + ZOrder 7 + Port "2" + IconDisplay "Port number" + } + Block { + BlockType Demux + Name " Demux " + SID "299::109" + Ports [1, 1] + Position [270, 230, 320, 270] + ZOrder 33 + Outputs "1" + } + Block { + BlockType S-Function + Name " SFunction " + SID "299::108" + Tag "Stateflow S-Function atlas_dynamic_library 34" + Ports [2, 2] + Position [180, 100, 230, 160] + ZOrder 32 + FunctionName "sf_sfun" + Parameters "MPV,atlas_arm_lr" + PortCounts "[2 2]" + EnableBusSupport off + Port { + PortNumber 2 + Name "tau_c" + RTWStorageClass "Auto" + DataLoggingNameMode "SignalName" + } + } + Block { + BlockType Terminator + Name " Terminator " + SID "299::110" + Position [460, 241, 480, 259] + ZOrder 34 + } + Block { + BlockType Outport + Name "tau_c" + SID "299::27" + Position [460, 101, 480, 119] + ZOrder 13 + IconDisplay "Port number" + } + Line { + ZOrder 6 + SrcBlock "q" + SrcPort 1 + Points [120, 0] + DstBlock " SFunction " + DstPort 1 + } + Line { + ZOrder 7 + SrcBlock "qD" + SrcPort 1 + DstBlock " SFunction " + DstPort 2 + } + Line { + Name "tau_c" + ZOrder 8 + Labels [0, 0] + SrcBlock " SFunction " + SrcPort 2 + DstBlock "tau_c" + DstPort 1 + } + Line { + ZOrder 9 + SrcBlock " Demux " + SrcPort 1 + DstBlock " Terminator " + DstPort 1 + } + Line { + ZOrder 10 + SrcBlock " SFunction " + SrcPort 1 + DstBlock " Demux " + DstPort 1 + } + } + } + Block { + BlockType Outport + Name "tau_c" + SID "300" + Position [160, 48, 190, 62] + ZOrder 119 + IconDisplay "Port number" + } + Line { + ZOrder 1 + SrcBlock "qD" + SrcPort 1 + DstBlock "mFcn_c" + DstPort 2 + } + Line { + ZOrder 2 + SrcBlock "q" + SrcPort 1 + DstBlock "mFcn_c" + DstPort 1 + } + Line { + ZOrder 3 + SrcBlock "mFcn_c" + SrcPort 1 + DstBlock "tau_c" + DstPort 1 + } + } + } + Block { + BlockType SubSystem + Name "atlas5_arm_energy" + SID "278" + Ports [3, 2] + Position [475, 475, 545, 525] + ZOrder 233 + TreatAsAtomicUnit on + RequestExecContextInheritance off + System { + Name "atlas5_arm_energy" + Location [0, 52, 1920, 1080] + Open off + ModelBrowserVisibility off + ModelBrowserWidth 200 + ScreenColor "white" + PaperOrientation "landscape" + PaperPositionMode "auto" + PaperType "A4" + PaperUnits "centimeters" + TiledPaperMargins [1.270000, 1.270000, 1.270000, 1.270000] + TiledPageScale 1 + ShowPageBoundaries off + ZoomFactor "100" + Block { + BlockType Inport + Name "q" + SID "318" + Position [20, 33, 50, 47] + ZOrder 86 + IconDisplay "Port number" + } + Block { + BlockType Inport + Name "qD" + SID "319" + Position [20, 63, 50, 77] + ZOrder 87 + Port "2" + IconDisplay "Port number" + } + Block { + BlockType Inport + Name "g" + SID "320" + Position [20, 118, 50, 132] + ZOrder 90 + NamePlacement "alternate" + Port "3" + IconDisplay "Port number" + } + Block { + BlockType SubSystem + Name "atlas5_arm_energy_fb" + SID "321" + Ports [3, 2] + Position [70, 23, 140, 87] + ZOrder 85 + NamePlacement "alternate" + LibraryVersion "1.32" + ErrorFcn "Stateflow.Translate.translate" + PermitHierarchicalResolution "ExplicitOnly" + TreatAsAtomicUnit on + RequestExecContextInheritance off + SFBlockType "MATLAB Function" + Object { + $PropName "MaskObject" + $ObjectID 52 + $ClassName "Simulink.Mask" + Initialization "if edit_lr == 1\n atlas_arm_lr = true; % left\nelse\n atlas_arm_lr = false; % right\nend\n" + Object { + $PropName "Parameters" + $ObjectID 53 + $ClassName "Simulink.MaskParameter" + Type "edit" + Name "edit_lr" + Prompt "Arm (left = true, right = false)" + Value "atlas_arm_lr" + } + } + System { + Name "atlas5_arm_energy_fb" + Location [223, 338, 826, 833] + Open off + ModelBrowserVisibility off + ModelBrowserWidth 200 + ScreenColor "white" + PaperOrientation "landscape" + PaperPositionMode "auto" + PaperType "A4" + PaperUnits "centimeters" + TiledPaperMargins [1.270000, 1.270000, 1.270000, 1.270000] + TiledPageScale 1 + ShowPageBoundaries off + ZoomFactor "100" + SIDHighWatermark "73" + Block { + BlockType Inport + Name "q" + SID "321::1" + Position [20, 101, 40, 119] + ZOrder -1 + IconDisplay "Port number" + } + Block { + BlockType Inport + Name "qD" + SID "321::21" + Position [20, 136, 40, 154] + ZOrder 7 + Port "2" + IconDisplay "Port number" + } + Block { + BlockType Inport + Name "g" + SID "321::70" + Position [20, 171, 40, 189] + ZOrder 18 + Port "3" + IconDisplay "Port number" + } + Block { + BlockType Demux + Name " Demux " + SID "321::72" + Ports [1, 1] + Position [270, 230, 320, 270] + ZOrder 20 + Outputs "1" + } + Block { + BlockType S-Function + Name " SFunction " + SID "321::71" + Tag "Stateflow S-Function atlas_dynamic_library 27" + Ports [3, 3] + Position [180, 100, 230, 180] + ZOrder 19 + FunctionName "sf_sfun" + Parameters "atlas_arm_lr" + PortCounts "[3 3]" + EnableBusSupport off + Port { + PortNumber 2 + Name "T" + RTWStorageClass "Auto" + DataLoggingNameMode "SignalName" + } + Port { + PortNumber 3 + Name "U" + RTWStorageClass "Auto" + DataLoggingNameMode "SignalName" + } + } + Block { + BlockType Terminator + Name " Terminator " + SID "321::73" + Position [460, 241, 480, 259] + ZOrder 21 + } + Block { + BlockType Outport + Name "T" + SID "321::5" + Position [460, 101, 480, 119] + ZOrder -5 + IconDisplay "Port number" + } + Block { + BlockType Outport + Name "U" + SID "321::25" + Position [460, 136, 480, 154] + ZOrder 11 + Port "2" + IconDisplay "Port number" + } + Line { + ZOrder 8 + SrcBlock "q" + SrcPort 1 + DstBlock " SFunction " + DstPort 1 + } + Line { + ZOrder 9 + SrcBlock "qD" + SrcPort 1 + DstBlock " SFunction " + DstPort 2 + } + Line { + ZOrder 10 + SrcBlock "g" + SrcPort 1 + DstBlock " SFunction " + DstPort 3 + } + Line { + Name "T" + ZOrder 11 + Labels [0, 0] + SrcBlock " SFunction " + SrcPort 2 + DstBlock "T" + DstPort 1 + } + Line { + Name "U" + ZOrder 12 + Labels [0, 0] + SrcBlock " SFunction " + SrcPort 3 + DstBlock "U" + DstPort 1 + } + Line { + ZOrder 13 + SrcBlock " Demux " + SrcPort 1 + DstBlock " Terminator " + DstPort 1 + } + Line { + ZOrder 14 + SrcBlock " SFunction " + SrcPort 1 + DstBlock " Demux " + DstPort 1 + } + } + } + Block { + BlockType Outport + Name "T" + SID "322" + Position [160, 33, 190, 47] + ZOrder 88 + IconDisplay "Port number" + } + Block { + BlockType Outport + Name "U" + SID "323" + Position [160, 63, 190, 77] + ZOrder 89 + Port "2" + IconDisplay "Port number" + } + Line { + ZOrder 1 + SrcBlock "q" + SrcPort 1 + DstBlock "atlas5_arm_energy_fb" + DstPort 1 + } + Line { + ZOrder 2 + SrcBlock "qD" + SrcPort 1 + DstBlock "atlas5_arm_energy_fb" + DstPort 2 + } + Line { + ZOrder 3 + SrcBlock "atlas5_arm_energy_fb" + SrcPort 2 + DstBlock "U" + DstPort 1 + } + Line { + ZOrder 4 + SrcBlock "atlas5_arm_energy_fb" + SrcPort 1 + DstBlock "T" + DstPort 1 + } + Line { + ZOrder 5 + SrcBlock "g" + SrcPort 1 + Points [2, 0; 0, -41; -2, 0] + DstBlock "atlas5_arm_energy_fb" + DstPort 3 + } + } + } + Block { + BlockType SubSystem + Name "atlas5_arm_energy_minvarpar" + SID "279" + Ports [3, 2] + Position [750, 474, 820, 526] + ZOrder 234 + TreatAsAtomicUnit on + RequestExecContextInheritance off + Object { + $PropName "MaskObject" + $ObjectID 54 + $ClassName "Simulink.Mask" + Object { + $PropName "Parameters" + $ObjectID 55 + $ClassName "Simulink.MaskParameter" + Type "edit" + Name "MPV" + Prompt "MPV (vector of minimal parameters)" + Value "MPV" + } + } + System { + Name "atlas5_arm_energy_minvarpar" + Location [0, 52, 1920, 1080] + Open off + ModelBrowserVisibility off + ModelBrowserWidth 200 + ScreenColor "white" + PaperOrientation "landscape" + PaperPositionMode "auto" + PaperType "A4" + PaperUnits "centimeters" + TiledPaperMargins [1.270000, 1.270000, 1.270000, 1.270000] + TiledPageScale 1 + ShowPageBoundaries off + ZoomFactor "100" + Block { + BlockType Inport + Name "q" + SID "301" + Position [5, 33, 35, 47] + ZOrder 91 + IconDisplay "Port number" + } + Block { + BlockType Inport + Name "qD" + SID "302" + Position [5, 63, 35, 77] + ZOrder 92 + Port "2" + IconDisplay "Port number" + } + Block { + BlockType Inport + Name "g" + SID "303" + Position [5, 93, 35, 107] + ZOrder 95 + Port "3" + IconDisplay "Port number" + } + Block { + BlockType SubSystem + Name "atlas5_arm_energy_fb" + SID "304" + Ports [3, 2] + Position [70, 28, 160, 112] + ZOrder 90 + NamePlacement "alternate" + LibraryVersion "1.86" + ErrorFcn "Stateflow.Translate.translate" + PermitHierarchicalResolution "ExplicitOnly" + TreatAsAtomicUnit on + RequestExecContextInheritance off + SFBlockType "MATLAB Function" + System { + Name "atlas5_arm_energy_fb" + Location [223, 338, 826, 833] + Open off + ModelBrowserVisibility off + ModelBrowserWidth 200 + ScreenColor "white" + PaperOrientation "landscape" + PaperPositionMode "auto" + PaperType "A4" + PaperUnits "centimeters" + TiledPaperMargins [1.270000, 1.270000, 1.270000, 1.270000] + TiledPageScale 1 + ShowPageBoundaries off + ZoomFactor "100" + SIDHighWatermark "91" + Block { + BlockType Inport + Name "q" + SID "304::1" + Position [20, 101, 40, 119] + ZOrder -1 + IconDisplay "Port number" + } + Block { + BlockType Inport + Name "qD" + SID "304::21" + Position [20, 136, 40, 154] + ZOrder 7 + Port "2" + IconDisplay "Port number" + } + Block { + BlockType Inport + Name "g_utorso" + SID "304::65" + Position [20, 171, 40, 189] + ZOrder 19 + Port "3" + IconDisplay "Port number" + } + Block { + BlockType Demux + Name " Demux " + SID "304::74" + Ports [1, 1] + Position [270, 230, 320, 270] + ZOrder 27 + Outputs "1" + } + Block { + BlockType S-Function + Name " SFunction " + SID "304::73" + Tag "Stateflow S-Function atlas_dynamic_library 32" + Ports [3, 3] + Position [180, 100, 230, 180] + ZOrder 26 + FunctionName "sf_sfun" + Parameters "MPV,atlas_arm_lr" + PortCounts "[3 3]" + EnableBusSupport off + Port { + PortNumber 2 + Name "T" + RTWStorageClass "Auto" + DataLoggingNameMode "SignalName" + } + Port { + PortNumber 3 + Name "U" + RTWStorageClass "Auto" + DataLoggingNameMode "SignalName" + } + } + Block { + BlockType Terminator + Name " Terminator " + SID "304::75" + Position [460, 241, 480, 259] + ZOrder 28 + } + Block { + BlockType Outport + Name "T" + SID "304::5" + Position [460, 101, 480, 119] + ZOrder -5 + IconDisplay "Port number" + } + Block { + BlockType Outport + Name "U" + SID "304::25" + Position [460, 136, 480, 154] + ZOrder 11 + Port "2" + IconDisplay "Port number" + } + Line { + ZOrder 8 + SrcBlock "q" + SrcPort 1 + DstBlock " SFunction " + DstPort 1 + } + Line { + ZOrder 9 + SrcBlock "qD" + SrcPort 1 + DstBlock " SFunction " + DstPort 2 + } + Line { + ZOrder 10 + SrcBlock "g_utorso" + SrcPort 1 + DstBlock " SFunction " + DstPort 3 + } + Line { + Name "T" + ZOrder 11 + Labels [0, 0] + SrcBlock " SFunction " + SrcPort 2 + DstBlock "T" + DstPort 1 + } + Line { + Name "U" + ZOrder 12 + Labels [0, 0] + SrcBlock " SFunction " + SrcPort 3 + DstBlock "U" + DstPort 1 + } + Line { + ZOrder 13 + SrcBlock " Demux " + SrcPort 1 + DstBlock " Terminator " + DstPort 1 + } + Line { + ZOrder 14 + SrcBlock " SFunction " + SrcPort 1 + DstBlock " Demux " + DstPort 1 + } + } + } + Block { + BlockType Outport + Name "T" + SID "305" + Position [215, 43, 245, 57] + ZOrder 93 + IconDisplay "Port number" + } + Block { + BlockType Outport + Name "U" + SID "306" + Position [215, 83, 245, 97] + ZOrder 94 + Port "2" + IconDisplay "Port number" + } + Line { + ZOrder 1 + SrcBlock "g" + SrcPort 1 + DstBlock "atlas5_arm_energy_fb" + DstPort 3 + } + Line { + ZOrder 2 + SrcBlock "q" + SrcPort 1 + DstBlock "atlas5_arm_energy_fb" + DstPort 1 + } + Line { + ZOrder 3 + SrcBlock "atlas5_arm_energy_fb" + SrcPort 2 + DstBlock "U" + DstPort 1 + } + Line { + ZOrder 4 + SrcBlock "atlas5_arm_energy_fb" + SrcPort 1 + DstBlock "T" + DstPort 1 + } + Line { + ZOrder 5 + SrcBlock "qD" + SrcPort 1 + DstBlock "atlas5_arm_energy_fb" + DstPort 2 + } + } + } + Block { + BlockType SubSystem + Name "atlas5_arm_fordyn_rj_damping" + SID "280" + Ports [3, 5] + Position [110, 472, 280, 548] + ZOrder 227 + RequestExecContextInheritance off + Object { + $PropName "MaskObject" + $ObjectID 56 + $ClassName "Simulink.Mask" + Array { + Type "Simulink.MaskParameter" + Dimension 5 + Object { + $ObjectID 57 + Type "edit" + Name "q0" + Prompt "q0 (initial pose)" + Value "q0" + } + Object { + $ObjectID 58 + Type "edit" + Name "qD0" + Prompt "qD0 (initial velocity)" + Value "qD0" + } + Object { + $ObjectID 59 + Type "edit" + Name "d" + Prompt "d (viscous friction)" + Value "d" + } + Object { + $ObjectID 60 + Type "edit" + Name "muC" + Prompt "muC (coulomb friction)" + Value "muC" + } + Object { + $ObjectID 61 + Type "edit" + Name "atlas_arm_lr" + Prompt "atlas_arm_lr (Arm: left = true, right = false)" + Value "atlas_arm_lr" + } + PropName "Parameters" + } + Array { + Type "Simulink.dialog.Group" + Dimension 2 + Object { + $ObjectID 62 + Prompt "%" + Object { + $PropName "DialogControls" + $ObjectID 63 + $ClassName "Simulink.dialog.Text" + Prompt "%" + Name "DescTextVar" + } + Name "DescGroupVar" + } + Object { + $ObjectID 64 + Prompt "Robot Parameters" + Array { + Type "Simulink.dialog.parameter.Edit" + Dimension 5 + Object { + $ObjectID 65 + Name "q0" + } + Object { + $ObjectID 66 + Name "qD0" + } + Object { + $ObjectID 67 + Name "d" + } + Object { + $ObjectID 68 + Name "muC" + } + Object { + $ObjectID 69 + Name "atlas_arm_lr" + } + PropName "DialogControls" + } + Name "ParameterGroupVar" + } + PropName "DialogControls" + } + } + System { + Name "atlas5_arm_fordyn_rj_damping" + Location [960, 0, 1920, 1160] + Open off + ModelBrowserVisibility off + ModelBrowserWidth 200 + ScreenColor "white" + PaperOrientation "landscape" + PaperPositionMode "auto" + PaperType "A4" + PaperUnits "centimeters" + TiledPaperMargins [1.270000, 1.270000, 1.270000, 1.270000] + TiledPageScale 1 + ShowPageBoundaries off + ZoomFactor "100" + Block { + BlockType Inport + Name "tau_ext\n" + SID "335" + Position [70, 233, 100, 247] + ZOrder 61 + IconDisplay "Port number" + } + Block { + BlockType Inport + Name "tau_m" + SID "336" + Position [70, 448, 100, 462] + ZOrder 62 + Port "2" + IconDisplay "Port number" + Port { + PortNumber 1 + Name "tau_m" + RTWStorageClass "Auto" + DataLogging on + DataLoggingNameMode "SignalName" + } + } + Block { + BlockType Inport + Name "g" + SID "337" + Position [695, 398, 725, 412] + ZOrder 125 + BlockMirror on + Port "3" + IconDisplay "Port number" + } + Block { + BlockType Integrator + Name "Integrator" + SID "338" + Ports [1, 1] + Position [335, 85, 365, 115] + ZOrder 36 + InitialCondition "qD0" + Port { + PortNumber 1 + Name "qD" + RTWStorageClass "Auto" + DataLogging on + DataLoggingNameMode "SignalName" + } + } + Block { + BlockType Integrator + Name "Integrator1" + SID "339" + Ports [1, 1] + Position [445, 84, 475, 116] + ZOrder 37 + InitialCondition "q0" + Port { + PortNumber 1 + Name "q" + RTWStorageClass "Auto" + DataLogging on + DataLoggingNameMode "SignalName" + } + } + Block { + BlockType Sum + Name "Sum2" + SID "340" + Ports [2, 1] + Position [180, 385, 200, 405] + ZOrder 45 + BlockRotation 270 + ShowName off + IconShape "round" + Inputs "|+-" + InputSameDT off + OutDataTypeStr "Inherit: Inherit via internal rule" + SaturateOnIntegerOverflow off + } + Block { + BlockType Sum + Name "Sum3" + SID "341" + Ports [3, 1] + Position [180, 230, 200, 250] + ZOrder 46 + BlockRotation 270 + ShowName off + IconShape "round" + Inputs "++-" + InputSameDT off + OutDataTypeStr "Inherit: Inherit via internal rule" + SaturateOnIntegerOverflow off + Port { + PortNumber 1 + Name "tau_acc" + RTWStorageClass "Auto" + DataLogging on + DataLoggingNameMode "SignalName" + } + } + Block { + BlockType Sum + Name "Sum4" + SID "342" + Ports [2, 1] + Position [180, 305, 200, 325] + ZOrder 52 + BlockRotation 270 + ShowName off + IconShape "round" + Inputs "|+-" + InputSameDT off + OutDataTypeStr "Inherit: Inherit via internal rule" + SaturateOnIntegerOverflow off + } + Block { + BlockType Reference + Name "atlas5_arm_coriolis_vec" + SID "343" + Ports [2, 1] + Position [295, 212, 365, 263] + ZOrder 147 + BlockMirror on + NamePlacement "alternate" + LibraryVersion "1.202" + SourceBlock "atlas_dynamic_library/atlas5_arm_coriolis_vec" + SourceType "SubSystem" + ContentPreviewEnabled off + Port { + PortNumber 1 + Name "tau_c" + RTWStorageClass "Auto" + DataLoggingNameMode "SignalName" + } + } + Block { + BlockType Reference + Name "atlas5_arm_gravload" + SID "344" + Ports [2, 1] + Position [300, 367, 365, 418] + ZOrder 146 + BlockMirror on + NamePlacement "alternate" + LibraryVersion "1.202" + SourceBlock "atlas_dynamic_library/atlas5_arm_gravload" + SourceType "SubSystem" + ContentPreviewEnabled off + Port { + PortNumber 1 + Name "tau_g" + RTWStorageClass "Auto" + DataLoggingNameMode "SignalName" + } + } + Block { + BlockType Reference + Name "atlas5_arm_inertia" + SID "345" + Ports [1, 1] + Position [90, 60, 160, 110] + ZOrder 148 + LibraryVersion "1.202" + SourceBlock "atlas_dynamic_library/atlas5_arm_inertia" + SourceType "SubSystem" + ContentPreviewEnabled off + } + Block { + BlockType Reference + Name "atlas_friction_model" + SID "346" + Ports [1, 1] + Position [295, 291, 365, 339] + ZOrder 145 + BlockMirror on + NamePlacement "alternate" + LibraryVersion "1.202" + SourceBlock "atlas_dynamic_library/atlas_friction_model" + SourceType "" + ContentPreviewEnabled off + muC "muC" + d "d" + Port { + PortNumber 1 + Name "tau_fr" + RTWStorageClass "Auto" + DataLoggingNameMode "SignalName" + } + } + Block { + BlockType SubSystem + Name "mFcn_Minv" + SID "347" + Ports [2, 1] + Position [205, 71, 290, 124] + ZOrder 144 + LibraryVersion "1.190" + ErrorFcn "Stateflow.Translate.translate" + PermitHierarchicalResolution "ExplicitOnly" + TreatAsAtomicUnit on + RequestExecContextInheritance off + SFBlockType "MATLAB Function" + Port { + PortNumber 1 + Name "qDD" + RTWStorageClass "Auto" + DataLoggingNameMode "SignalName" + } + System { + Name "mFcn_Minv" + Location [223, 338, 826, 833] + Open off + ModelBrowserVisibility off + ModelBrowserWidth 200 + ScreenColor "white" + PaperOrientation "landscape" + PaperPositionMode "auto" + PaperType "A4" + PaperUnits "centimeters" + TiledPaperMargins [1.270000, 1.270000, 1.270000, 1.270000] + TiledPageScale 1 + ShowPageBoundaries off + ZoomFactor "100" + SIDHighWatermark "51" + Block { + BlockType Inport + Name "M" + SID "347::1" + Position [20, 101, 40, 119] + ZOrder -1 + IconDisplay "Port number" + } + Block { + BlockType Inport + Name "tau" + SID "347::21" + Position [20, 136, 40, 154] + ZOrder 7 + Port "2" + IconDisplay "Port number" + } + Block { + BlockType Demux + Name " Demux " + SID "347::50" + Ports [1, 1] + Position [270, 230, 320, 270] + ZOrder 18 + Outputs "1" + } + Block { + BlockType S-Function + Name " SFunction " + SID "347::49" + Tag "Stateflow S-Function atlas_dynamic_library 38" + Ports [2, 2] + Position [180, 100, 230, 160] + ZOrder 17 + FunctionName "sf_sfun" + PortCounts "[2 2]" + EnableBusSupport off + Port { + PortNumber 2 + Name "q_ddot" + RTWStorageClass "Auto" + DataLoggingNameMode "SignalName" + } + } + Block { + BlockType Terminator + Name " Terminator " + SID "347::51" + Position [460, 241, 480, 259] + ZOrder 19 + } + Block { + BlockType Outport + Name "q_ddot" + SID "347::5" + Position [460, 101, 480, 119] + ZOrder -5 + IconDisplay "Port number" + } + Line { + ZOrder 6 + SrcBlock "M" + SrcPort 1 + Points [120, 0] + DstBlock " SFunction " + DstPort 1 + } + Line { + ZOrder 7 + SrcBlock "tau" + SrcPort 1 + DstBlock " SFunction " + DstPort 2 + } + Line { + Name "q_ddot" + ZOrder 8 + Labels [0, 0] + SrcBlock " SFunction " + SrcPort 2 + DstBlock "q_ddot" + DstPort 1 + } + Line { + ZOrder 9 + SrcBlock " Demux " + SrcPort 1 + DstBlock " Terminator " + DstPort 1 + } + Line { + ZOrder 10 + SrcBlock " SFunction " + SrcPort 1 + DstBlock " Demux " + DstPort 1 + } + } + } + Block { + BlockType Outport + Name "q" + SID "348" + Position [695, 93, 725, 107] + ZOrder 63 + IconDisplay "Port number" + } + Block { + BlockType Outport + Name "qD" + SID "349" + Position [695, 148, 725, 162] + ZOrder 64 + Port "2" + IconDisplay "Port number" + } + Block { + BlockType Outport + Name "qDD" + SID "350" + Position [695, 48, 725, 62] + ZOrder 65 + Port "3" + IconDisplay "Port number" + } + Block { + BlockType Outport + Name "tau_fr" + SID "371" + Position [70, 353, 100, 367] + ZOrder 231 + BlockMirror on + Port "4" + IconDisplay "Port number" + } + Block { + BlockType Outport + Name "tau_J" + SID "374" + Position [695, 448, 725, 462] + ZOrder 232 + Port "5" + IconDisplay "Port number" + } + Line { + Name "tau_g" + ZOrder 1 + Labels [0, 0] + SrcBlock "atlas5_arm_gravload" + SrcPort 1 + DstBlock "Sum2" + DstPort 2 + } + Line { + Name "q" + ZOrder 2 + Labels [-1, 0] + SrcBlock "Integrator1" + SrcPort 1 + Points [65, 0] + Branch { + ZOrder 3 + Labels [2, 1] + Points [0, -64; -465, 0; 0, 49] + DstBlock "atlas5_arm_inertia" + DstPort 1 + } + Branch { + ZOrder 4 + Labels [1, 1] + Points [0, 125] + DstBlock "atlas5_arm_coriolis_vec" + DstPort 1 + } + Branch { + ZOrder 5 + Labels [1, 1] + Points [67, 0] + Branch { + ZOrder 6 + Labels [1, 0] + Points [0, 280] + DstBlock "atlas5_arm_gravload" + DstPort 1 + } + Branch { + ZOrder 7 + Labels [1, 1] + DstBlock "q" + DstPort 1 + } + } + } + Line { + ZOrder 8 + SrcBlock "Sum2" + SrcPort 1 + DstBlock "Sum4" + DstPort 1 + } + Line { + Name "qDD" + ZOrder 9 + Labels [0, 0] + SrcBlock "mFcn_Minv" + SrcPort 1 + Points [18, 0] + Branch { + ZOrder 10 + Points [0, -45] + DstBlock "qDD" + DstPort 1 + } + Branch { + ZOrder 11 + DstBlock "Integrator" + DstPort 1 + } + } + Line { + ZOrder 12 + SrcBlock "Sum4" + SrcPort 1 + DstBlock "Sum3" + DstPort 2 + } + Line { + Name "tau_c" + ZOrder 13 + Labels [-1, 0] + SrcBlock "atlas5_arm_coriolis_vec" + SrcPort 1 + DstBlock "Sum3" + DstPort 3 + } + Line { + Name "tau_fr" + ZOrder 14 + Labels [0, 0] + SrcBlock "atlas_friction_model" + SrcPort 1 + Points [-34, 0] + Branch { + ZOrder 28 + Points [0, 45] + DstBlock "tau_fr" + DstPort 1 + } + Branch { + ZOrder 27 + DstBlock "Sum4" + DstPort 2 + } + } + Line { + ZOrder 15 + SrcBlock "tau_ext\n" + SrcPort 1 + DstBlock "Sum3" + DstPort 1 + } + Line { + Name "qD" + ZOrder 17 + Labels [1, 1] + SrcBlock "Integrator" + SrcPort 1 + Points [32, 0] + Branch { + ZOrder 18 + Points [0, 55] + Branch { + ZOrder 19 + DstBlock "qD" + DstPort 1 + } + Branch { + ZOrder 20 + Labels [1, 1; -1, 0] + Points [0, 95] + Branch { + ZOrder 21 + DstBlock "atlas5_arm_coriolis_vec" + DstPort 2 + } + Branch { + ZOrder 22 + Points [0, 65] + DstBlock "atlas_friction_model" + DstPort 1 + } + } + } + Branch { + ZOrder 23 + Labels [1, 1] + DstBlock "Integrator1" + DstPort 1 + } + } + Line { + Name "tau_acc" + ZOrder 24 + Labels [0, 0] + SrcBlock "Sum3" + SrcPort 1 + DstBlock "mFcn_Minv" + DstPort 2 + } + Line { + ZOrder 25 + SrcBlock "atlas5_arm_inertia" + SrcPort 1 + DstBlock "mFcn_Minv" + DstPort 1 + } + Line { + ZOrder 26 + SrcBlock "g" + SrcPort 1 + DstBlock "atlas5_arm_gravload" + DstPort 2 + } + Line { + Name "tau_m" + ZOrder 16 + Labels [0, 0] + SrcBlock "tau_m" + SrcPort 1 + Points [85, 0] + Branch { + ZOrder 32 + DstBlock "Sum2" + DstPort 1 + } + Branch { + ZOrder 31 + DstBlock "tau_J" + DstPort 1 + } + } + } + } + Block { + BlockType SubSystem + Name "atlas5_arm_fordyn_rj_damping_minvarpar" + SID "351" + Ports [3, 5] + Position [110, 572, 280, 648] + ZOrder 239 + RequestExecContextInheritance off + Object { + $PropName "MaskObject" + $ObjectID 70 + $ClassName "Simulink.Mask" + Array { + Type "Simulink.MaskParameter" + Dimension 6 + Object { + $ObjectID 71 + Type "edit" + Name "q0" + Prompt "q0 (initial pose)" + Value "q0" + } + Object { + $ObjectID 72 + Type "edit" + Name "qD0" + Prompt "qD0 (initial velocity)" + Value "qD0" + } + Object { + $ObjectID 73 + Type "edit" + Name "d" + Prompt "d (viscous friction)" + Value "d" + } + Object { + $ObjectID 74 + Type "edit" + Name "muC" + Prompt "muC (coulomb friction)" + Value "muC" + } + Object { + $ObjectID 75 + Type "edit" + Name "atlas_arm_lr" + Prompt "atlas_arm_lr (Arm: left = true, right = false)" + Value "atlas_arm_lr" + } + Object { + $ObjectID 76 + Type "edit" + Name "MPV" + Prompt "MPV (minimal parameter vector)" + Value "MPV" + } + PropName "Parameters" + } + Array { + Type "Simulink.dialog.Group" + Dimension 2 + Object { + $ObjectID 77 + Prompt "%" + Object { + $PropName "DialogControls" + $ObjectID 78 + $ClassName "Simulink.dialog.Text" + Prompt "%" + Name "DescTextVar" + } + Name "DescGroupVar" + } + Object { + $ObjectID 79 + Prompt "Robot Parameters" + Array { + Type "Simulink.dialog.parameter.Edit" + Dimension 6 + Object { + $ObjectID 80 + Name "q0" + } + Object { + $ObjectID 81 + Name "qD0" + } + Object { + $ObjectID 82 + Name "d" + } + Object { + $ObjectID 83 + Name "muC" + } + Object { + $ObjectID 84 + Name "atlas_arm_lr" + } + Object { + $ObjectID 85 + Name "MPV" + } + PropName "DialogControls" + } + Name "ParameterGroupVar" + } + PropName "DialogControls" + } + } + System { + Name "atlas5_arm_fordyn_rj_damping_minvarpar" + Location [960, 0, 1920, 1160] + Open off + ModelBrowserVisibility off + ModelBrowserWidth 200 + ScreenColor "white" + PaperOrientation "landscape" + PaperPositionMode "auto" + PaperType "A4" + PaperUnits "centimeters" + TiledPaperMargins [1.270000, 1.270000, 1.270000, 1.270000] + TiledPageScale 1 + ShowPageBoundaries off + ZoomFactor "100" + Block { + BlockType Inport + Name "tau_ext\n" + SID "352" + Position [70, 233, 100, 247] + ZOrder 61 + IconDisplay "Port number" + } + Block { + BlockType Inport + Name "tau_m" + SID "353" + Position [70, 448, 100, 462] + ZOrder 62 + Port "2" + IconDisplay "Port number" + Port { + PortNumber 1 + Name "tau_m" + RTWStorageClass "Auto" + DataLogging on + DataLoggingNameMode "SignalName" + } + } + Block { + BlockType Inport + Name "g" + SID "354" + Position [695, 398, 725, 412] + ZOrder 125 + BlockMirror on + Port "3" + IconDisplay "Port number" + } + Block { + BlockType Integrator + Name "Integrator" + SID "355" + Ports [1, 1] + Position [335, 85, 365, 115] + ZOrder 36 + InitialCondition "qD0" + Port { + PortNumber 1 + Name "qD" + RTWStorageClass "Auto" + DataLogging on + DataLoggingNameMode "SignalName" + } + } + Block { + BlockType Integrator + Name "Integrator1" + SID "356" + Ports [1, 1] + Position [445, 84, 475, 116] + ZOrder 37 + InitialCondition "q0" + Port { + PortNumber 1 + Name "q" + RTWStorageClass "Auto" + DataLogging on + DataLoggingNameMode "SignalName" + } + } + Block { + BlockType Sum + Name "Sum2" + SID "357" + Ports [2, 1] + Position [180, 385, 200, 405] + ZOrder 45 + BlockRotation 270 + ShowName off + IconShape "round" + Inputs "|+-" + InputSameDT off + OutDataTypeStr "Inherit: Inherit via internal rule" + SaturateOnIntegerOverflow off + } + Block { + BlockType Sum + Name "Sum3" + SID "358" + Ports [3, 1] + Position [180, 230, 200, 250] + ZOrder 46 + BlockRotation 270 + ShowName off + IconShape "round" + Inputs "++-" + InputSameDT off + OutDataTypeStr "Inherit: Inherit via internal rule" + SaturateOnIntegerOverflow off + Port { + PortNumber 1 + Name "tau_acc" + RTWStorageClass "Auto" + DataLogging on + DataLoggingNameMode "SignalName" + } + } + Block { + BlockType Sum + Name "Sum4" + SID "359" + Ports [2, 1] + Position [180, 305, 200, 325] + ZOrder 52 + BlockRotation 270 + ShowName off + IconShape "round" + Inputs "|+-" + InputSameDT off + OutDataTypeStr "Inherit: Inherit via internal rule" + SaturateOnIntegerOverflow off + } + Block { + BlockType Reference + Name "atlas5_arm_coriolis_vec_minvarpar" + SID "368" + Ports [2, 1] + Position [295, 212, 365, 263] + ZOrder 239 + BlockMirror on + LibraryVersion "1.202" + SourceBlock "atlas_dynamic_library/atlas5_arm_coriolis_vec_minvarpar" + SourceType "SubSystem" + ContentPreviewEnabled off + Port { + PortNumber 1 + Name "tau_c" + RTWStorageClass "Auto" + DataLoggingNameMode "SignalName" + } + } + Block { + BlockType Reference + Name "atlas5_arm_gravload_minvarpar" + SID "369" + Ports [2, 1] + Position [295, 367, 365, 418] + ZOrder 238 + BlockMirror on + LibraryVersion "1.202" + SourceBlock "atlas_dynamic_library/atlas5_arm_gravload_minvarpar" + SourceType "SubSystem" + ContentPreviewEnabled off + Port { + PortNumber 1 + Name "tau_g" + RTWStorageClass "Auto" + DataLoggingNameMode "SignalName" + } + } + Block { + BlockType Reference + Name "atlas5_arm_inertia_minvarpar" + SID "370" + Ports [1, 1] + Position [90, 61, 160, 109] + ZOrder 240 + LibraryVersion "1.202" + SourceBlock "atlas_dynamic_library/atlas5_arm_inertia_minvarpar" + SourceType "SubSystem" + ContentPreviewEnabled off + } + Block { + BlockType Reference + Name "atlas_friction_model" + SID "363" + Ports [1, 1] + Position [295, 291, 365, 339] + ZOrder 145 + BlockMirror on + LibraryVersion "1.202" + SourceBlock "atlas_dynamic_library/atlas_friction_model" + SourceType "" + ContentPreviewEnabled off + muC "muC" + d "d" + Port { + PortNumber 1 + Name "tau_fr" + RTWStorageClass "Auto" + DataLoggingNameMode "SignalName" + } + } + Block { + BlockType SubSystem + Name "mFcn_Minv" + SID "364" + Ports [2, 1] + Position [205, 71, 290, 124] + ZOrder 144 + LibraryVersion "1.190" + ErrorFcn "Stateflow.Translate.translate" + PermitHierarchicalResolution "ExplicitOnly" + TreatAsAtomicUnit on + RequestExecContextInheritance off + SFBlockType "MATLAB Function" + Port { + PortNumber 1 + Name "qDD" + RTWStorageClass "Auto" + DataLoggingNameMode "SignalName" + } + System { + Name "mFcn_Minv" + Location [223, 338, 826, 833] + Open off + ModelBrowserVisibility off + ModelBrowserWidth 200 + ScreenColor "white" + PaperOrientation "landscape" + PaperPositionMode "auto" + PaperType "A4" + PaperUnits "centimeters" + TiledPaperMargins [1.270000, 1.270000, 1.270000, 1.270000] + TiledPageScale 1 + ShowPageBoundaries off + ZoomFactor "100" + SIDHighWatermark "66" + Block { + BlockType Inport + Name "M" + SID "364::1" + Position [20, 101, 40, 119] + ZOrder -1 + IconDisplay "Port number" + } + Block { + BlockType Inport + Name "tau" + SID "364::21" + Position [20, 136, 40, 154] + ZOrder 7 + Port "2" + IconDisplay "Port number" + } + Block { + BlockType Demux + Name " Demux " + SID "364::53" + Ports [1, 1] + Position [270, 230, 320, 270] + ZOrder 21 + Outputs "1" + } + Block { + BlockType S-Function + Name " SFunction " + SID "364::52" + Tag "Stateflow S-Function atlas_dynamic_library 39" + Ports [2, 2] + Position [180, 100, 230, 160] + ZOrder 20 + FunctionName "sf_sfun" + PortCounts "[2 2]" + EnableBusSupport off + Port { + PortNumber 2 + Name "q_ddot" + RTWStorageClass "Auto" + DataLoggingNameMode "SignalName" + } + } + Block { + BlockType Terminator + Name " Terminator " + SID "364::54" + Position [460, 241, 480, 259] + ZOrder 22 + } + Block { + BlockType Outport + Name "q_ddot" + SID "364::5" + Position [460, 101, 480, 119] + ZOrder -5 + IconDisplay "Port number" + } + Line { + ZOrder 6 + SrcBlock "M" + SrcPort 1 + Points [120, 0] + DstBlock " SFunction " + DstPort 1 + } + Line { + ZOrder 7 + SrcBlock "tau" + SrcPort 1 + DstBlock " SFunction " + DstPort 2 + } + Line { + Name "q_ddot" + ZOrder 8 + Labels [0, 0] + SrcBlock " SFunction " + SrcPort 2 + DstBlock "q_ddot" + DstPort 1 + } + Line { + ZOrder 9 + SrcBlock " Demux " + SrcPort 1 + DstBlock " Terminator " + DstPort 1 + } + Line { + ZOrder 10 + SrcBlock " SFunction " + SrcPort 1 + DstBlock " Demux " + DstPort 1 + } + } + } + Block { + BlockType Outport + Name "q" + SID "365" + Position [695, 93, 725, 107] + ZOrder 63 + IconDisplay "Port number" + } + Block { + BlockType Outport + Name "qD" + SID "366" + Position [695, 148, 725, 162] + ZOrder 64 + Port "2" + IconDisplay "Port number" + } + Block { + BlockType Outport + Name "qDD" + SID "367" + Position [695, 48, 725, 62] + ZOrder 65 + Port "3" + IconDisplay "Port number" + } + Block { + BlockType Outport + Name "tau_fr" + SID "372" + Position [70, 343, 100, 357] + ZOrder 241 + BlockMirror on + Port "4" + IconDisplay "Port number" + } + Block { + BlockType Outport + Name "tau_J" + SID "375" + Position [695, 448, 725, 462] + ZOrder 242 + Port "5" + IconDisplay "Port number" + } + Line { + Name "tau_g" + ZOrder 29 + Labels [0, 0] + SrcBlock "atlas5_arm_gravload_minvarpar" + SrcPort 1 + DstBlock "Sum2" + DstPort 2 + } + Line { + Name "q" + ZOrder 2 + Labels [-1, 0] + SrcBlock "Integrator1" + SrcPort 1 + Points [65, 0] + Branch { + ZOrder 33 + Labels [0, 1] + Points [0, 125] + DstBlock "atlas5_arm_coriolis_vec_minvarpar" + DstPort 1 + } + Branch { + ZOrder 27 + Labels [2, 1] + Points [0, -64; -465, 0; 0, 49] + DstBlock "atlas5_arm_inertia_minvarpar" + DstPort 1 + } + Branch { + ZOrder 5 + Labels [1, 1] + Points [67, 0] + Branch { + ZOrder 30 + Labels [1, 0] + Points [0, 280] + DstBlock "atlas5_arm_gravload_minvarpar" + DstPort 1 + } + Branch { + ZOrder 7 + Labels [1, 1] + DstBlock "q" + DstPort 1 + } + } + } + Line { + ZOrder 8 + SrcBlock "Sum2" + SrcPort 1 + DstBlock "Sum4" + DstPort 1 + } + Line { + Name "qDD" + ZOrder 9 + Labels [0, 0] + SrcBlock "mFcn_Minv" + SrcPort 1 + Points [18, 0] + Branch { + ZOrder 10 + Points [0, -45] + DstBlock "qDD" + DstPort 1 + } + Branch { + ZOrder 11 + DstBlock "Integrator" + DstPort 1 + } + } + Line { + ZOrder 12 + SrcBlock "Sum4" + SrcPort 1 + DstBlock "Sum3" + DstPort 2 + } + Line { + Name "tau_c" + ZOrder 34 + Labels [-1, 0] + SrcBlock "atlas5_arm_coriolis_vec_minvarpar" + SrcPort 1 + DstBlock "Sum3" + DstPort 3 + } + Line { + Name "tau_fr" + ZOrder 14 + Labels [0, 0] + SrcBlock "atlas_friction_model" + SrcPort 1 + Points [-38, 0] + Branch { + ZOrder 37 + Points [0, 35] + DstBlock "tau_fr" + DstPort 1 + } + Branch { + ZOrder 35 + DstBlock "Sum4" + DstPort 2 + } + } + Line { + ZOrder 15 + SrcBlock "tau_ext\n" + SrcPort 1 + DstBlock "Sum3" + DstPort 1 + } + Line { + Name "qD" + ZOrder 17 + Labels [1, 1] + SrcBlock "Integrator" + SrcPort 1 + Points [32, 0] + Branch { + ZOrder 18 + Points [0, 55] + Branch { + ZOrder 19 + DstBlock "qD" + DstPort 1 + } + Branch { + ZOrder 20 + Labels [1, 1; -1, 0] + Points [0, 95] + Branch { + ZOrder 32 + DstBlock "atlas5_arm_coriolis_vec_minvarpar" + DstPort 2 + } + Branch { + ZOrder 22 + Points [0, 65] + DstBlock "atlas_friction_model" + DstPort 1 + } + } + } + Branch { + ZOrder 23 + Labels [1, 1] + DstBlock "Integrator1" + DstPort 1 + } + } + Line { + Name "tau_acc" + ZOrder 24 + Labels [0, 0] + SrcBlock "Sum3" + SrcPort 1 + DstBlock "mFcn_Minv" + DstPort 2 + } + Line { + ZOrder 28 + SrcBlock "atlas5_arm_inertia_minvarpar" + SrcPort 1 + DstBlock "mFcn_Minv" + DstPort 1 + } + Line { + ZOrder 31 + SrcBlock "g" + SrcPort 1 + DstBlock "atlas5_arm_gravload_minvarpar" + DstPort 2 + } + Line { + Name "tau_m" + ZOrder 16 + Labels [0, 0] + SrcBlock "tau_m" + SrcPort 1 + Points [85, 0] + Branch { + ZOrder 40 + DstBlock "tau_J" + DstPort 1 + } + Branch { + ZOrder 39 + DstBlock "Sum2" + DstPort 1 + } + } + } + } + Block { + BlockType SubSystem + Name "atlas5_arm_gravload" + SID "281" + Ports [2, 1] + Position [475, 552, 545, 603] + ZOrder 229 + TreatAsAtomicUnit on + RequestExecContextInheritance off + System { + Name "atlas5_arm_gravload" + Location [273, 19, 1233, 1179] + Open off + ModelBrowserVisibility off + ModelBrowserWidth 200 + ScreenColor "white" + PaperOrientation "landscape" + PaperPositionMode "auto" + PaperType "A4" + PaperUnits "centimeters" + TiledPaperMargins [1.270000, 1.270000, 1.270000, 1.270000] + TiledPageScale 1 + ShowPageBoundaries off + ZoomFactor "100" + Block { + BlockType Inport + Name "q" + SID "324" + Position [15, 33, 45, 47] + ZOrder 102 + IconDisplay "Port number" + } + Block { + BlockType Inport + Name "g" + SID "325" + Position [15, 58, 45, 72] + ZOrder 104 + Port "2" + IconDisplay "Port number" + } + Block { + BlockType SubSystem + Name "mFcn_g" + SID "326" + Ports [2, 1] + Position [70, 26, 140, 79] + ZOrder 101 + LibraryVersion "1.110" + ErrorFcn "Stateflow.Translate.translate" + PermitHierarchicalResolution "ExplicitOnly" + TreatAsAtomicUnit on + RequestExecContextInheritance off + SFBlockType "MATLAB Function" + System { + Name "mFcn_g" + Location [223, 338, 826, 833] + Open off + ModelBrowserVisibility off + ModelBrowserWidth 200 + ScreenColor "white" + PaperOrientation "landscape" + PaperPositionMode "auto" + PaperType "A4" + PaperUnits "centimeters" + TiledPaperMargins [1.270000, 1.270000, 1.270000, 1.270000] + TiledPageScale 1 + ShowPageBoundaries off + ZoomFactor "100" + SIDHighWatermark "54" + Block { + BlockType Inport + Name "q" + SID "326::1" + Position [20, 101, 40, 119] + ZOrder -1 + IconDisplay "Port number" + } + Block { + BlockType Inport + Name "g" + SID "326::48" + Position [20, 136, 40, 154] + ZOrder 16 + Port "2" + IconDisplay "Port number" + } + Block { + BlockType Demux + Name " Demux " + SID "326::53" + Ports [1, 1] + Position [270, 230, 320, 270] + ZOrder 21 + Outputs "1" + } + Block { + BlockType S-Function + Name " SFunction " + SID "326::52" + Tag "Stateflow S-Function atlas_dynamic_library 29" + Ports [2, 2] + Position [180, 100, 230, 160] + ZOrder 20 + FunctionName "sf_sfun" + Parameters "atlas_arm_lr" + PortCounts "[2 2]" + EnableBusSupport off + Port { + PortNumber 2 + Name "tau_g" + RTWStorageClass "Auto" + DataLoggingNameMode "SignalName" + } + } + Block { + BlockType Terminator + Name " Terminator " + SID "326::54" + Position [460, 241, 480, 259] + ZOrder 22 + } + Block { + BlockType Outport + Name "tau_g" + SID "326::5" + Position [460, 101, 480, 119] + ZOrder -5 + IconDisplay "Port number" + } + Line { + ZOrder 6 + SrcBlock "q" + SrcPort 1 + Points [120, 0] + DstBlock " SFunction " + DstPort 1 + } + Line { + ZOrder 7 + SrcBlock "g" + SrcPort 1 + DstBlock " SFunction " + DstPort 2 + } + Line { + Name "tau_g" + ZOrder 8 + Labels [0, 0] + SrcBlock " SFunction " + SrcPort 2 + DstBlock "tau_g" + DstPort 1 + } + Line { + ZOrder 9 + SrcBlock " Demux " + SrcPort 1 + DstBlock " Terminator " + DstPort 1 + } + Line { + ZOrder 10 + SrcBlock " SFunction " + SrcPort 1 + DstBlock " Demux " + DstPort 1 + } + } + } + Block { + BlockType Outport + Name "tau_g" + SID "327" + Position [160, 48, 190, 62] + ZOrder 103 + IconDisplay "Port number" + } + Line { + ZOrder 1 + SrcBlock "q" + SrcPort 1 + DstBlock "mFcn_g" + DstPort 1 + } + Line { + ZOrder 2 + SrcBlock "mFcn_g" + SrcPort 1 + DstBlock "tau_g" + DstPort 1 + } + Line { + ZOrder 3 + SrcBlock "g" + SrcPort 1 + DstBlock "mFcn_g" + DstPort 2 + } + } + } + Block { + BlockType SubSystem + Name "atlas5_arm_gravload_minvarpar" + SID "282" + Ports [2, 1] + Position [750, 552, 820, 603] + ZOrder 235 + TreatAsAtomicUnit on + RequestExecContextInheritance off + Object { + $PropName "MaskObject" + $ObjectID 86 + $ClassName "Simulink.Mask" + Array { + Type "Simulink.MaskParameter" + Dimension 2 + Object { + $ObjectID 87 + Type "edit" + Name "atlas_arm_lr" + Prompt "atlas_arm_lr (left = true, right = false)" + Value "atlas_arm_lr" + } + Object { + $ObjectID 88 + Type "edit" + Name "MPV" + Prompt "MPV (vector of minimal parameters)" + Value "MPV" + } + PropName "Parameters" + } + } + System { + Name "atlas5_arm_gravload_minvarpar" + Location [0, 52, 1920, 1080] + Open off + ModelBrowserVisibility off + ModelBrowserWidth 200 + ScreenColor "white" + PaperOrientation "landscape" + PaperPositionMode "auto" + PaperType "A4" + PaperUnits "centimeters" + TiledPaperMargins [1.270000, 1.270000, 1.270000, 1.270000] + TiledPageScale 1 + ShowPageBoundaries off + ZoomFactor "100" + Block { + BlockType Inport + Name "q" + SID "307" + Position [20, 33, 50, 47] + ZOrder 118 + IconDisplay "Port number" + } + Block { + BlockType Inport + Name "g" + SID "308" + Position [20, 63, 50, 77] + ZOrder 120 + Port "2" + IconDisplay "Port number" + } + Block { + BlockType SubSystem + Name "mFcn_g" + SID "309" + Ports [2, 1] + Position [70, 27, 140, 83] + ZOrder 117 + LibraryVersion "1.124" + ErrorFcn "Stateflow.Translate.translate" + PermitHierarchicalResolution "ExplicitOnly" + TreatAsAtomicUnit on + RequestExecContextInheritance off + SFBlockType "MATLAB Function" + System { + Name "mFcn_g" + Location [223, 338, 826, 833] + Open off + ModelBrowserVisibility off + ModelBrowserWidth 200 + ScreenColor "white" + PaperOrientation "landscape" + PaperPositionMode "auto" + PaperType "A4" + PaperUnits "centimeters" + TiledPaperMargins [1.270000, 1.270000, 1.270000, 1.270000] + TiledPageScale 1 + ShowPageBoundaries off + ZoomFactor "100" + SIDHighWatermark "127" + Block { + BlockType Inport + Name "q" + SID "309::1" + Position [20, 101, 40, 119] + ZOrder -1 + IconDisplay "Port number" + } + Block { + BlockType Inport + Name "g" + SID "309::75" + Position [20, 136, 40, 154] + ZOrder 22 + Port "2" + IconDisplay "Port number" + } + Block { + BlockType Demux + Name " Demux " + SID "309::102" + Ports [1, 1] + Position [270, 230, 320, 270] + ZOrder 30 + Outputs "1" + } + Block { + BlockType S-Function + Name " SFunction " + SID "309::101" + Tag "Stateflow S-Function atlas_dynamic_library 33" + Ports [2, 2] + Position [180, 100, 230, 160] + ZOrder 29 + FunctionName "sf_sfun" + Parameters "MPV,atlas_arm_lr" + PortCounts "[2 2]" + EnableBusSupport off + Port { + PortNumber 2 + Name "tau_g" + RTWStorageClass "Auto" + DataLoggingNameMode "SignalName" + } + } + Block { + BlockType Terminator + Name " Terminator " + SID "309::103" + Position [460, 241, 480, 259] + ZOrder 31 + } + Block { + BlockType Outport + Name "tau_g" + SID "309::5" + Position [460, 101, 480, 119] + ZOrder -5 + IconDisplay "Port number" + } + Line { + ZOrder 6 + SrcBlock "q" + SrcPort 1 + Points [120, 0] + DstBlock " SFunction " + DstPort 1 + } + Line { + ZOrder 7 + SrcBlock "g" + SrcPort 1 + DstBlock " SFunction " + DstPort 2 + } + Line { + Name "tau_g" + ZOrder 8 + Labels [0, 0] + SrcBlock " SFunction " + SrcPort 2 + DstBlock "tau_g" + DstPort 1 + } + Line { + ZOrder 9 + SrcBlock " Demux " + SrcPort 1 + DstBlock " Terminator " + DstPort 1 + } + Line { + ZOrder 10 + SrcBlock " SFunction " + SrcPort 1 + DstBlock " Demux " + DstPort 1 + } + } + } + Block { + BlockType Outport + Name "tau_g" + SID "310" + Position [160, 48, 190, 62] + ZOrder 119 + IconDisplay "Port number" + } + Line { + ZOrder 1 + SrcBlock "g" + SrcPort 1 + DstBlock "mFcn_g" + DstPort 2 + } + Line { + ZOrder 2 + SrcBlock "mFcn_g" + SrcPort 1 + DstBlock "tau_g" + DstPort 1 + } + Line { + ZOrder 3 + SrcBlock "q" + SrcPort 1 + DstBlock "mFcn_g" + DstPort 1 + } + } + } + Block { + BlockType SubSystem + Name "atlas5_arm_inertia" + SID "283" + Ports [1, 1] + Position [585, 550, 655, 600] + ZOrder 228 + TreatAsAtomicUnit on + RequestExecContextInheritance off + System { + Name "atlas5_arm_inertia" + Location [273, 19, 1233, 1179] + Open off + ModelBrowserVisibility off + ModelBrowserWidth 200 + ScreenColor "white" + PaperOrientation "landscape" + PaperPositionMode "auto" + PaperType "A4" + PaperUnits "centimeters" + TiledPaperMargins [1.270000, 1.270000, 1.270000, 1.270000] + TiledPageScale 1 + ShowPageBoundaries off + ZoomFactor "100" + Block { + BlockType Inport + Name "q" + SID "311" + Position [20, 43, 50, 57] + ZOrder 100 + IconDisplay "Port number" + } + Block { + BlockType SubSystem + Name "mFcn_M" + SID "312" + Ports [1, 1] + Position [70, 24, 140, 76] + ZOrder 99 + LibraryVersion "1.110" + ErrorFcn "Stateflow.Translate.translate" + PermitHierarchicalResolution "ExplicitOnly" + TreatAsAtomicUnit on + RequestExecContextInheritance off + SFBlockType "MATLAB Function" + System { + Name "mFcn_M" + Location [223, 338, 826, 833] + Open off + ModelBrowserVisibility off + ModelBrowserWidth 200 + ScreenColor "white" + PaperOrientation "landscape" + PaperPositionMode "auto" + PaperType "A4" + PaperUnits "centimeters" + TiledPaperMargins [1.270000, 1.270000, 1.270000, 1.270000] + TiledPageScale 1 + ShowPageBoundaries off + ZoomFactor "100" + SIDHighWatermark "53" + Block { + BlockType Inport + Name "q" + SID "312::1" + Position [20, 101, 40, 119] + ZOrder -1 + IconDisplay "Port number" + } + Block { + BlockType Demux + Name " Demux " + SID "312::52" + Ports [1, 1] + Position [270, 230, 320, 270] + ZOrder 20 + Outputs "1" + } + Block { + BlockType S-Function + Name " SFunction " + SID "312::51" + Tag "Stateflow S-Function atlas_dynamic_library 31" + Ports [1, 2] + Position [180, 100, 230, 160] + ZOrder 19 + FunctionName "sf_sfun" + Parameters "atlas_arm_lr" + PortCounts "[1 2]" + EnableBusSupport off + Port { + PortNumber 2 + Name "M" + RTWStorageClass "Auto" + DataLoggingNameMode "SignalName" + } + } + Block { + BlockType Terminator + Name " Terminator " + SID "312::53" + Position [460, 241, 480, 259] + ZOrder 21 + } + Block { + BlockType Outport + Name "M" + SID "312::5" + Position [460, 101, 480, 119] + ZOrder -5 + IconDisplay "Port number" + } + Line { + ZOrder 5 + SrcBlock "q" + SrcPort 1 + DstBlock " SFunction " + DstPort 1 + } + Line { + Name "M" + ZOrder 6 + Labels [0, 0] + SrcBlock " SFunction " + SrcPort 2 + DstBlock "M" + DstPort 1 + } + Line { + ZOrder 7 + SrcBlock " Demux " + SrcPort 1 + DstBlock " Terminator " + DstPort 1 + } + Line { + ZOrder 8 + SrcBlock " SFunction " + SrcPort 1 + DstBlock " Demux " + DstPort 1 + } + } + } + Block { + BlockType Outport + Name "M" + SID "313" + Position [160, 43, 190, 57] + ZOrder 101 + IconDisplay "Port number" + } + Line { + ZOrder 1 + SrcBlock "q" + SrcPort 1 + DstBlock "mFcn_M" + DstPort 1 + } + Line { + ZOrder 2 + SrcBlock "mFcn_M" + SrcPort 1 + DstBlock "M" + DstPort 1 + } + } + } + Block { + BlockType SubSystem + Name "atlas5_arm_inertia_minvarpar" + SID "284" + Ports [1, 1] + Position [880, 556, 950, 604] + ZOrder 237 + TreatAsAtomicUnit on + RequestExecContextInheritance off + Object { + $PropName "MaskObject" + $ObjectID 89 + $ClassName "Simulink.Mask" + Array { + Type "Simulink.MaskParameter" + Dimension 2 + Object { + $ObjectID 90 + Type "edit" + Name "atlas_arm_lr" + Prompt "atlas_arm_lr (left = true, right = false)" + Value "atlas_arm_lr" + } + Object { + $ObjectID 91 + Type "edit" + Name "MPV" + Prompt "MPV (vector of minimal parameters)" + Value "MPV" + } + PropName "Parameters" + } + } + System { + Name "atlas5_arm_inertia_minvarpar" + Location [0, 52, 1920, 1080] + Open off + ModelBrowserVisibility off + ModelBrowserWidth 200 + ScreenColor "white" + PaperOrientation "landscape" + PaperPositionMode "auto" + PaperType "A4" + PaperUnits "centimeters" + TiledPaperMargins [1.270000, 1.270000, 1.270000, 1.270000] + TiledPageScale 1 + ShowPageBoundaries off + ZoomFactor "100" + Block { + BlockType Inport + Name "q" + SID "288" + Position [20, 43, 50, 57] + ZOrder 116 + IconDisplay "Port number" + } + Block { + BlockType SubSystem + Name "mFcn_M" + SID "289" + Ports [1, 1] + Position [70, 22, 140, 78] + ZOrder 115 + LibraryVersion "1.124" + ErrorFcn "Stateflow.Translate.translate" + PermitHierarchicalResolution "ExplicitOnly" + TreatAsAtomicUnit on + RequestExecContextInheritance off + SFBlockType "MATLAB Function" + System { + Name "mFcn_M" + Location [223, 338, 826, 833] + Open off + ModelBrowserVisibility off + ModelBrowserWidth 200 + ScreenColor "white" + PaperOrientation "landscape" + PaperPositionMode "auto" + PaperType "A4" + PaperUnits "centimeters" + TiledPaperMargins [1.270000, 1.270000, 1.270000, 1.270000] + TiledPageScale 1 + ShowPageBoundaries off + ZoomFactor "100" + SIDHighWatermark "119" + Block { + BlockType Inport + Name "q" + SID "289::1" + Position [20, 101, 40, 119] + ZOrder -1 + IconDisplay "Port number" + } + Block { + BlockType Demux + Name " Demux " + SID "289::98" + Ports [1, 1] + Position [270, 230, 320, 270] + ZOrder 29 + Outputs "1" + } + Block { + BlockType S-Function + Name " SFunction " + SID "289::97" + Tag "Stateflow S-Function atlas_dynamic_library 35" + Ports [1, 2] + Position [180, 100, 230, 160] + ZOrder 28 + FunctionName "sf_sfun" + Parameters "MPV,atlas_arm_lr" + PortCounts "[1 2]" + EnableBusSupport off + Port { + PortNumber 2 + Name "M" + RTWStorageClass "Auto" + DataLoggingNameMode "SignalName" + } + } + Block { + BlockType Terminator + Name " Terminator " + SID "289::99" + Position [460, 241, 480, 259] + ZOrder 30 + } + Block { + BlockType Outport + Name "M" + SID "289::5" + Position [460, 101, 480, 119] + ZOrder -5 + IconDisplay "Port number" + } + Line { + ZOrder 5 + SrcBlock "q" + SrcPort 1 + DstBlock " SFunction " + DstPort 1 + } + Line { + Name "M" + ZOrder 6 + Labels [0, 0] + SrcBlock " SFunction " + SrcPort 2 + DstBlock "M" + DstPort 1 + } + Line { + ZOrder 7 + SrcBlock " Demux " + SrcPort 1 + DstBlock " Terminator " + DstPort 1 + } + Line { + ZOrder 8 + SrcBlock " SFunction " + SrcPort 1 + DstBlock " Demux " + DstPort 1 + } + } + } + Block { + BlockType Outport + Name "M" + SID "290" + Position [160, 43, 190, 57] + ZOrder 117 + IconDisplay "Port number" + } + Line { + ZOrder 1 + SrcBlock "mFcn_M" + SrcPort 1 + DstBlock "M" + DstPort 1 + } + Line { + ZOrder 2 + SrcBlock "q" + SrcPort 1 + DstBlock "mFcn_M" + DstPort 1 + } + } + } + Block { + BlockType SubSystem + Name "atlas5_arm_invdyn_fb_minvarpar" + SID "285" + Ports [4, 1] + Position [1005, 471, 1075, 524] + ZOrder 238 + TreatAsAtomicUnit on + RequestExecContextInheritance off + Object { + $PropName "MaskObject" + $ObjectID 92 + $ClassName "Simulink.Mask" + Object { + $PropName "Parameters" + $ObjectID 93 + $ClassName "Simulink.MaskParameter" + Type "edit" + Name "MPV" + Prompt "MPV (vector of minimal parameters)" + Value "MPV" + } + } + System { + Name "atlas5_arm_invdyn_fb_minvarpar" + Location [0, 52, 1920, 1080] + Open off + ModelBrowserVisibility off + ModelBrowserWidth 200 + ScreenColor "white" + PaperOrientation "landscape" + PaperPositionMode "auto" + PaperType "A4" + PaperUnits "centimeters" + TiledPaperMargins [1.270000, 1.270000, 1.270000, 1.270000] + TiledPageScale 1 + ShowPageBoundaries off + ZoomFactor "100" + Block { + BlockType Inport + Name "q" + SID "291" + Position [20, 33, 50, 47] + ZOrder 117 + IconDisplay "Port number" + } + Block { + BlockType Inport + Name "qD" + SID "292" + Position [20, 58, 50, 72] + ZOrder 118 + Port "2" + IconDisplay "Port number" + } + Block { + BlockType Inport + Name "qDD" + SID "293" + Position [20, 83, 50, 97] + ZOrder 121 + Port "3" + IconDisplay "Port number" + } + Block { + BlockType Inport + Name "g" + SID "294" + Position [20, 108, 50, 122] + ZOrder 122 + Port "4" + IconDisplay "Port number" + } + Block { + BlockType SubSystem + Name "mFcn_tau" + SID "295" + Ports [4, 1] + Position [70, 28, 190, 127] + ZOrder 116 + LibraryVersion "1.124" + ErrorFcn "Stateflow.Translate.translate" + PermitHierarchicalResolution "ExplicitOnly" + TreatAsAtomicUnit on + RequestExecContextInheritance off + SFBlockType "MATLAB Function" + System { + Name "mFcn_tau" + Location [223, 338, 826, 833] + Open off + ModelBrowserVisibility off + ModelBrowserWidth 200 + ScreenColor "white" + PaperOrientation "landscape" + PaperPositionMode "auto" + PaperType "A4" + PaperUnits "centimeters" + TiledPaperMargins [1.270000, 1.270000, 1.270000, 1.270000] + TiledPageScale 1 + ShowPageBoundaries off + ZoomFactor "100" + SIDHighWatermark "119" + Block { + BlockType Inport + Name "q" + SID "295::1" + Position [20, 101, 40, 119] + ZOrder -1 + IconDisplay "Port number" + } + Block { + BlockType Inport + Name "qD" + SID "295::21" + Position [20, 136, 40, 154] + ZOrder 7 + Port "2" + IconDisplay "Port number" + } + Block { + BlockType Inport + Name "qDD" + SID "295::96" + Position [20, 171, 40, 189] + ZOrder 32 + Port "3" + IconDisplay "Port number" + } + Block { + BlockType Inport + Name "g" + SID "295::97" + Position [20, 206, 40, 224] + ZOrder 33 + Port "4" + IconDisplay "Port number" + } + Block { + BlockType Demux + Name " Demux " + SID "295::118" + Ports [1, 1] + Position [270, 230, 320, 270] + ZOrder 38 + Outputs "1" + } + Block { + BlockType S-Function + Name " SFunction " + SID "295::117" + Tag "Stateflow S-Function atlas_dynamic_library 36" + Ports [4, 2] + Position [180, 102, 230, 203] + ZOrder 37 + FunctionName "sf_sfun" + Parameters "MPV,atlas_arm_lr" + PortCounts "[4 2]" + EnableBusSupport off + Port { + PortNumber 2 + Name "tau" + RTWStorageClass "Auto" + DataLoggingNameMode "SignalName" + } + } + Block { + BlockType Terminator + Name " Terminator " + SID "295::119" + Position [460, 241, 480, 259] + ZOrder 39 + } + Block { + BlockType Outport + Name "tau" + SID "295::27" + Position [460, 101, 480, 119] + ZOrder 13 + IconDisplay "Port number" + } + Line { + ZOrder 8 + SrcBlock "q" + SrcPort 1 + DstBlock " SFunction " + DstPort 1 + } + Line { + ZOrder 9 + SrcBlock "qD" + SrcPort 1 + DstBlock " SFunction " + DstPort 2 + } + Line { + ZOrder 10 + SrcBlock "qDD" + SrcPort 1 + DstBlock " SFunction " + DstPort 3 + } + Line { + ZOrder 11 + SrcBlock "g" + SrcPort 1 + DstBlock " SFunction " + DstPort 4 + } + Line { + Name "tau" + ZOrder 12 + Labels [0, 0] + SrcBlock " SFunction " + SrcPort 2 + DstBlock "tau" + DstPort 1 + } + Line { + ZOrder 13 + SrcBlock " Demux " + SrcPort 1 + DstBlock " Terminator " + DstPort 1 + } + Line { + ZOrder 14 + SrcBlock " SFunction " + SrcPort 1 + DstBlock " Demux " + DstPort 1 + } + } + } + Block { + BlockType Outport + Name "tau" + SID "296" + Position [260, 73, 290, 87] + ZOrder 119 + IconDisplay "Port number" + } + Line { + ZOrder 1 + SrcBlock "g" + SrcPort 1 + DstBlock "mFcn_tau" + DstPort 4 + } + Line { + ZOrder 2 + SrcBlock "qDD" + SrcPort 1 + DstBlock "mFcn_tau" + DstPort 3 + } + Line { + ZOrder 3 + SrcBlock "qD" + SrcPort 1 + DstBlock "mFcn_tau" + DstPort 2 + } + Line { + ZOrder 4 + SrcBlock "q" + SrcPort 1 + DstBlock "mFcn_tau" + DstPort 1 + } + Line { + ZOrder 5 + SrcBlock "mFcn_tau" + SrcPort 1 + DstBlock "tau" + DstPort 1 + } + } + } + Block { + BlockType SubSystem + Name "atlas5_arm_jacobig" + SID "286" + Ports [1, 1] + Position [370, 550, 440, 600] + ZOrder 231 + TreatAsAtomicUnit on + RequestExecContextInheritance off + System { + Name "atlas5_arm_jacobig" + Location [-10, -14, 1930, 1090] + Open off + ModelBrowserVisibility off + ModelBrowserWidth 200 + ScreenColor "white" + PaperOrientation "landscape" + PaperPositionMode "auto" + PaperType "A4" + PaperUnits "centimeters" + TiledPaperMargins [1.270000, 1.270000, 1.270000, 1.270000] + TiledPageScale 1 + ShowPageBoundaries off + ZoomFactor "100" + Block { + BlockType Inport + Name "q" + SID "328" + Position [20, 38, 50, 52] + ZOrder 88 + IconDisplay "Port number" + } + Block { + BlockType SubSystem + Name "atlas5_arm_jacobig" + SID "329" + Ports [1, 1] + Position [70, 20, 140, 70] + ZOrder 87 + NamePlacement "alternate" + LibraryVersion "1.72" + ErrorFcn "Stateflow.Translate.translate" + PermitHierarchicalResolution "ExplicitOnly" + TreatAsAtomicUnit on + RequestExecContextInheritance off + SFBlockType "MATLAB Function" + Object { + $PropName "MaskObject" + $ObjectID 94 + $ClassName "Simulink.Mask" + Initialization "if edit_lr == 1\n atlas_arm_lr = true; % left\nelse\n atlas_arm_lr = false; % right\nend\n" + Object { + $PropName "Parameters" + $ObjectID 95 + $ClassName "Simulink.MaskParameter" + Type "edit" + Name "edit_lr" + Prompt "Arm (left = true, right = false)" + Value "atlas_arm_lr" + } + } + System { + Name "atlas5_arm_jacobig" + Location [223, 338, 826, 833] + Open off + ModelBrowserVisibility off + ModelBrowserWidth 200 + ScreenColor "white" + PaperOrientation "landscape" + PaperPositionMode "auto" + PaperType "A4" + PaperUnits "centimeters" + TiledPaperMargins [1.270000, 1.270000, 1.270000, 1.270000] + TiledPageScale 1 + ShowPageBoundaries off + ZoomFactor "100" + SIDHighWatermark "77" + Block { + BlockType Inport + Name "q" + SID "329::1" + Position [20, 101, 40, 119] + ZOrder -1 + IconDisplay "Port number" + } + Block { + BlockType Demux + Name " Demux " + SID "329::56" + Ports [1, 1] + Position [270, 230, 320, 270] + ZOrder 25 + Outputs "1" + } + Block { + BlockType S-Function + Name " SFunction " + SID "329::55" + Tag "Stateflow S-Function atlas_dynamic_library 28" + Ports [1, 2] + Position [180, 100, 230, 160] + ZOrder 24 + FunctionName "sf_sfun" + Parameters "atlas_arm_lr" + PortCounts "[1 2]" + EnableBusSupport off + Port { + PortNumber 2 + Name "JG" + RTWStorageClass "Auto" + DataLoggingNameMode "SignalName" + } + } + Block { + BlockType Terminator + Name " Terminator " + SID "329::57" + Position [460, 241, 480, 259] + ZOrder 26 + } + Block { + BlockType Outport + Name "JG" + SID "329::5" + Position [460, 101, 480, 119] + ZOrder -5 + IconDisplay "Port number" + } + Line { + ZOrder 5 + SrcBlock "q" + SrcPort 1 + DstBlock " SFunction " + DstPort 1 + } + Line { + Name "JG" + ZOrder 6 + Labels [0, 0] + SrcBlock " SFunction " + SrcPort 2 + DstBlock "JG" + DstPort 1 + } + Line { + ZOrder 7 + SrcBlock " Demux " + SrcPort 1 + DstBlock " Terminator " + DstPort 1 + } + Line { + ZOrder 8 + SrcBlock " SFunction " + SrcPort 1 + DstBlock " Demux " + DstPort 1 + } + } + } + Block { + BlockType Outport + Name "JG" + SID "330" + Position [160, 38, 190, 52] + ZOrder 89 + IconDisplay "Port number" + } + Line { + ZOrder 1 + SrcBlock "atlas5_arm_jacobig" + SrcPort 1 + DstBlock "JG" + DstPort 1 + } + Line { + ZOrder 2 + SrcBlock "q" + SrcPort 1 + DstBlock "atlas5_arm_jacobig" + DstPort 1 + } + } + } + Block { + BlockType SubSystem + Name "atlas_arm_coriolis_vec" + SID "180" + Ports [2, 1] + Position [585, 242, 655, 293] + ZOrder 120 + TreatAsAtomicUnit on + RequestExecContextInheritance off + System { + Name "atlas_arm_coriolis_vec" + Location [718, 141, 1933, 1093] + Open off + ModelBrowserVisibility off + ModelBrowserWidth 200 + ScreenColor "white" + PaperOrientation "landscape" + PaperPositionMode "auto" + PaperType "A4" + PaperUnits "centimeters" + TiledPaperMargins [1.270000, 1.270000, 1.270000, 1.270000] + TiledPageScale 1 + ShowPageBoundaries off + ZoomFactor "100" + Block { + BlockType Inport + Name "q" + SID "181" + Position [20, 33, 50, 47] + ZOrder 117 + IconDisplay "Port number" + } + Block { + BlockType Inport + Name "qD" + SID "182" + Position [20, 63, 50, 77] + ZOrder 118 + Port "2" + IconDisplay "Port number" + } + Block { + BlockType SubSystem + Name "mFcn_c" + SID "172" + Ports [2, 1] + Position [70, 24, 140, 86] + ZOrder 116 + LibraryVersion "1.124" + ErrorFcn "Stateflow.Translate.translate" + PermitHierarchicalResolution "ExplicitOnly" + TreatAsAtomicUnit on + RequestExecContextInheritance off + SFBlockType "MATLAB Function" + System { + Name "mFcn_c" + Location [223, 338, 826, 833] + Open off + ModelBrowserVisibility off + ModelBrowserWidth 200 + ScreenColor "white" + PaperOrientation "landscape" + PaperPositionMode "auto" + PaperType "A4" + PaperUnits "centimeters" + TiledPaperMargins [1.270000, 1.270000, 1.270000, 1.270000] + TiledPageScale 1 + ShowPageBoundaries off + ZoomFactor "100" + SIDHighWatermark "136" + Block { + BlockType Inport + Name "q" + SID "172::1" + Position [20, 101, 40, 119] + ZOrder -1 + IconDisplay "Port number" + } + Block { + BlockType Inport + Name "qD" + SID "172::21" + Position [20, 136, 40, 154] + ZOrder 7 + Port "2" + IconDisplay "Port number" + } + Block { + BlockType Demux + Name " Demux " + SID "172::75" + Ports [1, 1] + Position [270, 230, 320, 270] + ZOrder 24 + Outputs "1" + } + Block { + BlockType S-Function + Name " SFunction " + SID "172::74" + Tag "Stateflow S-Function atlas_dynamic_library 10" + Ports [2, 2] + Position [180, 100, 230, 160] + ZOrder 23 + FunctionName "sf_sfun" + Parameters "atlas_arm_lr,atlas_version" + PortCounts "[2 2]" + EnableBusSupport off + Port { + PortNumber 2 + Name "tau_c" + RTWStorageClass "Auto" + DataLoggingNameMode "SignalName" + } + } + Block { + BlockType Terminator + Name " Terminator " + SID "172::76" + Position [460, 241, 480, 259] + ZOrder 25 + } + Block { + BlockType Outport + Name "tau_c" + SID "172::27" + Position [460, 101, 480, 119] + ZOrder 13 + IconDisplay "Port number" + } + Line { + ZOrder 6 + SrcBlock "q" + SrcPort 1 + Points [120, 0] + DstBlock " SFunction " + DstPort 1 + } + Line { + ZOrder 7 + SrcBlock "qD" + SrcPort 1 + DstBlock " SFunction " + DstPort 2 + } + Line { + Name "tau_c" + ZOrder 8 + Labels [0, 0] + SrcBlock " SFunction " + SrcPort 2 + DstBlock "tau_c" + DstPort 1 + } + Line { + ZOrder 9 + SrcBlock " Demux " + SrcPort 1 + DstBlock " Terminator " + DstPort 1 + } + Line { + ZOrder 10 + SrcBlock " SFunction " + SrcPort 1 + DstBlock " Demux " + DstPort 1 + } + } + } + Block { + BlockType Outport + Name "tau_c" + SID "183" + Position [160, 48, 190, 62] + ZOrder 119 + IconDisplay "Port number" + } + Line { + ZOrder 37 + SrcBlock "mFcn_c" + SrcPort 1 + DstBlock "tau_c" + DstPort 1 + } + Line { + ZOrder 35 + SrcBlock "q" + SrcPort 1 + DstBlock "mFcn_c" + DstPort 1 + } + Line { + ZOrder 36 + SrcBlock "qD" + SrcPort 1 + DstBlock "mFcn_c" + DstPort 2 + } + } + } + Block { + BlockType SubSystem + Name "atlas_arm_coriolis_vec_minvarpar" + SID "217" + Ports [2, 1] + Position [925, 247, 995, 298] + ZOrder 126 + TreatAsAtomicUnit on + RequestExecContextInheritance off + Object { + $PropName "MaskObject" + $ObjectID 96 + $ClassName "Simulink.Mask" + Array { + Type "Simulink.MaskParameter" + Dimension 3 + Object { + $ObjectID 97 + Type "edit" + Name "atlas_arm_lr" + Prompt "atlas_arm_lr (left = true, right = false)" + Value "atlas_arm_lr" + } + Object { + $ObjectID 98 + Type "edit" + Name "atlas_version" + Prompt "atlas_version (3, 4)" + Value "atlas_version" + } + Object { + $ObjectID 99 + Type "edit" + Name "MPV" + Prompt "MPV (vecotr of minimal parameters)" + Value "MPV" + } + PropName "Parameters" + } + } + System { + Name "atlas_arm_coriolis_vec_minvarpar" + Location [1421, 62, 2636, 1014] + Open off + ModelBrowserVisibility off + ModelBrowserWidth 200 + ScreenColor "white" + PaperOrientation "landscape" + PaperPositionMode "auto" + PaperType "A4" + PaperUnits "centimeters" + TiledPaperMargins [1.270000, 1.270000, 1.270000, 1.270000] + TiledPageScale 1 + ShowPageBoundaries off + ZoomFactor "100" + Block { + BlockType Inport + Name "q" + SID "218" + Position [20, 33, 50, 47] + ZOrder 117 + IconDisplay "Port number" + } + Block { + BlockType Inport + Name "qD" + SID "219" + Position [20, 63, 50, 77] + ZOrder 118 + Port "2" + IconDisplay "Port number" + } + Block { + BlockType SubSystem + Name "mFcn_c" + SID "220" + Ports [2, 1] + Position [70, 24, 140, 86] + ZOrder 116 + LibraryVersion "1.124" + ErrorFcn "Stateflow.Translate.translate" + PermitHierarchicalResolution "ExplicitOnly" + TreatAsAtomicUnit on + RequestExecContextInheritance off + SFBlockType "MATLAB Function" + System { + Name "mFcn_c" + Location [223, 338, 826, 833] + Open off + ModelBrowserVisibility off + ModelBrowserWidth 200 + ScreenColor "white" + PaperOrientation "landscape" + PaperPositionMode "auto" + PaperType "A4" + PaperUnits "centimeters" + TiledPaperMargins [1.270000, 1.270000, 1.270000, 1.270000] + TiledPageScale 1 + ShowPageBoundaries off + ZoomFactor "100" + SIDHighWatermark "152" + Block { + BlockType Inport + Name "q" + SID "220::1" + Position [20, 101, 40, 119] + ZOrder -1 + IconDisplay "Port number" + } + Block { + BlockType Inport + Name "qD" + SID "220::21" + Position [20, 136, 40, 154] + ZOrder 7 + Port "2" + IconDisplay "Port number" + } + Block { + BlockType Demux + Name " Demux " + SID "220::90" + Ports [1, 1] + Position [270, 230, 320, 270] + ZOrder 27 + Outputs "1" + } + Block { + BlockType S-Function + Name " SFunction " + SID "220::89" + Tag "Stateflow S-Function atlas_dynamic_library 15" + Ports [2, 2] + Position [180, 100, 230, 160] + ZOrder 26 + FunctionName "sf_sfun" + Parameters "MPV,atlas_arm_lr,atlas_version" + PortCounts "[2 2]" + EnableBusSupport off + Port { + PortNumber 2 + Name "tau_c" + RTWStorageClass "Auto" + DataLoggingNameMode "SignalName" + } + } + Block { + BlockType Terminator + Name " Terminator " + SID "220::91" + Position [460, 241, 480, 259] + ZOrder 28 + } + Block { + BlockType Outport + Name "tau_c" + SID "220::27" + Position [460, 101, 480, 119] + ZOrder 13 + IconDisplay "Port number" + } + Line { + ZOrder 17 + SrcBlock "q" + SrcPort 1 + DstBlock " SFunction " + DstPort 1 + } + Line { + ZOrder 18 + SrcBlock "qD" + SrcPort 1 + DstBlock " SFunction " + DstPort 2 + } + Line { + Name "tau_c" + ZOrder 19 + Labels [0, 0] + SrcBlock " SFunction " + SrcPort 2 + DstBlock "tau_c" + DstPort 1 + } + Line { + ZOrder 20 + SrcBlock " Demux " + SrcPort 1 + DstBlock " Terminator " + DstPort 1 + } + Line { + ZOrder 21 + SrcBlock " SFunction " + SrcPort 1 + DstBlock " Demux " + DstPort 1 + } + } + } + Block { + BlockType Outport + Name "tau_c" + SID "221" + Position [160, 48, 190, 62] + ZOrder 119 + IconDisplay "Port number" + } + Line { + ZOrder 1 + SrcBlock "qD" + SrcPort 1 + DstBlock "mFcn_c" + DstPort 2 + } + Line { + ZOrder 2 + SrcBlock "q" + SrcPort 1 + DstBlock "mFcn_c" + DstPort 1 + } + Line { + ZOrder 3 + SrcBlock "mFcn_c" + SrcPort 1 + DstBlock "tau_c" + DstPort 1 + } + } + } + Block { + BlockType SubSystem + Name "atlas_arm_energy" + SID "187" + Ports [3, 2] + Position [475, 244, 545, 296] + ZOrder 122 + TreatAsAtomicUnit on + RequestExecContextInheritance off + System { + Name "atlas_arm_energy" + Location [1411, 277, 2646, 993] + Open off + ModelBrowserVisibility off + ModelBrowserWidth 200 + ScreenColor "white" + PaperOrientation "landscape" + PaperPositionMode "auto" + PaperType "A4" + PaperUnits "centimeters" + TiledPaperMargins [1.270000, 1.270000, 1.270000, 1.270000] + TiledPageScale 1 + ShowPageBoundaries off + ZoomFactor "100" + Block { + BlockType Inport + Name "q" + SID "188" + Position [5, 33, 35, 47] + ZOrder 91 + IconDisplay "Port number" + } + Block { + BlockType Inport + Name "qD" + SID "189" + Position [5, 63, 35, 77] + ZOrder 92 + Port "2" + IconDisplay "Port number" + } + Block { + BlockType Inport + Name "g" + SID "212" + Position [5, 93, 35, 107] + ZOrder 95 + Port "3" + IconDisplay "Port number" + } + Block { + BlockType SubSystem + Name "atlas_arm_energy_fb" + SID "116" + Ports [3, 2] + Position [70, 28, 160, 112] + ZOrder 90 + NamePlacement "alternate" + LibraryVersion "1.86" + ErrorFcn "Stateflow.Translate.translate" + PermitHierarchicalResolution "ExplicitOnly" + TreatAsAtomicUnit on + RequestExecContextInheritance off + SFBlockType "MATLAB Function" + System { + Name "atlas_arm_energy_fb" + Location [223, 338, 826, 833] + Open off + ModelBrowserVisibility off + ModelBrowserWidth 200 + ScreenColor "white" + PaperOrientation "landscape" + PaperPositionMode "auto" + PaperType "A4" + PaperUnits "centimeters" + TiledPaperMargins [1.270000, 1.270000, 1.270000, 1.270000] + TiledPageScale 1 + ShowPageBoundaries off + ZoomFactor "100" + SIDHighWatermark "121" + Block { + BlockType Inport + Name "q" + SID "116::1" + Position [20, 101, 40, 119] + ZOrder -1 + IconDisplay "Port number" + } + Block { + BlockType Inport + Name "qD" + SID "116::21" + Position [20, 136, 40, 154] + ZOrder 7 + Port "2" + IconDisplay "Port number" + } + Block { + BlockType Inport + Name "g_utorso" + SID "116::65" + Position [20, 171, 40, 189] + ZOrder 19 + Port "3" + IconDisplay "Port number" + } + Block { + BlockType Demux + Name " Demux " + SID "116::47" + Ports [1, 1] + Position [270, 230, 320, 270] + ZOrder 16 + Outputs "1" + } + Block { + BlockType S-Function + Name " SFunction " + SID "116::46" + Tag "Stateflow S-Function atlas_dynamic_library 16" + Ports [3, 3] + Position [180, 100, 230, 180] + ZOrder 15 + FunctionName "sf_sfun" + Parameters "atlas_arm_lr,atlas_version" + PortCounts "[3 3]" + EnableBusSupport off + Port { + PortNumber 2 + Name "T" + RTWStorageClass "Auto" + DataLoggingNameMode "SignalName" + } + Port { + PortNumber 3 + Name "U" + RTWStorageClass "Auto" + DataLoggingNameMode "SignalName" + } + } + Block { + BlockType Terminator + Name " Terminator " + SID "116::48" + Position [460, 241, 480, 259] + ZOrder 17 + } + Block { + BlockType Outport + Name "T" + SID "116::5" + Position [460, 101, 480, 119] + ZOrder -5 + IconDisplay "Port number" + } + Block { + BlockType Outport + Name "U" + SID "116::25" + Position [460, 136, 480, 154] + ZOrder 11 + Port "2" + IconDisplay "Port number" + } + Line { + ZOrder 39 + SrcBlock "q" + SrcPort 1 + DstBlock " SFunction " + DstPort 1 + } + Line { + ZOrder 40 + SrcBlock "qD" + SrcPort 1 + DstBlock " SFunction " + DstPort 2 + } + Line { + ZOrder 41 + SrcBlock "g_utorso" + SrcPort 1 + DstBlock " SFunction " + DstPort 3 + } + Line { + Name "T" + ZOrder 42 + Labels [0, 0] + SrcBlock " SFunction " + SrcPort 2 + DstBlock "T" + DstPort 1 + } + Line { + Name "U" + ZOrder 43 + Labels [0, 0] + SrcBlock " SFunction " + SrcPort 3 + DstBlock "U" + DstPort 1 + } + Line { + ZOrder 44 + SrcBlock " Demux " + SrcPort 1 + DstBlock " Terminator " + DstPort 1 + } + Line { + ZOrder 45 + SrcBlock " SFunction " + SrcPort 1 + DstBlock " Demux " + DstPort 1 + } + } + } + Block { + BlockType Outport + Name "T" + SID "190" + Position [215, 43, 245, 57] + ZOrder 93 + IconDisplay "Port number" + } + Block { + BlockType Outport + Name "U" + SID "191" + Position [215, 83, 245, 97] + ZOrder 94 + Port "2" + IconDisplay "Port number" + } + Line { + ZOrder 42 + SrcBlock "qD" + SrcPort 1 + DstBlock "atlas_arm_energy_fb" + DstPort 2 + } + Line { + ZOrder 43 + SrcBlock "atlas_arm_energy_fb" + SrcPort 1 + DstBlock "T" + DstPort 1 + } + Line { + ZOrder 44 + SrcBlock "atlas_arm_energy_fb" + SrcPort 2 + DstBlock "U" + DstPort 1 + } + Line { + ZOrder 41 + SrcBlock "q" + SrcPort 1 + DstBlock "atlas_arm_energy_fb" + DstPort 1 + } + Line { + ZOrder 46 + SrcBlock "g" + SrcPort 1 + DstBlock "atlas_arm_energy_fb" + DstPort 3 + } + } + } + Block { + BlockType SubSystem + Name "atlas_arm_energy_minvarpar" + SID "222" + Ports [3, 2] + Position [820, 244, 890, 296] + ZOrder 127 + TreatAsAtomicUnit on + RequestExecContextInheritance off + Object { + $PropName "MaskObject" + $ObjectID 100 + $ClassName "Simulink.Mask" + Object { + $PropName "Parameters" + $ObjectID 101 + $ClassName "Simulink.MaskParameter" + Type "edit" + Name "MPV" + Prompt "MPV (vector of minimal parameters)" + Value "MPV" + } + } + System { + Name "atlas_arm_energy_minvarpar" + Location [976, 17, 1932, 1093] + Open off + ModelBrowserVisibility off + ModelBrowserWidth 200 + ScreenColor "white" + PaperOrientation "landscape" + PaperPositionMode "auto" + PaperType "A4" + PaperUnits "centimeters" + TiledPaperMargins [1.270000, 1.270000, 1.270000, 1.270000] + TiledPageScale 1 + ShowPageBoundaries off + ZoomFactor "100" + Block { + BlockType Inport + Name "q" + SID "223" + Position [5, 33, 35, 47] + ZOrder 91 + IconDisplay "Port number" + } + Block { + BlockType Inport + Name "qD" + SID "224" + Position [5, 63, 35, 77] + ZOrder 92 + Port "2" + IconDisplay "Port number" + } + Block { + BlockType Inport + Name "g" + SID "225" + Position [5, 93, 35, 107] + ZOrder 95 + Port "3" + IconDisplay "Port number" + } + Block { + BlockType SubSystem + Name "atlas_arm_energy_fb" + SID "226" + Ports [3, 2] + Position [70, 28, 160, 112] + ZOrder 90 + NamePlacement "alternate" + LibraryVersion "1.86" + ErrorFcn "Stateflow.Translate.translate" + PermitHierarchicalResolution "ExplicitOnly" + TreatAsAtomicUnit on + RequestExecContextInheritance off + SFBlockType "MATLAB Function" + System { + Name "atlas_arm_energy_fb" + Location [223, 338, 826, 833] + Open off + ModelBrowserVisibility off + ModelBrowserWidth 200 + ScreenColor "white" + PaperOrientation "landscape" + PaperPositionMode "auto" + PaperType "A4" + PaperUnits "centimeters" + TiledPaperMargins [1.270000, 1.270000, 1.270000, 1.270000] + TiledPageScale 1 + ShowPageBoundaries off + ZoomFactor "100" + SIDHighWatermark "69" + Block { + BlockType Inport + Name "q" + SID "226::1" + Position [20, 101, 40, 119] + ZOrder -1 + IconDisplay "Port number" + } + Block { + BlockType Inport + Name "qD" + SID "226::21" + Position [20, 136, 40, 154] + ZOrder 7 + Port "2" + IconDisplay "Port number" + } + Block { + BlockType Inport + Name "g_utorso" + SID "226::65" + Position [20, 171, 40, 189] + ZOrder 19 + Port "3" + IconDisplay "Port number" + } + Block { + BlockType Demux + Name " Demux " + SID "226::67" + Ports [1, 1] + Position [270, 230, 320, 270] + ZOrder 21 + Outputs "1" + } + Block { + BlockType S-Function + Name " SFunction " + SID "226::66" + Tag "Stateflow S-Function atlas_dynamic_library 19" + Ports [3, 3] + Position [180, 105, 230, 185] + ZOrder 20 + FunctionName "sf_sfun" + Parameters "MPV,atlas_arm_lr,atlas_version" + PortCounts "[3 3]" + EnableBusSupport off + Port { + PortNumber 2 + Name "T" + RTWStorageClass "Auto" + DataLoggingNameMode "SignalName" + } + Port { + PortNumber 3 + Name "U" + RTWStorageClass "Auto" + DataLoggingNameMode "SignalName" + } + } + Block { + BlockType Terminator + Name " Terminator " + SID "226::68" + Position [460, 241, 480, 259] + ZOrder 22 + } + Block { + BlockType Outport + Name "T" + SID "226::5" + Position [460, 101, 480, 119] + ZOrder -5 + IconDisplay "Port number" + } + Block { + BlockType Outport + Name "U" + SID "226::25" + Position [460, 136, 480, 154] + ZOrder 11 + Port "2" + IconDisplay "Port number" + } + Line { + ZOrder 23 + SrcBlock "q" + SrcPort 1 + DstBlock " SFunction " + DstPort 1 + } + Line { + ZOrder 24 + SrcBlock "qD" + SrcPort 1 + DstBlock " SFunction " + DstPort 2 + } + Line { + ZOrder 25 + SrcBlock "g_utorso" + SrcPort 1 + DstBlock " SFunction " + DstPort 3 + } + Line { + Name "T" + ZOrder 26 + Labels [0, 0] + SrcBlock " SFunction " + SrcPort 2 + DstBlock "T" + DstPort 1 + } + Line { + Name "U" + ZOrder 27 + Labels [0, 0] + SrcBlock " SFunction " + SrcPort 3 + DstBlock "U" + DstPort 1 + } + Line { + ZOrder 28 + SrcBlock " Demux " + SrcPort 1 + DstBlock " Terminator " + DstPort 1 + } + Line { + ZOrder 29 + SrcBlock " SFunction " + SrcPort 1 + DstBlock " Demux " + DstPort 1 + } + } + } + Block { + BlockType Outport + Name "T" + SID "227" + Position [215, 43, 245, 57] + ZOrder 93 + IconDisplay "Port number" + } + Block { + BlockType Outport + Name "U" + SID "228" + Position [215, 83, 245, 97] + ZOrder 94 + Port "2" + IconDisplay "Port number" + } + Line { + ZOrder 1 + SrcBlock "g" + SrcPort 1 + DstBlock "atlas_arm_energy_fb" + DstPort 3 + } + Line { + ZOrder 2 + SrcBlock "q" + SrcPort 1 + DstBlock "atlas_arm_energy_fb" + DstPort 1 + } + Line { + ZOrder 3 + SrcBlock "atlas_arm_energy_fb" + SrcPort 2 + DstBlock "U" + DstPort 1 + } + Line { + ZOrder 4 + SrcBlock "atlas_arm_energy_fb" + SrcPort 1 + DstBlock "T" + DstPort 1 + } + Line { + ZOrder 5 + SrcBlock "qD" + SrcPort 1 + DstBlock "atlas_arm_energy_fb" + DstPort 2 + } + } + } + Block { + BlockType SubSystem + Name "atlas_arm_fordyn_rj_damping" + SID "100" + Ports [3, 3] + Position [110, 242, 280, 318] + ZOrder 89 + RequestExecContextInheritance off + Object { + $PropName "MaskObject" + $ObjectID 102 + $ClassName "Simulink.Mask" + Array { + Type "Simulink.MaskParameter" + Dimension 6 + Object { + $ObjectID 103 + Type "edit" + Name "q0" + Prompt "q0 (initial pose)" + Value "q0" + } + Object { + $ObjectID 104 + Type "edit" + Name "qD0" + Prompt "qD0 (initial velocity)" + Value "qD0" + } + Object { + $ObjectID 105 + Type "edit" + Name "d" + Prompt "d (viscous friction)" + Value "d" + } + Object { + $ObjectID 106 + Type "edit" + Name "muC" + Prompt "muC (coulomb friction)" + Value "muC" + } + Object { + $ObjectID 107 + Type "edit" + Name "atlas_arm_lr" + Prompt "atlas_arm_lr (Arm: left = true, right = false)" + Value "atlas_arm_lr" + } + Object { + $ObjectID 108 + Type "edit" + Name "atlas_version" + Prompt "atlas_version (3, 4)" + Value "atlas_version" + } + PropName "Parameters" + } + Array { + Type "Simulink.dialog.Group" + Dimension 2 + Object { + $ObjectID 109 + Prompt "%" + Object { + $PropName "DialogControls" + $ObjectID 110 + $ClassName "Simulink.dialog.Text" + Prompt "%" + Name "DescTextVar" + } + Name "DescGroupVar" + } + Object { + $ObjectID 111 + Prompt "Robot Parameters" + Array { + Type "Simulink.dialog.parameter.Edit" + Dimension 6 + Object { + $ObjectID 112 + Name "q0" + } + Object { + $ObjectID 113 + Name "qD0" + } + Object { + $ObjectID 114 + Name "d" + } + Object { + $ObjectID 115 + Name "muC" + } + Object { + $ObjectID 116 + Name "atlas_arm_lr" + } + Object { + $ObjectID 117 + Name "atlas_version" + } + PropName "DialogControls" + } + Name "ParameterGroupVar" + } + PropName "DialogControls" + } + } + System { + Name "atlas_arm_fordyn_rj_damping" + Location [960, 0, 1920, 1160] + Open off + ModelBrowserVisibility off + ModelBrowserWidth 200 + ScreenColor "white" + PaperOrientation "landscape" + PaperPositionMode "auto" + PaperType "A4" + PaperUnits "centimeters" + TiledPaperMargins [1.270000, 1.270000, 1.270000, 1.270000] + TiledPageScale 1 + ShowPageBoundaries off + ZoomFactor "100" + Block { + BlockType Inport + Name "tau_ext\n" + SID "101" + Position [70, 233, 100, 247] + ZOrder 61 + IconDisplay "Port number" + } + Block { + BlockType Inport + Name "tau_m" + SID "102" + Position [70, 448, 100, 462] + ZOrder 62 + Port "2" + IconDisplay "Port number" + Port { + PortNumber 1 + Name "tau_m" + RTWStorageClass "Auto" + DataLogging on + DataLoggingNameMode "SignalName" + } + } + Block { + BlockType Inport + Name "g" + SID "204" + Position [695, 398, 725, 412] + ZOrder 124 + BlockMirror on + Port "3" + IconDisplay "Port number" + } + Block { + BlockType Integrator + Name "Integrator" + SID "104" + Ports [1, 1] + Position [335, 85, 365, 115] + ZOrder 36 + InitialCondition "qD0" + Port { + PortNumber 1 + Name "qD" + RTWStorageClass "Auto" + DataLogging on + DataLoggingNameMode "SignalName" + } + } + Block { + BlockType Integrator + Name "Integrator1" + SID "105" + Ports [1, 1] + Position [445, 84, 475, 116] + ZOrder 37 + InitialCondition "q0" + Port { + PortNumber 1 + Name "q" + RTWStorageClass "Auto" + DataLogging on + DataLoggingNameMode "SignalName" + } + } + Block { + BlockType Sum + Name "Sum2" + SID "106" + Ports [2, 1] + Position [180, 385, 200, 405] + ZOrder 45 + BlockRotation 270 + ShowName off + IconShape "round" + Inputs "|+-" + InputSameDT off + OutDataTypeStr "Inherit: Inherit via internal rule" + SaturateOnIntegerOverflow off + } + Block { + BlockType Sum + Name "Sum3" + SID "107" + Ports [3, 1] + Position [180, 230, 200, 250] + ZOrder 46 + BlockRotation 270 + ShowName off + IconShape "round" + Inputs "++-" + InputSameDT off + OutDataTypeStr "Inherit: Inherit via internal rule" + SaturateOnIntegerOverflow off + Port { + PortNumber 1 + Name "tau_acc" + RTWStorageClass "Auto" + DataLogging on + DataLoggingNameMode "SignalName" + } + } + Block { + BlockType Sum + Name "Sum4" + SID "108" + Ports [2, 1] + Position [180, 305, 200, 325] + ZOrder 52 + BlockRotation 270 + ShowName off + IconShape "round" + Inputs "|+-" + InputSameDT off + OutDataTypeStr "Inherit: Inherit via internal rule" + SaturateOnIntegerOverflow off + } + Block { + BlockType Reference + Name "atlas_arm_coriolis_vec" + SID "196" + Ports [2, 1] + Position [285, 212, 355, 263] + ZOrder 123 + BlockMirror on + LibraryVersion "1.201" + SourceBlock "atlas_dynamic_library/atlas_arm_coriolis_vec" + SourceType "SubSystem" + ContentPreviewEnabled off + Port { + PortNumber 1 + Name "tau_c" + RTWStorageClass "Auto" + DataLoggingNameMode "SignalName" + } + } + Block { + BlockType Reference + Name "atlas_arm_gravload" + SID "197" + Ports [2, 1] + Position [285, 367, 355, 418] + ZOrder 121 + BlockMirror on + LibraryVersion "1.201" + SourceBlock "atlas_dynamic_library/atlas_arm_gravload" + SourceType "SubSystem" + ContentPreviewEnabled off + Port { + PortNumber 1 + Name "tau_g" + RTWStorageClass "Auto" + DataLoggingNameMode "SignalName" + } + } + Block { + BlockType Reference + Name "atlas_arm_inertia" + SID "198" + Ports [1, 1] + Position [95, 61, 165, 109] + ZOrder 122 + LibraryVersion "1.201" + SourceBlock "atlas_dynamic_library/atlas_arm_inertia" + SourceType "SubSystem" + ContentPreviewEnabled off + } + Block { + BlockType Reference + Name "atlas_friction_model" + SID "241" + Ports [1, 1] + Position [285, 291, 355, 339] + ZOrder 132 + BlockMirror on + LibraryVersion "1.201" + SourceBlock "atlas_dynamic_library/atlas_friction_model" + SourceType "" + ContentPreviewEnabled off + muC "muC" + d "d" + Port { + PortNumber 1 + Name "tau_fr" + PropagatedSignals "tau_reib" + RTWStorageClass "Auto" + DataLoggingNameMode "SignalName" + } + } + Block { + BlockType SubSystem + Name "mFcn_Minv" + SID "110" + Ports [2, 1] + Position [210, 71, 295, 124] + ZOrder 35 + LibraryVersion "1.32" + ErrorFcn "Stateflow.Translate.translate" + PermitHierarchicalResolution "ExplicitOnly" + TreatAsAtomicUnit on + RequestExecContextInheritance off + SFBlockType "MATLAB Function" + Port { + PortNumber 1 + Name "qDD" + PropagatedSignals "q_ddot" + RTWStorageClass "Auto" + DataLogging on + DataLoggingNameMode "SignalName" + } + System { + Name "mFcn_Minv" + Location [223, 338, 826, 833] + Open off + ModelBrowserVisibility off + ModelBrowserWidth 200 + ScreenColor "white" + PaperOrientation "landscape" + PaperPositionMode "auto" + PaperType "A4" + PaperUnits "centimeters" + TiledPaperMargins [1.270000, 1.270000, 1.270000, 1.270000] + TiledPageScale 1 + ShowPageBoundaries off + ZoomFactor "100" + SIDHighWatermark "81" + Block { + BlockType Inport + Name "M" + SID "110::1" + Position [20, 101, 40, 119] + ZOrder -1 + IconDisplay "Port number" + } + Block { + BlockType Inport + Name "tau" + SID "110::21" + Position [20, 136, 40, 154] + ZOrder 7 + Port "2" + IconDisplay "Port number" + } + Block { + BlockType Demux + Name " Demux " + SID "110::50" + Ports [1, 1] + Position [270, 230, 320, 270] + ZOrder 18 + Outputs "1" + } + Block { + BlockType S-Function + Name " SFunction " + SID "110::49" + Tag "Stateflow S-Function atlas_dynamic_library 13" + Ports [2, 2] + Position [180, 100, 230, 160] + ZOrder 17 + FunctionName "sf_sfun" + PortCounts "[2 2]" + EnableBusSupport off + Port { + PortNumber 2 + Name "q_ddot" + RTWStorageClass "Auto" + DataLoggingNameMode "SignalName" + } + } + Block { + BlockType Terminator + Name " Terminator " + SID "110::51" + Position [460, 241, 480, 259] + ZOrder 19 + } + Block { + BlockType Outport + Name "q_ddot" + SID "110::5" + Position [460, 101, 480, 119] + ZOrder -5 + IconDisplay "Port number" + } + Line { + ZOrder 6 + SrcBlock "M" + SrcPort 1 + Points [120, 0] + DstBlock " SFunction " + DstPort 1 + } + Line { + ZOrder 7 + SrcBlock "tau" + SrcPort 1 + DstBlock " SFunction " + DstPort 2 + } + Line { + Name "q_ddot" + ZOrder 8 + Labels [0, 0] + SrcBlock " SFunction " + SrcPort 2 + DstBlock "q_ddot" + DstPort 1 + } + Line { + ZOrder 9 + SrcBlock " Demux " + SrcPort 1 + DstBlock " Terminator " + DstPort 1 + } + Line { + ZOrder 10 + SrcBlock " SFunction " + SrcPort 1 + DstBlock " Demux " + DstPort 1 + } + } + } + Block { + BlockType Outport + Name "q" + SID "113" + Position [695, 93, 725, 107] + ZOrder 63 + IconDisplay "Port number" + } + Block { + BlockType Outport + Name "qD" + SID "114" + Position [695, 148, 725, 162] + ZOrder 64 + Port "2" + IconDisplay "Port number" + } + Block { + BlockType Outport + Name "qDD" + SID "115" + Position [695, 48, 725, 62] + ZOrder 65 + Port "3" + IconDisplay "Port number" + } + Line { + Name "tau_g" + ZOrder 27 + Labels [0, 0] + SrcBlock "atlas_arm_gravload" + SrcPort 1 + DstBlock "Sum2" + DstPort 2 + } + Line { + Name "q" + ZOrder 2 + Labels [-1, 0] + SrcBlock "Integrator1" + SrcPort 1 + Points [65, 0] + Branch { + ZOrder 32 + Labels [2, 1] + Points [0, -64; -465, 0] + DstBlock "atlas_arm_inertia" + DstPort 1 + } + Branch { + ZOrder 29 + Labels [0, 1] + Points [0, 125] + DstBlock "atlas_arm_coriolis_vec" + DstPort 1 + } + Branch { + ZOrder 4 + Labels [1, 1] + Points [67, 0] + Branch { + ZOrder 56 + Labels [1, 0] + Points [0, 280] + DstBlock "atlas_arm_gravload" + DstPort 1 + } + Branch { + ZOrder 5 + Labels [1, 1] + DstBlock "q" + DstPort 1 + } + } + } + Line { + ZOrder 8 + SrcBlock "Sum2" + SrcPort 1 + DstBlock "Sum4" + DstPort 1 + } + Line { + Name "qDD" + ZOrder 9 + Labels [0, 0] + SrcBlock "mFcn_Minv" + SrcPort 1 + Points [13, 0] + Branch { + ZOrder 10 + Points [0, -45] + DstBlock "qDD" + DstPort 1 + } + Branch { + ZOrder 11 + DstBlock "Integrator" + DstPort 1 + } + } + Line { + ZOrder 12 + SrcBlock "Sum4" + SrcPort 1 + DstBlock "Sum3" + DstPort 2 + } + Line { + Name "tau_c" + ZOrder 28 + Labels [-1, 0] + SrcBlock "atlas_arm_coriolis_vec" + SrcPort 1 + DstBlock "Sum3" + DstPort 3 + } + Line { + Name "tau_fr" + ZOrder 78 + Labels [0, 0] + SrcBlock "atlas_friction_model" + SrcPort 1 + DstBlock "Sum4" + DstPort 2 + } + Line { + ZOrder 15 + SrcBlock "tau_ext\n" + SrcPort 1 + DstBlock "Sum3" + DstPort 1 + } + Line { + Name "tau_m" + ZOrder 16 + Labels [0, 0] + SrcBlock "tau_m" + SrcPort 1 + Points [85, 0] + DstBlock "Sum2" + DstPort 1 + } + Line { + Name "qD" + ZOrder 17 + Labels [1, 1] + SrcBlock "Integrator" + SrcPort 1 + Points [32, 0] + Branch { + ZOrder 18 + Points [0, 55] + Branch { + ZOrder 19 + DstBlock "qD" + DstPort 1 + } + Branch { + ZOrder 20 + Labels [1, 1; -1, 0] + Points [0, 95] + Branch { + ZOrder 77 + Points [0, 65] + DstBlock "atlas_friction_model" + DstPort 1 + } + Branch { + ZOrder 30 + DstBlock "atlas_arm_coriolis_vec" + DstPort 2 + } + } + } + Branch { + ZOrder 23 + Labels [1, 1] + DstBlock "Integrator1" + DstPort 1 + } + } + Line { + Name "tau_acc" + ZOrder 24 + Labels [0, 0] + SrcBlock "Sum3" + SrcPort 1 + Points [0, -115] + DstBlock "mFcn_Minv" + DstPort 2 + } + Line { + ZOrder 31 + SrcBlock "atlas_arm_inertia" + SrcPort 1 + DstBlock "mFcn_Minv" + DstPort 1 + } + Line { + ZOrder 57 + SrcBlock "g" + SrcPort 1 + DstBlock "atlas_arm_gravload" + DstPort 2 + } + } + } + Block { + BlockType SubSystem + Name "atlas_arm_fordyn_rj_damping_minvarpar" + SID "244" + Ports [3, 5] + Position [110, 342, 280, 418] + ZOrder 226 + LibraryVersion "*1.195" + RequestExecContextInheritance off + Object { + $PropName "MaskObject" + $ObjectID 118 + $ClassName "Simulink.Mask" + Array { + Type "Simulink.MaskParameter" + Dimension 7 + Object { + $ObjectID 119 + Type "edit" + Name "q0" + Prompt "q0 (initial pose)" + Value "q0" + } + Object { + $ObjectID 120 + Type "edit" + Name "qD0" + Prompt "qD0 (initial velocity)" + Value "qD0" + } + Object { + $ObjectID 121 + Type "edit" + Name "d" + Prompt "d (viscous friction)" + Value "d" + } + Object { + $ObjectID 122 + Type "edit" + Name "muC" + Prompt "muC (coulomb friction)" + Value "muC" + } + Object { + $ObjectID 123 + Type "edit" + Name "atlas_arm_lr" + Prompt "atlas_arm_lr (Arm: left = true, right = false)" + Value "atlas_arm_lr" + } + Object { + $ObjectID 124 + Type "edit" + Name "atlas_version" + Prompt "atlas_version (3, 4)" + Value "atlas_version" + } + Object { + $ObjectID 125 + Type "edit" + Name "MPV" + Prompt "MPV (minimal parameter vector)" + Value "MPV" + } + PropName "Parameters" + } + Array { + Type "Simulink.dialog.Group" + Dimension 2 + Object { + $ObjectID 126 + Prompt "%" + Object { + $PropName "DialogControls" + $ObjectID 127 + $ClassName "Simulink.dialog.Text" + Prompt "%" + Name "DescTextVar" + } + Name "DescGroupVar" + } + Object { + $ObjectID 128 + Prompt "Robot Parameters" + Array { + Type "Simulink.dialog.parameter.Edit" + Dimension 7 + Object { + $ObjectID 129 + Name "q0" + } + Object { + $ObjectID 130 + Name "qD0" + } + Object { + $ObjectID 131 + Name "d" + } + Object { + $ObjectID 132 + Name "muC" + } + Object { + $ObjectID 133 + Name "atlas_arm_lr" + } + Object { + $ObjectID 134 + Name "atlas_version" + } + Object { + $ObjectID 135 + Name "MPV" + } + PropName "DialogControls" + } + Name "ParameterGroupVar" + } + PropName "DialogControls" + } + } + System { + Name "atlas_arm_fordyn_rj_damping_minvarpar" + Location [960, 0, 1920, 1160] + Open off + ModelBrowserVisibility off + ModelBrowserWidth 200 + ScreenColor "white" + PaperOrientation "landscape" + PaperPositionMode "auto" + PaperType "usletter" + PaperUnits "inches" + TiledPaperMargins [0.500000, 0.500000, 0.500000, 0.500000] + TiledPageScale 1 + ShowPageBoundaries off + ZoomFactor "100" + Block { + BlockType Inport + Name "tau_ext\n" + SID "245" + Position [60, 343, 90, 357] + ZOrder 61 + IconDisplay "Port number" + } + Block { + BlockType Inport + Name "tau_m" + SID "246" + Position [60, 503, 90, 517] + ZOrder 62 + Port "2" + IconDisplay "Port number" + Port { + PortNumber 1 + Name "tau_m" + RTWStorageClass "Auto" + DataLogging on + DataLoggingNameMode "SignalName" + } + } + Block { + BlockType Inport + Name "g" + SID "247" + Position [795, 453, 825, 467] + ZOrder 124 + BlockMirror on + Port "3" + IconDisplay "Port number" + } + Block { + BlockType Integrator + Name "Integrator" + SID "248" + Ports [1, 1] + Position [435, 85, 465, 115] + ZOrder 36 + InitialCondition "qD0" + Port { + PortNumber 1 + Name "qD" + RTWStorageClass "Auto" + DataLogging on + DataLoggingNameMode "SignalName" + } + } + Block { + BlockType Integrator + Name "Integrator1" + SID "249" + Ports [1, 1] + Position [555, 84, 585, 116] + ZOrder 37 + InitialCondition "q0" + Port { + PortNumber 1 + Name "q" + RTWStorageClass "Auto" + DataLogging on + DataLoggingNameMode "SignalName" + } + } + Block { + BlockType Sum + Name "Sum1" + SID "271" + Ports [2, 1] + Position [170, 225, 190, 245] + ZOrder 138 + BlockRotation 270 + ShowName off + IconShape "round" + Inputs "|+-" + InputSameDT off + OutDataTypeStr "Inherit: Inherit via internal rule" + SaturateOnIntegerOverflow off + } + Block { + BlockType Sum + Name "Sum2" + SID "250" + Ports [2, 1] + Position [170, 440, 190, 460] + ZOrder 45 + BlockRotation 270 + ShowName off + IconShape "round" + Inputs "|+-" + InputSameDT off + OutDataTypeStr "Inherit: Inherit via internal rule" + SaturateOnIntegerOverflow off + } + Block { + BlockType Sum + Name "Sum3" + SID "251" + Ports [3, 1] + Position [170, 340, 190, 360] + ZOrder 46 + BlockRotation 270 + ShowName off + IconShape "round" + Inputs "++-" + InputSameDT off + OutDataTypeStr "Inherit: Inherit via internal rule" + SaturateOnIntegerOverflow off + Port { + PortNumber 1 + Name "tau_acc" + RTWStorageClass "Auto" + DataLogging on + DataLoggingNameMode "SignalName" + } + } + Block { + BlockType Reference + Name "atlas_arm_coriolis_vec_minvarpar" + SID "261" + Ports [2, 1] + Position [315, 322, 385, 373] + ZOrder 135 + BlockMirror on + LibraryVersion "1.201" + SourceBlock "atlas_dynamic_library/atlas_arm_coriolis_vec_minvarpar" + SourceType "" + ContentPreviewEnabled off + atlas_arm_lr "atlas_arm_lr" + atlas_version "atlas_version" + MPV "MPV" + Port { + PortNumber 1 + Name "tau_c" + RTWStorageClass "Auto" + DataLoggingNameMode "SignalName" + } + } + Block { + BlockType Reference + Name "atlas_arm_gravload_minvarpar" + SID "262" + Ports [2, 1] + Position [315, 422, 385, 473] + ZOrder 133 + BlockMirror on + LibraryVersion "1.201" + SourceBlock "atlas_dynamic_library/atlas_arm_gravload_minvarpar" + SourceType "" + ContentPreviewEnabled off + atlas_arm_lr "atlas_arm_lr" + atlas_version "atlas_version" + MPV "MPV" + Port { + PortNumber 1 + Name "tau_g" + RTWStorageClass "Auto" + DataLoggingNameMode "SignalName" + } + } + Block { + BlockType Reference + Name "atlas_arm_inertia_minvarpar" + SID "263" + Ports [1, 1] + Position [55, 51, 125, 99] + ZOrder 134 + LibraryVersion "1.201" + SourceBlock "atlas_dynamic_library/atlas_arm_inertia_minvarpar" + SourceType "" + ContentPreviewEnabled off + atlas_arm_lr "atlas_arm_lr" + atlas_version "atlas_version" + MPV "MPV" + } + Block { + BlockType Reference + Name "atlas_friction_model" + SID "272" + Ports [1, 1] + Position [315, 211, 385, 259] + ZOrder 139 + BlockMirror on + LibraryVersion "1.201" + SourceBlock "atlas_dynamic_library/atlas_friction_model" + SourceType "" + ContentPreviewEnabled off + muC "muC" + d "d" + } + Block { + BlockType SubSystem + Name "mFcn_Minv" + SID "257" + Ports [2, 1] + Position [305, 53, 395, 142] + ZOrder 35 + LibraryVersion "1.32" + ErrorFcn "Stateflow.Translate.translate" + PermitHierarchicalResolution "ExplicitOnly" + TreatAsAtomicUnit on + RequestExecContextInheritance off + SFBlockType "MATLAB Function" + Port { + PortNumber 1 + Name "qDD" + PropagatedSignals "q_ddot" + RTWStorageClass "Auto" + DataLogging on + DataLoggingNameMode "SignalName" + } + System { + Name "mFcn_Minv" + Location [223, 338, 826, 833] + Open off + ModelBrowserVisibility off + ModelBrowserWidth 200 + ScreenColor "white" + PaperOrientation "landscape" + PaperPositionMode "auto" + PaperType "usletter" + PaperUnits "inches" + TiledPaperMargins [0.500000, 0.500000, 0.500000, 0.500000] + TiledPageScale 1 + ShowPageBoundaries off + ZoomFactor "100" + SIDHighWatermark "138" + Block { + BlockType Inport + Name "M" + SID "257::1" + Position [20, 101, 40, 119] + ZOrder -1 + IconDisplay "Port number" + } + Block { + BlockType Inport + Name "tau" + SID "257::21" + Position [20, 136, 40, 154] + ZOrder 7 + Port "2" + IconDisplay "Port number" + } + Block { + BlockType Demux + Name " Demux " + SID "257::125" + Ports [1, 1] + Position [270, 230, 320, 270] + ZOrder 39 + Outputs "1" + } + Block { + BlockType S-Function + Name " SFunction " + SID "257::124" + Tag "Stateflow S-Function atlas_dynamic_library 25" + Ports [2, 2] + Position [180, 100, 230, 160] + ZOrder 38 + FunctionName "sf_sfun" + PortCounts "[2 2]" + EnableBusSupport off + Port { + PortNumber 2 + Name "q_ddot" + RTWStorageClass "Auto" + DataLoggingNameMode "SignalName" + } + } + Block { + BlockType Terminator + Name " Terminator " + SID "257::126" + Position [460, 241, 480, 259] + ZOrder 40 + } + Block { + BlockType Outport + Name "q_ddot" + SID "257::5" + Position [460, 101, 480, 119] + ZOrder -5 + IconDisplay "Port number" + } + Line { + ZOrder 6 + SrcBlock "M" + SrcPort 1 + Points [120, 0] + DstBlock " SFunction " + DstPort 1 + } + Line { + ZOrder 7 + SrcBlock "tau" + SrcPort 1 + DstBlock " SFunction " + DstPort 2 + } + Line { + Name "q_ddot" + ZOrder 8 + Labels [0, 0] + SrcBlock " SFunction " + SrcPort 2 + DstBlock "q_ddot" + DstPort 1 + } + Line { + ZOrder 9 + SrcBlock " Demux " + SrcPort 1 + DstBlock " Terminator " + DstPort 1 + } + Line { + ZOrder 10 + SrcBlock " SFunction " + SrcPort 1 + DstBlock " Demux " + DstPort 1 + } + } + } + Block { + BlockType Outport + Name "q" + SID "258" + Position [805, 93, 835, 107] + ZOrder 63 + IconDisplay "Port number" + } + Block { + BlockType Outport + Name "qD" + SID "259" + Position [805, 148, 835, 162] + ZOrder 64 + Port "2" + IconDisplay "Port number" + } + Block { + BlockType Outport + Name "qDD" + SID "260" + Position [805, 48, 835, 62] + ZOrder 65 + Port "3" + IconDisplay "Port number" + } + Block { + BlockType Outport + Name "tau_fr" + SID "275" + Position [60, 278, 90, 292] + ZOrder 141 + BlockMirror on + Port "4" + IconDisplay "Port number" + } + Block { + BlockType Outport + Name "tau_J" + SID "373" + Position [795, 503, 825, 517] + ZOrder 142 + Port "5" + IconDisplay "Port number" + } + Line { + Name "tau_g" + ZOrder 1 + Labels [0, 0] + SrcBlock "atlas_arm_gravload_minvarpar" + SrcPort 1 + DstBlock "Sum2" + DstPort 2 + } + Line { + Name "q" + ZOrder 2 + Labels [-1, 0] + SrcBlock "Integrator1" + SrcPort 1 + Points [65, 0] + Branch { + ZOrder 3 + Labels [2, 1] + Points [0, -64; -635, 0; 0, 39] + DstBlock "atlas_arm_inertia_minvarpar" + DstPort 1 + } + Branch { + ZOrder 4 + Labels [1, 1] + Points [0, 235] + DstBlock "atlas_arm_coriolis_vec_minvarpar" + DstPort 1 + } + Branch { + ZOrder 5 + Labels [1, 1] + Points [67, 0] + Branch { + ZOrder 6 + Labels [1, 0] + Points [0, 335] + DstBlock "atlas_arm_gravload_minvarpar" + DstPort 1 + } + Branch { + ZOrder 7 + Labels [1, 1] + DstBlock "q" + DstPort 1 + } + } + } + Line { + Name "qDD" + ZOrder 8 + Labels [0, 0] + SrcBlock "mFcn_Minv" + SrcPort 1 + Points [13, 0] + Branch { + ZOrder 9 + Points [0, -45] + DstBlock "qDD" + DstPort 1 + } + Branch { + ZOrder 10 + DstBlock "Integrator" + DstPort 1 + } + } + Line { + ZOrder 11 + SrcBlock "Sum2" + SrcPort 1 + DstBlock "Sum3" + DstPort 2 + } + Line { + Name "tau_c" + ZOrder 12 + Labels [-1, 0] + SrcBlock "atlas_arm_coriolis_vec_minvarpar" + SrcPort 1 + DstBlock "Sum3" + DstPort 3 + } + Line { + ZOrder 13 + SrcBlock "tau_ext\n" + SrcPort 1 + DstBlock "Sum3" + DstPort 1 + } + Line { + Name "tau_m" + ZOrder 14 + Labels [0, 0] + SrcBlock "tau_m" + SrcPort 1 + Points [85, 0] + Branch { + ZOrder 50 + DstBlock "tau_J" + DstPort 1 + } + Branch { + ZOrder 49 + DstBlock "Sum2" + DstPort 1 + } + } + Line { + Name "qD" + ZOrder 15 + Labels [1, 1] + SrcBlock "Integrator" + SrcPort 1 + Points [42, 0] + Branch { + ZOrder 16 + Points [0, 55] + Branch { + ZOrder 17 + DstBlock "qD" + DstPort 1 + } + Branch { + ZOrder 18 + Points [0, 80] + Branch { + ZOrder 19 + DstBlock "atlas_friction_model" + DstPort 1 + } + Branch { + ZOrder 20 + Labels [1, 1; -1, 0] + Points [0, 125] + DstBlock "atlas_arm_coriolis_vec_minvarpar" + DstPort 2 + } + } + } + Branch { + ZOrder 21 + Labels [1, 1] + DstBlock "Integrator1" + DstPort 1 + } + } + Line { + ZOrder 22 + SrcBlock "atlas_arm_inertia_minvarpar" + SrcPort 1 + DstBlock "mFcn_Minv" + DstPort 1 + } + Line { + ZOrder 23 + SrcBlock "g" + SrcPort 1 + DstBlock "atlas_arm_gravload_minvarpar" + DstPort 2 + } + Line { + Name "tau_acc" + ZOrder 24 + Labels [0, 0] + SrcBlock "Sum3" + SrcPort 1 + DstBlock "Sum1" + DstPort 1 + } + Line { + ZOrder 25 + SrcBlock "atlas_friction_model" + SrcPort 1 + Points [-55, 0] + Branch { + ZOrder 26 + DstBlock "Sum1" + DstPort 2 + } + Branch { + ZOrder 27 + Points [0, 50] + DstBlock "tau_fr" + DstPort 1 + } + } + Line { + ZOrder 28 + SrcBlock "Sum1" + SrcPort 1 + Points [0, -100] + DstBlock "mFcn_Minv" + DstPort 2 + } + } + } + Block { + BlockType SubSystem + Name "atlas_arm_gravload" + SID "174" + Ports [2, 1] + Position [475, 327, 545, 378] + ZOrder 118 + TreatAsAtomicUnit on + RequestExecContextInheritance off + System { + Name "atlas_arm_gravload" + Location [976, 17, 1932, 1093] + Open off + ModelBrowserVisibility off + ModelBrowserWidth 200 + ScreenColor "white" + PaperOrientation "landscape" + PaperPositionMode "auto" + PaperType "A4" + PaperUnits "centimeters" + TiledPaperMargins [1.270000, 1.270000, 1.270000, 1.270000] + TiledPageScale 1 + ShowPageBoundaries off + ZoomFactor "100" + Block { + BlockType Inport + Name "q" + SID "175" + Position [20, 33, 50, 47] + ZOrder 118 + IconDisplay "Port number" + } + Block { + BlockType Inport + Name "g" + SID "201" + Position [20, 58, 50, 72] + ZOrder 120 + Port "2" + IconDisplay "Port number" + } + Block { + BlockType SubSystem + Name "mFcn_g" + SID "173" + Ports [2, 1] + Position [70, 25, 140, 80] + ZOrder 117 + LibraryVersion "1.124" + ErrorFcn "Stateflow.Translate.translate" + PermitHierarchicalResolution "ExplicitOnly" + TreatAsAtomicUnit on + RequestExecContextInheritance off + SFBlockType "MATLAB Function" + System { + Name "mFcn_g" + Location [223, 338, 826, 833] + Open off + ModelBrowserVisibility off + ModelBrowserWidth 200 + ScreenColor "white" + PaperOrientation "landscape" + PaperPositionMode "auto" + PaperType "A4" + PaperUnits "centimeters" + TiledPaperMargins [1.270000, 1.270000, 1.270000, 1.270000] + TiledPageScale 1 + ShowPageBoundaries off + ZoomFactor "100" + SIDHighWatermark "129" + Block { + BlockType Inport + Name "q" + SID "173::1" + Position [20, 101, 40, 119] + ZOrder -1 + IconDisplay "Port number" + } + Block { + BlockType Inport + Name "g" + SID "173::75" + Position [20, 136, 40, 154] + ZOrder 22 + Port "2" + IconDisplay "Port number" + } + Block { + BlockType Demux + Name " Demux " + SID "173::68" + Ports [1, 1] + Position [270, 230, 320, 270] + ZOrder 20 + Outputs "1" + } + Block { + BlockType S-Function + Name " SFunction " + SID "173::67" + Tag "Stateflow S-Function atlas_dynamic_library 11" + Ports [2, 2] + Position [180, 100, 230, 160] + ZOrder 19 + FunctionName "sf_sfun" + Parameters "atlas_arm_lr,atlas_version" + PortCounts "[2 2]" + EnableBusSupport off + Port { + PortNumber 2 + Name "tau_g" + RTWStorageClass "Auto" + DataLoggingNameMode "SignalName" + } + } + Block { + BlockType Terminator + Name " Terminator " + SID "173::69" + Position [460, 241, 480, 259] + ZOrder 21 + } + Block { + BlockType Outport + Name "tau_g" + SID "173::5" + Position [460, 101, 480, 119] + ZOrder -5 + IconDisplay "Port number" + } + Line { + ZOrder 9 + SrcBlock "q" + SrcPort 1 + DstBlock " SFunction " + DstPort 1 + } + Line { + ZOrder 10 + SrcBlock "g" + SrcPort 1 + DstBlock " SFunction " + DstPort 2 + } + Line { + Name "tau_g" + ZOrder 11 + Labels [0, 0] + SrcBlock " SFunction " + SrcPort 2 + DstBlock "tau_g" + DstPort 1 + } + Line { + ZOrder 12 + SrcBlock " Demux " + SrcPort 1 + DstBlock " Terminator " + DstPort 1 + } + Line { + ZOrder 13 + SrcBlock " SFunction " + SrcPort 1 + DstBlock " Demux " + DstPort 1 + } + } + } + Block { + BlockType Outport + Name "tau_g" + SID "176" + Position [160, 48, 190, 62] + ZOrder 119 + IconDisplay "Port number" + } + Line { + ZOrder 29 + SrcBlock "q" + SrcPort 1 + DstBlock "mFcn_g" + DstPort 1 + } + Line { + ZOrder 30 + SrcBlock "mFcn_g" + SrcPort 1 + DstBlock "tau_g" + DstPort 1 + } + Line { + ZOrder 31 + SrcBlock "g" + SrcPort 1 + DstBlock "mFcn_g" + DstPort 2 + } + } + } + Block { + BlockType SubSystem + Name "atlas_arm_gravload_minvarpar" + SID "207" + Ports [2, 1] + Position [820, 327, 890, 378] + ZOrder 124 + TreatAsAtomicUnit on + RequestExecContextInheritance off + Object { + $PropName "MaskObject" + $ObjectID 136 + $ClassName "Simulink.Mask" + Array { + Type "Simulink.MaskParameter" + Dimension 3 + Object { + $ObjectID 137 + Type "edit" + Name "atlas_arm_lr" + Prompt "atlas_arm_lr (left = true, right = false)" + Value "atlas_arm_lr" + } + Object { + $ObjectID 138 + Type "edit" + Name "atlas_version" + Prompt "atlas_version (3, 4)" + Value "atlas_version" + } + Object { + $ObjectID 139 + Type "edit" + Name "MPV" + Prompt "MPV (vector of minimal parameters)" + Value "MPV" + } + PropName "Parameters" + } + } + System { + Name "atlas_arm_gravload_minvarpar" + Location [976, 17, 1932, 1093] + Open off + ModelBrowserVisibility off + ModelBrowserWidth 200 + ScreenColor "white" + PaperOrientation "landscape" + PaperPositionMode "auto" + PaperType "A4" + PaperUnits "centimeters" + TiledPaperMargins [1.270000, 1.270000, 1.270000, 1.270000] + TiledPageScale 1 + ShowPageBoundaries off + ZoomFactor "100" + Block { + BlockType Inport + Name "q" + SID "208" + Position [20, 33, 50, 47] + ZOrder 118 + IconDisplay "Port number" + } + Block { + BlockType Inport + Name "g" + SID "209" + Position [20, 63, 50, 77] + ZOrder 120 + Port "2" + IconDisplay "Port number" + } + Block { + BlockType SubSystem + Name "mFcn_g" + SID "210" + Ports [2, 1] + Position [70, 27, 140, 83] + ZOrder 117 + LibraryVersion "1.124" + ErrorFcn "Stateflow.Translate.translate" + PermitHierarchicalResolution "ExplicitOnly" + TreatAsAtomicUnit on + RequestExecContextInheritance off + SFBlockType "MATLAB Function" + System { + Name "mFcn_g" + Location [223, 338, 826, 833] + Open off + ModelBrowserVisibility off + ModelBrowserWidth 200 + ScreenColor "white" + PaperOrientation "landscape" + PaperPositionMode "auto" + PaperType "A4" + PaperUnits "centimeters" + TiledPaperMargins [1.270000, 1.270000, 1.270000, 1.270000] + TiledPageScale 1 + ShowPageBoundaries off + ZoomFactor "100" + SIDHighWatermark "145" + Block { + BlockType Inport + Name "q" + SID "210::1" + Position [20, 101, 40, 119] + ZOrder -1 + IconDisplay "Port number" + } + Block { + BlockType Inport + Name "g" + SID "210::75" + Position [20, 136, 40, 154] + ZOrder 22 + Port "2" + IconDisplay "Port number" + } + Block { + BlockType Demux + Name " Demux " + SID "210::83" + Ports [1, 1] + Position [270, 230, 320, 270] + ZOrder 24 + Outputs "1" + } + Block { + BlockType S-Function + Name " SFunction " + SID "210::82" + Tag "Stateflow S-Function atlas_dynamic_library 12" + Ports [2, 2] + Position [180, 100, 230, 160] + ZOrder 23 + FunctionName "sf_sfun" + Parameters "MPV,atlas_arm_lr,atlas_version" + PortCounts "[2 2]" + EnableBusSupport off + Port { + PortNumber 2 + Name "tau_g" + RTWStorageClass "Auto" + DataLoggingNameMode "SignalName" + } + } + Block { + BlockType Terminator + Name " Terminator " + SID "210::84" + Position [460, 241, 480, 259] + ZOrder 25 + } + Block { + BlockType Outport + Name "tau_g" + SID "210::5" + Position [460, 101, 480, 119] + ZOrder -5 + IconDisplay "Port number" + } + Line { + ZOrder 17 + SrcBlock "q" + SrcPort 1 + DstBlock " SFunction " + DstPort 1 + } + Line { + ZOrder 18 + SrcBlock "g" + SrcPort 1 + DstBlock " SFunction " + DstPort 2 + } + Line { + Name "tau_g" + ZOrder 19 + Labels [0, 0] + SrcBlock " SFunction " + SrcPort 2 + DstBlock "tau_g" + DstPort 1 + } + Line { + ZOrder 20 + SrcBlock " Demux " + SrcPort 1 + DstBlock " Terminator " + DstPort 1 + } + Line { + ZOrder 21 + SrcBlock " SFunction " + SrcPort 1 + DstBlock " Demux " + DstPort 1 + } + } + } + Block { + BlockType Outport + Name "tau_g" + SID "211" + Position [160, 48, 190, 62] + ZOrder 119 + IconDisplay "Port number" + } + Line { + ZOrder 1 + SrcBlock "g" + SrcPort 1 + DstBlock "mFcn_g" + DstPort 2 + } + Line { + ZOrder 2 + SrcBlock "mFcn_g" + SrcPort 1 + DstBlock "tau_g" + DstPort 1 + } + Line { + ZOrder 3 + SrcBlock "q" + SrcPort 1 + DstBlock "mFcn_g" + DstPort 1 + } + } + } + Block { + BlockType SubSystem + Name "atlas_arm_inertia" + SID "177" + Ports [1, 1] + Position [585, 326, 655, 374] + ZOrder 119 + TreatAsAtomicUnit on + RequestExecContextInheritance off + System { + Name "atlas_arm_inertia" + Location [65, 24, 1920, 1080] + Open off + ModelBrowserVisibility off + ModelBrowserWidth 200 + ScreenColor "white" + PaperOrientation "landscape" + PaperPositionMode "auto" + PaperType "A4" + PaperUnits "centimeters" + TiledPaperMargins [1.270000, 1.270000, 1.270000, 1.270000] + TiledPageScale 1 + ShowPageBoundaries off + ZoomFactor "100" + Block { + BlockType Inport + Name "q" + SID "178" + Position [20, 43, 50, 57] + ZOrder 116 + IconDisplay "Port number" + } + Block { + BlockType SubSystem + Name "mFcn_M" + SID "171" + Ports [1, 1] + Position [70, 23, 140, 77] + ZOrder 115 + LibraryVersion "1.124" + ErrorFcn "Stateflow.Translate.translate" + PermitHierarchicalResolution "ExplicitOnly" + TreatAsAtomicUnit on + RequestExecContextInheritance off + SFBlockType "MATLAB Function" + System { + Name "mFcn_M" + Location [223, 338, 826, 833] + Open off + ModelBrowserVisibility off + ModelBrowserWidth 200 + ScreenColor "white" + PaperOrientation "landscape" + PaperPositionMode "auto" + PaperType "A4" + PaperUnits "centimeters" + TiledPaperMargins [1.270000, 1.270000, 1.270000, 1.270000] + TiledPageScale 1 + ShowPageBoundaries off + ZoomFactor "100" + SIDHighWatermark "89" + Block { + BlockType Inport + Name "q" + SID "171::1" + Position [20, 101, 40, 119] + ZOrder -1 + IconDisplay "Port number" + } + Block { + BlockType Demux + Name " Demux " + SID "171::68" + Ports [1, 1] + Position [270, 230, 320, 270] + ZOrder 20 + Outputs "1" + } + Block { + BlockType S-Function + Name " SFunction " + SID "171::67" + Tag "Stateflow S-Function atlas_dynamic_library 8" + Ports [1, 2] + Position [180, 100, 230, 160] + ZOrder 19 + FunctionName "sf_sfun" + Parameters "atlas_arm_lr,atlas_version" + PortCounts "[1 2]" + EnableBusSupport off + Port { + PortNumber 2 + Name "M" + RTWStorageClass "Auto" + DataLoggingNameMode "SignalName" + } + } + Block { + BlockType Terminator + Name " Terminator " + SID "171::69" + Position [460, 241, 480, 259] + ZOrder 21 + } + Block { + BlockType Outport + Name "M" + SID "171::5" + Position [460, 101, 480, 119] + ZOrder -5 + IconDisplay "Port number" + } + Line { + ZOrder 5 + SrcBlock "q" + SrcPort 1 + DstBlock " SFunction " + DstPort 1 + } + Line { + Name "M" + ZOrder 6 + Labels [0, 0] + SrcBlock " SFunction " + SrcPort 2 + DstBlock "M" + DstPort 1 + } + Line { + ZOrder 7 + SrcBlock " Demux " + SrcPort 1 + DstBlock " Terminator " + DstPort 1 + } + Line { + ZOrder 8 + SrcBlock " SFunction " + SrcPort 1 + DstBlock " Demux " + DstPort 1 + } + } + } + Block { + BlockType Outport + Name "M" + SID "179" + Position [160, 43, 190, 57] + ZOrder 117 + IconDisplay "Port number" + } + Line { + ZOrder 32 + SrcBlock "mFcn_M" + SrcPort 1 + DstBlock "M" + DstPort 1 + } + Line { + ZOrder 31 + SrcBlock "q" + SrcPort 1 + DstBlock "mFcn_M" + DstPort 1 + } + } + } + Block { + BlockType SubSystem + Name "atlas_arm_inertia_minvarpar" + SID "213" + Ports [1, 1] + Position [925, 331, 995, 379] + ZOrder 125 + TreatAsAtomicUnit on + RequestExecContextInheritance off + Object { + $PropName "MaskObject" + $ObjectID 140 + $ClassName "Simulink.Mask" + Array { + Type "Simulink.MaskParameter" + Dimension 3 + Object { + $ObjectID 141 + Type "edit" + Name "atlas_arm_lr" + Prompt "atlas_arm_lr (left = true, right = false)" + Value "atlas_arm_lr" + } + Object { + $ObjectID 142 + Type "edit" + Name "atlas_version" + Prompt "atlas_version (3, 4)" + Value "atlas_version" + } + Object { + $ObjectID 143 + Type "edit" + Name "MPV" + Prompt "MPV (vector of minimal parameters)" + Value "MPV" + } + PropName "Parameters" + } + } + System { + Name "atlas_arm_inertia_minvarpar" + Location [1421, 62, 2636, 1014] + Open off + ModelBrowserVisibility off + ModelBrowserWidth 200 + ScreenColor "white" + PaperOrientation "landscape" + PaperPositionMode "auto" + PaperType "A4" + PaperUnits "centimeters" + TiledPaperMargins [1.270000, 1.270000, 1.270000, 1.270000] + TiledPageScale 1 + ShowPageBoundaries off + ZoomFactor "100" + Block { + BlockType Inport + Name "q" + SID "214" + Position [20, 43, 50, 57] + ZOrder 116 + IconDisplay "Port number" + } + Block { + BlockType SubSystem + Name "mFcn_M" + SID "215" + Ports [1, 1] + Position [70, 22, 140, 78] + ZOrder 115 + LibraryVersion "1.124" + ErrorFcn "Stateflow.Translate.translate" + PermitHierarchicalResolution "ExplicitOnly" + TreatAsAtomicUnit on + RequestExecContextInheritance off + SFBlockType "MATLAB Function" + System { + Name "mFcn_M" + Location [223, 338, 826, 833] + Open off + ModelBrowserVisibility off + ModelBrowserWidth 200 + ScreenColor "white" + PaperOrientation "landscape" + PaperPositionMode "auto" + PaperType "A4" + PaperUnits "centimeters" + TiledPaperMargins [1.270000, 1.270000, 1.270000, 1.270000] + TiledPageScale 1 + ShowPageBoundaries off + ZoomFactor "100" + SIDHighWatermark "133" + Block { + BlockType Inport + Name "q" + SID "215::1" + Position [20, 101, 40, 119] + ZOrder -1 + IconDisplay "Port number" + } + Block { + BlockType Demux + Name " Demux " + SID "215::81" + Ports [1, 1] + Position [270, 230, 320, 270] + ZOrder 23 + Outputs "1" + } + Block { + BlockType S-Function + Name " SFunction " + SID "215::80" + Tag "Stateflow S-Function atlas_dynamic_library 14" + Ports [1, 2] + Position [180, 100, 230, 160] + ZOrder 22 + FunctionName "sf_sfun" + Parameters "MPV,atlas_arm_lr,atlas_version" + PortCounts "[1 2]" + EnableBusSupport off + Port { + PortNumber 2 + Name "M" + RTWStorageClass "Auto" + DataLoggingNameMode "SignalName" + } + } + Block { + BlockType Terminator + Name " Terminator " + SID "215::82" + Position [460, 241, 480, 259] + ZOrder 24 + } + Block { + BlockType Outport + Name "M" + SID "215::5" + Position [460, 101, 480, 119] + ZOrder -5 + IconDisplay "Port number" + } + Line { + ZOrder 14 + SrcBlock "q" + SrcPort 1 + DstBlock " SFunction " + DstPort 1 + } + Line { + Name "M" + ZOrder 15 + Labels [0, 0] + SrcBlock " SFunction " + SrcPort 2 + DstBlock "M" + DstPort 1 + } + Line { + ZOrder 16 + SrcBlock " Demux " + SrcPort 1 + DstBlock " Terminator " + DstPort 1 + } + Line { + ZOrder 17 + SrcBlock " SFunction " + SrcPort 1 + DstBlock " Demux " + DstPort 1 + } + } + } + Block { + BlockType Outport + Name "M" + SID "216" + Position [160, 43, 190, 57] + ZOrder 117 + IconDisplay "Port number" + } + Line { + ZOrder 1 + SrcBlock "q" + SrcPort 1 + DstBlock "mFcn_M" + DstPort 1 + } + Line { + ZOrder 2 + SrcBlock "mFcn_M" + SrcPort 1 + DstBlock "M" + DstPort 1 + } + } + } + Block { + BlockType SubSystem + Name "atlas_arm_invdyn_fb_minvarpar" + SID "229" + Ports [4, 1] + Position [1035, 241, 1105, 294] + ZOrder 128 + TreatAsAtomicUnit on + RequestExecContextInheritance off + Object { + $PropName "MaskObject" + $ObjectID 144 + $ClassName "Simulink.Mask" + Object { + $PropName "Parameters" + $ObjectID 145 + $ClassName "Simulink.MaskParameter" + Type "edit" + Name "MPV" + Prompt "MPV (vector of minimal parameters)" + Value "MPV" + } + } + System { + Name "atlas_arm_invdyn_fb_minvarpar" + Location [976, 17, 1932, 1093] + Open off + ModelBrowserVisibility off + ModelBrowserWidth 200 + ScreenColor "white" + PaperOrientation "landscape" + PaperPositionMode "auto" + PaperType "A4" + PaperUnits "centimeters" + TiledPaperMargins [1.270000, 1.270000, 1.270000, 1.270000] + TiledPageScale 1 + ShowPageBoundaries off + ZoomFactor "100" + Block { + BlockType Inport + Name "q" + SID "230" + Position [20, 33, 50, 47] + ZOrder 117 + IconDisplay "Port number" + } + Block { + BlockType Inport + Name "qD" + SID "231" + Position [20, 58, 50, 72] + ZOrder 118 + Port "2" + IconDisplay "Port number" + } + Block { + BlockType Inport + Name "qDD" + SID "235" + Position [20, 83, 50, 97] + ZOrder 121 + Port "3" + IconDisplay "Port number" + } + Block { + BlockType Inport + Name "g" + SID "236" + Position [20, 108, 50, 122] + ZOrder 122 + Port "4" + IconDisplay "Port number" + } + Block { + BlockType SubSystem + Name "mFcn_tau" + SID "232" + Ports [4, 1] + Position [70, 28, 190, 127] + ZOrder 116 + LibraryVersion "1.124" + ErrorFcn "Stateflow.Translate.translate" + PermitHierarchicalResolution "ExplicitOnly" + TreatAsAtomicUnit on + RequestExecContextInheritance off + SFBlockType "MATLAB Function" + System { + Name "mFcn_tau" + Location [223, 338, 826, 833] + Open off + ModelBrowserVisibility off + ModelBrowserWidth 200 + ScreenColor "white" + PaperOrientation "landscape" + PaperPositionMode "auto" + PaperType "A4" + PaperUnits "centimeters" + TiledPaperMargins [1.270000, 1.270000, 1.270000, 1.270000] + TiledPageScale 1 + ShowPageBoundaries off + ZoomFactor "100" + SIDHighWatermark "97" + Block { + BlockType Inport + Name "q" + SID "232::1" + Position [20, 101, 40, 119] + ZOrder -1 + IconDisplay "Port number" + } + Block { + BlockType Inport + Name "qD" + SID "232::21" + Position [20, 136, 40, 154] + ZOrder 7 + Port "2" + IconDisplay "Port number" + } + Block { + BlockType Inport + Name "qDD" + SID "232::96" + Position [20, 171, 40, 189] + ZOrder 32 + Port "3" + IconDisplay "Port number" + } + Block { + BlockType Inport + Name "g" + SID "232::97" + Position [20, 206, 40, 224] + ZOrder 33 + Port "4" + IconDisplay "Port number" + } + Block { + BlockType Demux + Name " Demux " + SID "232::94" + Ports [1, 1] + Position [270, 230, 320, 270] + ZOrder 30 + Outputs "1" + } + Block { + BlockType S-Function + Name " SFunction " + SID "232::93" + Tag "Stateflow S-Function atlas_dynamic_library 23" + Ports [4, 2] + Position [180, 102, 230, 203] + ZOrder 29 + FunctionName "sf_sfun" + Parameters "MPV,atlas_arm_lr,atlas_version" + PortCounts "[4 2]" + EnableBusSupport off + Port { + PortNumber 2 + Name "tau" + RTWStorageClass "Auto" + DataLoggingNameMode "SignalName" + } + } + Block { + BlockType Terminator + Name " Terminator " + SID "232::95" + Position [460, 241, 480, 259] + ZOrder 31 + } + Block { + BlockType Outport + Name "tau" + SID "232::27" + Position [460, 101, 480, 119] + ZOrder 13 + IconDisplay "Port number" + } + Line { + ZOrder 17 + SrcBlock "q" + SrcPort 1 + Points [120, 0] + DstBlock " SFunction " + DstPort 1 + } + Line { + ZOrder 18 + SrcBlock "qD" + SrcPort 1 + DstBlock " SFunction " + DstPort 2 + } + Line { + ZOrder 19 + SrcBlock "qDD" + SrcPort 1 + DstBlock " SFunction " + DstPort 3 + } + Line { + ZOrder 20 + SrcBlock "g" + SrcPort 1 + DstBlock " SFunction " + DstPort 4 + } + Line { + Name "tau" + ZOrder 21 + Labels [0, 0] + SrcBlock " SFunction " + SrcPort 2 + DstBlock "tau" + DstPort 1 + } + Line { + ZOrder 22 + SrcBlock " Demux " + SrcPort 1 + DstBlock " Terminator " + DstPort 1 + } + Line { + ZOrder 23 + SrcBlock " SFunction " + SrcPort 1 + DstBlock " Demux " + DstPort 1 + } + } + } + Block { + BlockType Outport + Name "tau" + SID "233" + Position [260, 73, 290, 87] + ZOrder 119 + IconDisplay "Port number" + } + Line { + ZOrder 1 + SrcBlock "mFcn_tau" + SrcPort 1 + DstBlock "tau" + DstPort 1 + } + Line { + ZOrder 2 + SrcBlock "q" + SrcPort 1 + DstBlock "mFcn_tau" + DstPort 1 + } + Line { + ZOrder 3 + SrcBlock "qD" + SrcPort 1 + DstBlock "mFcn_tau" + DstPort 2 + } + Line { + ZOrder 4 + SrcBlock "qDD" + SrcPort 1 + DstBlock "mFcn_tau" + DstPort 3 + } + Line { + ZOrder 5 + SrcBlock "g" + SrcPort 1 + DstBlock "mFcn_tau" + DstPort 4 + } + } + } + Block { + BlockType SubSystem + Name "atlas_arm_jacobig" + SID "184" + Ports [1, 1] + Position [370, 325, 440, 375] + ZOrder 121 + TreatAsAtomicUnit on + RequestExecContextInheritance off + System { + Name "atlas_arm_jacobig" + Location [960, 0, 1920, 1160] + Open off + ModelBrowserVisibility off + ModelBrowserWidth 200 + ScreenColor "white" + PaperOrientation "landscape" + PaperPositionMode "auto" + PaperType "A4" + PaperUnits "centimeters" + TiledPaperMargins [1.270000, 1.270000, 1.270000, 1.270000] + TiledPageScale 1 + ShowPageBoundaries off + ZoomFactor "100" + Block { + BlockType Inport + Name "q" + SID "185" + Position [20, 43, 50, 57] + ZOrder 93 + IconDisplay "Port number" + } + Block { + BlockType SubSystem + Name "atlas_arm_jacobig" + SID "118" + Ports [1, 1] + Position [70, 24, 140, 76] + ZOrder 92 + NamePlacement "alternate" + LibraryVersion "1.90" + ErrorFcn "Stateflow.Translate.translate" + PermitHierarchicalResolution "ExplicitOnly" + TreatAsAtomicUnit on + RequestExecContextInheritance off + SFBlockType "MATLAB Function" + Object { + $PropName "MaskObject" + $ObjectID 146 + $ClassName "Simulink.Mask" + Initialization "if edit_lr == 1\n atlas_arm_lr = true; % left\nelse\n atlas_arm_lr = false; % right\nend\n\n" + "if edit_version == 3\n atlas_version = uint8(3);\nelseif edit_version == 4\n atlas_version = uint8(4);\nelse\n " + " error('Version %d not implemented', edit_version);\nend\n" + Array { + Type "Simulink.MaskParameter" + Dimension 2 + Object { + $ObjectID 147 + Type "edit" + Name "edit_lr" + Prompt "Arm (left = true, right = false)" + Value "atlas_arm_lr" + } + Object { + $ObjectID 148 + Type "edit" + Name "edit_version" + Prompt "Version (3, 4)" + Value "atlas_version" + } + PropName "Parameters" + } + } + System { + Name "atlas_arm_jacobig" + Location [223, 338, 826, 833] + Open off + ModelBrowserVisibility off + ModelBrowserWidth 200 + ScreenColor "white" + PaperOrientation "landscape" + PaperPositionMode "auto" + PaperType "A4" + PaperUnits "centimeters" + TiledPaperMargins [1.270000, 1.270000, 1.270000, 1.270000] + TiledPageScale 1 + ShowPageBoundaries off + ZoomFactor "100" + SIDHighWatermark "95" + Block { + BlockType Inport + Name "q" + SID "118::1" + Position [20, 101, 40, 119] + ZOrder -1 + IconDisplay "Port number" + } + Block { + BlockType Demux + Name " Demux " + SID "118::53" + Ports [1, 1] + Position [270, 230, 320, 270] + ZOrder 22 + Outputs "1" + } + Block { + BlockType S-Function + Name " SFunction " + SID "118::52" + Tag "Stateflow S-Function atlas_dynamic_library 18" + Ports [1, 2] + Position [180, 100, 230, 160] + ZOrder 21 + FunctionName "sf_sfun" + Parameters "atlas_arm_lr,atlas_version" + PortCounts "[1 2]" + EnableBusSupport off + Port { + PortNumber 2 + Name "JG" + RTWStorageClass "Auto" + DataLoggingNameMode "SignalName" + } + } + Block { + BlockType Terminator + Name " Terminator " + SID "118::54" + Position [460, 241, 480, 259] + ZOrder 23 + } + Block { + BlockType Outport + Name "JG" + SID "118::5" + Position [460, 101, 480, 119] + ZOrder -5 + IconDisplay "Port number" + } + Line { + ZOrder 14 + SrcBlock "q" + SrcPort 1 + DstBlock " SFunction " + DstPort 1 + } + Line { + Name "JG" + ZOrder 15 + Labels [0, 0] + SrcBlock " SFunction " + SrcPort 2 + DstBlock "JG" + DstPort 1 + } + Line { + ZOrder 16 + SrcBlock " Demux " + SrcPort 1 + DstBlock " Terminator " + DstPort 1 + } + Line { + ZOrder 17 + SrcBlock " SFunction " + SrcPort 1 + DstBlock " Demux " + DstPort 1 + } + } + } + Block { + BlockType Outport + Name "JG" + SID "186" + Position [160, 43, 190, 57] + ZOrder 94 + IconDisplay "Port number" + } + Line { + ZOrder 37 + SrcBlock "q" + SrcPort 1 + DstBlock "atlas_arm_jacobig" + DstPort 1 + } + Line { + ZOrder 38 + SrcBlock "atlas_arm_jacobig" + SrcPort 1 + DstBlock "JG" + DstPort 1 + } + } + } + Block { + BlockType SubSystem + Name "atlas_arm_jacobigD" + SID "192" + Ports [2, 1] + Position [370, 242, 440, 293] + ZOrder 123 + TreatAsAtomicUnit on + RequestExecContextInheritance off + System { + Name "atlas_arm_jacobigD" + Location [960, 0, 1920, 1160] + Open off + ModelBrowserVisibility off + ModelBrowserWidth 200 + ScreenColor "white" + PaperOrientation "landscape" + PaperPositionMode "auto" + PaperType "A4" + PaperUnits "centimeters" + TiledPaperMargins [1.270000, 1.270000, 1.270000, 1.270000] + TiledPageScale 1 + ShowPageBoundaries off + ZoomFactor "100" + Block { + BlockType Inport + Name "q" + SID "193" + Position [20, 33, 50, 47] + ZOrder 92 + IconDisplay "Port number" + } + Block { + BlockType Inport + Name "qD" + SID "194" + Position [20, 68, 50, 82] + ZOrder 93 + Port "2" + IconDisplay "Port number" + } + Block { + BlockType SubSystem + Name "atlas_arm_jacobigD" + SID "117" + Ports [2, 1] + Position [70, 22, 140, 93] + ZOrder 91 + NamePlacement "alternate" + LibraryVersion "1.90" + ErrorFcn "Stateflow.Translate.translate" + PermitHierarchicalResolution "ExplicitOnly" + TreatAsAtomicUnit on + RequestExecContextInheritance off + SFBlockType "MATLAB Function" + Object { + $PropName "MaskObject" + $ObjectID 149 + $ClassName "Simulink.Mask" + Initialization "if edit_lr == 1\n atlas_arm_lr = true; % left\nelse\n atlas_arm_lr = false; % right\nend\n" + Array { + Type "Simulink.MaskParameter" + Dimension 2 + Object { + $ObjectID 150 + Type "edit" + Name "edit_lr" + Prompt "Arm (left = true, right = false)" + Value "atlas_arm_lr" + } + Object { + $ObjectID 151 + Type "edit" + Name "edit_version" + Prompt "Version (3, 4)" + Value "atlas_version" + } + PropName "Parameters" + } + } + System { + Name "atlas_arm_jacobigD" + Location [223, 338, 826, 833] + Open off + ModelBrowserVisibility off + ModelBrowserWidth 200 + ScreenColor "white" + PaperOrientation "landscape" + PaperPositionMode "auto" + PaperType "A4" + PaperUnits "centimeters" + TiledPaperMargins [1.270000, 1.270000, 1.270000, 1.270000] + TiledPageScale 1 + ShowPageBoundaries off + ZoomFactor "100" + SIDHighWatermark "52" + Block { + BlockType Inport + Name "q" + SID "117::1" + Position [20, 101, 40, 119] + ZOrder -1 + IconDisplay "Port number" + } + Block { + BlockType Inport + Name "qD" + SID "117::21" + Position [20, 136, 40, 154] + ZOrder 7 + Port "2" + IconDisplay "Port number" + } + Block { + BlockType Demux + Name " Demux " + SID "117::50" + Ports [1, 1] + Position [270, 230, 320, 270] + ZOrder 19 + Outputs "1" + } + Block { + BlockType S-Function + Name " SFunction " + SID "117::49" + Tag "Stateflow S-Function atlas_dynamic_library 17" + Ports [2, 2] + Position [180, 100, 230, 160] + ZOrder 18 + FunctionName "sf_sfun" + Parameters "atlas_arm_lr,atlas_version" + PortCounts "[2 2]" + EnableBusSupport off + Port { + PortNumber 2 + Name "JGD" + RTWStorageClass "Auto" + DataLoggingNameMode "SignalName" + } + } + Block { + BlockType Terminator + Name " Terminator " + SID "117::51" + Position [460, 241, 480, 259] + ZOrder 20 + } + Block { + BlockType Outport + Name "JGD" + SID "117::5" + Position [460, 101, 480, 119] + ZOrder -5 + IconDisplay "Port number" + } + Line { + ZOrder 17 + SrcBlock "q" + SrcPort 1 + DstBlock " SFunction " + DstPort 1 + } + Line { + ZOrder 18 + SrcBlock "qD" + SrcPort 1 + DstBlock " SFunction " + DstPort 2 + } + Line { + Name "JGD" + ZOrder 19 + Labels [0, 0] + SrcBlock " SFunction " + SrcPort 2 + DstBlock "JGD" + DstPort 1 + } + Line { + ZOrder 20 + SrcBlock " Demux " + SrcPort 1 + DstBlock " Terminator " + DstPort 1 + } + Line { + ZOrder 21 + SrcBlock " SFunction " + SrcPort 1 + DstBlock " Demux " + DstPort 1 + } + } + } + Block { + BlockType Outport + Name "JGD" + SID "195" + Position [160, 53, 190, 67] + ZOrder 94 + IconDisplay "Port number" + } + Line { + ZOrder 45 + SrcBlock "qD" + SrcPort 1 + DstBlock "atlas_arm_jacobigD" + DstPort 2 + } + Line { + ZOrder 44 + SrcBlock "q" + SrcPort 1 + DstBlock "atlas_arm_jacobigD" + DstPort 1 + } + Line { + ZOrder 46 + SrcBlock "atlas_arm_jacobigD" + SrcPort 1 + DstBlock "JGD" + DstPort 1 + } + } + } + Block { + BlockType SubSystem + Name "atlas_friction_and_stiction_model" + SID "264" + Ports [2, 1] + Position [700, 243, 770, 292] + ZOrder 133 + TreatAsAtomicUnit on + RequestExecContextInheritance off + Object { + $PropName "MaskObject" + $ObjectID 152 + $ClassName "Simulink.Mask" + Array { + Type "Simulink.MaskParameter" + Dimension 5 + Object { + $ObjectID 153 + Type "edit" + Name "tau_c" + Prompt "tau_c (vector with coulomb friciton momentums for all joints)" + Value "tau_c" + } + Object { + $ObjectID 154 + Type "edit" + Name "B" + Prompt "B (vector with viscous friction coefficients of all joints)" + Value "B" + } + Object { + $ObjectID 155 + Type "edit" + Name "tau_s" + Prompt "tau_s (vector with sticition momentums of all joints)" + Value "tau_s" + } + Object { + $ObjectID 156 + Type "edit" + Name "qD_s" + Prompt "qD_s (vector with Stribeck velocities of all joints)" + Value "qD_s" + } + Object { + $ObjectID 157 + Type "edit" + Name "delta_s" + Prompt "delta_s (vector with stiction exponents for all joints)" + Value "delta_s" + } + PropName "Parameters" + } + } + System { + Name "atlas_friction_and_stiction_model" + Location [964, 65, 1920, 1080] + Open off + ModelBrowserVisibility off + ModelBrowserWidth 200 + ScreenColor "white" + PaperOrientation "landscape" + PaperPositionMode "auto" + PaperType "usletter" + PaperUnits "inches" + TiledPaperMargins [0.500000, 0.500000, 0.500000, 0.500000] + TiledPageScale 1 + ShowPageBoundaries off + ZoomFactor "100" + Block { + BlockType Inport + Name "qD" + SID "265" + Position [20, 43, 50, 57] + ZOrder 131 + IconDisplay "Port number" + } + Block { + BlockType Inport + Name "tau_dyn" + SID "269" + Position [20, 78, 50, 92] + ZOrder 133 + Port "2" + IconDisplay "Port number" + } + Block { + BlockType SubSystem + Name "atlas_friction_model" + SID "266" + Ports [2, 1] + Position [70, 30, 175, 105] + ZOrder 130 + ErrorFcn "Stateflow.Translate.translate" + PermitHierarchicalResolution "ExplicitOnly" + TreatAsAtomicUnit on + RequestExecContextInheritance off + SFBlockType "MATLAB Function" + System { + Name "atlas_friction_model" + Location [223, 338, 826, 833] + Open off + ModelBrowserVisibility off + ModelBrowserWidth 200 + ScreenColor "white" + PaperOrientation "landscape" + PaperPositionMode "auto" + PaperType "usletter" + PaperUnits "inches" + TiledPaperMargins [0.500000, 0.500000, 0.500000, 0.500000] + TiledPageScale 1 + ShowPageBoundaries off + ZoomFactor "100" + SIDHighWatermark "99" + SIDPrevWatermark "91" + Block { + BlockType Inport + Name "qD" + SID "266::21" + Position [20, 101, 40, 119] + ZOrder 7 + IconDisplay "Port number" + } + Block { + BlockType Inport + Name "tau_dyn" + SID "266::99" + Position [20, 136, 40, 154] + ZOrder 39 + Port "2" + IconDisplay "Port number" + } + Block { + BlockType Demux + Name " Demux " + SID "266::93" + Ports [1, 1] + Position [270, 230, 320, 270] + ZOrder 33 + Outputs "1" + } + Block { + BlockType S-Function + Name " SFunction " + SID "266::92" + Tag "Stateflow S-Function atlas_dynamic_library 26" + Ports [2, 2] + Position [180, 110, 230, 170] + ZOrder 32 + FunctionName "sf_sfun" + Parameters "B,delta_s,qD_s,tau_c,tau_s" + PortCounts "[2 2]" + EnableBusSupport off + Port { + PortNumber 2 + Name "tau_reib" + RTWStorageClass "Auto" + DataLoggingNameMode "SignalName" + } + } + Block { + BlockType Terminator + Name " Terminator " + SID "266::94" + Position [460, 241, 480, 259] + ZOrder 34 + } + Block { + BlockType Outport + Name "tau_reib" + SID "266::27" + Position [460, 101, 480, 119] + ZOrder 13 + IconDisplay "Port number" + } + Line { + ZOrder 57 + SrcBlock "qD" + SrcPort 1 + DstBlock " SFunction " + DstPort 1 + } + Line { + ZOrder 58 + SrcBlock "tau_dyn" + SrcPort 1 + DstBlock " SFunction " + DstPort 2 + } + Line { + Name "tau_reib" + ZOrder 59 + Labels [0, 0] + SrcBlock " SFunction " + SrcPort 2 + DstBlock "tau_reib" + DstPort 1 + } + Line { + ZOrder 60 + SrcBlock " Demux " + SrcPort 1 + DstBlock " Terminator " + DstPort 1 + } + Line { + ZOrder 61 + SrcBlock " SFunction " + SrcPort 1 + DstBlock " Demux " + DstPort 1 + } + } + } + Block { + BlockType Outport + Name "tau_fr" + SID "267" + Position [210, 63, 240, 77] + ZOrder 132 + IconDisplay "Port number" + } + Line { + ZOrder 1 + SrcBlock "qD" + SrcPort 1 + DstBlock "atlas_friction_model" + DstPort 1 + } + Line { + ZOrder 2 + SrcBlock "atlas_friction_model" + SrcPort 1 + DstBlock "tau_fr" + DstPort 1 + } + Line { + ZOrder 3 + SrcBlock "tau_dyn" + SrcPort 1 + DstBlock "atlas_friction_model" + DstPort 2 + } + } + } + Block { + BlockType SubSystem + Name "atlas_friction_model" + SID "238" + Ports [1, 1] + Position [700, 326, 770, 374] + ZOrder 131 + TreatAsAtomicUnit on + RequestExecContextInheritance off + Object { + $PropName "MaskObject" + $ObjectID 158 + $ClassName "Simulink.Mask" + Array { + Type "Simulink.MaskParameter" + Dimension 2 + Object { + $ObjectID 159 + Type "edit" + Name "muC" + Prompt "muC" + Value "muC" + } + Object { + $ObjectID 160 + Type "edit" + Name "d" + Prompt "d" + Value "d" + } + PropName "Parameters" + } + } + System { + Name "atlas_friction_model" + Location [1985, 316, 3840, 1372] + Open off + ModelBrowserVisibility off + ModelBrowserWidth 200 + ScreenColor "white" + PaperOrientation "landscape" + PaperPositionMode "auto" + PaperType "usletter" + PaperUnits "inches" + TiledPaperMargins [0.500000, 0.500000, 0.500000, 0.500000] + TiledPageScale 1 + ShowPageBoundaries off + ZoomFactor "150" + Block { + BlockType Inport + Name "qD" + SID "239" + Position [20, 43, 50, 57] + ZOrder 131 + IconDisplay "Port number" + } + Block { + BlockType SubSystem + Name "atlas_friction_model" + SID "237" + Ports [1, 1] + Position [70, 23, 175, 77] + ZOrder 130 + ErrorFcn "Stateflow.Translate.translate" + PermitHierarchicalResolution "ExplicitOnly" + TreatAsAtomicUnit on + RequestExecContextInheritance off + SFBlockType "MATLAB Function" + System { + Name "atlas_friction_model" + Location [223, 338, 826, 833] + Open off + ModelBrowserVisibility off + ModelBrowserWidth 200 + ScreenColor "white" + PaperOrientation "landscape" + PaperPositionMode "auto" + PaperType "usletter" + PaperUnits "inches" + TiledPaperMargins [0.500000, 0.500000, 0.500000, 0.500000] + TiledPageScale 1 + ShowPageBoundaries off + ZoomFactor "100" + SIDHighWatermark "91" + SIDPrevWatermark "91" + Block { + BlockType Inport + Name "qD" + SID "237::21" + Position [20, 101, 40, 119] + ZOrder 7 + IconDisplay "Port number" + } + Block { + BlockType Demux + Name " Demux " + SID "237::90" + Ports [1, 1] + Position [270, 230, 320, 270] + ZOrder 30 + Outputs "1" + } + Block { + BlockType S-Function + Name " SFunction " + SID "237::89" + Tag "Stateflow S-Function atlas_dynamic_library 24" + Ports [1, 2] + Position [180, 100, 230, 160] + ZOrder 29 + FunctionName "sf_sfun" + Parameters "d,muC" + PortCounts "[1 2]" + EnableBusSupport off + Port { + PortNumber 2 + Name "tau_fr" + RTWStorageClass "Auto" + DataLoggingNameMode "SignalName" + } + } + Block { + BlockType Terminator + Name " Terminator " + SID "237::91" + Position [460, 241, 480, 259] + ZOrder 31 + } + Block { + BlockType Outport + Name "tau_fr" + SID "237::27" + Position [460, 101, 480, 119] + ZOrder 13 + IconDisplay "Port number" + } + Line { + ZOrder 1 + SrcBlock "qD" + SrcPort 1 + DstBlock " SFunction " + DstPort 1 + } + Line { + Name "tau_fr" + ZOrder 2 + Labels [0, 0] + SrcBlock " SFunction " + SrcPort 2 + DstBlock "tau_fr" + DstPort 1 + } + Line { + ZOrder 3 + SrcBlock " Demux " + SrcPort 1 + DstBlock " Terminator " + DstPort 1 + } + Line { + ZOrder 4 + SrcBlock " SFunction " + SrcPort 1 + DstBlock " Demux " + DstPort 1 + } + } + } + Block { + BlockType Outport + Name "tau_fr" + SID "240" + Position [210, 43, 240, 57] + ZOrder 132 + IconDisplay "Port number" + } + Line { + ZOrder 3 + SrcBlock "qD" + SrcPort 1 + DstBlock "atlas_friction_model" + DstPort 1 + } + Line { + ZOrder 4 + SrcBlock "atlas_friction_model" + SrcPort 1 + DstBlock "tau_fr" + DstPort 1 + } + } + } + Block { + BlockType SubSystem + Name "atlas_leg_coriolis_vec_minvarpar" + SID "410" + Ports [2, 1] + Position [940, 712, 1010, 763] + ZOrder 247 + TreatAsAtomicUnit on + RequestExecContextInheritance off + Object { + $PropName "MaskObject" + $ObjectID 161 + $ClassName "Simulink.Mask" + Array { + Type "Simulink.MaskParameter" + Dimension 3 + Object { + $ObjectID 162 + Type "edit" + Name "atlas_arm_lr" + Prompt "atlas_arm_lr (left = true, right = false)" + Value "atlas_leg_lr" + } + Object { + $ObjectID 163 + Type "edit" + Name "atlas_version" + Prompt "atlas_version (3, 4)" + Value "atlas_version" + } + Object { + $ObjectID 164 + Type "edit" + Name "MPV" + Prompt "MPV (vecotr of minimal parameters)" + Value "MPV" + } + PropName "Parameters" + } + } + System { + Name "atlas_leg_coriolis_vec_minvarpar" + Location [65, 30, 1920, 1086] + Open off + ModelBrowserVisibility off + ModelBrowserWidth 200 + ScreenColor "white" + PaperOrientation "landscape" + PaperPositionMode "auto" + PaperType "A4" + PaperUnits "centimeters" + TiledPaperMargins [1.270000, 1.270000, 1.270000, 1.270000] + TiledPageScale 1 + ShowPageBoundaries off + ZoomFactor "100" + Block { + BlockType Inport + Name "q" + SID "411" + Position [20, 33, 50, 47] + ZOrder 117 + IconDisplay "Port number" + } + Block { + BlockType Inport + Name "qD" + SID "412" + Position [20, 63, 50, 77] + ZOrder 118 + Port "2" + IconDisplay "Port number" + } + Block { + BlockType SubSystem + Name "mFcn_c" + SID "413" + Ports [2, 1] + Position [70, 24, 140, 86] + ZOrder 116 + LibraryVersion "1.124" + ErrorFcn "Stateflow.Translate.translate" + PermitHierarchicalResolution "ExplicitOnly" + TreatAsAtomicUnit on + RequestExecContextInheritance off + SFBlockType "MATLAB Function" + System { + Name "mFcn_c" + Location [223, 338, 826, 833] + Open off + ModelBrowserVisibility off + ModelBrowserWidth 200 + ScreenColor "white" + PaperOrientation "landscape" + PaperPositionMode "auto" + PaperType "A4" + PaperUnits "centimeters" + TiledPaperMargins [1.270000, 1.270000, 1.270000, 1.270000] + TiledPageScale 1 + ShowPageBoundaries off + ZoomFactor "100" + SIDHighWatermark "155" + Block { + BlockType Inport + Name "q" + SID "413::1" + Position [20, 101, 40, 119] + ZOrder -1 + IconDisplay "Port number" + } + Block { + BlockType Inport + Name "qD" + SID "413::21" + Position [20, 136, 40, 154] + ZOrder 7 + Port "2" + IconDisplay "Port number" + } + Block { + BlockType Demux + Name " Demux " + SID "413::130" + Ports [1, 1] + Position [270, 230, 320, 270] + ZOrder 30 + Outputs "1" + } + Block { + BlockType S-Function + Name " SFunction " + SID "413::129" + Tag "Stateflow S-Function atlas_dynamic_library 43" + Ports [2, 2] + Position [180, 100, 230, 160] + ZOrder 29 + FunctionName "sf_sfun" + Parameters "MPV,atlas_leg_lr,atlas_version" + PortCounts "[2 2]" + EnableBusSupport off + Port { + PortNumber 2 + Name "tau_c" + RTWStorageClass "Auto" + DataLoggingNameMode "SignalName" + } + } + Block { + BlockType Terminator + Name " Terminator " + SID "413::131" + Position [460, 241, 480, 259] + ZOrder 31 + } + Block { + BlockType Outport + Name "tau_c" + SID "413::27" + Position [460, 101, 480, 119] + ZOrder 13 + IconDisplay "Port number" + } + Line { + ZOrder 6 + SrcBlock "q" + SrcPort 1 + Points [120, 0] + DstBlock " SFunction " + DstPort 1 + } + Line { + ZOrder 7 + SrcBlock "qD" + SrcPort 1 + DstBlock " SFunction " + DstPort 2 + } + Line { + Name "tau_c" + ZOrder 8 + Labels [0, 0] + SrcBlock " SFunction " + SrcPort 2 + DstBlock "tau_c" + DstPort 1 + } + Line { + ZOrder 9 + SrcBlock " Demux " + SrcPort 1 + DstBlock " Terminator " + DstPort 1 + } + Line { + ZOrder 10 + SrcBlock " SFunction " + SrcPort 1 + DstBlock " Demux " + DstPort 1 + } + } + } + Block { + BlockType Outport + Name "tau_c" + SID "414" + Position [160, 48, 190, 62] + ZOrder 119 + IconDisplay "Port number" + } + Line { + ZOrder 1 + SrcBlock "mFcn_c" + SrcPort 1 + DstBlock "tau_c" + DstPort 1 + } + Line { + ZOrder 2 + SrcBlock "q" + SrcPort 1 + DstBlock "mFcn_c" + DstPort 1 + } + Line { + ZOrder 3 + SrcBlock "qD" + SrcPort 1 + DstBlock "mFcn_c" + DstPort 2 + } + } + } + Block { + BlockType SubSystem + Name "atlas_leg_energy_minvarpar" + SID "415" + Ports [3, 2] + Position [820, 709, 890, 761] + ZOrder 248 + TreatAsAtomicUnit on + RequestExecContextInheritance off + Object { + $PropName "MaskObject" + $ObjectID 165 + $ClassName "Simulink.Mask" + Array { + Type "Simulink.MaskParameter" + Dimension 2 + Object { + $ObjectID 166 + Type "edit" + Name "MPV" + Prompt "MPV (vector of minimal parameters)" + Value "MPV" + } + Object { + $ObjectID 167 + Type "edit" + Name "atlas_version" + Prompt "Version" + Value "atlas_version" + } + PropName "Parameters" + } + } + System { + Name "atlas_leg_energy_minvarpar" + Location [65, 30, 1920, 1086] + Open off + ModelBrowserVisibility off + ModelBrowserWidth 200 + ScreenColor "white" + PaperOrientation "landscape" + PaperPositionMode "auto" + PaperType "A4" + PaperUnits "centimeters" + TiledPaperMargins [1.270000, 1.270000, 1.270000, 1.270000] + TiledPageScale 1 + ShowPageBoundaries off + ZoomFactor "100" + Block { + BlockType Inport + Name "q" + SID "416" + Position [5, 33, 35, 47] + ZOrder 91 + IconDisplay "Port number" + } + Block { + BlockType Inport + Name "qD" + SID "417" + Position [5, 63, 35, 77] + ZOrder 92 + Port "2" + IconDisplay "Port number" + } + Block { + BlockType Inport + Name "g" + SID "418" + Position [5, 93, 35, 107] + ZOrder 95 + Port "3" + IconDisplay "Port number" + } + Block { + BlockType SubSystem + Name "atlas_leg_energy_fb" + SID "419" + Ports [3, 2] + Position [70, 28, 160, 112] + ZOrder 90 + NamePlacement "alternate" + LibraryVersion "1.86" + ErrorFcn "Stateflow.Translate.translate" + PermitHierarchicalResolution "ExplicitOnly" + TreatAsAtomicUnit on + RequestExecContextInheritance off + SFBlockType "MATLAB Function" + System { + Name "atlas_leg_energy_fb" + Location [223, 338, 826, 833] + Open off + ModelBrowserVisibility off + ModelBrowserWidth 200 + ScreenColor "white" + PaperOrientation "landscape" + PaperPositionMode "auto" + PaperType "A4" + PaperUnits "centimeters" + TiledPaperMargins [1.270000, 1.270000, 1.270000, 1.270000] + TiledPageScale 1 + ShowPageBoundaries off + ZoomFactor "100" + SIDHighWatermark "104" + Block { + BlockType Inport + Name "q" + SID "419::1" + Position [20, 101, 40, 119] + ZOrder -1 + IconDisplay "Port number" + } + Block { + BlockType Inport + Name "qD" + SID "419::21" + Position [20, 136, 40, 154] + ZOrder 7 + Port "2" + IconDisplay "Port number" + } + Block { + BlockType Inport + Name "g_utorso" + SID "419::65" + Position [20, 171, 40, 189] + ZOrder 19 + Port "3" + IconDisplay "Port number" + } + Block { + BlockType Demux + Name " Demux " + SID "419::71" + Ports [1, 1] + Position [270, 230, 320, 270] + ZOrder 24 + Outputs "1" + } + Block { + BlockType S-Function + Name " SFunction " + SID "419::70" + Tag "Stateflow S-Function atlas_dynamic_library 44" + Ports [3, 3] + Position [180, 100, 230, 180] + ZOrder 23 + FunctionName "sf_sfun" + Parameters "MPV,atlas_leg_lr,atlas_version" + PortCounts "[3 3]" + EnableBusSupport off + Port { + PortNumber 2 + Name "T" + RTWStorageClass "Auto" + DataLoggingNameMode "SignalName" + } + Port { + PortNumber 3 + Name "U" + RTWStorageClass "Auto" + DataLoggingNameMode "SignalName" + } + } + Block { + BlockType Terminator + Name " Terminator " + SID "419::72" + Position [460, 241, 480, 259] + ZOrder 25 + } + Block { + BlockType Outport + Name "T" + SID "419::5" + Position [460, 101, 480, 119] + ZOrder -5 + IconDisplay "Port number" + } + Block { + BlockType Outport + Name "U" + SID "419::25" + Position [460, 136, 480, 154] + ZOrder 11 + Port "2" + IconDisplay "Port number" + } + Line { + ZOrder 8 + SrcBlock "q" + SrcPort 1 + DstBlock " SFunction " + DstPort 1 + } + Line { + ZOrder 9 + SrcBlock "qD" + SrcPort 1 + DstBlock " SFunction " + DstPort 2 + } + Line { + ZOrder 10 + SrcBlock "g_utorso" + SrcPort 1 + DstBlock " SFunction " + DstPort 3 + } + Line { + Name "T" + ZOrder 11 + Labels [0, 0] + SrcBlock " SFunction " + SrcPort 2 + DstBlock "T" + DstPort 1 + } + Line { + Name "U" + ZOrder 12 + Labels [0, 0] + SrcBlock " SFunction " + SrcPort 3 + DstBlock "U" + DstPort 1 + } + Line { + ZOrder 13 + SrcBlock " Demux " + SrcPort 1 + DstBlock " Terminator " + DstPort 1 + } + Line { + ZOrder 14 + SrcBlock " SFunction " + SrcPort 1 + DstBlock " Demux " + DstPort 1 + } + } + } + Block { + BlockType Outport + Name "T" + SID "420" + Position [215, 43, 245, 57] + ZOrder 93 + IconDisplay "Port number" + } + Block { + BlockType Outport + Name "U" + SID "421" + Position [215, 83, 245, 97] + ZOrder 94 + Port "2" + IconDisplay "Port number" + } + Line { + ZOrder 1 + SrcBlock "qD" + SrcPort 1 + DstBlock "atlas_leg_energy_fb" + DstPort 2 + } + Line { + ZOrder 2 + SrcBlock "atlas_leg_energy_fb" + SrcPort 1 + DstBlock "T" + DstPort 1 + } + Line { + ZOrder 3 + SrcBlock "atlas_leg_energy_fb" + SrcPort 2 + DstBlock "U" + DstPort 1 + } + Line { + ZOrder 4 + SrcBlock "q" + SrcPort 1 + DstBlock "atlas_leg_energy_fb" + DstPort 1 + } + Line { + ZOrder 5 + SrcBlock "g" + SrcPort 1 + DstBlock "atlas_leg_energy_fb" + DstPort 3 + } + } + } + Block { + BlockType SubSystem + Name "atlas_leg_fordyn_rj_damping_minvarpar" + SID "422" + Ports [3, 5] + Position [110, 772, 280, 848] + ZOrder 275 + LibraryVersion "1.227" + RequestExecContextInheritance off + Object { + $PropName "MaskObject" + $ObjectID 168 + $ClassName "Simulink.Mask" + Array { + Type "Simulink.MaskParameter" + Dimension 7 + Object { + $ObjectID 169 + Type "edit" + Name "q0" + Prompt "q0 (initial pose)" + Value "q0" + } + Object { + $ObjectID 170 + Type "edit" + Name "qD0" + Prompt "qD0 (initial velocity)" + Value "qD0" + } + Object { + $ObjectID 171 + Type "edit" + Name "d" + Prompt "d (viscous friction)" + Value "d" + } + Object { + $ObjectID 172 + Type "edit" + Name "muC" + Prompt "muC (coulomb friction)" + Value "muC" + } + Object { + $ObjectID 173 + Type "edit" + Name "atlas_arm_lr" + Prompt "atlas_leg_lr (Leg: left = true, right = false)" + Value "atlas_leg_lr" + } + Object { + $ObjectID 174 + Type "edit" + Name "atlas_version" + Prompt "atlas_version (3, 4)" + Value "uint8(5)" + } + Object { + $ObjectID 175 + Type "edit" + Name "MPV" + Prompt "MPV (minimal parameter vector)" + Value "MPV" + } + PropName "Parameters" + } + Array { + Type "Simulink.dialog.Group" + Dimension 2 + Object { + $ObjectID 176 + Prompt "%" + Object { + $PropName "DialogControls" + $ObjectID 177 + $ClassName "Simulink.dialog.Text" + Prompt "%" + Name "DescTextVar" + } + Name "DescGroupVar" + } + Object { + $ObjectID 178 + Prompt "Robot Parameters" + Array { + Type "Simulink.dialog.parameter.Edit" + Dimension 7 + Object { + $ObjectID 179 + Name "q0" + } + Object { + $ObjectID 180 + Name "qD0" + } + Object { + $ObjectID 181 + Name "d" + } + Object { + $ObjectID 182 + Name "muC" + } + Object { + $ObjectID 183 + Name "atlas_arm_lr" + } + Object { + $ObjectID 184 + Name "atlas_version" + } + Object { + $ObjectID 185 + Name "MPV" + } + PropName "DialogControls" + } + Name "ParameterGroupVar" + } + PropName "DialogControls" + } + } + System { + Name "atlas_leg_fordyn_rj_damping_minvarpar" + Location [65, 30, 1920, 1086] + Open on + ModelBrowserVisibility off + ModelBrowserWidth 200 + ScreenColor "white" + PaperOrientation "landscape" + PaperPositionMode "auto" + PaperType "usletter" + PaperUnits "inches" + TiledPaperMargins [0.500000, 0.500000, 0.500000, 0.500000] + TiledPageScale 1 + ShowPageBoundaries off + ZoomFactor "100" + Block { + BlockType Inport + Name "tau_ext\n" + SID "423" + Position [60, 343, 90, 357] + ZOrder 61 + IconDisplay "Port number" + } + Block { + BlockType Inport + Name "tau_m" + SID "424" + Position [60, 503, 90, 517] + ZOrder 62 + Port "2" + IconDisplay "Port number" + Port { + PortNumber 1 + Name "tau_m" + RTWStorageClass "Auto" + DataLogging on + DataLoggingNameMode "SignalName" + } + } + Block { + BlockType Inport + Name "g" + SID "425" + Position [795, 453, 825, 467] + ZOrder 124 + BlockMirror on + Port "3" + IconDisplay "Port number" + } + Block { + BlockType Integrator + Name "Integrator" + SID "426" + Ports [1, 1] + Position [435, 85, 465, 115] + ZOrder 36 + InitialCondition "qD0" + Port { + PortNumber 1 + Name "qD" + RTWStorageClass "Auto" + DataLogging on + DataLoggingNameMode "SignalName" + } + } + Block { + BlockType Integrator + Name "Integrator1" + SID "427" + Ports [1, 1] + Position [555, 84, 585, 116] + ZOrder 37 + InitialCondition "q0" + Port { + PortNumber 1 + Name "q" + RTWStorageClass "Auto" + DataLogging on + DataLoggingNameMode "SignalName" + } + } + Block { + BlockType Sum + Name "Sum1" + SID "428" + Ports [2, 1] + Position [170, 225, 190, 245] + ZOrder 138 + BlockRotation 270 + ShowName off + IconShape "round" + Inputs "|+-" + InputSameDT off + OutDataTypeStr "Inherit: Inherit via internal rule" + SaturateOnIntegerOverflow off + } + Block { + BlockType Sum + Name "Sum2" + SID "429" + Ports [2, 1] + Position [170, 440, 190, 460] + ZOrder 45 + BlockRotation 270 + ShowName off + IconShape "round" + Inputs "|+-" + InputSameDT off + OutDataTypeStr "Inherit: Inherit via internal rule" + SaturateOnIntegerOverflow off + } + Block { + BlockType Sum + Name "Sum3" + SID "430" + Ports [3, 1] + Position [170, 340, 190, 360] + ZOrder 46 + BlockRotation 270 + ShowName off + IconShape "round" + Inputs "++-" + InputSameDT off + OutDataTypeStr "Inherit: Inherit via internal rule" + SaturateOnIntegerOverflow off + Port { + PortNumber 1 + Name "tau_acc" + RTWStorageClass "Auto" + DataLogging on + DataLoggingNameMode "SignalName" + } + } + Block { + BlockType Reference + Name "atlas_friction_model" + SID "434" + Ports [1, 1] + Position [315, 211, 385, 259] + ZOrder 139 + BlockMirror on + LibraryVersion "1.227" + SourceBlock "atlas_dynamic_library/atlas_friction_model" + SourceType "" + ContentPreviewEnabled off + muC "muC" + d "d" + } + Block { + BlockType Reference + Name "atlas_leg_coriolis_vec_minvarpar" + SID "441" + Ports [2, 1] + Position [315, 322, 385, 373] + ZOrder 248 + BlockMirror on + NamePlacement "alternate" + LibraryVersion "1.227" + SourceBlock "atlas_dynamic_library/atlas_leg_coriolis_vec_minvarpar" + SourceType "" + ContentPreviewEnabled off + atlas_arm_lr "atlas_leg_lr" + atlas_version "atlas_version" + MPV "MPV" + Port { + PortNumber 1 + Name "tau_c" + RTWStorageClass "Auto" + DataLoggingNameMode "SignalName" + } + } + Block { + BlockType Reference + Name "atlas_leg_gravload_minvarpar" + SID "442" + Ports [2, 1] + Position [315, 422, 385, 473] + ZOrder 249 + BlockMirror on + NamePlacement "alternate" + LibraryVersion "1.227" + SourceBlock "atlas_dynamic_library/atlas_leg_gravload_minvarpar" + SourceType "" + ContentPreviewEnabled off + atlas_arm_lr "atlas_leg_lr" + atlas_version "atlas_version" + MPV "MPV" + Port { + PortNumber 1 + Name "tau_g" + RTWStorageClass "Auto" + DataLoggingNameMode "SignalName" + } + } + Block { + BlockType Reference + Name "atlas_leg_inertia_minvarpar" + SID "443" + Ports [1, 1] + Position [60, 51, 130, 99] + ZOrder 250 + LibraryVersion "1.227" + SourceBlock "atlas_dynamic_library/atlas_leg_inertia_minvarpar" + SourceType "" + ContentPreviewEnabled off + atlas_arm_lr "atlas_leg_lr" + atlas_version "atlas_version" + MPV "MPV" + } + Block { + BlockType SubSystem + Name "mFcn_Minv" + SID "435" + Ports [2, 1] + Position [305, 53, 395, 142] + ZOrder 35 + LibraryVersion "1.32" + ErrorFcn "Stateflow.Translate.translate" + PermitHierarchicalResolution "ExplicitOnly" + TreatAsAtomicUnit on + RequestExecContextInheritance off + SFBlockType "MATLAB Function" + Port { + PortNumber 1 + Name "qDD" + PropagatedSignals "q_ddot" + RTWStorageClass "Auto" + DataLogging on + DataLoggingNameMode "SignalName" + } + System { + Name "mFcn_Minv" + Location [223, 338, 826, 833] + Open off + ModelBrowserVisibility off + ModelBrowserWidth 200 + ScreenColor "white" + PaperOrientation "landscape" + PaperPositionMode "auto" + PaperType "usletter" + PaperUnits "inches" + TiledPaperMargins [0.500000, 0.500000, 0.500000, 0.500000] + TiledPageScale 1 + ShowPageBoundaries off + ZoomFactor "100" + SIDHighWatermark "171" + Block { + BlockType Inport + Name "M" + SID "435::1" + Position [20, 101, 40, 119] + ZOrder -1 + IconDisplay "Port number" + } + Block { + BlockType Inport + Name "tau" + SID "435::21" + Position [20, 136, 40, 154] + ZOrder 7 + Port "2" + IconDisplay "Port number" + } + Block { + BlockType Demux + Name " Demux " + SID "435::170" + Ports [1, 1] + Position [270, 230, 320, 270] + ZOrder 48 + Outputs "1" + } + Block { + BlockType S-Function + Name " SFunction " + SID "435::169" + Tag "Stateflow S-Function atlas_dynamic_library 45" + Ports [2, 2] + Position [180, 100, 230, 160] + ZOrder 47 + FunctionName "sf_sfun" + PortCounts "[2 2]" + EnableBusSupport off + Port { + PortNumber 2 + Name "q_ddot" + RTWStorageClass "Auto" + DataLoggingNameMode "SignalName" + } + } + Block { + BlockType Terminator + Name " Terminator " + SID "435::171" + Position [460, 241, 480, 259] + ZOrder 49 + } + Block { + BlockType Outport + Name "q_ddot" + SID "435::5" + Position [460, 101, 480, 119] + ZOrder -5 + IconDisplay "Port number" + } + Line { + ZOrder 6 + SrcBlock "M" + SrcPort 1 + Points [120, 0] + DstBlock " SFunction " + DstPort 1 + } + Line { + ZOrder 7 + SrcBlock "tau" + SrcPort 1 + DstBlock " SFunction " + DstPort 2 + } + Line { + Name "q_ddot" + ZOrder 8 + Labels [0, 0] + SrcBlock " SFunction " + SrcPort 2 + DstBlock "q_ddot" + DstPort 1 + } + Line { + ZOrder 9 + SrcBlock " Demux " + SrcPort 1 + DstBlock " Terminator " + DstPort 1 + } + Line { + ZOrder 10 + SrcBlock " SFunction " + SrcPort 1 + DstBlock " Demux " + DstPort 1 + } + } + } + Block { + BlockType Outport + Name "q" + SID "436" + Position [805, 93, 835, 107] + ZOrder 63 + IconDisplay "Port number" + } + Block { + BlockType Outport + Name "qD" + SID "437" + Position [805, 148, 835, 162] + ZOrder 64 + Port "2" + IconDisplay "Port number" + } + Block { + BlockType Outport + Name "qDD" + SID "438" + Position [805, 48, 835, 62] + ZOrder 65 + Port "3" + IconDisplay "Port number" + } + Block { + BlockType Outport + Name "tau_fr" + SID "439" + Position [60, 278, 90, 292] + ZOrder 141 + BlockMirror on + Port "4" + IconDisplay "Port number" + } + Block { + BlockType Outport + Name "tau_J" + SID "440" + Position [795, 503, 825, 517] + ZOrder 142 + Port "5" + IconDisplay "Port number" + } + Line { + ZOrder 1 + SrcBlock "Sum1" + SrcPort 1 + Points [0, -100] + DstBlock "mFcn_Minv" + DstPort 2 + } + Line { + ZOrder 2 + SrcBlock "atlas_friction_model" + SrcPort 1 + Points [-55, 0] + Branch { + ZOrder 3 + Points [0, 50] + DstBlock "tau_fr" + DstPort 1 + } + Branch { + ZOrder 4 + DstBlock "Sum1" + DstPort 2 + } + } + Line { + Name "tau_acc" + ZOrder 5 + Labels [0, 0] + SrcBlock "Sum3" + SrcPort 1 + DstBlock "Sum1" + DstPort 1 + } + Line { + ZOrder 6 + SrcBlock "g" + SrcPort 1 + DstBlock "atlas_leg_gravload_minvarpar" + DstPort 2 + } + Line { + ZOrder 7 + SrcBlock "atlas_leg_inertia_minvarpar" + SrcPort 1 + DstBlock "mFcn_Minv" + DstPort 1 + } + Line { + Name "qD" + ZOrder 8 + Labels [1, 1] + SrcBlock "Integrator" + SrcPort 1 + Points [42, 0] + Branch { + ZOrder 9 + Labels [1, 1] + DstBlock "Integrator1" + DstPort 1 + } + Branch { + ZOrder 10 + Points [0, 55] + Branch { + ZOrder 11 + Points [0, 80] + Branch { + ZOrder 12 + Labels [1, 0; -1, 0] + Points [0, 125] + DstBlock "atlas_leg_coriolis_vec_minvarpar" + DstPort 2 + } + Branch { + ZOrder 13 + DstBlock "atlas_friction_model" + DstPort 1 + } + } + Branch { + ZOrder 14 + DstBlock "qD" + DstPort 1 + } + } + } + Line { + Name "tau_m" + ZOrder 15 + Labels [0, 0] + SrcBlock "tau_m" + SrcPort 1 + Points [85, 0] + Branch { + ZOrder 16 + DstBlock "Sum2" + DstPort 1 + } + Branch { + ZOrder 17 + DstBlock "tau_J" + DstPort 1 + } + } + Line { + ZOrder 18 + SrcBlock "tau_ext\n" + SrcPort 1 + DstBlock "Sum3" + DstPort 1 + } + Line { + Name "tau_c" + ZOrder 19 + Labels [-1, 0] + SrcBlock "atlas_leg_coriolis_vec_minvarpar" + SrcPort 1 + DstBlock "Sum3" + DstPort 3 + } + Line { + ZOrder 20 + SrcBlock "Sum2" + SrcPort 1 + DstBlock "Sum3" + DstPort 2 + } + Line { + Name "qDD" + ZOrder 21 + Labels [0, 0] + SrcBlock "mFcn_Minv" + SrcPort 1 + Points [13, 0] + Branch { + ZOrder 22 + DstBlock "Integrator" + DstPort 1 + } + Branch { + ZOrder 23 + Points [0, -45] + DstBlock "qDD" + DstPort 1 + } + } + Line { + Name "q" + ZOrder 24 + Labels [-1, 0] + SrcBlock "Integrator1" + SrcPort 1 + Points [65, 0] + Branch { + ZOrder 25 + Labels [2, 1] + Points [0, -64; -635, 0; 0, 39] + DstBlock "atlas_leg_inertia_minvarpar" + DstPort 1 + } + Branch { + ZOrder 26 + Labels [1, 1] + Points [0, 235] + DstBlock "atlas_leg_coriolis_vec_minvarpar" + DstPort 1 + } + Branch { + ZOrder 27 + Labels [1, 1] + Points [67, 0] + Branch { + ZOrder 28 + Labels [1, 0] + Points [0, 335] + DstBlock "atlas_leg_gravload_minvarpar" + DstPort 1 + } + Branch { + ZOrder 29 + Labels [1, 1] + DstBlock "q" + DstPort 1 + } + } + } + Line { + Name "tau_g" + ZOrder 30 + Labels [0, 0] + SrcBlock "atlas_leg_gravload_minvarpar" + SrcPort 1 + DstBlock "Sum2" + DstPort 2 + } + } + } + Block { + BlockType SubSystem + Name "atlas_leg_gravload_minvarpar" + SID "393" + Ports [2, 1] + Position [820, 797, 890, 848] + ZOrder 243 + TreatAsAtomicUnit on + RequestExecContextInheritance off + Object { + $PropName "MaskObject" + $ObjectID 186 + $ClassName "Simulink.Mask" + Array { + Type "Simulink.MaskParameter" + Dimension 3 + Object { + $ObjectID 187 + Type "edit" + Name "atlas_arm_lr" + Prompt "atlas_arm_lr (left = true, right = false)" + Value "atlas_leg_lr" + } + Object { + $ObjectID 188 + Type "edit" + Name "atlas_version" + Prompt "atlas_version (3, 4)" + Value "atlas_version" + } + Object { + $ObjectID 189 + Type "edit" + Name "MPV" + Prompt "MPV (vector of minimal parameters)" + Value "MPV" + } + PropName "Parameters" + } + } + System { + Name "atlas_leg_gravload_minvarpar" + Location [65, 30, 1920, 1086] + Open off + ModelBrowserVisibility off + ModelBrowserWidth 200 + ScreenColor "white" + PaperOrientation "landscape" + PaperPositionMode "auto" + PaperType "A4" + PaperUnits "centimeters" + TiledPaperMargins [1.270000, 1.270000, 1.270000, 1.270000] + TiledPageScale 1 + ShowPageBoundaries off + ZoomFactor "100" + Block { + BlockType Inport + Name "q" + SID "394" + Position [20, 33, 50, 47] + ZOrder 118 + IconDisplay "Port number" + } + Block { + BlockType Inport + Name "g" + SID "395" + Position [20, 63, 50, 77] + ZOrder 120 + Port "2" + IconDisplay "Port number" + } + Block { + BlockType SubSystem + Name "mFcn_g" + SID "396" + Ports [2, 1] + Position [70, 27, 140, 83] + ZOrder 117 + LibraryVersion "1.124" + ErrorFcn "Stateflow.Translate.translate" + PermitHierarchicalResolution "ExplicitOnly" + TreatAsAtomicUnit on + RequestExecContextInheritance off + SFBlockType "MATLAB Function" + System { + Name "mFcn_g" + Location [223, 338, 826, 833] + Open off + ModelBrowserVisibility off + ModelBrowserWidth 200 + ScreenColor "white" + PaperOrientation "landscape" + PaperPositionMode "auto" + PaperType "A4" + PaperUnits "centimeters" + TiledPaperMargins [1.270000, 1.270000, 1.270000, 1.270000] + TiledPageScale 1 + ShowPageBoundaries off + ZoomFactor "100" + SIDHighWatermark "148" + Block { + BlockType Inport + Name "q" + SID "396::1" + Position [20, 101, 40, 119] + ZOrder -1 + IconDisplay "Port number" + } + Block { + BlockType Inport + Name "g" + SID "396::75" + Position [20, 136, 40, 154] + ZOrder 22 + Port "2" + IconDisplay "Port number" + } + Block { + BlockType Demux + Name " Demux " + SID "396::123" + Ports [1, 1] + Position [270, 230, 320, 270] + ZOrder 27 + Outputs "1" + } + Block { + BlockType S-Function + Name " SFunction " + SID "396::122" + Tag "Stateflow S-Function atlas_dynamic_library 40" + Ports [2, 2] + Position [180, 100, 230, 160] + ZOrder 26 + FunctionName "sf_sfun" + Parameters "MPV,atlas_leg_lr,atlas_version" + PortCounts "[2 2]" + EnableBusSupport off + Port { + PortNumber 2 + Name "tau_g" + RTWStorageClass "Auto" + DataLoggingNameMode "SignalName" + } + } + Block { + BlockType Terminator + Name " Terminator " + SID "396::124" + Position [460, 241, 480, 259] + ZOrder 28 + } + Block { + BlockType Outport + Name "tau_g" + SID "396::5" + Position [460, 101, 480, 119] + ZOrder -5 + IconDisplay "Port number" + } + Line { + ZOrder 6 + SrcBlock "q" + SrcPort 1 + Points [120, 0] + DstBlock " SFunction " + DstPort 1 + } + Line { + ZOrder 7 + SrcBlock "g" + SrcPort 1 + DstBlock " SFunction " + DstPort 2 + } + Line { + Name "tau_g" + ZOrder 8 + Labels [0, 0] + SrcBlock " SFunction " + SrcPort 2 + DstBlock "tau_g" + DstPort 1 + } + Line { + ZOrder 9 + SrcBlock " Demux " + SrcPort 1 + DstBlock " Terminator " + DstPort 1 + } + Line { + ZOrder 10 + SrcBlock " SFunction " + SrcPort 1 + DstBlock " Demux " + DstPort 1 + } + } + } + Block { + BlockType Outport + Name "tau_g" + SID "397" + Position [160, 48, 190, 62] + ZOrder 119 + IconDisplay "Port number" + } + Line { + ZOrder 1 + SrcBlock "q" + SrcPort 1 + DstBlock "mFcn_g" + DstPort 1 + } + Line { + ZOrder 2 + SrcBlock "mFcn_g" + SrcPort 1 + DstBlock "tau_g" + DstPort 1 + } + Line { + ZOrder 3 + SrcBlock "g" + SrcPort 1 + DstBlock "mFcn_g" + DstPort 2 + } + } + } + Block { + BlockType SubSystem + Name "atlas_leg_inertia_minvarpar" + SID "398" + Ports [1, 1] + Position [940, 801, 1010, 849] + ZOrder 244 + TreatAsAtomicUnit on + RequestExecContextInheritance off + Object { + $PropName "MaskObject" + $ObjectID 190 + $ClassName "Simulink.Mask" + Array { + Type "Simulink.MaskParameter" + Dimension 3 + Object { + $ObjectID 191 + Type "edit" + Name "atlas_arm_lr" + Prompt "atlas_arm_lr (left = true, right = false)" + Value "atlas_leg_lr" + } + Object { + $ObjectID 192 + Type "edit" + Name "atlas_version" + Prompt "atlas_version (3, 4)" + Value "atlas_version" + } + Object { + $ObjectID 193 + Type "edit" + Name "MPV" + Prompt "MPV (vector of minimal parameters)" + Value "MPV" + } + PropName "Parameters" + } + } + System { + Name "atlas_leg_inertia_minvarpar" + Location [1985, 316, 3840, 1372] + Open off + ModelBrowserVisibility off + ModelBrowserWidth 200 + ScreenColor "white" + PaperOrientation "landscape" + PaperPositionMode "auto" + PaperType "A4" + PaperUnits "centimeters" + TiledPaperMargins [1.270000, 1.270000, 1.270000, 1.270000] + TiledPageScale 1 + ShowPageBoundaries off + ZoomFactor "100" + Block { + BlockType Inport + Name "q" + SID "399" + Position [20, 43, 50, 57] + ZOrder 116 + IconDisplay "Port number" + } + Block { + BlockType SubSystem + Name "mFcn_M" + SID "400" + Ports [1, 1] + Position [70, 22, 140, 78] + ZOrder 115 + LibraryVersion "1.124" + ErrorFcn "Stateflow.Translate.translate" + PermitHierarchicalResolution "ExplicitOnly" + TreatAsAtomicUnit on + RequestExecContextInheritance off + SFBlockType "MATLAB Function" + System { + Name "mFcn_M" + Location [223, 338, 826, 833] + Open off + ModelBrowserVisibility off + ModelBrowserWidth 200 + ScreenColor "white" + PaperOrientation "landscape" + PaperPositionMode "auto" + PaperType "A4" + PaperUnits "centimeters" + TiledPaperMargins [1.270000, 1.270000, 1.270000, 1.270000] + TiledPageScale 1 + ShowPageBoundaries off + ZoomFactor "100" + SIDHighWatermark "126" + Block { + BlockType Inport + Name "q" + SID "400::1" + Position [20, 101, 40, 119] + ZOrder -1 + IconDisplay "Port number" + } + Block { + BlockType Demux + Name " Demux " + SID "400::115" + Ports [1, 1] + Position [270, 230, 320, 270] + ZOrder 26 + Outputs "1" + } + Block { + BlockType S-Function + Name " SFunction " + SID "400::114" + Tag "Stateflow S-Function atlas_dynamic_library 41" + Ports [1, 2] + Position [180, 100, 230, 160] + ZOrder 25 + FunctionName "sf_sfun" + Parameters "MPV,atlas_leg_lr,atlas_version" + PortCounts "[1 2]" + EnableBusSupport off + Port { + PortNumber 2 + Name "M" + RTWStorageClass "Auto" + DataLoggingNameMode "SignalName" + } + } + Block { + BlockType Terminator + Name " Terminator " + SID "400::116" + Position [460, 241, 480, 259] + ZOrder 27 + } + Block { + BlockType Outport + Name "M" + SID "400::5" + Position [460, 101, 480, 119] + ZOrder -5 + IconDisplay "Port number" + } + Line { + ZOrder 5 + SrcBlock "q" + SrcPort 1 + DstBlock " SFunction " + DstPort 1 + } + Line { + Name "M" + ZOrder 6 + Labels [0, 0] + SrcBlock " SFunction " + SrcPort 2 + DstBlock "M" + DstPort 1 + } + Line { + ZOrder 7 + SrcBlock " Demux " + SrcPort 1 + DstBlock " Terminator " + DstPort 1 + } + Line { + ZOrder 8 + SrcBlock " SFunction " + SrcPort 1 + DstBlock " Demux " + DstPort 1 + } + } + } + Block { + BlockType Outport + Name "M" + SID "401" + Position [160, 43, 190, 57] + ZOrder 117 + IconDisplay "Port number" + } + Line { + ZOrder 1 + SrcBlock "mFcn_M" + SrcPort 1 + DstBlock "M" + DstPort 1 + } + Line { + ZOrder 2 + SrcBlock "q" + SrcPort 1 + DstBlock "mFcn_M" + DstPort 1 + } + } + } + Block { + BlockType SubSystem + Name "atlas_leg_invdyn_fb_minvarpar" + SID "403" + Ports [4, 1] + Position [1085, 721, 1155, 774] + ZOrder 246 + TreatAsAtomicUnit on + RequestExecContextInheritance off + Object { + $PropName "MaskObject" + $ObjectID 194 + $ClassName "Simulink.Mask" + Object { + $PropName "Parameters" + $ObjectID 195 + $ClassName "Simulink.MaskParameter" + Type "edit" + Name "MPV" + Prompt "MPV (vector of minimal parameters)" + Value "MPV" + } + } + System { + Name "atlas_leg_invdyn_fb_minvarpar" + Location [976, 17, 1932, 1093] + Open off + ModelBrowserVisibility off + ModelBrowserWidth 200 + ScreenColor "white" + PaperOrientation "landscape" + PaperPositionMode "auto" + PaperType "A4" + PaperUnits "centimeters" + TiledPaperMargins [1.270000, 1.270000, 1.270000, 1.270000] + TiledPageScale 1 + ShowPageBoundaries off + ZoomFactor "100" + Block { + BlockType Inport + Name "q" + SID "404" + Position [20, 33, 50, 47] + ZOrder 117 + IconDisplay "Port number" + } + Block { + BlockType Inport + Name "qD" + SID "405" + Position [20, 58, 50, 72] + ZOrder 118 + Port "2" + IconDisplay "Port number" + } + Block { + BlockType Inport + Name "qDD" + SID "406" + Position [20, 83, 50, 97] + ZOrder 121 + Port "3" + IconDisplay "Port number" + } + Block { + BlockType Inport + Name "g" + SID "407" + Position [20, 108, 50, 122] + ZOrder 122 + Port "4" + IconDisplay "Port number" + } + Block { + BlockType SubSystem + Name "mFcn_tau" + SID "408" + Ports [4, 1] + Position [70, 28, 190, 127] + ZOrder 116 + LibraryVersion "1.124" + ErrorFcn "Stateflow.Translate.translate" + PermitHierarchicalResolution "ExplicitOnly" + TreatAsAtomicUnit on + RequestExecContextInheritance off + SFBlockType "MATLAB Function" + System { + Name "mFcn_tau" + Location [223, 338, 826, 833] + Open off + ModelBrowserVisibility off + ModelBrowserWidth 200 + ScreenColor "white" + PaperOrientation "landscape" + PaperPositionMode "auto" + PaperType "A4" + PaperUnits "centimeters" + TiledPaperMargins [1.270000, 1.270000, 1.270000, 1.270000] + TiledPageScale 1 + ShowPageBoundaries off + ZoomFactor "100" + SIDHighWatermark "100" + Block { + BlockType Inport + Name "q" + SID "408::1" + Position [20, 101, 40, 119] + ZOrder -1 + IconDisplay "Port number" + } + Block { + BlockType Inport + Name "qD" + SID "408::21" + Position [20, 136, 40, 154] + ZOrder 7 + Port "2" + IconDisplay "Port number" + } + Block { + BlockType Inport + Name "qDD" + SID "408::96" + Position [20, 171, 40, 189] + ZOrder 32 + Port "3" + IconDisplay "Port number" + } + Block { + BlockType Inport + Name "g" + SID "408::97" + Position [20, 206, 40, 224] + ZOrder 33 + Port "4" + IconDisplay "Port number" + } + Block { + BlockType Demux + Name " Demux " + SID "408::99" + Ports [1, 1] + Position [270, 230, 320, 270] + ZOrder 35 + Outputs "1" + } + Block { + BlockType S-Function + Name " SFunction " + SID "408::98" + Tag "Stateflow S-Function atlas_dynamic_library 42" + Ports [4, 2] + Position [180, 102, 230, 203] + ZOrder 34 + FunctionName "sf_sfun" + Parameters "MPV,atlas_arm_lr,atlas_version" + PortCounts "[4 2]" + EnableBusSupport off + Port { + PortNumber 2 + Name "tau" + RTWStorageClass "Auto" + DataLoggingNameMode "SignalName" + } + } + Block { + BlockType Terminator + Name " Terminator " + SID "408::100" + Position [460, 241, 480, 259] + ZOrder 36 + } + Block { + BlockType Outport + Name "tau" + SID "408::27" + Position [460, 101, 480, 119] + ZOrder 13 + IconDisplay "Port number" + } + Line { + ZOrder 8 + SrcBlock "q" + SrcPort 1 + DstBlock " SFunction " + DstPort 1 + } + Line { + ZOrder 9 + SrcBlock "qD" + SrcPort 1 + DstBlock " SFunction " + DstPort 2 + } + Line { + ZOrder 10 + SrcBlock "qDD" + SrcPort 1 + DstBlock " SFunction " + DstPort 3 + } + Line { + ZOrder 11 + SrcBlock "g" + SrcPort 1 + DstBlock " SFunction " + DstPort 4 + } + Line { + Name "tau" + ZOrder 12 + Labels [0, 0] + SrcBlock " SFunction " + SrcPort 2 + DstBlock "tau" + DstPort 1 + } + Line { + ZOrder 13 + SrcBlock " Demux " + SrcPort 1 + DstBlock " Terminator " + DstPort 1 + } + Line { + ZOrder 14 + SrcBlock " SFunction " + SrcPort 1 + DstBlock " Demux " + DstPort 1 + } + } + } + Block { + BlockType Outport + Name "tau" + SID "409" + Position [260, 73, 290, 87] + ZOrder 119 + IconDisplay "Port number" + } + Line { + ZOrder 1 + SrcBlock "g" + SrcPort 1 + DstBlock "mFcn_tau" + DstPort 4 + } + Line { + ZOrder 2 + SrcBlock "qDD" + SrcPort 1 + DstBlock "mFcn_tau" + DstPort 3 + } + Line { + ZOrder 3 + SrcBlock "qD" + SrcPort 1 + DstBlock "mFcn_tau" + DstPort 2 + } + Line { + ZOrder 4 + SrcBlock "q" + SrcPort 1 + DstBlock "mFcn_tau" + DstPort 1 + } + Line { + ZOrder 5 + SrcBlock "mFcn_tau" + SrcPort 1 + DstBlock "tau" + DstPort 1 + } + } + } + Block { + BlockType SubSystem + Name "atlas_leg_jacobig" + SID "444" + Ports [1, 1] + Position [370, 710, 440, 760] + ZOrder 250 + TreatAsAtomicUnit on + RequestExecContextInheritance off + Object { + $PropName "MaskObject" + $ObjectID 196 + $ClassName "Simulink.Mask" + Array { + Type "Simulink.MaskParameter" + Dimension 2 + Object { + $ObjectID 197 + Type "edit" + Name "atlas_version" + Prompt "Version" + Value "atlas_version" + } + Object { + $ObjectID 198 + Type "edit" + Name "atlas_leg_lr" + Prompt "LeftRight" + Value "atlas_leg_lr" + } + PropName "Parameters" + } + } + System { + Name "atlas_leg_jacobig" + Location [65, 24, 1920, 1080] + Open off + ModelBrowserVisibility off + ModelBrowserWidth 200 + ScreenColor "white" + PaperOrientation "landscape" + PaperPositionMode "auto" + PaperType "A4" + PaperUnits "centimeters" + TiledPaperMargins [1.270000, 1.270000, 1.270000, 1.270000] + TiledPageScale 1 + ShowPageBoundaries off + ZoomFactor "100" + Block { + BlockType Inport + Name "q" + SID "445" + Position [20, 38, 50, 52] + ZOrder 88 + IconDisplay "Port number" + } + Block { + BlockType SubSystem + Name "atlas_leg_jacobig" + SID "446" + Ports [1, 1] + Position [70, 24, 140, 76] + ZOrder 87 + NamePlacement "alternate" + LibraryVersion "1.72" + ErrorFcn "Stateflow.Translate.translate" + PermitHierarchicalResolution "ExplicitOnly" + TreatAsAtomicUnit on + RequestExecContextInheritance off + SFBlockType "MATLAB Function" + Object { + $PropName "MaskObject" + $ObjectID 199 + $ClassName "Simulink.Mask" + Initialization "if edit_lr == 1\n atlas_arm_lr = true; % left\nelse\n atlas_arm_lr = false; % right\nend\n" + Array { + Type "Simulink.MaskParameter" + Dimension 2 + Object { + $ObjectID 200 + Type "edit" + Name "edit_lr" + Prompt "Arm (left = true, right = false)" + Value "atlas_leg_lr" + } + Object { + $ObjectID 201 + Type "edit" + Name "atlas_version" + Prompt "Version" + Value "atlas_version" + } + PropName "Parameters" + } + } + System { + Name "atlas_leg_jacobig" + Location [223, 338, 826, 833] + Open off + ModelBrowserVisibility off + ModelBrowserWidth 200 + ScreenColor "white" + PaperOrientation "landscape" + PaperPositionMode "auto" + PaperType "A4" + PaperUnits "centimeters" + TiledPaperMargins [1.270000, 1.270000, 1.270000, 1.270000] + TiledPageScale 1 + ShowPageBoundaries off + ZoomFactor "100" + SIDHighWatermark "86" + Block { + BlockType Inport + Name "q" + SID "446::1" + Position [20, 101, 40, 119] + ZOrder -1 + IconDisplay "Port number" + } + Block { + BlockType Demux + Name " Demux " + SID "446::64" + Ports [1, 1] + Position [270, 230, 320, 270] + ZOrder 28 + Outputs "1" + } + Block { + BlockType S-Function + Name " SFunction " + SID "446::63" + Tag "Stateflow S-Function atlas_dynamic_library 46" + Ports [1, 2] + Position [180, 100, 230, 160] + ZOrder 27 + FunctionName "sf_sfun" + Parameters "atlas_leg_lr,atlas_version" + PortCounts "[1 2]" + EnableBusSupport off + Port { + PortNumber 2 + Name "JG" + RTWStorageClass "Auto" + DataLoggingNameMode "SignalName" + } + } + Block { + BlockType Terminator + Name " Terminator " + SID "446::65" + Position [460, 241, 480, 259] + ZOrder 29 + } + Block { + BlockType Outport + Name "JG" + SID "446::5" + Position [460, 101, 480, 119] + ZOrder -5 + IconDisplay "Port number" + } + Line { + ZOrder 14 + SrcBlock "q" + SrcPort 1 + DstBlock " SFunction " + DstPort 1 + } + Line { + Name "JG" + ZOrder 15 + Labels [0, 0] + SrcBlock " SFunction " + SrcPort 2 + DstBlock "JG" + DstPort 1 + } + Line { + ZOrder 16 + SrcBlock " Demux " + SrcPort 1 + DstBlock " Terminator " + DstPort 1 + } + Line { + ZOrder 17 + SrcBlock " SFunction " + SrcPort 1 + DstBlock " Demux " + DstPort 1 + } + } + } + Block { + BlockType Outport + Name "JG" + SID "447" + Position [160, 38, 190, 52] + ZOrder 89 + IconDisplay "Port number" + PortDimensions "[6 6]" + } + Line { + ZOrder 1 + SrcBlock "q" + SrcPort 1 + DstBlock "atlas_leg_jacobig" + DstPort 1 + } + Line { + ZOrder 2 + SrcBlock "atlas_leg_jacobig" + SrcPort 1 + DstBlock "JG" + DstPort 1 + } + } + } + Block { + BlockType SubSystem + Name "atlsa3_arm_jacobigD" + SID "143" + Ports [2, 1] + Position [370, 77, 440, 128] + ZOrder 107 + TreatAsAtomicUnit on + RequestExecContextInheritance off + System { + Name "atlsa3_arm_jacobigD" + Location [960, 0, 1920, 1160] + Open off + ModelBrowserVisibility off + ModelBrowserWidth 200 + ScreenColor "white" + PaperOrientation "landscape" + PaperPositionMode "auto" + PaperType "A4" + PaperUnits "centimeters" + TiledPaperMargins [1.270000, 1.270000, 1.270000, 1.270000] + TiledPageScale 1 + ShowPageBoundaries off + ZoomFactor "100" + Block { + BlockType Inport + Name "q" + SID "144" + Position [20, 28, 50, 42] + ZOrder 87 + IconDisplay "Port number" + } + Block { + BlockType Inport + Name "qD" + SID "145" + Position [20, 58, 50, 72] + ZOrder 88 + Port "2" + IconDisplay "Port number" + } + Block { + BlockType SubSystem + Name "atlas3_arm_jacobigD" + SID "82" + Ports [2, 1] + Position [70, 20, 140, 80] + ZOrder 86 + NamePlacement "alternate" + LibraryVersion "1.69" + ErrorFcn "Stateflow.Translate.translate" + PermitHierarchicalResolution "ExplicitOnly" + TreatAsAtomicUnit on + RequestExecContextInheritance off + SFBlockType "MATLAB Function" + Object { + $PropName "MaskObject" + $ObjectID 202 + $ClassName "Simulink.Mask" + Initialization "if edit_lr == 1\n atlas_arm_lr = true; % left\nelse\n atlas_arm_lr = false; % right\nend\n" + Object { + $PropName "Parameters" + $ObjectID 203 + $ClassName "Simulink.MaskParameter" + Type "edit" + Name "edit_lr" + Prompt "Arm (left = true, right = false)" + Value "atlas_arm_lr" + } + } + System { + Name "atlas3_arm_jacobigD" + Location [223, 338, 826, 833] + Open off + ModelBrowserVisibility off + ModelBrowserWidth 200 + ScreenColor "white" + PaperOrientation "landscape" + PaperPositionMode "auto" + PaperType "A4" + PaperUnits "centimeters" + TiledPaperMargins [1.270000, 1.270000, 1.270000, 1.270000] + TiledPageScale 1 + ShowPageBoundaries off + ZoomFactor "100" + SIDHighWatermark "48" + Block { + BlockType Inport + Name "q" + SID "82::1" + Position [20, 101, 40, 119] + ZOrder -1 + IconDisplay "Port number" + } + Block { + BlockType Inport + Name "qD" + SID "82::21" + Position [20, 136, 40, 154] + ZOrder 7 + Port "2" + IconDisplay "Port number" + } + Block { + BlockType Demux + Name " Demux " + SID "82::47" + Ports [1, 1] + Position [270, 230, 320, 270] + ZOrder 16 + Outputs "1" + } + Block { + BlockType S-Function + Name " SFunction " + SID "82::46" + Tag "Stateflow S-Function atlas_dynamic_library 5" + Ports [2, 2] + Position [180, 100, 230, 160] + ZOrder 15 + FunctionName "sf_sfun" + Parameters "atlas_arm_lr" + PortCounts "[2 2]" + EnableBusSupport off + Port { + PortNumber 2 + Name "JGD" + RTWStorageClass "Auto" + DataLoggingNameMode "SignalName" + } + } + Block { + BlockType Terminator + Name " Terminator " + SID "82::48" + Position [460, 241, 480, 259] + ZOrder 17 + } + Block { + BlockType Outport + Name "JGD" + SID "82::5" + Position [460, 101, 480, 119] + ZOrder -5 + IconDisplay "Port number" + } + Line { + ZOrder 13 + SrcBlock "q" + SrcPort 1 + DstBlock " SFunction " + DstPort 1 + } + Line { + ZOrder 14 + SrcBlock "qD" + SrcPort 1 + DstBlock " SFunction " + DstPort 2 + } + Line { + Name "JGD" + ZOrder 15 + Labels [0, 0] + SrcBlock " SFunction " + SrcPort 2 + DstBlock "JGD" + DstPort 1 + } + Line { + ZOrder 16 + SrcBlock " Demux " + SrcPort 1 + DstBlock " Terminator " + DstPort 1 + } + Line { + ZOrder 17 + SrcBlock " SFunction " + SrcPort 1 + DstBlock " Demux " + DstPort 1 + } + } + } + Block { + BlockType Outport + Name "JGD" + SID "146" + Position [160, 43, 190, 57] + ZOrder 89 + IconDisplay "Port number" + } + Line { + ZOrder 16 + SrcBlock "atlas3_arm_jacobigD" + SrcPort 1 + DstBlock "JGD" + DstPort 1 + } + Line { + ZOrder 15 + SrcBlock "qD" + SrcPort 1 + DstBlock "atlas3_arm_jacobigD" + DstPort 2 + } + Line { + ZOrder 14 + SrcBlock "q" + SrcPort 1 + DstBlock "atlas3_arm_jacobigD" + DstPort 1 + } + } + } + Block { + BlockType SubSystem + Name "atlsa5_arm_jacobigD" + SID "287" + Ports [2, 1] + Position [370, 472, 440, 523] + ZOrder 232 + TreatAsAtomicUnit on + RequestExecContextInheritance off + System { + Name "atlsa5_arm_jacobigD" + Location [-10, -14, 1930, 1090] + Open off + ModelBrowserVisibility off + ModelBrowserWidth 200 + ScreenColor "white" + PaperOrientation "landscape" + PaperPositionMode "auto" + PaperType "A4" + PaperUnits "centimeters" + TiledPaperMargins [1.270000, 1.270000, 1.270000, 1.270000] + TiledPageScale 1 + ShowPageBoundaries off + ZoomFactor "100" + Block { + BlockType Inport + Name "q" + SID "331" + Position [20, 28, 50, 42] + ZOrder 87 + IconDisplay "Port number" + } + Block { + BlockType Inport + Name "qD" + SID "332" + Position [20, 58, 50, 72] + ZOrder 88 + Port "2" + IconDisplay "Port number" + } + Block { + BlockType SubSystem + Name "atlas5_arm_jacobigD" + SID "333" + Ports [2, 1] + Position [70, 20, 140, 80] + ZOrder 86 + NamePlacement "alternate" + LibraryVersion "1.69" + ErrorFcn "Stateflow.Translate.translate" + PermitHierarchicalResolution "ExplicitOnly" + TreatAsAtomicUnit on + RequestExecContextInheritance off + SFBlockType "MATLAB Function" + Object { + $PropName "MaskObject" + $ObjectID 204 + $ClassName "Simulink.Mask" + Initialization "if edit_lr == 1\n atlas_arm_lr = true; % left\nelse\n atlas_arm_lr = false; % right\nend\n" + Object { + $PropName "Parameters" + $ObjectID 205 + $ClassName "Simulink.MaskParameter" + Type "edit" + Name "edit_lr" + Prompt "Arm (left = true, right = false)" + Value "atlas_arm_lr" + } + } + System { + Name "atlas5_arm_jacobigD" + Location [223, 338, 826, 833] + Open off + ModelBrowserVisibility off + ModelBrowserWidth 200 + ScreenColor "white" + PaperOrientation "landscape" + PaperPositionMode "auto" + PaperType "A4" + PaperUnits "centimeters" + TiledPaperMargins [1.270000, 1.270000, 1.270000, 1.270000] + TiledPageScale 1 + ShowPageBoundaries off + ZoomFactor "100" + SIDHighWatermark "54" + Block { + BlockType Inport + Name "q" + SID "333::1" + Position [20, 101, 40, 119] + ZOrder -1 + IconDisplay "Port number" + } + Block { + BlockType Inport + Name "qD" + SID "333::21" + Position [20, 136, 40, 154] + ZOrder 7 + Port "2" + IconDisplay "Port number" + } + Block { + BlockType Demux + Name " Demux " + SID "333::53" + Ports [1, 1] + Position [270, 230, 320, 270] + ZOrder 22 + Outputs "1" + } + Block { + BlockType S-Function + Name " SFunction " + SID "333::52" + Tag "Stateflow S-Function atlas_dynamic_library 37" + Ports [2, 2] + Position [180, 100, 230, 160] + ZOrder 21 + FunctionName "sf_sfun" + Parameters "atlas_arm_lr" + PortCounts "[2 2]" + EnableBusSupport off + Port { + PortNumber 2 + Name "JGD" + RTWStorageClass "Auto" + DataLoggingNameMode "SignalName" + } + } + Block { + BlockType Terminator + Name " Terminator " + SID "333::54" + Position [460, 241, 480, 259] + ZOrder 23 + } + Block { + BlockType Outport + Name "JGD" + SID "333::5" + Position [460, 101, 480, 119] + ZOrder -5 + IconDisplay "Port number" + } + Line { + ZOrder 6 + SrcBlock "q" + SrcPort 1 + Points [120, 0] + DstBlock " SFunction " + DstPort 1 + } + Line { + ZOrder 7 + SrcBlock "qD" + SrcPort 1 + DstBlock " SFunction " + DstPort 2 + } + Line { + Name "JGD" + ZOrder 8 + Labels [0, 0] + SrcBlock " SFunction " + SrcPort 2 + DstBlock "JGD" + DstPort 1 + } + Line { + ZOrder 9 + SrcBlock " Demux " + SrcPort 1 + DstBlock " Terminator " + DstPort 1 + } + Line { + ZOrder 10 + SrcBlock " SFunction " + SrcPort 1 + DstBlock " Demux " + DstPort 1 + } + } + } + Block { + BlockType Outport + Name "JGD" + SID "334" + Position [160, 43, 190, 57] + ZOrder 89 + IconDisplay "Port number" + } + Line { + ZOrder 1 + SrcBlock "atlas5_arm_jacobigD" + SrcPort 1 + DstBlock "JGD" + DstPort 1 + } + Line { + ZOrder 2 + SrcBlock "qD" + SrcPort 1 + DstBlock "atlas5_arm_jacobigD" + DstPort 2 + } + Line { + ZOrder 3 + SrcBlock "q" + SrcPort 1 + DstBlock "atlas5_arm_jacobigD" + DstPort 1 + } + } + } + } +} +#Finite State Machines +# +# Stateflow 80000001 +# +# +Stateflow { + machine { + id 1 + name "atlas_dynamic_library" + created "20-Oct-2014 14:12:52" + isLibrary 1 + firstTarget 451 + sfVersion 80000001 + } + chart { + id 2 + name "atlas3_arm_fordyn_rj_damping/mFcn_Minv" + windowPosition [357.331 483.407 167 391] + viewLimits [0 156.75 0 153.75] + screen [1 1 1280 1024 1.041050272174191] + treeNode [0 3 0 0] + firstTransition 8 + firstJunction 7 + viewObj 2 + machine 1 + toolbarMode LIBRARY_TOOLBAR + ssIdHighWaterMark 6 + decomposition CLUSTER_CHART + type EML_CHART + firstData 4 + chartFileNumber 1 + disableImplicitCasting 1 + eml { + name "fcn" + } + } + state { + id 3 + labelString "eML_blk_kernel()" + position [18 64.5 118 66] + fontSize 12 + chart 2 + treeNode [2 0 0 0] + superState SUBCHART + subviewer 2 + ssIdNumber 1 + type FUNC_STATE + decomposition CLUSTER_STATE + eml { + isEML 1 + script "function q_ddot = fcn(M,tau)\n%#codegen\nq_ddot=M\\tau;" + editorLayout "100 M4x1[10 5 700 500]" + } + } + data { + id 4 + ssIdNumber 4 + name "M" + linkNode [2 0 5] + scope INPUT_DATA + machine 1 + props { + array { + size "-1" + } + type { + method SF_INHERITED_TYPE + primitive SF_DOUBLE_TYPE + } + complexity SF_COMPLEX_INHERITED + } + dataType "Inherit: Same as Simulink" + } + data { + id 5 + ssIdNumber 5 + name "q_ddot" + linkNode [2 4 6] + scope OUTPUT_DATA + machine 1 + props { + array { + size "-1" + } + type { + method SF_INHERITED_TYPE + primitive SF_DOUBLE_TYPE + } + complexity SF_COMPLEX_INHERITED + frame SF_FRAME_NO + } + dataType "Inherit: Same as Simulink" + } + data { + id 6 + ssIdNumber 6 + name "tau" + linkNode [2 5 0] + scope INPUT_DATA + machine 1 + props { + array { + size "-1" + } + type { + method SF_INHERITED_TYPE + primitive SF_DOUBLE_TYPE + isSigned 1 + wordLength "16" + } + complexity SF_COMPLEX_INHERITED + frame SF_FRAME_INHERITED + } + dataType "Inherit: Same as Simulink" + } + junction { + id 7 + position [23.5747 49.5747 7] + chart 2 + linkNode [2 0 0] + subviewer 2 + ssIdNumber 3 + type CONNECTIVE_JUNCTION + } + transition { + id 8 + labelString "{eML_blk_kernel();}" + labelPosition [32.125 19.875 102.544 14.964] + fontSize 12 + src { + intersection [0 0 1 0 23.5747 14.625 0 0] + } + dst { + id 7 + intersection [1 0 -1 0 23.5747 42.5747 0 0] + } + midPoint [23.5747 24.9468] + chart 2 + linkNode [2 0 0] + dataLimits [21.175 25.975 14.625 42.575] + subviewer 2 + drawStyle SMART + slide { + sticky BOTH_STICK + } + executionOrder 1 + ssIdNumber 2 + } + instance { + id 9 + name "atlas3_arm_fordyn_rj_damping/mFcn_Minv" + machine 1 + chart 2 + } + chart { + id 10 + name "atlas4_arm_inertia/mFcn_M" + windowPosition [357.331 483.407 167 391] + viewLimits [0 156.75 0 153.75] + screen [1 1 1280 1024 1.041050272174191] + treeNode [0 11 0 0] + firstTransition 16 + firstJunction 15 + viewObj 10 + machine 1 + toolbarMode LIBRARY_TOOLBAR + ssIdHighWaterMark 8 + decomposition CLUSTER_CHART + type EML_CHART + firstData 12 + chartFileNumber 2 + disableImplicitCasting 1 + eml { + name "fcn" + } + } + state { + id 11 + labelString "eML_blk_kernel()" + position [18 64.5 118 66] + fontSize 12 + chart 10 + treeNode [10 0 0 0] + superState SUBCHART + subviewer 10 + ssIdNumber 1 + type FUNC_STATE + decomposition CLUSTER_STATE + eml { + isEML 1 + script "function M = fcn(q, atlas_arm_lr)\n%#codegen\nM = atlas4_arm_inertia(q', atlas_arm_lr);" + editorLayout "100 M4x1[10 5 700 500]" + } + } + data { + id 12 + ssIdNumber 4 + name "q" + linkNode [10 0 13] + scope INPUT_DATA + machine 1 + props { + array { + size "-1" + } + type { + method SF_INHERITED_TYPE + primitive SF_DOUBLE_TYPE + } + complexity SF_COMPLEX_INHERITED + } + dataType "Inherit: Same as Simulink" + } + data { + id 13 + ssIdNumber 5 + name "M" + linkNode [10 12 14] + scope OUTPUT_DATA + machine 1 + props { + array { + size "-1" + } + type { + method SF_INHERITED_TYPE + primitive SF_DOUBLE_TYPE + } + complexity SF_COMPLEX_INHERITED + frame SF_FRAME_NO + } + dataType "Inherit: Same as Simulink" + } + data { + id 14 + ssIdNumber 7 + name "atlas_arm_lr" + linkNode [10 13 0] + scope PARAMETER_DATA + machine 1 + props { + array { + size "-1" + } + type { + method SF_INHERITED_TYPE + primitive SF_DOUBLE_TYPE + isSigned 1 + wordLength "16" + } + complexity SF_COMPLEX_INHERITED + frame SF_FRAME_INHERITED + } + dataType "Inherit: Same as Simulink" + } + junction { + id 15 + position [23.5747 49.5747 7] + chart 10 + linkNode [10 0 0] + subviewer 10 + ssIdNumber 3 + type CONNECTIVE_JUNCTION + } + transition { + id 16 + labelString "{eML_blk_kernel();}" + labelPosition [32.125 19.875 102.544 14.964] + fontSize 12 + src { + intersection [0 0 1 0 23.5747 14.625 0 0] + } + dst { + id 15 + intersection [1 0 -1 0 23.5747 42.5747 0 0] + } + midPoint [23.5747 24.9468] + chart 10 + linkNode [10 0 0] + dataLimits [21.175 25.975 14.625 42.575] + subviewer 10 + drawStyle SMART + slide { + sticky BOTH_STICK + } + executionOrder 1 + ssIdNumber 2 + } + instance { + id 17 + name "atlas4_arm_inertia/mFcn_M" + machine 1 + chart 10 + } + chart { + id 18 + name "atlas4_arm_coriolis_vec/mFcn_c" + windowPosition [357.331 483.407 167 391] + viewLimits [0 156.75 0 153.75] + screen [1 1 1280 1024 1.041050272174191] + treeNode [0 19 0 0] + firstTransition 25 + firstJunction 24 + viewObj 18 + machine 1 + toolbarMode LIBRARY_TOOLBAR + ssIdHighWaterMark 8 + decomposition CLUSTER_CHART + type EML_CHART + firstData 20 + chartFileNumber 3 + disableImplicitCasting 1 + eml { + name "fcn" + } + } + state { + id 19 + labelString "eML_blk_kernel()" + position [18 64.5 118 66] + fontSize 12 + chart 18 + treeNode [18 0 0 0] + superState SUBCHART + subviewer 18 + ssIdNumber 1 + type FUNC_STATE + decomposition CLUSTER_STATE + eml { + isEML 1 + script "function tau_c = fcn(q,qD, atlas_arm_lr)\n%#codegen\n\ntau_c=atlas4_arm_coriolisvec_fb(q', qD', a" + "tlas_arm_lr)';\n" + editorLayout "100 M4x1[10 5 700 500]" + } + } + data { + id 20 + ssIdNumber 4 + name "q" + linkNode [18 0 21] + scope INPUT_DATA + machine 1 + props { + array { + size "-1" + } + type { + method SF_INHERITED_TYPE + primitive SF_DOUBLE_TYPE + } + complexity SF_COMPLEX_INHERITED + } + dataType "Inherit: Same as Simulink" + } + data { + id 21 + ssIdNumber 6 + name "qD" + linkNode [18 20 22] + scope INPUT_DATA + machine 1 + props { + array { + size "-1" + } + type { + method SF_INHERITED_TYPE + primitive SF_DOUBLE_TYPE + isSigned 1 + wordLength "16" + } + complexity SF_COMPLEX_INHERITED + frame SF_FRAME_INHERITED + } + dataType "Inherit: Same as Simulink" + } + data { + id 22 + ssIdNumber 8 + name "atlas_arm_lr" + linkNode [18 21 23] + scope PARAMETER_DATA + machine 1 + props { + array { + size "-1" + } + type { + method SF_INHERITED_TYPE + primitive SF_DOUBLE_TYPE + isSigned 1 + wordLength "16" + } + complexity SF_COMPLEX_INHERITED + frame SF_FRAME_INHERITED + } + dataType "Inherit: Same as Simulink" + } + data { + id 23 + ssIdNumber 5 + name "tau_c" + linkNode [18 22 0] + scope OUTPUT_DATA + paramIndexForInitFromWorkspace 1 + machine 1 + props { + array { + size "-1" + } + type { + method SF_INHERITED_TYPE + primitive SF_DOUBLE_TYPE + } + complexity SF_COMPLEX_INHERITED + frame SF_FRAME_NO + } + dataType "Inherit: Same as Simulink" + } + junction { + id 24 + position [23.5747 49.5747 7] + chart 18 + linkNode [18 0 0] + subviewer 18 + ssIdNumber 3 + type CONNECTIVE_JUNCTION + } + transition { + id 25 + labelString "{eML_blk_kernel();}" + labelPosition [32.125 19.875 102.544 14.964] + fontSize 12 + src { + intersection [0 0 1 0 23.5747 14.625 0 0] + } + dst { + id 24 + intersection [1 0 -1 0 23.5747 42.5747 0 0] + } + midPoint [23.5747 24.9468] + chart 18 + linkNode [18 0 0] + dataLimits [21.175 25.975 14.625 42.575] + subviewer 18 + drawStyle SMART + slide { + sticky BOTH_STICK + } + executionOrder 1 + ssIdNumber 2 + } + instance { + id 26 + name "atlas4_arm_coriolis_vec/mFcn_c" + machine 1 + chart 18 + } + chart { + id 27 + name "atlas4_arm_gravload/mFcn_g" + windowPosition [357.331 483.407 167 391] + viewLimits [0 156.75 0 153.75] + screen [1 1 1280 1024 1.041050272174191] + treeNode [0 28 0 0] + firstTransition 34 + firstJunction 33 + viewObj 27 + machine 1 + toolbarMode LIBRARY_TOOLBAR + ssIdHighWaterMark 9 + decomposition CLUSTER_CHART + type EML_CHART + firstData 29 + chartFileNumber 4 + disableImplicitCasting 1 + eml { + name "fcn" + } + } + state { + id 28 + labelString "eML_blk_kernel()" + position [18 64.5 118 66] + fontSize 12 + chart 27 + treeNode [27 0 0 0] + superState SUBCHART + subviewer 27 + ssIdNumber 1 + type FUNC_STATE + decomposition CLUSTER_STATE + eml { + isEML 1 + script "function tau_g = fcn(q, g, atlas_arm_lr)\n%#codegen\n\ntau_g = atlas4_arm_gravload(q', g', atlas_" + "arm_lr)';" + editorLayout "100 M4x1[10 5 700 500]" + } + } + data { + id 29 + ssIdNumber 4 + name "q" + linkNode [27 0 30] + scope INPUT_DATA + machine 1 + props { + array { + size "-1" + } + type { + method SF_INHERITED_TYPE + primitive SF_DOUBLE_TYPE + } + complexity SF_COMPLEX_INHERITED + } + dataType "Inherit: Same as Simulink" + } + data { + id 30 + ssIdNumber 9 + name "g" + linkNode [27 29 31] + scope INPUT_DATA + machine 1 + props { + array { + size "-1" + } + type { + method SF_INHERITED_TYPE + primitive SF_DOUBLE_TYPE + isSigned 1 + wordLength "16" + } + complexity SF_COMPLEX_INHERITED + frame SF_FRAME_INHERITED + } + dataType "Inherit: Same as Simulink" + } + data { + id 31 + ssIdNumber 8 + name "atlas_arm_lr" + linkNode [27 30 32] + scope PARAMETER_DATA + machine 1 + props { + array { + size "-1" + } + type { + method SF_INHERITED_TYPE + primitive SF_DOUBLE_TYPE + isSigned 1 + wordLength "16" + } + complexity SF_COMPLEX_INHERITED + frame SF_FRAME_INHERITED + } + dataType "Inherit: Same as Simulink" + } + data { + id 32 + ssIdNumber 5 + name "tau_g" + linkNode [27 31 0] + scope OUTPUT_DATA + machine 1 + props { + array { + size "-1" + } + type { + method SF_INHERITED_TYPE + primitive SF_DOUBLE_TYPE + } + complexity SF_COMPLEX_INHERITED + frame SF_FRAME_NO + } + dataType "Inherit: Same as Simulink" + } + junction { + id 33 + position [23.5747 49.5747 7] + chart 27 + linkNode [27 0 0] + subviewer 27 + ssIdNumber 3 + type CONNECTIVE_JUNCTION + } + transition { + id 34 + labelString "{eML_blk_kernel();}" + labelPosition [32.125 19.875 102.544 14.964] + fontSize 12 + src { + intersection [0 0 1 0 23.5747 14.625 0 0] + } + dst { + id 33 + intersection [1 0 -1 0 23.5747 42.5747 0 0] + } + midPoint [23.5747 24.9468] + chart 27 + linkNode [27 0 0] + dataLimits [21.175 25.975 14.625 42.575] + subviewer 27 + drawStyle SMART + slide { + sticky BOTH_STICK + } + executionOrder 1 + ssIdNumber 2 + } + instance { + id 35 + name "atlas4_arm_gravload/mFcn_g" + machine 1 + chart 27 + } + chart { + id 36 + name "atlsa3_arm_jacobigD/atlas3_arm_jacobigD" + windowPosition [357.331 483.407 167 391] + viewLimits [0 156.75 0 153.75] + screen [1 1 1280 1024 1.041050272174191] + treeNode [0 37 0 0] + firstTransition 43 + firstJunction 42 + viewObj 36 + machine 1 + toolbarMode LIBRARY_TOOLBAR + ssIdHighWaterMark 10 + decomposition CLUSTER_CHART + type EML_CHART + firstData 38 + chartFileNumber 5 + disableImplicitCasting 1 + eml { + name "fcn" + } + } + state { + id 37 + labelString "eML_blk_kernel()" + position [18 64.5 118 66] + fontSize 12 + chart 36 + treeNode [36 0 0 0] + superState SUBCHART + subviewer 36 + ssIdNumber 1 + type FUNC_STATE + decomposition CLUSTER_STATE + eml { + isEML 1 + script "function JGD = fcn(q, qD, atlas_arm_lr)\n%#codegen\n\nJGD = atlas3_arm_jacobigD(q', qD', atlas_ar" + "m_lr);\n" + editorLayout "100 M4x1[10 5 700 500]" + } + } + data { + id 38 + ssIdNumber 4 + name "q" + linkNode [36 0 39] + scope INPUT_DATA + machine 1 + props { + array { + size "-1" + } + type { + method SF_INHERITED_TYPE + primitive SF_DOUBLE_TYPE + } + complexity SF_COMPLEX_INHERITED + } + dataType "Inherit: Same as Simulink" + } + data { + id 39 + ssIdNumber 6 + name "qD" + linkNode [36 38 40] + scope INPUT_DATA + machine 1 + props { + array { + size "-1" + } + type { + method SF_INHERITED_TYPE + primitive SF_DOUBLE_TYPE + isSigned 1 + wordLength "16" + } + complexity SF_COMPLEX_INHERITED + frame SF_FRAME_INHERITED + } + dataType "Inherit: Same as Simulink" + } + data { + id 40 + ssIdNumber 5 + name "JGD" + linkNode [36 39 41] + scope OUTPUT_DATA + machine 1 + props { + array { + size "-1" + } + type { + method SF_INHERITED_TYPE + primitive SF_DOUBLE_TYPE + } + complexity SF_COMPLEX_INHERITED + frame SF_FRAME_NO + } + dataType "Inherit: Same as Simulink" + } + data { + id 41 + ssIdNumber 9 + name "atlas_arm_lr" + linkNode [36 40 0] + scope PARAMETER_DATA + machine 1 + props { + array { + size "-1" + } + type { + method SF_INHERITED_TYPE + primitive SF_DOUBLE_TYPE + isSigned 1 + wordLength "16" + } + complexity SF_COMPLEX_INHERITED + frame SF_FRAME_INHERITED + } + dataType "Inherit: Same as Simulink" + } + junction { + id 42 + position [23.5747 49.5747 7] + chart 36 + linkNode [36 0 0] + subviewer 36 + ssIdNumber 3 + type CONNECTIVE_JUNCTION + } + transition { + id 43 + labelString "{eML_blk_kernel();}" + labelPosition [32.125 19.875 102.544 14.964] + fontSize 12 + src { + intersection [0 0 1 0 23.5747 14.625 0 0] + } + dst { + id 42 + intersection [1 0 -1 0 23.5747 42.5747 0 0] + } + midPoint [23.5747 24.9468] + chart 36 + linkNode [36 0 0] + dataLimits [21.175 25.975 14.625 42.575] + subviewer 36 + drawStyle SMART + slide { + sticky BOTH_STICK + } + executionOrder 1 + ssIdNumber 2 + } + instance { + id 44 + name "atlsa3_arm_jacobigD/atlas3_arm_jacobigD" + machine 1 + chart 36 + } + chart { + id 45 + name "atlas3_arm_energy/atlas3_arm_energy_fb" + windowPosition [357.331 483.407 167 391] + viewLimits [0 156.75 0 153.75] + screen [1 1 1280 1024 1.041050272174191] + treeNode [0 46 0 0] + firstTransition 53 + firstJunction 52 + viewObj 45 + machine 1 + toolbarMode LIBRARY_TOOLBAR + ssIdHighWaterMark 10 + decomposition CLUSTER_CHART + type EML_CHART + firstData 47 + chartFileNumber 6 + disableImplicitCasting 1 + eml { + name "fcn" + } + } + state { + id 46 + labelString "eML_blk_kernel()" + position [18 64.5 118 66] + fontSize 12 + chart 45 + treeNode [45 0 0 0] + superState SUBCHART + subviewer 45 + ssIdNumber 1 + type FUNC_STATE + decomposition CLUSTER_STATE + eml { + isEML 1 + script "function [T, U] = fcn(q, qD, atlas_arm_lr)\n%#codegen\n\nT = atlas3_arm_energy_kinetic_fb_sym_lag" + "(q', qD', atlas_arm_lr);\n\nU = atlas3_arm_energy_potential_sym_lag(q', [0,0,-9.81], atlas_arm_lr);" + editorLayout "100 M4x1[10 5 700 500]" + } + } + data { + id 47 + ssIdNumber 4 + name "q" + linkNode [45 0 48] + scope INPUT_DATA + machine 1 + props { + array { + size "-1" + } + type { + method SF_INHERITED_TYPE + primitive SF_DOUBLE_TYPE + } + complexity SF_COMPLEX_INHERITED + } + dataType "Inherit: Same as Simulink" + } + data { + id 48 + ssIdNumber 6 + name "qD" + linkNode [45 47 49] + scope INPUT_DATA + machine 1 + props { + array { + size "-1" + } + type { + method SF_INHERITED_TYPE + primitive SF_DOUBLE_TYPE + isSigned 1 + wordLength "16" + } + complexity SF_COMPLEX_INHERITED + frame SF_FRAME_INHERITED + } + dataType "Inherit: Same as Simulink" + } + data { + id 49 + ssIdNumber 5 + name "T" + linkNode [45 48 50] + scope OUTPUT_DATA + machine 1 + props { + array { + size "-1" + } + type { + method SF_INHERITED_TYPE + primitive SF_DOUBLE_TYPE + } + complexity SF_COMPLEX_INHERITED + frame SF_FRAME_NO + } + dataType "Inherit: Same as Simulink" + } + data { + id 50 + ssIdNumber 7 + name "U" + linkNode [45 49 51] + scope OUTPUT_DATA + machine 1 + props { + array { + size "-1" + } + type { + method SF_INHERITED_TYPE + primitive SF_DOUBLE_TYPE + isSigned 1 + wordLength "16" + } + complexity SF_COMPLEX_INHERITED + frame SF_FRAME_NO + } + dataType "Inherit: Same as Simulink" + } + data { + id 51 + ssIdNumber 9 + name "atlas_arm_lr" + linkNode [45 50 0] + scope PARAMETER_DATA + machine 1 + props { + array { + size "-1" + } + type { + method SF_INHERITED_TYPE + primitive SF_DOUBLE_TYPE + isSigned 1 + wordLength "16" + } + complexity SF_COMPLEX_INHERITED + frame SF_FRAME_INHERITED + } + dataType "Inherit: Same as Simulink" + } + junction { + id 52 + position [23.5747 49.5747 7] + chart 45 + linkNode [45 0 0] + subviewer 45 + ssIdNumber 3 + type CONNECTIVE_JUNCTION + } + transition { + id 53 + labelString "{eML_blk_kernel();}" + labelPosition [32.125 19.875 102.544 14.964] + fontSize 12 + src { + intersection [0 0 1 0 23.5747 14.625 0 0] + } + dst { + id 52 + intersection [1 0 -1 0 23.5747 42.5747 0 0] + } + midPoint [23.5747 24.9468] + chart 45 + linkNode [45 0 0] + dataLimits [21.175 25.975 14.625 42.575] + subviewer 45 + drawStyle SMART + slide { + sticky BOTH_STICK + } + executionOrder 1 + ssIdNumber 2 + } + instance { + id 54 + name "atlas3_arm_energy/atlas3_arm_energy_fb" + machine 1 + chart 45 + } + chart { + id 55 + name "atlas3_arm_jacobig/atlas3_arm_jacobig" + windowPosition [357.331 483.407 167 391] + viewLimits [0 156.75 0 153.75] + screen [1 1 1280 1024 1.041050272174191] + treeNode [0 56 0 0] + firstTransition 61 + firstJunction 60 + viewObj 55 + machine 1 + toolbarMode LIBRARY_TOOLBAR + ssIdHighWaterMark 10 + decomposition CLUSTER_CHART + type EML_CHART + firstData 57 + chartFileNumber 7 + disableImplicitCasting 1 + eml { + name "fcn" + } + } + state { + id 56 + labelString "eML_blk_kernel()" + position [18 64.5 118 66] + fontSize 12 + chart 55 + treeNode [55 0 0 0] + superState SUBCHART + subviewer 55 + ssIdNumber 1 + type FUNC_STATE + decomposition CLUSTER_STATE + eml { + isEML 1 + script "function JG = fcn(q, atlas_arm_lr)\n%#codegen\n\nJG = atlas3_arm_jacobig(q', atlas_arm_lr);\n" + editorLayout "100 M4x1[10 5 700 500]" + } + } + data { + id 57 + ssIdNumber 4 + name "q" + linkNode [55 0 58] + scope INPUT_DATA + machine 1 + props { + array { + size "-1" + } + type { + method SF_INHERITED_TYPE + primitive SF_DOUBLE_TYPE + } + complexity SF_COMPLEX_INHERITED + } + dataType "Inherit: Same as Simulink" + } + data { + id 58 + ssIdNumber 5 + name "JG" + linkNode [55 57 59] + scope OUTPUT_DATA + machine 1 + props { + array { + size "-1" + } + type { + method SF_INHERITED_TYPE + primitive SF_DOUBLE_TYPE + } + complexity SF_COMPLEX_INHERITED + frame SF_FRAME_NO + } + dataType "Inherit: Same as Simulink" + } + data { + id 59 + ssIdNumber 9 + name "atlas_arm_lr" + linkNode [55 58 0] + scope PARAMETER_DATA + machine 1 + props { + array { + size "-1" + } + type { + method SF_INHERITED_TYPE + primitive SF_DOUBLE_TYPE + isSigned 1 + wordLength "16" + } + complexity SF_COMPLEX_INHERITED + frame SF_FRAME_INHERITED + } + dataType "Inherit: Same as Simulink" + } + junction { + id 60 + position [23.5747 49.5747 7] + chart 55 + linkNode [55 0 0] + subviewer 55 + ssIdNumber 3 + type CONNECTIVE_JUNCTION + } + transition { + id 61 + labelString "{eML_blk_kernel();}" + labelPosition [32.125 19.875 102.544 14.964] + fontSize 12 + src { + intersection [0 0 1 0 23.5747 14.625 0 0] + } + dst { + id 60 + intersection [1 0 -1 0 23.5747 42.5747 0 0] + } + midPoint [23.5747 24.9468] + chart 55 + linkNode [55 0 0] + dataLimits [21.175 25.975 14.625 42.575] + subviewer 55 + drawStyle SMART + slide { + sticky BOTH_STICK + } + executionOrder 1 + ssIdNumber 2 + } + instance { + id 62 + name "atlas3_arm_jacobig/atlas3_arm_jacobig" + machine 1 + chart 55 + } + chart { + id 63 + name "atlas_arm_inertia/mFcn_M" + windowPosition [357.331 483.407 167 391] + viewLimits [0 156.75 0 153.75] + screen [1 1 1280 1024 1.041050272174191] + treeNode [0 64 0 0] + firstTransition 70 + firstJunction 69 + viewObj 63 + machine 1 + toolbarMode LIBRARY_TOOLBAR + ssIdHighWaterMark 9 + decomposition CLUSTER_CHART + type EML_CHART + firstData 65 + chartFileNumber 8 + disableImplicitCasting 1 + eml { + name "fcn" + } + } + state { + id 64 + labelString "eML_blk_kernel()" + position [18 64.5 118 66] + fontSize 12 + chart 63 + treeNode [63 0 0 0] + superState SUBCHART + subviewer 63 + ssIdNumber 1 + type FUNC_STATE + decomposition CLUSTER_STATE + eml { + isEML 1 + script "function M = fcn(q, atlas_arm_lr, atlas_version)\n%#codegen\nM = atlas_arm_inertia(q', atlas_arm_" + "lr, atlas_version);" + editorLayout "100 M4x1[10 5 700 500]" + } + } + data { + id 65 + ssIdNumber 4 + name "q" + linkNode [63 0 66] + scope INPUT_DATA + machine 1 + props { + array { + size "-1" + } + type { + method SF_INHERITED_TYPE + primitive SF_DOUBLE_TYPE + } + complexity SF_COMPLEX_INHERITED + } + dataType "Inherit: Same as Simulink" + } + data { + id 66 + ssIdNumber 5 + name "M" + linkNode [63 65 67] + scope OUTPUT_DATA + machine 1 + props { + array { + size "-1" + } + type { + method SF_INHERITED_TYPE + primitive SF_DOUBLE_TYPE + } + complexity SF_COMPLEX_INHERITED + frame SF_FRAME_NO + } + dataType "Inherit: Same as Simulink" + } + data { + id 67 + ssIdNumber 7 + name "atlas_arm_lr" + linkNode [63 66 68] + scope PARAMETER_DATA + machine 1 + props { + array { + size "-1" + } + type { + method SF_INHERITED_TYPE + primitive SF_DOUBLE_TYPE + isSigned 1 + wordLength "16" + } + complexity SF_COMPLEX_INHERITED + frame SF_FRAME_INHERITED + } + dataType "Inherit: Same as Simulink" + } + data { + id 68 + ssIdNumber 9 + name "atlas_version" + linkNode [63 67 0] + scope PARAMETER_DATA + paramIndexForInitFromWorkspace 1 + machine 1 + props { + array { + size "-1" + } + type { + method SF_INHERITED_TYPE + primitive SF_DOUBLE_TYPE + isSigned 1 + wordLength "16" + } + complexity SF_COMPLEX_INHERITED + frame SF_FRAME_INHERITED + } + dataType "Inherit: Same as Simulink" + } + junction { + id 69 + position [23.5747 49.5747 7] + chart 63 + linkNode [63 0 0] + subviewer 63 + ssIdNumber 3 + type CONNECTIVE_JUNCTION + } + transition { + id 70 + labelString "{eML_blk_kernel();}" + labelPosition [32.125 19.875 102.544 14.964] + fontSize 12 + src { + intersection [0 0 1 0 23.5747 14.625 0 0] + } + dst { + id 69 + intersection [1 0 -1 0 23.5747 42.5747 0 0] + } + midPoint [23.5747 24.9468] + chart 63 + linkNode [63 0 0] + dataLimits [21.175 25.975 14.625 42.575] + subviewer 63 + drawStyle SMART + slide { + sticky BOTH_STICK + } + executionOrder 1 + ssIdNumber 2 + } + instance { + id 71 + name "atlas_arm_inertia/mFcn_M" + machine 1 + chart 63 + } + chart { + id 72 + name "atlas4_arm_fordyn_rj_damping/mFcn_Minv" + windowPosition [357.331 483.407 167 391] + viewLimits [0 156.75 0 153.75] + screen [1 1 1280 1024 1.041050272174191] + treeNode [0 73 0 0] + firstTransition 78 + firstJunction 77 + viewObj 72 + machine 1 + toolbarMode LIBRARY_TOOLBAR + ssIdHighWaterMark 6 + decomposition CLUSTER_CHART + type EML_CHART + firstData 74 + chartFileNumber 9 + disableImplicitCasting 1 + eml { + name "fcn" + } + } + state { + id 73 + labelString "eML_blk_kernel()" + position [18 64.5 118 66] + fontSize 12 + chart 72 + treeNode [72 0 0 0] + superState SUBCHART + subviewer 72 + ssIdNumber 1 + type FUNC_STATE + decomposition CLUSTER_STATE + eml { + isEML 1 + script "function q_ddot = fcn(M,tau)\n%#codegen\nq_ddot=M\\tau;" + editorLayout "100 M4x1[10 5 700 500]" + } + } + data { + id 74 + ssIdNumber 4 + name "M" + linkNode [72 0 75] + scope INPUT_DATA + machine 1 + props { + array { + size "-1" + } + type { + method SF_INHERITED_TYPE + primitive SF_DOUBLE_TYPE + } + complexity SF_COMPLEX_INHERITED + } + dataType "Inherit: Same as Simulink" + } + data { + id 75 + ssIdNumber 5 + name "q_ddot" + linkNode [72 74 76] + scope OUTPUT_DATA + machine 1 + props { + array { + size "-1" + } + type { + method SF_INHERITED_TYPE + primitive SF_DOUBLE_TYPE + } + complexity SF_COMPLEX_INHERITED + frame SF_FRAME_NO + } + dataType "Inherit: Same as Simulink" + } + data { + id 76 + ssIdNumber 6 + name "tau" + linkNode [72 75 0] + scope INPUT_DATA + machine 1 + props { + array { + size "-1" + } + type { + method SF_INHERITED_TYPE + primitive SF_DOUBLE_TYPE + isSigned 1 + wordLength "16" + } + complexity SF_COMPLEX_INHERITED + frame SF_FRAME_INHERITED + } + dataType "Inherit: Same as Simulink" + } + junction { + id 77 + position [23.5747 49.5747 7] + chart 72 + linkNode [72 0 0] + subviewer 72 + ssIdNumber 3 + type CONNECTIVE_JUNCTION + } + transition { + id 78 + labelString "{eML_blk_kernel();}" + labelPosition [32.125 19.875 102.544 14.964] + fontSize 12 + src { + intersection [0 0 1 0 23.5747 14.625 0 0] + } + dst { + id 77 + intersection [1 0 -1 0 23.5747 42.5747 0 0] + } + midPoint [23.5747 24.9468] + chart 72 + linkNode [72 0 0] + dataLimits [21.175 25.975 14.625 42.575] + subviewer 72 + drawStyle SMART + slide { + sticky BOTH_STICK + } + executionOrder 1 + ssIdNumber 2 + } + instance { + id 79 + name "atlas4_arm_fordyn_rj_damping/mFcn_Minv" + machine 1 + chart 72 + } + chart { + id 80 + name "atlas_arm_coriolis_vec/mFcn_c" + windowPosition [357.331 483.407 167 391] + viewLimits [0 156.75 0 153.75] + screen [1 1 1280 1024 1.041050272174191] + treeNode [0 81 0 0] + firstTransition 88 + firstJunction 87 + viewObj 80 + machine 1 + ssIdHighWaterMark 9 + decomposition CLUSTER_CHART + type EML_CHART + firstData 82 + chartFileNumber 10 + disableImplicitCasting 1 + eml { + name "fcn" + } + } + state { + id 81 + labelString "eML_blk_kernel()" + position [18 64.5 118 66] + fontSize 12 + chart 80 + treeNode [80 0 0 0] + superState SUBCHART + subviewer 80 + ssIdNumber 1 + type FUNC_STATE + decomposition CLUSTER_STATE + eml { + isEML 1 + script "function tau_c = fcn(q,qD, atlas_arm_lr, atlas_version)\n%#codegen\n\ntau_c=atlas_arm_coriolisvec" + "_fb(q', qD', atlas_arm_lr, atlas_version)';\n" + editorLayout "100 M4x1[10 5 700 500]" + } + } + data { + id 82 + ssIdNumber 4 + name "q" + linkNode [80 0 83] + scope INPUT_DATA + machine 1 + props { + array { + size "-1" + } + type { + method SF_INHERITED_TYPE + primitive SF_DOUBLE_TYPE + } + complexity SF_COMPLEX_INHERITED + } + dataType "Inherit: Same as Simulink" + } + data { + id 83 + ssIdNumber 6 + name "qD" + linkNode [80 82 84] + scope INPUT_DATA + machine 1 + props { + array { + size "-1" + } + type { + method SF_INHERITED_TYPE + primitive SF_DOUBLE_TYPE + isSigned 1 + wordLength "16" + } + complexity SF_COMPLEX_INHERITED + frame SF_FRAME_INHERITED + } + dataType "Inherit: Same as Simulink" + } + data { + id 84 + ssIdNumber 8 + name "atlas_arm_lr" + linkNode [80 83 85] + scope PARAMETER_DATA + machine 1 + props { + array { + size "-1" + } + type { + method SF_INHERITED_TYPE + primitive SF_DOUBLE_TYPE + isSigned 1 + wordLength "16" + } + complexity SF_COMPLEX_INHERITED + frame SF_FRAME_INHERITED + } + dataType "Inherit: Same as Simulink" + } + data { + id 85 + ssIdNumber 5 + name "tau_c" + linkNode [80 84 86] + scope OUTPUT_DATA + paramIndexForInitFromWorkspace 1 + machine 1 + props { + array { + size "-1" + } + type { + method SF_INHERITED_TYPE + primitive SF_DOUBLE_TYPE + } + complexity SF_COMPLEX_INHERITED + frame SF_FRAME_NO + } + dataType "Inherit: Same as Simulink" + } + data { + id 86 + ssIdNumber 9 + name "atlas_version" + linkNode [80 85 0] + scope PARAMETER_DATA + paramIndexForInitFromWorkspace 1 + machine 1 + props { + array { + size "-1" + } + type { + method SF_INHERITED_TYPE + primitive SF_DOUBLE_TYPE + isSigned 1 + wordLength "16" + } + complexity SF_COMPLEX_INHERITED + frame SF_FRAME_INHERITED + } + dataType "Inherit: Same as Simulink" + } + junction { + id 87 + position [23.5747 49.5747 7] + chart 80 + linkNode [80 0 0] + subviewer 80 + ssIdNumber 3 + type CONNECTIVE_JUNCTION + } + transition { + id 88 + labelString "{eML_blk_kernel();}" + labelPosition [32.125 19.875 102.544 14.964] + fontSize 12 + src { + intersection [0 0 1 0 23.5747 14.625 0 0] + } + dst { + id 87 + intersection [1 0 -1 0 23.5747 42.5747 0 0] + } + midPoint [23.5747 24.9468] + chart 80 + linkNode [80 0 0] + dataLimits [21.175 25.975 14.625 42.575] + subviewer 80 + drawStyle SMART + slide { + sticky BOTH_STICK + } + executionOrder 1 + ssIdNumber 2 + } + instance { + id 89 + name "atlas_arm_coriolis_vec/mFcn_c" + machine 1 + chart 80 + } + chart { + id 90 + name "atlas_arm_gravload/mFcn_g" + windowPosition [357.331 483.407 167 391] + viewLimits [0 156.75 0 153.75] + screen [1 1 1280 1024 1.041050272174191] + treeNode [0 91 0 0] + firstTransition 98 + firstJunction 97 + viewObj 90 + machine 1 + toolbarMode LIBRARY_TOOLBAR + ssIdHighWaterMark 10 + decomposition CLUSTER_CHART + type EML_CHART + firstData 92 + chartFileNumber 11 + disableImplicitCasting 1 + eml { + name "fcn" + } + } + state { + id 91 + labelString "eML_blk_kernel()" + position [18 64.5 118 66] + fontSize 12 + chart 90 + treeNode [90 0 0 0] + superState SUBCHART + subviewer 90 + ssIdNumber 1 + type FUNC_STATE + decomposition CLUSTER_STATE + eml { + isEML 1 + script "function tau_g = fcn(q, g, atlas_arm_lr, atlas_version)\n%#codegen\n\ntau_g = atlas_arm_gravload(" + "q', g', atlas_arm_lr, atlas_version)';" + editorLayout "100 M4x1[10 5 700 500]" + } + } + data { + id 92 + ssIdNumber 4 + name "q" + linkNode [90 0 93] + scope INPUT_DATA + machine 1 + props { + array { + size "-1" + } + type { + method SF_INHERITED_TYPE + primitive SF_DOUBLE_TYPE + } + complexity SF_COMPLEX_INHERITED + } + dataType "Inherit: Same as Simulink" + } + data { + id 93 + ssIdNumber 10 + name "g" + linkNode [90 92 94] + scope INPUT_DATA + machine 1 + props { + array { + size "-1" + } + type { + method SF_INHERITED_TYPE + primitive SF_DOUBLE_TYPE + isSigned 1 + wordLength "16" + } + complexity SF_COMPLEX_INHERITED + frame SF_FRAME_INHERITED + } + dataType "Inherit: Same as Simulink" + } + data { + id 94 + ssIdNumber 8 + name "atlas_arm_lr" + linkNode [90 93 95] + scope PARAMETER_DATA + machine 1 + props { + array { + size "-1" + } + type { + method SF_INHERITED_TYPE + primitive SF_DOUBLE_TYPE + isSigned 1 + wordLength "16" + } + complexity SF_COMPLEX_INHERITED + frame SF_FRAME_INHERITED + } + dataType "Inherit: Same as Simulink" + } + data { + id 95 + ssIdNumber 5 + name "tau_g" + linkNode [90 94 96] + scope OUTPUT_DATA + machine 1 + props { + array { + size "-1" + } + type { + method SF_INHERITED_TYPE + primitive SF_DOUBLE_TYPE + } + complexity SF_COMPLEX_INHERITED + frame SF_FRAME_NO + } + dataType "Inherit: Same as Simulink" + } + data { + id 96 + ssIdNumber 9 + name "atlas_version" + linkNode [90 95 0] + scope PARAMETER_DATA + paramIndexForInitFromWorkspace 1 + machine 1 + props { + array { + size "-1" + } + type { + method SF_INHERITED_TYPE + primitive SF_DOUBLE_TYPE + isSigned 1 + wordLength "16" + } + complexity SF_COMPLEX_INHERITED + frame SF_FRAME_INHERITED + } + dataType "Inherit: Same as Simulink" + } + junction { + id 97 + position [23.5747 49.5747 7] + chart 90 + linkNode [90 0 0] + subviewer 90 + ssIdNumber 3 + type CONNECTIVE_JUNCTION + } + transition { + id 98 + labelString "{eML_blk_kernel();}" + labelPosition [32.125 19.875 102.544 14.964] + fontSize 12 + src { + intersection [0 0 1 0 23.5747 14.625 0 0] + } + dst { + id 97 + intersection [1 0 -1 0 23.5747 42.5747 0 0] + } + midPoint [23.5747 24.9468] + chart 90 + linkNode [90 0 0] + dataLimits [21.175 25.975 14.625 42.575] + subviewer 90 + drawStyle SMART + slide { + sticky BOTH_STICK + } + executionOrder 1 + ssIdNumber 2 + } + instance { + id 99 + name "atlas_arm_gravload/mFcn_g" + machine 1 + chart 90 + } + chart { + id 100 + name "atlas_arm_gravload_minvarpar/mFcn_g" + windowPosition [357.331 483.407 167 391] + viewLimits [0 156.75 0 153.75] + screen [1 1 1280 1024 1.041050272174191] + treeNode [0 101 0 0] + firstTransition 109 + firstJunction 108 + viewObj 100 + machine 1 + toolbarMode LIBRARY_TOOLBAR + ssIdHighWaterMark 11 + decomposition CLUSTER_CHART + type EML_CHART + firstData 102 + chartFileNumber 12 + disableImplicitCasting 1 + eml { + name "fcn" + } + } + state { + id 101 + labelString "eML_blk_kernel()" + position [18 64.5 118 66] + fontSize 12 + chart 100 + treeNode [100 0 0 0] + superState SUBCHART + subviewer 100 + ssIdNumber 1 + type FUNC_STATE + decomposition CLUSTER_STATE + eml { + isEML 1 + script "function tau_g = fcn(q, g, MPV, atlas_arm_lr, atlas_version)\n%#codegen\n\ntau_g = atlas_arm_grav" + "load_plin_minpar_sym_lag_varpar( ...\n q', g', MPV, atlas_arm_lr, atlas_version)';" + editorLayout "100 M4x1[10 5 700 500]" + } + } + data { + id 102 + ssIdNumber 4 + name "q" + linkNode [100 0 103] + scope INPUT_DATA + machine 1 + props { + array { + size "-1" + } + type { + method SF_INHERITED_TYPE + primitive SF_DOUBLE_TYPE + } + complexity SF_COMPLEX_INHERITED + } + dataType "Inherit: Same as Simulink" + } + data { + id 103 + ssIdNumber 10 + name "g" + linkNode [100 102 104] + scope INPUT_DATA + machine 1 + props { + array { + size "-1" + } + type { + method SF_INHERITED_TYPE + primitive SF_DOUBLE_TYPE + isSigned 1 + wordLength "16" + } + complexity SF_COMPLEX_INHERITED + frame SF_FRAME_INHERITED + } + dataType "Inherit: Same as Simulink" + } + data { + id 104 + ssIdNumber 11 + name "MPV" + linkNode [100 103 105] + scope PARAMETER_DATA + machine 1 + props { + array { + size "-1" + } + type { + method SF_INHERITED_TYPE + primitive SF_DOUBLE_TYPE + isSigned 1 + wordLength "16" + } + complexity SF_COMPLEX_INHERITED + frame SF_FRAME_INHERITED + } + dataType "Inherit: Same as Simulink" + } + data { + id 105 + ssIdNumber 8 + name "atlas_arm_lr" + linkNode [100 104 106] + scope PARAMETER_DATA + paramIndexForInitFromWorkspace 1 + machine 1 + props { + array { + size "-1" + } + type { + method SF_INHERITED_TYPE + primitive SF_DOUBLE_TYPE + isSigned 1 + wordLength "16" + } + complexity SF_COMPLEX_INHERITED + frame SF_FRAME_INHERITED + } + dataType "Inherit: Same as Simulink" + } + data { + id 106 + ssIdNumber 5 + name "tau_g" + linkNode [100 105 107] + scope OUTPUT_DATA + machine 1 + props { + array { + size "-1" + } + type { + method SF_INHERITED_TYPE + primitive SF_DOUBLE_TYPE + } + complexity SF_COMPLEX_INHERITED + frame SF_FRAME_NO + } + dataType "Inherit: Same as Simulink" + } + data { + id 107 + ssIdNumber 9 + name "atlas_version" + linkNode [100 106 0] + scope PARAMETER_DATA + paramIndexForInitFromWorkspace 2 + machine 1 + props { + array { + size "-1" + } + type { + method SF_INHERITED_TYPE + primitive SF_DOUBLE_TYPE + isSigned 1 + wordLength "16" + } + complexity SF_COMPLEX_INHERITED + frame SF_FRAME_INHERITED + } + dataType "Inherit: Same as Simulink" + } + junction { + id 108 + position [23.5747 49.5747 7] + chart 100 + linkNode [100 0 0] + subviewer 100 + ssIdNumber 3 + type CONNECTIVE_JUNCTION + } + transition { + id 109 + labelString "{eML_blk_kernel();}" + labelPosition [32.125 19.875 102.544 14.964] + fontSize 12 + src { + intersection [0 0 1 0 23.5747 14.625 0 0] + } + dst { + id 108 + intersection [1 0 -1 0 23.5747 42.5747 0 0] + } + midPoint [23.5747 24.9468] + chart 100 + linkNode [100 0 0] + dataLimits [21.175 25.975 14.625 42.575] + subviewer 100 + drawStyle SMART + slide { + sticky BOTH_STICK + } + executionOrder 1 + ssIdNumber 2 + } + instance { + id 110 + name "atlas_arm_gravload_minvarpar/mFcn_g" + machine 1 + chart 100 + } + chart { + id 111 + name "atlas_arm_fordyn_rj_damping/mFcn_Minv" + windowPosition [357.331 483.407 167 391] + viewLimits [0 156.75 0 153.75] + screen [1 1 1280 1024 1.041050272174191] + treeNode [0 112 0 0] + firstTransition 117 + firstJunction 116 + viewObj 111 + machine 1 + toolbarMode LIBRARY_TOOLBAR + ssIdHighWaterMark 6 + decomposition CLUSTER_CHART + type EML_CHART + firstData 113 + chartFileNumber 13 + disableImplicitCasting 1 + eml { + name "fcn" + } + } + state { + id 112 + labelString "eML_blk_kernel()" + position [18 64.5 118 66] + fontSize 12 + chart 111 + treeNode [111 0 0 0] + superState SUBCHART + subviewer 111 + ssIdNumber 1 + type FUNC_STATE + decomposition CLUSTER_STATE + eml { + isEML 1 + script "function q_ddot = fcn(M,tau)\n%#codegen\nq_ddot=M\\tau;" + editorLayout "100 M4x1[10 5 700 500]" + } + } + data { + id 113 + ssIdNumber 4 + name "M" + linkNode [111 0 114] + scope INPUT_DATA + machine 1 + props { + array { + size "-1" + } + type { + method SF_INHERITED_TYPE + primitive SF_DOUBLE_TYPE + } + complexity SF_COMPLEX_INHERITED + } + dataType "Inherit: Same as Simulink" + } + data { + id 114 + ssIdNumber 5 + name "q_ddot" + linkNode [111 113 115] + scope OUTPUT_DATA + machine 1 + props { + array { + size "-1" + } + type { + method SF_INHERITED_TYPE + primitive SF_DOUBLE_TYPE + } + complexity SF_COMPLEX_INHERITED + frame SF_FRAME_NO + } + dataType "Inherit: Same as Simulink" + } + data { + id 115 + ssIdNumber 6 + name "tau" + linkNode [111 114 0] + scope INPUT_DATA + machine 1 + props { + array { + size "-1" + } + type { + method SF_INHERITED_TYPE + primitive SF_DOUBLE_TYPE + isSigned 1 + wordLength "16" + } + complexity SF_COMPLEX_INHERITED + frame SF_FRAME_INHERITED + } + dataType "Inherit: Same as Simulink" + } + junction { + id 116 + position [23.5747 49.5747 7] + chart 111 + linkNode [111 0 0] + subviewer 111 + ssIdNumber 3 + type CONNECTIVE_JUNCTION + } + transition { + id 117 + labelString "{eML_blk_kernel();}" + labelPosition [32.125 19.875 102.544 14.964] + fontSize 12 + src { + intersection [0 0 1 0 23.5747 14.625 0 0] + } + dst { + id 116 + intersection [1 0 -1 0 23.5747 42.5747 0 0] + } + midPoint [23.5747 24.9468] + chart 111 + linkNode [111 0 0] + dataLimits [21.175 25.975 14.625 42.575] + subviewer 111 + drawStyle SMART + slide { + sticky BOTH_STICK + } + executionOrder 1 + ssIdNumber 2 + } + instance { + id 118 + name "atlas_arm_fordyn_rj_damping/mFcn_Minv" + machine 1 + chart 111 + } + chart { + id 119 + name "atlas_arm_inertia_minvarpar/mFcn_M" + windowPosition [357.331 483.407 167 391] + viewLimits [0 156.75 0 153.75] + screen [1 1 1280 1024 1.041050272174191] + treeNode [0 120 0 0] + firstTransition 127 + firstJunction 126 + viewObj 119 + machine 1 + toolbarMode LIBRARY_TOOLBAR + ssIdHighWaterMark 10 + decomposition CLUSTER_CHART + type EML_CHART + firstData 121 + chartFileNumber 14 + disableImplicitCasting 1 + eml { + name "fcn" + } + } + state { + id 120 + labelString "eML_blk_kernel()" + position [18 64.5 118 66] + fontSize 12 + chart 119 + treeNode [119 0 0 0] + superState SUBCHART + subviewer 119 + ssIdNumber 1 + type FUNC_STATE + decomposition CLUSTER_STATE + eml { + isEML 1 + script "function M = fcn(q, MPV, atlas_arm_lr, atlas_version)\n%#codegen\nM = atlas_arm_inertia_plin_minp" + "ar_sym_lag_varpar(q', MPV, atlas_arm_lr, atlas_version);" + editorLayout "100 M4x1[10 5 700 500]" + } + } + data { + id 121 + ssIdNumber 4 + name "q" + linkNode [119 0 122] + scope INPUT_DATA + machine 1 + props { + array { + size "-1" + } + type { + method SF_INHERITED_TYPE + primitive SF_DOUBLE_TYPE + } + complexity SF_COMPLEX_INHERITED + } + dataType "Inherit: Same as Simulink" + } + data { + id 122 + ssIdNumber 10 + name "MPV" + linkNode [119 121 123] + scope PARAMETER_DATA + machine 1 + props { + array { + size "-1" + } + type { + method SF_INHERITED_TYPE + primitive SF_DOUBLE_TYPE + isSigned 1 + wordLength "16" + } + complexity SF_COMPLEX_INHERITED + frame SF_FRAME_INHERITED + } + dataType "Inherit: Same as Simulink" + } + data { + id 123 + ssIdNumber 5 + name "M" + linkNode [119 122 124] + scope OUTPUT_DATA + machine 1 + props { + array { + size "-1" + } + type { + method SF_INHERITED_TYPE + primitive SF_DOUBLE_TYPE + } + complexity SF_COMPLEX_INHERITED + frame SF_FRAME_NO + } + dataType "Inherit: Same as Simulink" + } + data { + id 124 + ssIdNumber 7 + name "atlas_arm_lr" + linkNode [119 123 125] + scope PARAMETER_DATA + paramIndexForInitFromWorkspace 1 + machine 1 + props { + array { + size "-1" + } + type { + method SF_INHERITED_TYPE + primitive SF_DOUBLE_TYPE + isSigned 1 + wordLength "16" + } + complexity SF_COMPLEX_INHERITED + frame SF_FRAME_INHERITED + } + dataType "Inherit: Same as Simulink" + } + data { + id 125 + ssIdNumber 9 + name "atlas_version" + linkNode [119 124 0] + scope PARAMETER_DATA + paramIndexForInitFromWorkspace 2 + machine 1 + props { + array { + size "-1" + } + type { + method SF_INHERITED_TYPE + primitive SF_DOUBLE_TYPE + isSigned 1 + wordLength "16" + } + complexity SF_COMPLEX_INHERITED + frame SF_FRAME_INHERITED + } + dataType "Inherit: Same as Simulink" + } + junction { + id 126 + position [23.5747 49.5747 7] + chart 119 + linkNode [119 0 0] + subviewer 119 + ssIdNumber 3 + type CONNECTIVE_JUNCTION + } + transition { + id 127 + labelString "{eML_blk_kernel();}" + labelPosition [32.125 19.875 102.544 14.964] + fontSize 12 + src { + intersection [0 0 1 0 23.5747 14.625 0 0] + } + dst { + id 126 + intersection [1 0 -1 0 23.5747 42.5747 0 0] + } + midPoint [23.5747 24.9468] + chart 119 + linkNode [119 0 0] + dataLimits [21.175 25.975 14.625 42.575] + subviewer 119 + drawStyle SMART + slide { + sticky BOTH_STICK + } + executionOrder 1 + ssIdNumber 2 + } + instance { + id 128 + name "atlas_arm_inertia_minvarpar/mFcn_M" + machine 1 + chart 119 + } + chart { + id 129 + name "atlas_arm_coriolis_vec_minvarpar/mFcn_c" + windowPosition [357.331 483.407 167 391] + viewLimits [0 156.75 0 153.75] + screen [1 1 1280 1024 1.041050272174191] + treeNode [0 130 0 0] + firstTransition 138 + firstJunction 137 + viewObj 129 + machine 1 + toolbarMode LIBRARY_TOOLBAR + ssIdHighWaterMark 10 + decomposition CLUSTER_CHART + type EML_CHART + firstData 131 + chartFileNumber 15 + disableImplicitCasting 1 + eml { + name "fcn" + } + } + state { + id 130 + labelString "eML_blk_kernel()" + position [18 64.5 118 66] + fontSize 12 + chart 129 + treeNode [129 0 0 0] + superState SUBCHART + subviewer 129 + ssIdNumber 1 + type FUNC_STATE + decomposition CLUSTER_STATE + eml { + isEML 1 + script "function tau_c = fcn(q,qD, MPV, atlas_arm_lr, atlas_version)\n%#codegen\n\ntau_c=atlas_arm_coriol" + "isvec_fb_plin_minpar_sym_lag_varpar(q', qD', MPV, atlas_arm_lr, atlas_version)';\n" + editorLayout "100 M4x1[10 5 700 500]" + } + } + data { + id 131 + ssIdNumber 4 + name "q" + linkNode [129 0 132] + scope INPUT_DATA + machine 1 + props { + array { + size "-1" + } + type { + method SF_INHERITED_TYPE + primitive SF_DOUBLE_TYPE + } + complexity SF_COMPLEX_INHERITED + } + dataType "Inherit: Same as Simulink" + } + data { + id 132 + ssIdNumber 6 + name "qD" + linkNode [129 131 133] + scope INPUT_DATA + machine 1 + props { + array { + size "-1" + } + type { + method SF_INHERITED_TYPE + primitive SF_DOUBLE_TYPE + isSigned 1 + wordLength "16" + } + complexity SF_COMPLEX_INHERITED + frame SF_FRAME_INHERITED + } + dataType "Inherit: Same as Simulink" + } + data { + id 133 + ssIdNumber 10 + name "MPV" + linkNode [129 132 134] + scope PARAMETER_DATA + machine 1 + props { + array { + size "-1" + } + type { + method SF_INHERITED_TYPE + primitive SF_DOUBLE_TYPE + isSigned 1 + wordLength "16" + } + complexity SF_COMPLEX_INHERITED + frame SF_FRAME_INHERITED + } + dataType "Inherit: Same as Simulink" + } + data { + id 134 + ssIdNumber 8 + name "atlas_arm_lr" + linkNode [129 133 135] + scope PARAMETER_DATA + paramIndexForInitFromWorkspace 1 + machine 1 + props { + array { + size "-1" + } + type { + method SF_INHERITED_TYPE + primitive SF_DOUBLE_TYPE + isSigned 1 + wordLength "16" + } + complexity SF_COMPLEX_INHERITED + frame SF_FRAME_INHERITED + } + dataType "Inherit: Same as Simulink" + } + data { + id 135 + ssIdNumber 5 + name "tau_c" + linkNode [129 134 136] + scope OUTPUT_DATA + paramIndexForInitFromWorkspace 1 + machine 1 + props { + array { + size "-1" + } + type { + method SF_INHERITED_TYPE + primitive SF_DOUBLE_TYPE + } + complexity SF_COMPLEX_INHERITED + frame SF_FRAME_NO + } + dataType "Inherit: Same as Simulink" + } + data { + id 136 + ssIdNumber 9 + name "atlas_version" + linkNode [129 135 0] + scope PARAMETER_DATA + paramIndexForInitFromWorkspace 2 + machine 1 + props { + array { + size "-1" + } + type { + method SF_INHERITED_TYPE + primitive SF_DOUBLE_TYPE + isSigned 1 + wordLength "16" + } + complexity SF_COMPLEX_INHERITED + frame SF_FRAME_INHERITED + } + dataType "Inherit: Same as Simulink" + } + junction { + id 137 + position [23.5747 49.5747 7] + chart 129 + linkNode [129 0 0] + subviewer 129 + ssIdNumber 3 + type CONNECTIVE_JUNCTION + } + transition { + id 138 + labelString "{eML_blk_kernel();}" + labelPosition [32.125 19.875 102.544 14.964] + fontSize 12 + src { + intersection [0 0 1 0 23.5747 14.625 0 0] + } + dst { + id 137 + intersection [1 0 -1 0 23.5747 42.5747 0 0] + } + midPoint [23.5747 24.9468] + chart 129 + linkNode [129 0 0] + dataLimits [21.175 25.975 14.625 42.575] + subviewer 129 + drawStyle SMART + slide { + sticky BOTH_STICK + } + executionOrder 1 + ssIdNumber 2 + } + instance { + id 139 + name "atlas_arm_coriolis_vec_minvarpar/mFcn_c" + machine 1 + chart 129 + } + chart { + id 140 + name "atlas_arm_energy/atlas_arm_energy_fb" + windowPosition [357.331 483.407 167 391] + viewLimits [0 156.75 0 153.75] + screen [1 1 1280 1024 1.041050272174191] + treeNode [0 141 0 0] + firstTransition 150 + firstJunction 149 + viewObj 140 + machine 1 + toolbarMode LIBRARY_TOOLBAR + ssIdHighWaterMark 12 + decomposition CLUSTER_CHART + type EML_CHART + firstData 142 + chartFileNumber 16 + disableImplicitCasting 1 + eml { + name "fcn" + } + } + state { + id 141 + labelString "eML_blk_kernel()" + position [18 64.5 118 66] + fontSize 12 + chart 140 + treeNode [140 0 0 0] + superState SUBCHART + subviewer 140 + ssIdNumber 1 + type FUNC_STATE + decomposition CLUSTER_STATE + eml { + isEML 1 + script "function [T, U] = fcn(q, qD, g_utorso, atlas_arm_lr, atlas_version)\n%#codegen\n\nT = atlas_arm_e" + "nergy_kinetic_fb(q', qD', atlas_arm_lr, atlas_version);\nU = atlas_arm_energy_potential(q', g_utorso', atlas_arm" + "_lr, atlas_version);" + editorLayout "100 M4x1[10 5 700 500]" + } + } + data { + id 142 + ssIdNumber 4 + name "q" + linkNode [140 0 143] + scope INPUT_DATA + machine 1 + props { + array { + size "-1" + } + type { + method SF_INHERITED_TYPE + primitive SF_DOUBLE_TYPE + } + complexity SF_COMPLEX_INHERITED + } + dataType "Inherit: Same as Simulink" + } + data { + id 143 + ssIdNumber 6 + name "qD" + linkNode [140 142 144] + scope INPUT_DATA + machine 1 + props { + array { + size "-1" + } + type { + method SF_INHERITED_TYPE + primitive SF_DOUBLE_TYPE + isSigned 1 + wordLength "16" + } + complexity SF_COMPLEX_INHERITED + frame SF_FRAME_INHERITED + } + dataType "Inherit: Same as Simulink" + } + data { + id 144 + ssIdNumber 5 + name "T" + linkNode [140 143 145] + scope OUTPUT_DATA + machine 1 + props { + array { + size "-1" + } + type { + method SF_INHERITED_TYPE + primitive SF_DOUBLE_TYPE + } + complexity SF_COMPLEX_INHERITED + frame SF_FRAME_NO + } + dataType "Inherit: Same as Simulink" + } + data { + id 145 + ssIdNumber 7 + name "U" + linkNode [140 144 146] + scope OUTPUT_DATA + machine 1 + props { + array { + size "-1" + } + type { + method SF_INHERITED_TYPE + primitive SF_DOUBLE_TYPE + isSigned 1 + wordLength "16" + } + complexity SF_COMPLEX_INHERITED + frame SF_FRAME_NO + } + dataType "Inherit: Same as Simulink" + } + data { + id 146 + ssIdNumber 9 + name "g_utorso" + linkNode [140 145 147] + scope INPUT_DATA + paramIndexForInitFromWorkspace 2 + machine 1 + props { + array { + size "-1" + } + type { + method SF_INHERITED_TYPE + primitive SF_DOUBLE_TYPE + isSigned 1 + wordLength "16" + } + complexity SF_COMPLEX_INHERITED + frame SF_FRAME_INHERITED + } + dataType "Inherit: Same as Simulink" + } + data { + id 147 + ssIdNumber 12 + name "atlas_arm_lr" + linkNode [140 146 148] + scope PARAMETER_DATA + machine 1 + props { + array { + size "-1" + } + type { + method SF_INHERITED_TYPE + primitive SF_DOUBLE_TYPE + isSigned 1 + wordLength "16" + } + complexity SF_COMPLEX_INHERITED + frame SF_FRAME_INHERITED + } + dataType "Inherit: Same as Simulink" + } + data { + id 148 + ssIdNumber 11 + name "atlas_version" + linkNode [140 147 0] + scope PARAMETER_DATA + paramIndexForInitFromWorkspace 1 + machine 1 + props { + array { + size "-1" + } + type { + method SF_INHERITED_TYPE + primitive SF_DOUBLE_TYPE + isSigned 1 + wordLength "16" + } + complexity SF_COMPLEX_INHERITED + frame SF_FRAME_INHERITED + } + dataType "Inherit: Same as Simulink" + } + junction { + id 149 + position [23.5747 49.5747 7] + chart 140 + linkNode [140 0 0] + subviewer 140 + ssIdNumber 3 + type CONNECTIVE_JUNCTION + } + transition { + id 150 + labelString "{eML_blk_kernel();}" + labelPosition [32.125 19.875 102.544 14.964] + fontSize 12 + src { + intersection [0 0 1 0 23.5747 14.625 0 0] + } + dst { + id 149 + intersection [1 0 -1 0 23.5747 42.5747 0 0] + } + midPoint [23.5747 24.9468] + chart 140 + linkNode [140 0 0] + dataLimits [21.175 25.975 14.625 42.575] + subviewer 140 + drawStyle SMART + slide { + sticky BOTH_STICK + } + executionOrder 1 + ssIdNumber 2 + } + instance { + id 151 + name "atlas_arm_energy/atlas_arm_energy_fb" + machine 1 + chart 140 + } + chart { + id 152 + name "atlas_arm_jacobigD/atlas_arm_jacobigD" + windowPosition [357.331 483.407 167 391] + viewLimits [0 156.75 0 153.75] + screen [1 1 1280 1024 1.041050272174191] + treeNode [0 153 0 0] + firstTransition 160 + firstJunction 159 + viewObj 152 + machine 1 + toolbarMode LIBRARY_TOOLBAR + ssIdHighWaterMark 11 + decomposition CLUSTER_CHART + type EML_CHART + firstData 154 + chartFileNumber 17 + disableImplicitCasting 1 + eml { + name "fcn" + } + } + state { + id 153 + labelString "eML_blk_kernel()" + position [18 64.5 118 66] + fontSize 12 + chart 152 + treeNode [152 0 0 0] + superState SUBCHART + subviewer 152 + ssIdNumber 1 + type FUNC_STATE + decomposition CLUSTER_STATE + eml { + isEML 1 + script "function JGD = fcn(q, qD, atlas_arm_lr, atlas_version)\n%#codegen\n\nJGD = atlas_arm_jacobigD(q'," + " qD', atlas_arm_lr, atlas_version);\n" + editorLayout "100 M4x1[10 5 700 500]" + } + } + data { + id 154 + ssIdNumber 4 + name "q" + linkNode [152 0 155] + scope INPUT_DATA + machine 1 + props { + array { + size "-1" + } + type { + method SF_INHERITED_TYPE + primitive SF_DOUBLE_TYPE + } + complexity SF_COMPLEX_INHERITED + } + dataType "Inherit: Same as Simulink" + } + data { + id 155 + ssIdNumber 6 + name "qD" + linkNode [152 154 156] + scope INPUT_DATA + machine 1 + props { + array { + size "-1" + } + type { + method SF_INHERITED_TYPE + primitive SF_DOUBLE_TYPE + isSigned 1 + wordLength "16" + } + complexity SF_COMPLEX_INHERITED + frame SF_FRAME_INHERITED + } + dataType "Inherit: Same as Simulink" + } + data { + id 156 + ssIdNumber 5 + name "JGD" + linkNode [152 155 157] + scope OUTPUT_DATA + machine 1 + props { + array { + size "-1" + } + type { + method SF_INHERITED_TYPE + primitive SF_DOUBLE_TYPE + } + complexity SF_COMPLEX_INHERITED + frame SF_FRAME_NO + } + dataType "Inherit: Same as Simulink" + } + data { + id 157 + ssIdNumber 9 + name "atlas_arm_lr" + linkNode [152 156 158] + scope PARAMETER_DATA + machine 1 + props { + array { + size "-1" + } + type { + method SF_INHERITED_TYPE + primitive SF_DOUBLE_TYPE + isSigned 1 + wordLength "16" + } + complexity SF_COMPLEX_INHERITED + frame SF_FRAME_INHERITED + } + dataType "Inherit: Same as Simulink" + } + data { + id 158 + ssIdNumber 11 + name "atlas_version" + linkNode [152 157 0] + scope PARAMETER_DATA + paramIndexForInitFromWorkspace 1 + machine 1 + props { + array { + size "-1" + } + type { + method SF_INHERITED_TYPE + primitive SF_DOUBLE_TYPE + isSigned 1 + wordLength "16" + } + complexity SF_COMPLEX_INHERITED + frame SF_FRAME_INHERITED + } + dataType "Inherit: Same as Simulink" + } + junction { + id 159 + position [23.5747 49.5747 7] + chart 152 + linkNode [152 0 0] + subviewer 152 + ssIdNumber 3 + type CONNECTIVE_JUNCTION + } + transition { + id 160 + labelString "{eML_blk_kernel();}" + labelPosition [32.125 19.875 102.544 14.964] + fontSize 12 + src { + intersection [0 0 1 0 23.5747 14.625 0 0] + } + dst { + id 159 + intersection [1 0 -1 0 23.5747 42.5747 0 0] + } + midPoint [23.5747 24.9468] + chart 152 + linkNode [152 0 0] + dataLimits [21.175 25.975 14.625 42.575] + subviewer 152 + drawStyle SMART + slide { + sticky BOTH_STICK + } + executionOrder 1 + ssIdNumber 2 + } + instance { + id 161 + name "atlas_arm_jacobigD/atlas_arm_jacobigD" + machine 1 + chart 152 + } + chart { + id 162 + name "atlas_arm_jacobig/atlas_arm_jacobig" + windowPosition [357.331 483.407 167 391] + viewLimits [0 156.75 0 153.75] + screen [1 1 1280 1024 1.041050272174191] + treeNode [0 163 0 0] + firstTransition 169 + firstJunction 168 + viewObj 162 + machine 1 + toolbarMode LIBRARY_TOOLBAR + ssIdHighWaterMark 11 + decomposition CLUSTER_CHART + type EML_CHART + firstData 164 + chartFileNumber 18 + disableImplicitCasting 1 + eml { + name "fcn" + } + } + state { + id 163 + labelString "eML_blk_kernel()" + position [18 64.5 118 66] + fontSize 12 + chart 162 + treeNode [162 0 0 0] + superState SUBCHART + subviewer 162 + ssIdNumber 1 + type FUNC_STATE + decomposition CLUSTER_STATE + eml { + isEML 1 + script "function JG = fcn(q, atlas_arm_lr, atlas_version)\n%#codegen\n\nJG = atlas_arm_jacobig(q', atlas_" + "arm_lr, atlas_version);\n" + editorLayout "100 M4x1[10 5 700 500]" + } + } + data { + id 164 + ssIdNumber 4 + name "q" + linkNode [162 0 165] + scope INPUT_DATA + machine 1 + props { + array { + size "-1" + } + type { + method SF_INHERITED_TYPE + primitive SF_DOUBLE_TYPE + } + complexity SF_COMPLEX_INHERITED + } + dataType "Inherit: Same as Simulink" + } + data { + id 165 + ssIdNumber 5 + name "JG" + linkNode [162 164 166] + scope OUTPUT_DATA + machine 1 + props { + array { + size "-1" + } + type { + method SF_INHERITED_TYPE + primitive SF_DOUBLE_TYPE + } + complexity SF_COMPLEX_INHERITED + frame SF_FRAME_NO + } + dataType "Inherit: Same as Simulink" + } + data { + id 166 + ssIdNumber 9 + name "atlas_arm_lr" + linkNode [162 165 167] + scope PARAMETER_DATA + machine 1 + props { + array { + size "-1" + } + type { + method SF_INHERITED_TYPE + primitive SF_DOUBLE_TYPE + isSigned 1 + wordLength "16" + } + complexity SF_COMPLEX_INHERITED + frame SF_FRAME_INHERITED + } + dataType "Inherit: Same as Simulink" + } + data { + id 167 + ssIdNumber 11 + name "atlas_version" + linkNode [162 166 0] + scope PARAMETER_DATA + paramIndexForInitFromWorkspace 1 + machine 1 + props { + array { + size "-1" + } + type { + method SF_INHERITED_TYPE + primitive SF_DOUBLE_TYPE + isSigned 1 + wordLength "16" + } + complexity SF_COMPLEX_INHERITED + frame SF_FRAME_INHERITED + } + dataType "Inherit: Same as Simulink" + } + junction { + id 168 + position [23.5747 49.5747 7] + chart 162 + linkNode [162 0 0] + subviewer 162 + ssIdNumber 3 + type CONNECTIVE_JUNCTION + } + transition { + id 169 + labelString "{eML_blk_kernel();}" + labelPosition [32.125 19.875 102.544 14.964] + fontSize 12 + src { + intersection [0 0 1 0 23.5747 14.625 0 0] + } + dst { + id 168 + intersection [1 0 -1 0 23.5747 42.5747 0 0] + } + midPoint [23.5747 24.9468] + chart 162 + linkNode [162 0 0] + dataLimits [21.175 25.975 14.625 42.575] + subviewer 162 + drawStyle SMART + slide { + sticky BOTH_STICK + } + executionOrder 1 + ssIdNumber 2 + } + instance { + id 170 + name "atlas_arm_jacobig/atlas_arm_jacobig" + machine 1 + chart 162 + } + chart { + id 171 + name "atlas_arm_energy_minvarpar/atlas_arm_energy_fb" + windowPosition [357.331 483.407 167 391] + viewLimits [0 156.75 0 153.75] + screen [1 1 1280 1024 1.041050272174191] + treeNode [0 172 0 0] + firstTransition 182 + firstJunction 181 + viewObj 171 + machine 1 + toolbarMode LIBRARY_TOOLBAR + ssIdHighWaterMark 13 + decomposition CLUSTER_CHART + type EML_CHART + firstData 173 + chartFileNumber 19 + disableImplicitCasting 1 + eml { + name "fcn" + } + } + state { + id 172 + labelString "eML_blk_kernel()" + position [18 64.5 118 66] + fontSize 12 + chart 171 + treeNode [171 0 0 0] + superState SUBCHART + subviewer 171 + ssIdNumber 1 + type FUNC_STATE + decomposition CLUSTER_STATE + eml { + isEML 1 + script "function [T, U] = fcn(q, qD, g_utorso, MPV, atlas_arm_lr, atlas_version)\n%#codegen\n\nT = atlas_" + "arm_energy_kinetic_fb_minpar_sym_lag_varpar(q', qD', atlas_arm_lr, atlas_version);\nU = atlas_arm_energy_potenti" + "al_minpar_sym_lag_varpar(q', g_utorso', atlas_arm_lr, atlas_version);" + editorLayout "100 M4x1[10 5 700 500]" + } + } + data { + id 173 + ssIdNumber 4 + name "q" + linkNode [171 0 174] + scope INPUT_DATA + machine 1 + props { + array { + size "-1" + } + type { + method SF_INHERITED_TYPE + primitive SF_DOUBLE_TYPE + } + complexity SF_COMPLEX_INHERITED + } + dataType "Inherit: Same as Simulink" + } + data { + id 174 + ssIdNumber 6 + name "qD" + linkNode [171 173 175] + scope INPUT_DATA + machine 1 + props { + array { + size "-1" + } + type { + method SF_INHERITED_TYPE + primitive SF_DOUBLE_TYPE + isSigned 1 + wordLength "16" + } + complexity SF_COMPLEX_INHERITED + frame SF_FRAME_INHERITED + } + dataType "Inherit: Same as Simulink" + } + data { + id 175 + ssIdNumber 5 + name "T" + linkNode [171 174 176] + scope OUTPUT_DATA + machine 1 + props { + array { + size "-1" + } + type { + method SF_INHERITED_TYPE + primitive SF_DOUBLE_TYPE + } + complexity SF_COMPLEX_INHERITED + frame SF_FRAME_NO + } + dataType "Inherit: Same as Simulink" + } + data { + id 176 + ssIdNumber 7 + name "U" + linkNode [171 175 177] + scope OUTPUT_DATA + machine 1 + props { + array { + size "-1" + } + type { + method SF_INHERITED_TYPE + primitive SF_DOUBLE_TYPE + isSigned 1 + wordLength "16" + } + complexity SF_COMPLEX_INHERITED + frame SF_FRAME_NO + } + dataType "Inherit: Same as Simulink" + } + data { + id 177 + ssIdNumber 9 + name "g_utorso" + linkNode [171 176 178] + scope INPUT_DATA + paramIndexForInitFromWorkspace 2 + machine 1 + props { + array { + size "-1" + } + type { + method SF_INHERITED_TYPE + primitive SF_DOUBLE_TYPE + isSigned 1 + wordLength "16" + } + complexity SF_COMPLEX_INHERITED + frame SF_FRAME_INHERITED + } + dataType "Inherit: Same as Simulink" + } + data { + id 178 + ssIdNumber 13 + name "MPV" + linkNode [171 177 179] + scope PARAMETER_DATA + machine 1 + props { + array { + size "-1" + } + type { + method SF_INHERITED_TYPE + primitive SF_DOUBLE_TYPE + isSigned 1 + wordLength "16" + } + complexity SF_COMPLEX_INHERITED + frame SF_FRAME_INHERITED + } + dataType "Inherit: Same as Simulink" + } + data { + id 179 + ssIdNumber 12 + name "atlas_arm_lr" + linkNode [171 178 180] + scope PARAMETER_DATA + paramIndexForInitFromWorkspace 1 + machine 1 + props { + array { + size "-1" + } + type { + method SF_INHERITED_TYPE + primitive SF_DOUBLE_TYPE + isSigned 1 + wordLength "16" + } + complexity SF_COMPLEX_INHERITED + frame SF_FRAME_INHERITED + } + dataType "Inherit: Same as Simulink" + } + data { + id 180 + ssIdNumber 11 + name "atlas_version" + linkNode [171 179 0] + scope PARAMETER_DATA + paramIndexForInitFromWorkspace 2 + machine 1 + props { + array { + size "-1" + } + type { + method SF_INHERITED_TYPE + primitive SF_DOUBLE_TYPE + isSigned 1 + wordLength "16" + } + complexity SF_COMPLEX_INHERITED + frame SF_FRAME_INHERITED + } + dataType "Inherit: Same as Simulink" + } + junction { + id 181 + position [23.5747 49.5747 7] + chart 171 + linkNode [171 0 0] + subviewer 171 + ssIdNumber 3 + type CONNECTIVE_JUNCTION + } + transition { + id 182 + labelString "{eML_blk_kernel();}" + labelPosition [32.125 19.875 102.544 14.964] + fontSize 12 + src { + intersection [0 0 1 0 23.5747 14.625 0 0] + } + dst { + id 181 + intersection [1 0 -1 0 23.5747 42.5747 0 0] + } + midPoint [23.5747 24.9468] + chart 171 + linkNode [171 0 0] + dataLimits [21.175 25.975 14.625 42.575] + subviewer 171 + drawStyle SMART + slide { + sticky BOTH_STICK + } + executionOrder 1 + ssIdNumber 2 + } + instance { + id 183 + name "atlas_arm_energy_minvarpar/atlas_arm_energy_fb" + machine 1 + chart 171 + } + chart { + id 184 + name "atlas3_arm_inertia/mFcn_M" + windowPosition [357.331 483.407 167 391] + viewLimits [0 156.75 0 153.75] + screen [1 1 1280 1024 1.041050272174191] + treeNode [0 185 0 0] + firstTransition 190 + firstJunction 189 + viewObj 184 + machine 1 + toolbarMode LIBRARY_TOOLBAR + ssIdHighWaterMark 8 + decomposition CLUSTER_CHART + type EML_CHART + firstData 186 + chartFileNumber 20 + disableImplicitCasting 1 + eml { + name "fcn" + } + } + state { + id 185 + labelString "eML_blk_kernel()" + position [18 64.5 118 66] + fontSize 12 + chart 184 + treeNode [184 0 0 0] + superState SUBCHART + subviewer 184 + ssIdNumber 1 + type FUNC_STATE + decomposition CLUSTER_STATE + eml { + isEML 1 + script "function M = fcn(q, atlas_arm_lr)\n%#codegen\nM = atlas3_arm_inertia(q', atlas_arm_lr);" + editorLayout "100 M4x1[10 5 700 500]" + } + } + data { + id 186 + ssIdNumber 4 + name "q" + linkNode [184 0 187] + scope INPUT_DATA + machine 1 + props { + array { + size "-1" + } + type { + method SF_INHERITED_TYPE + primitive SF_DOUBLE_TYPE + } + complexity SF_COMPLEX_INHERITED + } + dataType "Inherit: Same as Simulink" + } + data { + id 187 + ssIdNumber 5 + name "M" + linkNode [184 186 188] + scope OUTPUT_DATA + machine 1 + props { + array { + size "-1" + } + type { + method SF_INHERITED_TYPE + primitive SF_DOUBLE_TYPE + } + complexity SF_COMPLEX_INHERITED + frame SF_FRAME_NO + } + dataType "Inherit: Same as Simulink" + } + data { + id 188 + ssIdNumber 7 + name "atlas_arm_lr" + linkNode [184 187 0] + scope PARAMETER_DATA + machine 1 + props { + array { + size "-1" + } + type { + method SF_INHERITED_TYPE + primitive SF_DOUBLE_TYPE + isSigned 1 + wordLength "16" + } + complexity SF_COMPLEX_INHERITED + frame SF_FRAME_INHERITED + } + dataType "Inherit: Same as Simulink" + } + junction { + id 189 + position [23.5747 49.5747 7] + chart 184 + linkNode [184 0 0] + subviewer 184 + ssIdNumber 3 + type CONNECTIVE_JUNCTION + } + transition { + id 190 + labelString "{eML_blk_kernel();}" + labelPosition [32.125 19.875 102.544 14.964] + fontSize 12 + src { + intersection [0 0 1 0 23.5747 14.625 0 0] + } + dst { + id 189 + intersection [1 0 -1 0 23.5747 42.5747 0 0] + } + midPoint [23.5747 24.9468] + chart 184 + linkNode [184 0 0] + dataLimits [21.175 25.975 14.625 42.575] + subviewer 184 + drawStyle SMART + slide { + sticky BOTH_STICK + } + executionOrder 1 + ssIdNumber 2 + } + instance { + id 191 + name "atlas3_arm_inertia/mFcn_M" + machine 1 + chart 184 + } + chart { + id 192 + name "atlas3_arm_coriolis_vec/mFcn_c" + windowPosition [357.331 483.407 167 391] + viewLimits [0 156.75 0 153.75] + screen [1 1 1280 1024 1.041050272174191] + treeNode [0 193 0 0] + firstTransition 199 + firstJunction 198 + viewObj 192 + machine 1 + toolbarMode LIBRARY_TOOLBAR + ssIdHighWaterMark 8 + decomposition CLUSTER_CHART + type EML_CHART + firstData 194 + chartFileNumber 21 + disableImplicitCasting 1 + eml { + name "fcn" + } + } + state { + id 193 + labelString "eML_blk_kernel()" + position [18 64.5 118 66] + fontSize 12 + chart 192 + treeNode [192 0 0 0] + superState SUBCHART + subviewer 192 + ssIdNumber 1 + type FUNC_STATE + decomposition CLUSTER_STATE + eml { + isEML 1 + script "function tau_c = fcn(q,qD, atlas_arm_lr)\n%#codegen\n\ntau_c=atlas3_arm_coriolisvec_fb(q', qD', a" + "tlas_arm_lr)';\n" + editorLayout "100 M4x1[10 5 700 500]" + } + } + data { + id 194 + ssIdNumber 4 + name "q" + linkNode [192 0 195] + scope INPUT_DATA + machine 1 + props { + array { + size "-1" + } + type { + method SF_INHERITED_TYPE + primitive SF_DOUBLE_TYPE + } + complexity SF_COMPLEX_INHERITED + } + dataType "Inherit: Same as Simulink" + } + data { + id 195 + ssIdNumber 6 + name "qD" + linkNode [192 194 196] + scope INPUT_DATA + machine 1 + props { + array { + size "-1" + } + type { + method SF_INHERITED_TYPE + primitive SF_DOUBLE_TYPE + isSigned 1 + wordLength "16" + } + complexity SF_COMPLEX_INHERITED + frame SF_FRAME_INHERITED + } + dataType "Inherit: Same as Simulink" + } + data { + id 196 + ssIdNumber 8 + name "atlas_arm_lr" + linkNode [192 195 197] + scope PARAMETER_DATA + machine 1 + props { + array { + size "-1" + } + type { + method SF_INHERITED_TYPE + primitive SF_DOUBLE_TYPE + isSigned 1 + wordLength "16" + } + complexity SF_COMPLEX_INHERITED + frame SF_FRAME_INHERITED + } + dataType "Inherit: Same as Simulink" + } + data { + id 197 + ssIdNumber 5 + name "tau_c" + linkNode [192 196 0] + scope OUTPUT_DATA + paramIndexForInitFromWorkspace 1 + machine 1 + props { + array { + size "-1" + } + type { + method SF_INHERITED_TYPE + primitive SF_DOUBLE_TYPE + } + complexity SF_COMPLEX_INHERITED + frame SF_FRAME_NO + } + dataType "Inherit: Same as Simulink" + } + junction { + id 198 + position [23.5747 49.5747 7] + chart 192 + linkNode [192 0 0] + subviewer 192 + ssIdNumber 3 + type CONNECTIVE_JUNCTION + } + transition { + id 199 + labelString "{eML_blk_kernel();}" + labelPosition [32.125 19.875 102.544 14.964] + fontSize 12 + src { + intersection [0 0 1 0 23.5747 14.625 0 0] + } + dst { + id 198 + intersection [1 0 -1 0 23.5747 42.5747 0 0] + } + midPoint [23.5747 24.9468] + chart 192 + linkNode [192 0 0] + dataLimits [21.175 25.975 14.625 42.575] + subviewer 192 + drawStyle SMART + slide { + sticky BOTH_STICK + } + executionOrder 1 + ssIdNumber 2 + } + instance { + id 200 + name "atlas3_arm_coriolis_vec/mFcn_c" + machine 1 + chart 192 + } + chart { + id 201 + name "atlas3_arm_gravload/mFcn_g" + windowPosition [357.331 483.407 167 391] + viewLimits [0 156.75 0 153.75] + screen [1 1 1280 1024 1.041050272174191] + treeNode [0 202 0 0] + firstTransition 208 + firstJunction 207 + viewObj 201 + machine 1 + toolbarMode LIBRARY_TOOLBAR + ssIdHighWaterMark 9 + decomposition CLUSTER_CHART + type EML_CHART + firstData 203 + chartFileNumber 22 + disableImplicitCasting 1 + eml { + name "fcn" + } + } + state { + id 202 + labelString "eML_blk_kernel()" + position [18 64.5 118 66] + fontSize 12 + chart 201 + treeNode [201 0 0 0] + superState SUBCHART + subviewer 201 + ssIdNumber 1 + type FUNC_STATE + decomposition CLUSTER_STATE + eml { + isEML 1 + script "function tau_g = fcn(q, g, atlas_arm_lr)\n%#codegen\n\ntau_g = atlas3_arm_gravload(q', g', atlas_" + "arm_lr)';" + editorLayout "100 M4x1[10 5 700 500]" + } + } + data { + id 203 + ssIdNumber 4 + name "q" + linkNode [201 0 204] + scope INPUT_DATA + machine 1 + props { + array { + size "-1" + } + type { + method SF_INHERITED_TYPE + primitive SF_DOUBLE_TYPE + } + complexity SF_COMPLEX_INHERITED + } + dataType "Inherit: Same as Simulink" + } + data { + id 204 + ssIdNumber 9 + name "g" + linkNode [201 203 205] + scope INPUT_DATA + machine 1 + props { + array { + size "-1" + } + type { + method SF_INHERITED_TYPE + primitive SF_DOUBLE_TYPE + isSigned 1 + wordLength "16" + } + complexity SF_COMPLEX_INHERITED + frame SF_FRAME_INHERITED + } + dataType "Inherit: Same as Simulink" + } + data { + id 205 + ssIdNumber 8 + name "atlas_arm_lr" + linkNode [201 204 206] + scope PARAMETER_DATA + machine 1 + props { + array { + size "-1" + } + type { + method SF_INHERITED_TYPE + primitive SF_DOUBLE_TYPE + isSigned 1 + wordLength "16" + } + complexity SF_COMPLEX_INHERITED + frame SF_FRAME_INHERITED + } + dataType "Inherit: Same as Simulink" + } + data { + id 206 + ssIdNumber 5 + name "tau_g" + linkNode [201 205 0] + scope OUTPUT_DATA + machine 1 + props { + array { + size "-1" + } + type { + method SF_INHERITED_TYPE + primitive SF_DOUBLE_TYPE + } + complexity SF_COMPLEX_INHERITED + frame SF_FRAME_NO + } + dataType "Inherit: Same as Simulink" + } + junction { + id 207 + position [23.5747 49.5747 7] + chart 201 + linkNode [201 0 0] + subviewer 201 + ssIdNumber 3 + type CONNECTIVE_JUNCTION + } + transition { + id 208 + labelString "{eML_blk_kernel();}" + labelPosition [32.125 19.875 102.544 14.964] + fontSize 12 + src { + intersection [0 0 1 0 23.5747 14.625 0 0] + } + dst { + id 207 + intersection [1 0 -1 0 23.5747 42.5747 0 0] + } + midPoint [23.5747 24.9468] + chart 201 + linkNode [201 0 0] + dataLimits [21.175 25.975 14.625 42.575] + subviewer 201 + drawStyle SMART + slide { + sticky BOTH_STICK + } + executionOrder 1 + ssIdNumber 2 + } + instance { + id 209 + name "atlas3_arm_gravload/mFcn_g" + machine 1 + chart 201 + } + chart { + id 210 + name "atlas_arm_invdyn_fb_minvarpar/mFcn_tau" + windowPosition [357.331 483.407 167 391] + viewLimits [0 156.75 0 153.75] + screen [1 1 1280 1024 1.041050272174191] + treeNode [0 211 0 0] + firstTransition 221 + firstJunction 220 + viewObj 210 + machine 1 + toolbarMode LIBRARY_TOOLBAR + ssIdHighWaterMark 12 + decomposition CLUSTER_CHART + type EML_CHART + firstData 212 + chartFileNumber 23 + disableImplicitCasting 1 + eml { + name "fcn" + } + } + state { + id 211 + labelString "eML_blk_kernel()" + position [18 64.5 118 66] + fontSize 12 + chart 210 + treeNode [210 0 0 0] + superState SUBCHART + subviewer 210 + ssIdNumber 1 + type FUNC_STATE + decomposition CLUSTER_STATE + eml { + isEML 1 + script "function tau = fcn(q,qD, qDD, g, MPV, atlas_arm_lr, atlas_version)\n%#codegen\n\ntau=atlas_arm_in" + "vdyn_fb_plin_minpar_sym_lag_varpar(q', qD',qDD', g', MPV, atlas_arm_lr, atlas_version)';\n" + editorLayout "100 M4x1[10 5 700 500]" + } + } + data { + id 212 + ssIdNumber 4 + name "q" + linkNode [210 0 213] + scope INPUT_DATA + machine 1 + props { + array { + size "-1" + } + type { + method SF_INHERITED_TYPE + primitive SF_DOUBLE_TYPE + } + complexity SF_COMPLEX_INHERITED + } + dataType "Inherit: Same as Simulink" + } + data { + id 213 + ssIdNumber 6 + name "qD" + linkNode [210 212 214] + scope INPUT_DATA + machine 1 + props { + array { + size "-1" + } + type { + method SF_INHERITED_TYPE + primitive SF_DOUBLE_TYPE + isSigned 1 + wordLength "16" + } + complexity SF_COMPLEX_INHERITED + frame SF_FRAME_INHERITED + } + dataType "Inherit: Same as Simulink" + } + data { + id 214 + ssIdNumber 11 + name "qDD" + linkNode [210 213 215] + scope INPUT_DATA + machine 1 + props { + array { + size "-1" + } + type { + method SF_INHERITED_TYPE + primitive SF_DOUBLE_TYPE + isSigned 1 + wordLength "16" + } + complexity SF_COMPLEX_INHERITED + frame SF_FRAME_INHERITED + } + dataType "Inherit: Same as Simulink" + } + data { + id 215 + ssIdNumber 12 + name "g" + linkNode [210 214 216] + scope INPUT_DATA + machine 1 + props { + array { + size "-1" + } + type { + method SF_INHERITED_TYPE + primitive SF_DOUBLE_TYPE + isSigned 1 + wordLength "16" + } + complexity SF_COMPLEX_INHERITED + frame SF_FRAME_INHERITED + } + dataType "Inherit: Same as Simulink" + } + data { + id 216 + ssIdNumber 10 + name "MPV" + linkNode [210 215 217] + scope PARAMETER_DATA + machine 1 + props { + array { + size "-1" + } + type { + method SF_INHERITED_TYPE + primitive SF_DOUBLE_TYPE + isSigned 1 + wordLength "16" + } + complexity SF_COMPLEX_INHERITED + frame SF_FRAME_INHERITED + } + dataType "Inherit: Same as Simulink" + } + data { + id 217 + ssIdNumber 8 + name "atlas_arm_lr" + linkNode [210 216 218] + scope PARAMETER_DATA + paramIndexForInitFromWorkspace 1 + machine 1 + props { + array { + size "-1" + } + type { + method SF_INHERITED_TYPE + primitive SF_DOUBLE_TYPE + isSigned 1 + wordLength "16" + } + complexity SF_COMPLEX_INHERITED + frame SF_FRAME_INHERITED + } + dataType "Inherit: Same as Simulink" + } + data { + id 218 + ssIdNumber 5 + name "tau" + linkNode [210 217 219] + scope OUTPUT_DATA + paramIndexForInitFromWorkspace 1 + machine 1 + props { + array { + size "-1" + } + type { + method SF_INHERITED_TYPE + primitive SF_DOUBLE_TYPE + } + complexity SF_COMPLEX_INHERITED + frame SF_FRAME_NO + } + dataType "Inherit: Same as Simulink" + } + data { + id 219 + ssIdNumber 9 + name "atlas_version" + linkNode [210 218 0] + scope PARAMETER_DATA + paramIndexForInitFromWorkspace 2 + machine 1 + props { + array { + size "-1" + } + type { + method SF_INHERITED_TYPE + primitive SF_DOUBLE_TYPE + isSigned 1 + wordLength "16" + } + complexity SF_COMPLEX_INHERITED + frame SF_FRAME_INHERITED + } + dataType "Inherit: Same as Simulink" + } + junction { + id 220 + position [23.5747 49.5747 7] + chart 210 + linkNode [210 0 0] + subviewer 210 + ssIdNumber 3 + type CONNECTIVE_JUNCTION + } + transition { + id 221 + labelString "{eML_blk_kernel();}" + labelPosition [32.125 19.875 102.544 14.964] + fontSize 12 + src { + intersection [0 0 1 0 23.5747 14.625 0 0] + } + dst { + id 220 + intersection [1 0 -1 0 23.5747 42.5747 0 0] + } + midPoint [23.5747 24.9468] + chart 210 + linkNode [210 0 0] + dataLimits [21.175 25.975 14.625 42.575] + subviewer 210 + drawStyle SMART + slide { + sticky BOTH_STICK + } + executionOrder 1 + ssIdNumber 2 + } + instance { + id 222 + name "atlas_arm_invdyn_fb_minvarpar/mFcn_tau" + machine 1 + chart 210 + } + chart { + id 223 + name "atlas_friction_model/atlas_friction_model" + windowPosition [357.331 483.407 167 391] + viewLimits [0 156.75 0 153.75] + screen [1 1 1280 1024 1.041050272174191] + treeNode [0 224 0 0] + firstTransition 230 + firstJunction 229 + viewObj 223 + machine 1 + toolbarMode LIBRARY_TOOLBAR + ssIdHighWaterMark 10 + decomposition CLUSTER_CHART + type EML_CHART + firstData 225 + chartFileNumber 24 + disableImplicitCasting 1 + eml { + name "fcn" + } + } + state { + id 224 + labelString "eML_blk_kernel()" + position [18 64.5 118 66] + fontSize 12 + chart 223 + treeNode [223 0 0 0] + superState SUBCHART + subviewer 223 + ssIdNumber 1 + type FUNC_STATE + decomposition CLUSTER_STATE + eml { + isEML 1 + script "function tau_fr = fcn(qD, muC, d)\n%#codegen\n\ntau_fr = ((atan(1000*qD)*(2/pi)) .* muC) + (qD .*" + " d);" + editorLayout "100 M4x1[10 5 700 500]" + } + } + data { + id 225 + ssIdNumber 6 + name "qD" + linkNode [223 0 226] + scope INPUT_DATA + machine 1 + props { + array { + size "-1" + } + type { + method SF_INHERITED_TYPE + primitive SF_DOUBLE_TYPE + isSigned 1 + wordLength "16" + } + complexity SF_COMPLEX_INHERITED + frame SF_FRAME_INHERITED + } + dataType "Inherit: Same as Simulink" + } + data { + id 226 + ssIdNumber 4 + name "muC" + linkNode [223 225 227] + scope PARAMETER_DATA + paramIndexForInitFromWorkspace 1 + machine 1 + props { + array { + size "-1" + } + type { + method SF_INHERITED_TYPE + primitive SF_DOUBLE_TYPE + } + complexity SF_COMPLEX_INHERITED + } + dataType "Inherit: Same as Simulink" + } + data { + id 227 + ssIdNumber 5 + name "tau_fr" + linkNode [223 226 228] + scope OUTPUT_DATA + paramIndexForInitFromWorkspace 1 + machine 1 + props { + array { + size "-1" + } + type { + method SF_INHERITED_TYPE + primitive SF_DOUBLE_TYPE + } + complexity SF_COMPLEX_INHERITED + frame SF_FRAME_NO + } + dataType "Inherit: Same as Simulink" + } + data { + id 228 + ssIdNumber 10 + name "d" + linkNode [223 227 0] + scope PARAMETER_DATA + machine 1 + props { + array { + size "-1" + } + type { + method SF_INHERITED_TYPE + primitive SF_DOUBLE_TYPE + isSigned 1 + wordLength "16" + } + complexity SF_COMPLEX_INHERITED + frame SF_FRAME_INHERITED + } + dataType "Inherit: Same as Simulink" + } + junction { + id 229 + position [23.5747 49.5747 7] + chart 223 + linkNode [223 0 0] + subviewer 223 + ssIdNumber 3 + type CONNECTIVE_JUNCTION + } + transition { + id 230 + labelString "{eML_blk_kernel();}" + labelPosition [32.125 19.875 102.544 14.964] + fontSize 12 + src { + intersection [0 0 1 0 23.5747 14.625 0 0] + } + dst { + id 229 + intersection [1 0 -1 0 23.5747 42.5747 0 0] + } + midPoint [23.5747 24.9468] + chart 223 + linkNode [223 0 0] + dataLimits [21.175 25.975 14.625 42.575] + subviewer 223 + drawStyle SMART + slide { + sticky BOTH_STICK + } + executionOrder 1 + ssIdNumber 2 + } + instance { + id 231 + name "atlas_friction_model/atlas_friction_model" + machine 1 + chart 223 + } + chart { + id 232 + name "atlas_arm_fordyn_rj_damping_minvarpar/mFcn_Minv" + windowPosition [357.331 483.407 167 391] + viewLimits [0 156.75 0 153.75] + screen [1 1 1280 1024 1.041050272174191] + treeNode [0 233 0 0] + firstTransition 238 + firstJunction 237 + viewObj 232 + machine 1 + toolbarMode LIBRARY_TOOLBAR + ssIdHighWaterMark 6 + decomposition CLUSTER_CHART + type EML_CHART + firstData 234 + chartFileNumber 25 + disableImplicitCasting 1 + eml { + name "fcn" + } + } + state { + id 233 + labelString "eML_blk_kernel()" + position [18 64.5 118 66] + fontSize 12 + chart 232 + treeNode [232 0 0 0] + superState SUBCHART + subviewer 232 + ssIdNumber 1 + type FUNC_STATE + decomposition CLUSTER_STATE + eml { + isEML 1 + script "function q_ddot = fcn(M,tau)\n%#codegen\nq_ddot=M\\tau;" + editorLayout "100 M4x1[10 5 700 500]" + } + } + data { + id 234 + ssIdNumber 4 + name "M" + linkNode [232 0 235] + scope INPUT_DATA + machine 1 + props { + array { + size "-1" + } + type { + method SF_INHERITED_TYPE + primitive SF_DOUBLE_TYPE + } + complexity SF_COMPLEX_INHERITED + } + dataType "Inherit: Same as Simulink" + } + data { + id 235 + ssIdNumber 5 + name "q_ddot" + linkNode [232 234 236] + scope OUTPUT_DATA + machine 1 + props { + array { + size "-1" + } + type { + method SF_INHERITED_TYPE + primitive SF_DOUBLE_TYPE + } + complexity SF_COMPLEX_INHERITED + frame SF_FRAME_NO + } + dataType "Inherit: Same as Simulink" + } + data { + id 236 + ssIdNumber 6 + name "tau" + linkNode [232 235 0] + scope INPUT_DATA + machine 1 + props { + array { + size "-1" + } + type { + method SF_INHERITED_TYPE + primitive SF_DOUBLE_TYPE + isSigned 1 + wordLength "16" + } + complexity SF_COMPLEX_INHERITED + frame SF_FRAME_INHERITED + } + dataType "Inherit: Same as Simulink" + } + junction { + id 237 + position [23.5747 49.5747 7] + chart 232 + linkNode [232 0 0] + subviewer 232 + ssIdNumber 3 + type CONNECTIVE_JUNCTION + } + transition { + id 238 + labelString "{eML_blk_kernel();}" + labelPosition [32.125 19.875 102.544 14.964] + fontSize 12 + src { + intersection [0 0 1 0 23.5747 14.625 0 0] + } + dst { + id 237 + intersection [1 0 -1 0 23.5747 42.5747 0 0] + } + midPoint [23.5747 24.9468] + chart 232 + linkNode [232 0 0] + dataLimits [21.175 25.975 14.625 42.575] + subviewer 232 + drawStyle SMART + slide { + sticky BOTH_STICK + } + executionOrder 1 + ssIdNumber 2 + } + instance { + id 239 + name "atlas_arm_fordyn_rj_damping_minvarpar/mFcn_Minv" + machine 1 + chart 232 + } + chart { + id 240 + name "atlas_friction_and_stiction_model/atlas_friction_model" + windowPosition [357.331 483.407 167 391] + viewLimits [0 156.75 0 153.75] + screen [1 1 1280 1024 1.041050272174191] + treeNode [0 241 0 0] + firstTransition 251 + firstJunction 250 + viewObj 240 + machine 1 + toolbarMode LIBRARY_TOOLBAR + ssIdHighWaterMark 14 + decomposition CLUSTER_CHART + type EML_CHART + firstData 242 + chartFileNumber 26 + disableImplicitCasting 1 + eml { + name "fcn" + } + } + state { + id 241 + labelString "eML_blk_kernel()" + position [18 64.5 118 66] + fontSize 12 + chart 240 + treeNode [240 0 0 0] + superState SUBCHART + subviewer 240 + ssIdNumber 1 + type FUNC_STATE + decomposition CLUSTER_STATE + eml { + isEML 1 + script "function tau_reib = fcn(qD, tau_dyn, tau_c, B, tau_s, qD_s, delta_s)\n%#codegen\ntau_reib=zeros(l" + "ength(qD),1);\nfor i=1:length(qD)\n if (abs(qD(i))<1e-9)\n if (abs(tau_dyn(i))" + LastModifiedBy "schappler" + ModifiedDateFormat "%" + LastModifiedDate "Fri May 20 17:24:57 2016" + RTWModifiedTimeStamp 385665887 + ModelVersionFormat "1.%" + ConfigurationManager "none" + SampleTimeColors off + SampleTimeAnnotations off + LibraryLinkDisplay "all" + WideLines off + ShowLineDimensions off + ShowPortDataTypes off + ShowDesignRanges off + ShowLoopsOnError on + IgnoreBidirectionalLines off + ShowStorageClass off + ShowTestPointIcons on + ShowSignalResolutionIcons on + ShowViewerIcons on + SortedOrder off + ExecutionContextIcon off + ShowLinearizationAnnotations on + ShowMarkup on + BlockNameDataTip off + BlockParametersDataTip off + BlockDescriptionStringDataTip off + ToolBar on + StatusBar on + BrowserShowLibraryLinks on + BrowserLookUnderMasks on + SimulationMode "normal" + PauseTimes "5" + NumberOfSteps 1 + SnapshotBufferSize 10 + SnapshotInterval 10 + NumberOfLastSnapshots 0 + LinearizationMsg "none" + Profile off + ParamWorkspaceSource "MATLABWorkspace" + RecordCoverage off + CovSaveName "covdata" + CovMetricSettings "dw" + CovNameIncrementing off + CovHtmlReporting on + CovForceBlockReductionOff on + CovEnableCumulative on + covSaveCumulativeToWorkspaceVar on + CovSaveSingleToWorkspaceVar on + CovCumulativeReport off + CovReportOnPause on + CovModelRefEnable "Off" + CovExternalEMLEnable off + CovSFcnEnable off + CovBoundaryAbsTol 0.000010 + CovBoundaryRelTol 0.010000 + CovUseTimeInterval off + CovStartTime 0 + CovStopTime 0 + ExtModeBatchMode off + ExtModeEnableFloating on + ExtModeTrigType "manual" + ExtModeTrigMode "normal" + ExtModeTrigPort "1" + ExtModeTrigElement "any" + ExtModeTrigDuration 1000 + ExtModeTrigDurationFloating "auto" + ExtModeTrigHoldOff 0 + ExtModeTrigDelay 0 + ExtModeTrigDirection "rising" + ExtModeTrigLevel 0 + ExtModeArchiveMode "off" + ExtModeAutoIncOneShot off + ExtModeIncDirWhenArm off + ExtModeAddSuffixToVar off + ExtModeWriteAllDataToWs off + ExtModeArmWhenConnect on + ExtModeSkipDownloadWhenConnect off + ExtModeLogAll on + ExtModeAutoUpdateStatusClock on + ShowModelReferenceBlockVersion off + ShowModelReferenceBlockIO off + Array { + Type "Handle" + Dimension 1 + Simulink.ConfigSet { + $ObjectID 6 + Version "1.15.0" + Array { + Type "Handle" + Dimension 8 + Simulink.SolverCC { + $ObjectID 7 + Version "1.15.0" + StartTime "0.0" + StopTime "10.0" + AbsTol "auto" + FixedStep "auto" + InitialStep "auto" + MaxNumMinSteps "-1" + MaxOrder 5 + ZcThreshold "auto" + ConsecutiveZCsStepRelTol "10*128*eps" + MaxConsecutiveZCs "1000" + ExtrapolationOrder 4 + NumberNewtonIterations 1 + MaxStep "auto" + MinStep "auto" + MaxConsecutiveMinStep "1" + RelTol "1e-3" + SolverMode "Auto" + EnableConcurrentExecution off + ConcurrentTasks off + Solver "ode45" + SolverName "ode45" + SolverJacobianMethodControl "auto" + ShapePreserveControl "DisableAll" + ZeroCrossControl "UseLocalSettings" + ZeroCrossAlgorithm "Nonadaptive" + AlgebraicLoopSolver "TrustRegion" + SolverResetMethod "Fast" + PositivePriorityOrder off + AutoInsertRateTranBlk off + SampleTimeConstraint "Unconstrained" + InsertRTBMode "Whenever possible" + } + Simulink.DataIOCC { + $ObjectID 8 + Version "1.15.0" + Decimation "1" + ExternalInput "[t, u]" + FinalStateName "xFinal" + InitialState "xInitial" + LimitDataPoints on + MaxDataPoints "1000" + LoadExternalInput off + LoadInitialState off + SaveFinalState off + SaveCompleteFinalSimState off + SaveFormat "Array" + SignalLoggingSaveFormat "Dataset" + SaveOutput on + SaveState off + SignalLogging on + DSMLogging on + InspectSignalLogs off + VisualizeSimOutput on + SaveTime on + ReturnWorkspaceOutputs off + StateSaveName "xout" + TimeSaveName "tout" + OutputSaveName "yout" + SignalLoggingName "logsout" + DSMLoggingName "dsmout" + OutputOption "RefineOutputTimes" + OutputTimes "[]" + ReturnWorkspaceOutputsName "out" + Refine "1" + } + Simulink.OptimizationCC { + $ObjectID 9 + Version "1.15.0" + Array { + Type "Cell" + Dimension 8 + Cell "BooleansAsBitfields" + Cell "PassReuseOutputArgsAs" + Cell "PassReuseOutputArgsThreshold" + Cell "ZeroExternalMemoryAtStartup" + Cell "ZeroInternalMemoryAtStartup" + Cell "OptimizeModelRefInitCode" + Cell "NoFixptDivByZeroProtection" + Cell "UseSpecifiedMinMax" + PropName "DisabledProps" + } + BlockReduction on + BooleanDataType on + ConditionallyExecuteInputs on + InlineParams off + UseDivisionForNetSlopeComputation "off" + UseFloatMulNetSlope off + DefaultUnderspecifiedDataType "double" + UseSpecifiedMinMax off + InlineInvariantSignals off + OptimizeBlockIOStorage on + BufferReuse on + EnhancedBackFolding off + CachingGlobalReferences off + GlobalBufferReuse on + StrengthReduction off + ExpressionFolding on + BooleansAsBitfields off + BitfieldContainerType "uint_T" + EnableMemcpy on + MemcpyThreshold 64 + PassReuseOutputArgsAs "Structure reference" + PassReuseOutputArgsThreshold 12 + ExpressionDepthLimit 128 + LocalBlockOutputs on + RollThreshold 5 + StateBitsets off + DataBitsets off + ActiveStateOutputEnumStorageType "Native Integer" + ZeroExternalMemoryAtStartup on + ZeroInternalMemoryAtStartup on + InitFltsAndDblsToZero off + NoFixptDivByZeroProtection off + EfficientFloat2IntCast off + EfficientMapNaN2IntZero on + OptimizeModelRefInitCode off + LifeSpan "inf" + MaxStackSize "Inherit from target" + BufferReusableBoundary on + SimCompilerOptimization "off" + AccelVerboseBuild off + } + Simulink.DebuggingCC { + $ObjectID 10 + Version "1.15.0" + RTPrefix "error" + ConsistencyChecking "none" + ArrayBoundsChecking "none" + SignalInfNanChecking "none" + SignalRangeChecking "none" + ReadBeforeWriteMsg "UseLocalSettings" + WriteAfterWriteMsg "UseLocalSettings" + WriteAfterReadMsg "UseLocalSettings" + AlgebraicLoopMsg "warning" + ArtificialAlgebraicLoopMsg "warning" + SaveWithDisabledLinksMsg "warning" + SaveWithParameterizedLinksMsg "warning" + CheckSSInitialOutputMsg on + UnderspecifiedInitializationDetection "Simplified" + MergeDetectMultiDrivingBlocksExec "error" + CheckExecutionContextPreStartOutputMsg off + CheckExecutionContextRuntimeOutputMsg off + SignalResolutionControl "UseLocalSettings" + BlockPriorityViolationMsg "warning" + MinStepSizeMsg "warning" + TimeAdjustmentMsg "none" + MaxConsecutiveZCsMsg "error" + MaskedZcDiagnostic "warning" + IgnoredZcDiagnostic "warning" + SolverPrmCheckMsg "warning" + InheritedTsInSrcMsg "warning" + DiscreteInheritContinuousMsg "warning" + MultiTaskDSMMsg "error" + MultiTaskCondExecSysMsg "error" + MultiTaskRateTransMsg "error" + SingleTaskRateTransMsg "none" + TasksWithSamePriorityMsg "warning" + SigSpecEnsureSampleTimeMsg "warning" + CheckMatrixSingularityMsg "none" + IntegerOverflowMsg "warning" + Int32ToFloatConvMsg "warning" + ParameterDowncastMsg "error" + ParameterOverflowMsg "error" + ParameterUnderflowMsg "none" + ParameterPrecisionLossMsg "warning" + ParameterTunabilityLossMsg "warning" + FixptConstUnderflowMsg "none" + FixptConstOverflowMsg "none" + FixptConstPrecisionLossMsg "none" + UnderSpecifiedDataTypeMsg "none" + UnnecessaryDatatypeConvMsg "none" + VectorMatrixConversionMsg "none" + InvalidFcnCallConnMsg "error" + FcnCallInpInsideContextMsg "EnableAllAsError" + SignalLabelMismatchMsg "none" + UnconnectedInputMsg "warning" + UnconnectedOutputMsg "warning" + UnconnectedLineMsg "warning" + SFcnCompatibilityMsg "none" + FrameProcessingCompatibilityMsg "error" + UniqueDataStoreMsg "none" + BusObjectLabelMismatch "warning" + RootOutportRequireBusObject "warning" + AssertControl "UseLocalSettings" + ModelReferenceIOMsg "none" + ModelReferenceMultiInstanceNormalModeStructChecksumCheck "error" + ModelReferenceVersionMismatchMessage "none" + ModelReferenceIOMismatchMessage "none" + UnknownTsInhSupMsg "warning" + ModelReferenceDataLoggingMessage "warning" + ModelReferenceSymbolNameMessage "warning" + ModelReferenceExtraNoncontSigs "error" + StateNameClashWarn "none" + SimStateInterfaceChecksumMismatchMsg "warning" + SimStateOlderReleaseMsg "error" + InitInArrayFormatMsg "warning" + StrictBusMsg "ErrorLevel1" + BusNameAdapt "WarnAndRepair" + NonBusSignalsTreatedAsBus "none" + BlockIODiagnostic "none" + SFUnusedDataAndEventsDiag "warning" + SFUnexpectedBacktrackingDiag "warning" + SFInvalidInputDataAccessInChartInitDiag "warning" + SFNoUnconditionalDefaultTransitionDiag "warning" + SFTransitionOutsideNaturalParentDiag "warning" + SFUnconditionalTransitionShadowingDiag "warning" + SFUndirectedBroadcastEventsDiag "warning" + SFTransitionActionBeforeConditionDiag "warning" + SFOutputUsedAsStateInMooreChartDiag "error" + IntegerSaturationMsg "warning" + } + Simulink.HardwareCC { + $ObjectID 11 + Version "1.15.0" + ProdBitPerChar 8 + ProdBitPerShort 16 + ProdBitPerInt 32 + ProdBitPerLong 32 + ProdBitPerLongLong 64 + ProdBitPerFloat 32 + ProdBitPerDouble 64 + ProdBitPerPointer 32 + ProdLargestAtomicInteger "Char" + ProdLargestAtomicFloat "None" + ProdIntDivRoundTo "Undefined" + ProdEndianess "Unspecified" + ProdWordSize 32 + ProdShiftRightIntArith on + ProdLongLongMode off + ProdHWDeviceType "32-bit Generic" + TargetBitPerChar 8 + TargetBitPerShort 16 + TargetBitPerInt 32 + TargetBitPerLong 32 + TargetBitPerLongLong 64 + TargetBitPerFloat 32 + TargetBitPerDouble 64 + TargetBitPerPointer 32 + TargetLargestAtomicInteger "Char" + TargetLargestAtomicFloat "None" + TargetShiftRightIntArith on + TargetLongLongMode off + TargetIntDivRoundTo "Undefined" + TargetEndianess "Unspecified" + TargetWordSize 32 + TargetPreprocMaxBitsSint 32 + TargetPreprocMaxBitsUint 32 + TargetHWDeviceType "Specified" + TargetUnknown off + ProdEqTarget on + } + Simulink.ModelReferenceCC { + $ObjectID 12 + Version "1.15.0" + UpdateModelReferenceTargets "IfOutOfDateOrStructuralChange" + CheckModelReferenceTargetMessage "error" + EnableParallelModelReferenceBuilds off + ParallelModelReferenceErrorOnInvalidPool on + ParallelModelReferenceMATLABWorkerInit "None" + ModelReferenceNumInstancesAllowed "Multi" + PropagateVarSize "Infer from blocks in model" + ModelReferencePassRootInputsByReference on + ModelReferenceMinAlgLoopOccurrences off + PropagateSignalLabelsOutOfModel off + SupportModelReferenceSimTargetCustomCode off + } + Simulink.SFSimCC { + $ObjectID 13 + Version "1.15.0" + SFSimOverflowDetection on + SFSimEcho on + SimCtrlC on + SimIntegrity on + SimUseLocalCustomCode off + SimParseCustomCode on + SimBuildMode "sf_incremental_build" + SimGenImportedTypeDefs off + } + Simulink.RTWCC { + $BackupClass "Simulink.RTWCC" + $ObjectID 14 + Version "1.15.0" + Array { + Type "Cell" + Dimension 15 + Cell "IncludeHyperlinkInReport" + Cell "GenerateTraceInfo" + Cell "GenerateTraceReport" + Cell "GenerateTraceReportSl" + Cell "GenerateTraceReportSf" + Cell "GenerateTraceReportEml" + Cell "PortableWordSizes" + Cell "GenerateWebview" + Cell "GenerateCodeMetricsReport" + Cell "GenerateCodeReplacementReport" + Cell "GenerateErtSFunction" + Cell "CreateSILPILBlock" + Cell "CodeExecutionProfiling" + Cell "CodeProfilingSaveOptions" + Cell "CodeProfilingInstrumentation" + PropName "DisabledProps" + } + SystemTargetFile "grt.tlc" + TLCOptions "" + GenCodeOnly off + MakeCommand "make_rtw" + GenerateMakefile on + PackageGeneratedCodeAndArtifacts off + PackageName "" + TemplateMakefile "grt_default_tmf" + PostCodeGenCommand "" + Description "" + GenerateReport off + SaveLog off + RTWVerbose on + RetainRTWFile off + ProfileTLC off + TLCDebug off + TLCCoverage off + TLCAssert off + RTWUseLocalCustomCode off + RTWUseSimCustomCode off + CustomSourceCode "" + CustomHeaderCode "" + CustomInclude "" + CustomSource "" + CustomLibrary "" + CustomInitializer "" + CustomTerminator "" + Toolchain "Automatically locate an installed toolchain" + BuildConfiguration "Faster Builds" + IncludeHyperlinkInReport off + LaunchReport off + PortableWordSizes off + CreateSILPILBlock "None" + CodeExecutionProfiling off + CodeExecutionProfileVariable "executionProfile" + CodeProfilingSaveOptions "SummaryOnly" + CodeProfilingInstrumentation off + SILDebugging off + TargetLang "C" + IncludeBusHierarchyInRTWFileBlockHierarchyMap off + GenerateTraceInfo off + GenerateTraceReport off + GenerateTraceReportSl off + GenerateTraceReportSf off + GenerateTraceReportEml off + GenerateWebview off + GenerateCodeMetricsReport off + GenerateCodeReplacementReport off + GenerateMissedCodeReplacementReport off + RTWCompilerOptimization "off" + RTWCustomCompilerOptimizations "" + CheckMdlBeforeBuild "Off" + SharedConstantsCachingThreshold 1024 + Array { + Type "Handle" + Dimension 2 + Simulink.CodeAppCC { + $ObjectID 15 + Version "1.15.0" + Array { + Type "Cell" + Dimension 24 + Cell "IgnoreCustomStorageClasses" + Cell "ParameterTuningSideEffectCode" + Cell "IgnoreTestpoints" + Cell "InsertBlockDesc" + Cell "InsertPolySpaceComments" + Cell "SFDataObjDesc" + Cell "MATLABFcnDesc" + Cell "SimulinkDataObjDesc" + Cell "DefineNamingRule" + Cell "SignalNamingRule" + Cell "ParamNamingRule" + Cell "InternalIdentifier" + Cell "InlinedPrmAccess" + Cell "CustomSymbolStr" + Cell "CustomSymbolStrGlobalVar" + Cell "CustomSymbolStrType" + Cell "CustomSymbolStrField" + Cell "CustomSymbolStrFcn" + Cell "CustomSymbolStrFcnArg" + Cell "CustomSymbolStrBlkIO" + Cell "CustomSymbolStrTmpVar" + Cell "CustomSymbolStrMacro" + Cell "CustomSymbolStrUtil" + Cell "ReqsInCode" + PropName "DisabledProps" + } + ForceParamTrailComments off + GenerateComments on + CommentStyle "Auto" + IgnoreCustomStorageClasses on + IgnoreTestpoints off + IncHierarchyInIds off + MaxIdLength 31 + PreserveName off + PreserveNameWithParent off + ShowEliminatedStatement off + OperatorAnnotations off + IncAutoGenComments off + SimulinkDataObjDesc off + SFDataObjDesc off + MATLABFcnDesc off + IncDataTypeInIds off + MangleLength 1 + CustomSymbolStrGlobalVar "$R$N$M" + CustomSymbolStrType "$N$R$M_T" + CustomSymbolStrField "$N$M" + CustomSymbolStrFcn "$R$N$M$F" + CustomSymbolStrFcnArg "rt$I$N$M" + CustomSymbolStrBlkIO "rtb_$N$M" + CustomSymbolStrTmpVar "$N$M" + CustomSymbolStrMacro "$R$N$M" + CustomSymbolStrUtil "$N$C" + DefineNamingRule "None" + ParamNamingRule "None" + SignalNamingRule "None" + InsertBlockDesc off + InsertPolySpaceComments off + SimulinkBlockComments on + MATLABSourceComments off + EnableCustomComments off + InternalIdentifier "Shortened" + InlinedPrmAccess "Literals" + ReqsInCode off + UseSimReservedNames off + } + Simulink.GRTTargetCC { + $BackupClass "Simulink.TargetCC" + $ObjectID 16 + Version "1.15.0" + Array { + Type "Cell" + Dimension 13 + Cell "GeneratePreprocessorConditionals" + Cell "IncludeMdlTerminateFcn" + Cell "SuppressErrorStatus" + Cell "ERTCustomFileBanners" + Cell "GenerateSampleERTMain" + Cell "GenerateTestInterfaces" + Cell "ModelStepFunctionPrototypeControlCompliant" + Cell "GenerateAllocFcn" + Cell "PurelyIntegerCode" + Cell "SupportComplex" + Cell "SupportAbsoluteTime" + Cell "SupportContinuousTime" + Cell "SupportNonInlinedSFcns" + PropName "DisabledProps" + } + TargetFcnLib "ansi_tfl_table_tmw.mat" + TargetLibSuffix "" + TargetPreCompLibLocation "" + GenFloatMathFcnCalls "NOT IN USE" + TargetLangStandard "C89/C90 (ANSI)" + CodeReplacementLibrary "None" + UtilityFuncGeneration "Auto" + ERTMultiwordTypeDef "System defined" + ERTMultiwordLength 256 + MultiwordLength 2048 + GenerateFullHeader on + InferredTypesCompatibility off + GenerateSampleERTMain off + GenerateTestInterfaces off + ModelReferenceCompliant on + ParMdlRefBuildCompliant on + CompOptLevelCompliant on + ConcurrentExecutionCompliant on + IncludeMdlTerminateFcn on + GeneratePreprocessorConditionals "Disable all" + CombineOutputUpdateFcns on + CombineSignalStateStructs off + SuppressErrorStatus off + ERTFirstTimeCompliant off + IncludeFileDelimiter "Auto" + ERTCustomFileBanners off + SupportAbsoluteTime on + LogVarNameModifier "rt_" + MatFileLogging on + MultiInstanceERTCode off + CodeInterfacePackaging "Nonreusable function" + SupportNonFinite on + SupportComplex on + PurelyIntegerCode off + SupportContinuousTime on + SupportNonInlinedSFcns on + SupportVariableSizeSignals off + ParenthesesLevel "Nominal" + CastingMode "Nominal" + MATLABClassNameForMDSCustomization "Simulink.SoftwareTarget.GRTCustomization" + ModelStepFunctionPrototypeControlCompliant off + CPPClassGenCompliant on + AutosarCompliant off + GRTInterface off + GenerateAllocFcn off + GenerateSharedConstants on + UseMalloc off + ExtMode off + ExtModeStaticAlloc off + ExtModeTesting off + ExtModeStaticAllocSize 1000000 + ExtModeTransport 0 + ExtModeMexFile "ext_comm" + ExtModeIntrfLevel "Level1" + RTWCAPISignals off + RTWCAPIParams off + RTWCAPIStates off + RTWCAPIRootIO off + GenerateASAP2 off + MultiInstanceErrorCode "Error" + } + PropName "Components" + } + } + PropName "Components" + } + Name "Configuration" + CurrentDlgPage "Solver" + ConfigPrmDlgPosition [ 420, 220, 1500, 860 ] + } + PropName "ConfigurationSets" + } + ExplicitPartitioning off + BlockDefaults { + ForegroundColor "black" + BackgroundColor "white" + DropShadow off + NamePlacement "normal" + FontName "Helvetica" + FontSize 10 + FontWeight "normal" + FontAngle "normal" + ShowName on + BlockRotation 0 + BlockMirror off + } + AnnotationDefaults { + HorizontalAlignment "center" + VerticalAlignment "middle" + ForegroundColor "black" + BackgroundColor "white" + DropShadow off + FontName "Helvetica" + FontSize 10 + FontWeight "normal" + FontAngle "normal" + UseDisplayTextAsClickCallback off + } + LineDefaults { + FontName "Helvetica" + FontSize 9 + FontWeight "normal" + FontAngle "normal" + } + MaskDefaults { + SelfModifiable "off" + IconFrame "on" + IconOpaque "on" + RunInitForIconRedraw "off" + IconRotate "none" + PortRotate "default" + IconUnits "autoscale" + } + MaskParameterDefaults { + Evaluate "on" + Tunable "on" + NeverSave "off" + Internal "off" + ReadOnly "off" + Enabled "on" + Visible "on" + ToolTip "on" + } + BlockParameterDefaults { + Block { + BlockType Constant + Value "1" + VectorParams1D on + SamplingMode "Sample based" + OutMin "[]" + OutMax "[]" + OutDataTypeStr "Inherit: Inherit from 'Constant value'" + LockScale off + SampleTime "inf" + FramePeriod "inf" + PreserveConstantTs off + } + Block { + BlockType Demux + Outputs "4" + DisplayOption "none" + BusSelectionMode off + } + Block { + BlockType Derivative + CoefficientInTFapproximation "inf" + } + Block { + BlockType Gain + Gain "1" + Multiplication "Element-wise(K.*u)" + ParamMin "[]" + ParamMax "[]" + ParamDataTypeStr "Inherit: Same as input" + OutMin "[]" + OutMax "[]" + OutDataTypeStr "Inherit: Same as input" + LockScale off + RndMeth "Floor" + SaturateOnIntegerOverflow on + SampleTime "-1" + } + Block { + BlockType Inport + Port "1" + OutputFunctionCall off + OutMin "[]" + OutMax "[]" + OutDataTypeStr "Inherit: auto" + LockScale off + BusOutputAsStruct off + PortDimensions "-1" + VarSizeSig "Inherit" + SampleTime "-1" + SignalType "auto" + SamplingMode "auto" + LatchByDelayingOutsideSignal off + LatchInputForFeedbackSignals off + Interpolate on + } + Block { + BlockType Integrator + ExternalReset "none" + InitialConditionSource "internal" + InitialCondition "0" + LimitOutput off + UpperSaturationLimit "inf" + LowerSaturationLimit "-inf" + WrapState off + WrappedStateUpperValue "pi" + WrappedStateLowerValue "-pi" + ShowSaturationPort off + ShowStatePort off + AbsoluteTolerance "auto" + IgnoreLimit off + ZeroCross on + ContinuousStateAttributes "''" + } + Block { + BlockType Math + Operator "exp" + OutputSignalType "auto" + SampleTime "-1" + OutMin "[]" + OutMax "[]" + OutDataTypeStr "Inherit: Same as first input" + LockScale off + RndMeth "Floor" + SaturateOnIntegerOverflow on + IntermediateResultsDataTypeStr "Inherit: Inherit via internal rule" + AlgorithmType "Newton-Raphson" + Iterations "3" + } + Block { + BlockType Outport + Port "1" + OutMin "[]" + OutMax "[]" + OutDataTypeStr "Inherit: auto" + LockScale off + BusOutputAsStruct off + PortDimensions "-1" + VarSizeSig "Inherit" + SampleTime "-1" + SignalType "auto" + SamplingMode "auto" + SourceOfInitialOutputValue "Dialog" + OutputWhenDisabled "held" + InitialOutput "[]" + } + Block { + BlockType Product + Inputs "2" + Multiplication "Element-wise(.*)" + CollapseMode "All dimensions" + CollapseDim "1" + InputSameDT on + OutMin "[]" + OutMax "[]" + OutDataTypeStr "Inherit: Same as first input" + LockScale off + RndMeth "Zero" + SaturateOnIntegerOverflow on + SampleTime "-1" + } + Block { + BlockType S-Function + FunctionName "system" + SFunctionModules "''" + PortCounts "[]" + SFunctionDeploymentMode off + EnableBusSupport off + } + Block { + BlockType Sqrt + Operator "sqrt" + OutputSignalType "auto" + SampleTime "-1" + OutMin "[]" + OutMax "[]" + OutDataTypeStr "Inherit: Same as first input" + LockScale off + RndMeth "Floor" + SaturateOnIntegerOverflow on + IntermediateResultsDataTypeStr "Inherit: Inherit via internal rule" + AlgorithmType "Exact" + Iterations "3" + } + Block { + BlockType SubSystem + ShowPortLabels "FromPortIcon" + Permissions "ReadWrite" + PermitHierarchicalResolution "All" + TreatAsAtomicUnit off + MinAlgLoopOccurrences off + PropExecContextOutsideSubsystem off + CheckFcnCallInpInsideContextMsg off + SystemSampleTime "-1" + RTWSystemCode "Auto" + RTWFcnNameOpts "Auto" + RTWFileNameOpts "Auto" + FunctionInterfaceSpec "void_void" + FunctionWithSeparateData off + RTWMemSecFuncInitTerm "Inherit from model" + RTWMemSecFuncExecute "Inherit from model" + RTWMemSecDataConstants "Inherit from model" + RTWMemSecDataInternal "Inherit from model" + RTWMemSecDataParameters "Inherit from model" + SimViewingDevice off + DataTypeOverride "UseLocalSettings" + DataTypeOverrideAppliesTo "AllNumericTypes" + MinMaxOverflowLogging "UseLocalSettings" + Opaque off + MaskHideContents off + SFBlockType "NONE" + Variant off + GeneratePreprocessorConditionals off + ContentPreviewEnabled off + IsWebBlock off + } + Block { + BlockType Sum + IconShape "rectangular" + Inputs "++" + CollapseMode "All dimensions" + CollapseDim "1" + InputSameDT on + AccumDataTypeStr "Inherit: Inherit via internal rule" + OutMin "[]" + OutMax "[]" + OutDataTypeStr "Inherit: Same as first input" + LockScale off + RndMeth "Floor" + SaturateOnIntegerOverflow on + SampleTime "-1" + } + Block { + BlockType Terminator + } + Block { + BlockType UnitDelay + InitialCondition "0" + InputProcessing "Inherited" + SampleTime "1" + StateMustResolveToSignalObject off + CodeGenStateStorageClass "Auto" + HasFrameUpgradeWarning on + } + } + System { + Name "atlas_impctrl_library" + Location [49, 24, 1920, 1080] + Open on + ModelBrowserVisibility off + ModelBrowserWidth 200 + ScreenColor "white" + PaperOrientation "landscape" + PaperPositionMode "auto" + PaperType "A4" + PaperUnits "centimeters" + TiledPaperMargins [1.270000, 1.270000, 1.270000, 1.270000] + TiledPageScale 1 + ShowPageBoundaries off + ZoomFactor "100" + ReportName "simulink-default.rpt" + SIDHighWatermark "734" + Block { + BlockType SubSystem + Name "atlas3_cart_impctrl" + SID "114" + Ports [11, 1] + Position [635, 1087, 915, 1363] + ZOrder 139 + LibraryVersion "*1.4" + TreatAsAtomicUnit on + RequestExecContextInheritance off + System { + Name "atlas3_cart_impctrl" + Location [0, 0, 960, 1160] + Open off + ModelBrowserVisibility off + ModelBrowserWidth 200 + ScreenColor "white" + PaperOrientation "landscape" + PaperPositionMode "auto" + PaperType "A4" + PaperUnits "centimeters" + TiledPaperMargins [1.270000, 1.270000, 1.270000, 1.270000] + TiledPageScale 1 + ShowPageBoundaries off + ZoomFactor "80" + Block { + BlockType Inport + Name "q" + SID "115" + Position [55, 103, 85, 117] + ZOrder 53 + IconDisplay "Port number" + } + Block { + BlockType Inport + Name "qD" + SID "116" + Position [55, 158, 85, 172] + ZOrder 54 + Port "2" + IconDisplay "Port number" + } + Block { + BlockType Inport + Name "qDD" + SID "117" + Position [55, 188, 85, 202] + ZOrder 55 + Port "3" + IconDisplay "Port number" + } + Block { + BlockType Inport + Name "tauC" + SID "118" + Position [55, 458, 85, 472] + ZOrder 59 + Port "4" + IconDisplay "Port number" + } + Block { + BlockType Inport + Name "xd" + SID "119" + Position [55, 493, 85, 507] + ZOrder 60 + Port "5" + IconDisplay "Port number" + } + Block { + BlockType Inport + Name "xdD" + SID "120" + Position [55, 533, 85, 547] + ZOrder 61 + Port "6" + IconDisplay "Port number" + } + Block { + BlockType Inport + Name "xdDD" + SID "121" + Position [55, 593, 85, 607] + ZOrder 62 + Port "7" + IconDisplay "Port number" + } + Block { + BlockType Inport + Name "Kd" + SID "122" + Position [220, 808, 250, 822] + ZOrder 63 + Port "8" + IconDisplay "Port number" + } + Block { + BlockType Inport + Name "D_epsilon" + SID "123" + Position [220, 838, 250, 852] + ZOrder 77 + Port "9" + IconDisplay "Port number" + } + Block { + BlockType Inport + Name "M" + SID "124" + Position [340, 83, 370, 97] + ZOrder 78 + Port "10" + IconDisplay "Port number" + } + Block { + BlockType Inport + Name "g" + SID "125" + Position [30, 763, 60, 777] + ZOrder 79 + Port "11" + IconDisplay "Port number" + } + Block { + BlockType SubSystem + Name "DDD" + SID "127" + Ports [2, 1] + Position [330, 800, 370, 860] + ZOrder 76 + RequestExecContextInheritance off + System { + Name "DDD" + Location [660, 120, 1920, 1072] + Open off + ModelBrowserVisibility off + ModelBrowserWidth 200 + ScreenColor "white" + PaperOrientation "landscape" + PaperPositionMode "auto" + PaperType "A4" + PaperUnits "centimeters" + TiledPaperMargins [1.270000, 1.270000, 1.270000, 1.270000] + TiledPageScale 1 + ShowPageBoundaries off + ZoomFactor "100" + Block { + BlockType Inport + Name "Kd" + SID "128" + Position [20, 243, 50, 257] + ZOrder 76 + IconDisplay "Port number" + } + Block { + BlockType Inport + Name "D_epsilon" + SID "129" + Position [30, 438, 60, 452] + ZOrder 91 + Port "2" + IconDisplay "Port number" + } + Block { + BlockType Constant + Name "Constant" + SID "131" + Position [645, 120, 675, 150] + ZOrder 86 + Value "2" + } + Block { + BlockType SubSystem + Name "Eigenvalue" + SID "132" + Ports [1, 3] + Position [120, 226, 190, 274] + ZOrder 75 + LibraryVersion "1.32" + ErrorFcn "Stateflow.Translate.translate" + PermitHierarchicalResolution "ExplicitOnly" + TreatAsAtomicUnit on + RequestExecContextInheritance off + SFBlockType "MATLAB Function" + System { + Name "Eigenvalue" + Location [223, 338, 826, 833] + Open off + ModelBrowserVisibility off + ModelBrowserWidth 200 + ScreenColor "white" + PaperOrientation "landscape" + PaperPositionMode "auto" + PaperType "A4" + PaperUnits "centimeters" + TiledPaperMargins [1.270000, 1.270000, 1.270000, 1.270000] + TiledPageScale 1 + ShowPageBoundaries off + ZoomFactor "100" + SIDHighWatermark "36" + Block { + BlockType Inport + Name "A" + SID "132::1" + Position [20, 101, 40, 119] + ZOrder -1 + IconDisplay "Port number" + } + Block { + BlockType Demux + Name " Demux " + SID "132::35" + Ports [1, 1] + Position [270, 245, 320, 285] + ZOrder 19 + Outputs "1" + } + Block { + BlockType S-Function + Name " SFunction " + SID "132::34" + Tag "Stateflow S-Function atlas_impctrl_library 2" + Ports [1, 4] + Position [180, 102, 230, 203] + ZOrder 18 + FunctionName "sf_sfun" + PortCounts "[1 4]" + Port { + PortNumber 2 + Name "V" + RTWStorageClass "Auto" + DataLoggingNameMode "SignalName" + } + Port { + PortNumber 3 + Name "E" + RTWStorageClass "Auto" + DataLoggingNameMode "SignalName" + } + Port { + PortNumber 4 + Name "D" + RTWStorageClass "Auto" + DataLoggingNameMode "SignalName" + } + } + Block { + BlockType Terminator + Name " Terminator " + SID "132::36" + Position [460, 256, 480, 274] + ZOrder 20 + } + Block { + BlockType Outport + Name "V" + SID "132::5" + Position [460, 101, 480, 119] + ZOrder -5 + IconDisplay "Port number" + } + Block { + BlockType Outport + Name "E" + SID "132::19" + Position [460, 136, 480, 154] + ZOrder 10 + Port "2" + IconDisplay "Port number" + } + Block { + BlockType Outport + Name "D" + SID "132::20" + Position [460, 171, 480, 189] + ZOrder 11 + Port "3" + IconDisplay "Port number" + } + Line { + ZOrder 13 + SrcBlock "A" + SrcPort 1 + DstBlock " SFunction " + DstPort 1 + } + Line { + Name "V" + ZOrder 14 + Labels [0, 0] + SrcBlock " SFunction " + SrcPort 2 + DstBlock "V" + DstPort 1 + } + Line { + Name "E" + ZOrder 15 + Labels [0, 0] + SrcBlock " SFunction " + SrcPort 3 + DstBlock "E" + DstPort 1 + } + Line { + Name "D" + ZOrder 16 + Labels [0, 0] + SrcBlock " SFunction " + SrcPort 4 + DstBlock "D" + DstPort 1 + } + Line { + ZOrder 17 + SrcBlock " Demux " + SrcPort 1 + DstBlock " Terminator " + DstPort 1 + } + Line { + ZOrder 18 + SrcBlock " SFunction " + SrcPort 1 + DstBlock " Demux " + DstPort 1 + } + } + } + Block { + BlockType SubSystem + Name "Inverse" + SID "188" + Ports [1, 1] + Position [310, 122, 380, 168] + ZOrder 92 + LibraryVersion "1.32" + ErrorFcn "Stateflow.Translate.translate" + PermitHierarchicalResolution "ExplicitOnly" + TreatAsAtomicUnit on + RequestExecContextInheritance off + SFBlockType "MATLAB Function" + System { + Name "Inverse" + Location [223, 338, 826, 833] + Open off + ModelBrowserVisibility off + ModelBrowserWidth 200 + ScreenColor "white" + PaperOrientation "landscape" + PaperPositionMode "auto" + PaperType "A4" + PaperUnits "centimeters" + TiledPaperMargins [1.270000, 1.270000, 1.270000, 1.270000] + TiledPageScale 1 + ShowPageBoundaries off + ZoomFactor "100" + SIDHighWatermark "29" + Block { + BlockType Inport + Name "u" + SID "188::1" + Position [20, 101, 40, 119] + ZOrder -1 + IconDisplay "Port number" + } + Block { + BlockType Demux + Name " Demux " + SID "188::28" + Ports [1, 1] + Position [270, 230, 320, 270] + ZOrder 14 + Outputs "1" + } + Block { + BlockType S-Function + Name " SFunction " + SID "188::27" + Tag "Stateflow S-Function atlas_impctrl_library 6" + Ports [1, 2] + Position [180, 100, 230, 160] + ZOrder 13 + FunctionName "sf_sfun" + PortCounts "[1 2]" + Port { + PortNumber 2 + Name "y" + RTWStorageClass "Auto" + DataLoggingNameMode "SignalName" + } + } + Block { + BlockType Terminator + Name " Terminator " + SID "188::29" + Position [460, 241, 480, 259] + ZOrder 15 + } + Block { + BlockType Outport + Name "y" + SID "188::5" + Position [460, 101, 480, 119] + ZOrder -5 + IconDisplay "Port number" + } + Line { + ZOrder 9 + SrcBlock "u" + SrcPort 1 + DstBlock " SFunction " + DstPort 1 + } + Line { + Name "y" + ZOrder 10 + Labels [0, 0] + SrcBlock " SFunction " + SrcPort 2 + DstBlock "y" + DstPort 1 + } + Line { + ZOrder 11 + SrcBlock " Demux " + SrcPort 1 + DstBlock " Terminator " + DstPort 1 + } + Line { + ZOrder 12 + SrcBlock " SFunction " + SrcPort 1 + DstBlock " Demux " + DstPort 1 + } + } + } + Block { + BlockType Product + Name "Product" + SID "133" + Ports [2, 1] + Position [750, 252, 780, 283] + ZOrder 82 + InputSameDT off + OutDataTypeStr "Inherit: Inherit via internal rule" + RndMeth "Floor" + SaturateOnIntegerOverflow off + } + Block { + BlockType Product + Name "Product1" + SID "134" + Ports [2, 1] + Position [645, 232, 675, 263] + ZOrder 83 + InputSameDT off + OutDataTypeStr "Inherit: Inherit via internal rule" + RndMeth "Floor" + SaturateOnIntegerOverflow off + } + Block { + BlockType Product + Name "Product2" + SID "135" + Ports [2, 1] + Position [590, 197, 620, 228] + ZOrder 84 + InputSameDT off + OutDataTypeStr "Inherit: Inherit via internal rule" + RndMeth "Floor" + SaturateOnIntegerOverflow off + } + Block { + BlockType Product + Name "Product3" + SID "136" + Ports [2, 1] + Position [690, 242, 720, 273] + ZOrder 85 + InputSameDT off + OutDataTypeStr "Inherit: Inherit via internal rule" + RndMeth "Floor" + SaturateOnIntegerOverflow off + } + Block { + BlockType Sqrt + Name "Sqrt" + SID "137" + Position [530, 350, 560, 380] + ZOrder 90 + } + Block { + BlockType Reference + Name "Transpose" + SID "138" + Ports [1, 1] + Position [445, 245, 500, 285] + ZOrder 80 + LibraryVersion "1.898" + SourceBlock "dspmtrx3/Transpose" + SourceType "Transpose" + ContentPreviewEnabled off + Hermitian off + overflowFlag off + } + Block { + BlockType Outport + Name "Dd" + SID "139" + Position [795, 278, 825, 292] + ZOrder 77 + IconDisplay "Port number" + } + Line { + ZOrder 1 + SrcBlock "Kd" + SrcPort 1 + DstBlock "Eigenvalue" + DstPort 1 + } + Line { + ZOrder 2 + SrcBlock "Eigenvalue" + SrcPort 1 + Points [99, 0; 0, -90] + DstBlock "Inverse" + DstPort 1 + } + Line { + ZOrder 3 + SrcBlock "Inverse" + SrcPort 1 + Points [32, 0; 0, 75] + Branch { + ZOrder 4 + DstBlock "Product2" + DstPort 2 + } + Branch { + ZOrder 5 + Points [0, 45] + DstBlock "Transpose" + DstPort 1 + } + } + Line { + ZOrder 6 + SrcBlock "Eigenvalue" + SrcPort 3 + Points [40, 0; 0, 100] + DstBlock "Sqrt" + DstPort 1 + } + Line { + ZOrder 7 + SrcBlock "Product" + SrcPort 1 + Points [3, 0; 0, 15] + DstBlock "Dd" + DstPort 1 + } + Line { + ZOrder 8 + SrcBlock "Constant" + SrcPort 1 + Points [11, 0; 0, 42; -147, 0; 0, 28] + DstBlock "Product2" + DstPort 1 + } + Line { + ZOrder 9 + SrcBlock "Product2" + SrcPort 1 + Points [5, 0] + DstBlock "Product1" + DstPort 1 + } + Line { + ZOrder 10 + SrcBlock "Product1" + SrcPort 1 + DstBlock "Product3" + DstPort 1 + } + Line { + ZOrder 11 + SrcBlock "Product3" + SrcPort 1 + DstBlock "Product" + DstPort 1 + } + Line { + ZOrder 12 + SrcBlock "Sqrt" + SrcPort 1 + Points [59, 0; 0, -100] + DstBlock "Product3" + DstPort 2 + } + Line { + ZOrder 13 + SrcBlock "Transpose" + SrcPort 1 + Points [87, 0; 0, 35; 143, 0] + DstBlock "Product" + DstPort 2 + } + Line { + ZOrder 14 + SrcBlock "D_epsilon" + SrcPort 1 + Points [543, 0; 0, -190] + DstBlock "Product1" + DstPort 2 + } + } + } + Block { + BlockType SubSystem + Name "Inverse" + SID "189" + Ports [1, 1] + Position [465, 102, 535, 148] + ZOrder 93 + LibraryVersion "1.32" + ErrorFcn "Stateflow.Translate.translate" + PermitHierarchicalResolution "ExplicitOnly" + TreatAsAtomicUnit on + RequestExecContextInheritance off + SFBlockType "MATLAB Function" + System { + Name "Inverse" + Location [223, 338, 826, 833] + Open off + ModelBrowserVisibility off + ModelBrowserWidth 200 + ScreenColor "white" + PaperOrientation "landscape" + PaperPositionMode "auto" + PaperType "A4" + PaperUnits "centimeters" + TiledPaperMargins [1.270000, 1.270000, 1.270000, 1.270000] + TiledPageScale 1 + ShowPageBoundaries off + ZoomFactor "100" + SIDHighWatermark "29" + Block { + BlockType Inport + Name "u" + SID "189::1" + Position [20, 101, 40, 119] + ZOrder -1 + IconDisplay "Port number" + } + Block { + BlockType Demux + Name " Demux " + SID "189::28" + Ports [1, 1] + Position [270, 230, 320, 270] + ZOrder 14 + Outputs "1" + } + Block { + BlockType S-Function + Name " SFunction " + SID "189::27" + Tag "Stateflow S-Function atlas_impctrl_library 7" + Ports [1, 2] + Position [180, 100, 230, 160] + ZOrder 13 + FunctionName "sf_sfun" + PortCounts "[1 2]" + Port { + PortNumber 2 + Name "y" + RTWStorageClass "Auto" + DataLoggingNameMode "SignalName" + } + } + Block { + BlockType Terminator + Name " Terminator " + SID "189::29" + Position [460, 241, 480, 259] + ZOrder 15 + } + Block { + BlockType Outport + Name "y" + SID "189::5" + Position [460, 101, 480, 119] + ZOrder -5 + IconDisplay "Port number" + } + Line { + ZOrder 9 + SrcBlock "u" + SrcPort 1 + DstBlock " SFunction " + DstPort 1 + } + Line { + Name "y" + ZOrder 10 + Labels [0, 0] + SrcBlock " SFunction " + SrcPort 2 + DstBlock "y" + DstPort 1 + } + Line { + ZOrder 11 + SrcBlock " Demux " + SrcPort 1 + DstBlock " Terminator " + DstPort 1 + } + Line { + ZOrder 12 + SrcBlock " SFunction " + SrcPort 1 + DstBlock " Demux " + DstPort 1 + } + } + } + Block { + BlockType Product + Name "Lambda1" + SID "140" + Ports [2, 1] + Position [355, 442, 385, 473] + ZOrder 31 + InputSameDT off + OutDataTypeStr "Inherit: Inherit via internal rule" + RndMeth "Floor" + SaturateOnIntegerOverflow off + } + Block { + BlockType SubSystem + Name "MATLAB J" + SID "141" + Ports [1, 1] + Position [180, 2, 250, 48] + ZOrder 81 + LibraryVersion "1.32" + ErrorFcn "Stateflow.Translate.translate" + PermitHierarchicalResolution "ExplicitOnly" + TreatAsAtomicUnit on + RequestExecContextInheritance off + SFBlockType "MATLAB Function" + System { + Name "MATLAB J" + Location [223, 338, 826, 833] + Open off + ModelBrowserVisibility off + ModelBrowserWidth 200 + ScreenColor "white" + PaperOrientation "landscape" + PaperPositionMode "auto" + PaperType "A4" + PaperUnits "centimeters" + TiledPaperMargins [1.270000, 1.270000, 1.270000, 1.270000] + TiledPageScale 1 + ShowPageBoundaries off + ZoomFactor "100" + SIDHighWatermark "32" + Block { + BlockType Inport + Name "qs" + SID "141::1" + Position [20, 101, 40, 119] + ZOrder -1 + IconDisplay "Port number" + } + Block { + BlockType Demux + Name " Demux " + SID "141::31" + Ports [1, 1] + Position [270, 230, 320, 270] + ZOrder 17 + Outputs "1" + } + Block { + BlockType S-Function + Name " SFunction " + SID "141::30" + Tag "Stateflow S-Function atlas_impctrl_library 4" + Ports [1, 2] + Position [180, 100, 230, 160] + ZOrder 16 + FunctionName "sf_sfun" + PortCounts "[1 2]" + Port { + PortNumber 2 + Name "Jg" + RTWStorageClass "Auto" + DataLoggingNameMode "SignalName" + } + } + Block { + BlockType Terminator + Name " Terminator " + SID "141::32" + Position [460, 241, 480, 259] + ZOrder 18 + } + Block { + BlockType Outport + Name "Jg" + SID "141::5" + Position [460, 101, 480, 119] + ZOrder -5 + IconDisplay "Port number" + } + Line { + ZOrder 9 + SrcBlock "qs" + SrcPort 1 + DstBlock " SFunction " + DstPort 1 + } + Line { + Name "Jg" + ZOrder 10 + Labels [0, 0] + SrcBlock " SFunction " + SrcPort 2 + DstBlock "Jg" + DstPort 1 + } + Line { + ZOrder 11 + SrcBlock " Demux " + SrcPort 1 + DstBlock " Terminator " + DstPort 1 + } + Line { + ZOrder 12 + SrcBlock " SFunction " + SrcPort 1 + DstBlock " Demux " + DstPort 1 + } + } + } + Block { + BlockType SubSystem + Name "MATLAB JD" + SID "142" + Ports [1, 1] + Position [180, 117, 250, 163] + ZOrder 80 + LibraryVersion "1.32" + ErrorFcn "Stateflow.Translate.translate" + PermitHierarchicalResolution "ExplicitOnly" + TreatAsAtomicUnit on + RequestExecContextInheritance off + SFBlockType "MATLAB Function" + System { + Name "MATLAB JD" + Location [223, 338, 826, 833] + Open off + ModelBrowserVisibility off + ModelBrowserWidth 200 + ScreenColor "white" + PaperOrientation "landscape" + PaperPositionMode "auto" + PaperType "A4" + PaperUnits "centimeters" + TiledPaperMargins [1.270000, 1.270000, 1.270000, 1.270000] + TiledPageScale 1 + ShowPageBoundaries off + ZoomFactor "100" + SIDHighWatermark "32" + Block { + BlockType Inport + Name "u" + SID "142::1" + Position [20, 101, 40, 119] + ZOrder -1 + IconDisplay "Port number" + } + Block { + BlockType Demux + Name " Demux " + SID "142::31" + Ports [1, 1] + Position [270, 230, 320, 270] + ZOrder 17 + Outputs "1" + } + Block { + BlockType S-Function + Name " SFunction " + SID "142::30" + Tag "Stateflow S-Function atlas_impctrl_library 5" + Ports [1, 2] + Position [180, 100, 230, 160] + ZOrder 16 + FunctionName "sf_sfun" + PortCounts "[1 2]" + Port { + PortNumber 2 + Name "y" + RTWStorageClass "Auto" + DataLoggingNameMode "SignalName" + } + } + Block { + BlockType Terminator + Name " Terminator " + SID "142::32" + Position [460, 241, 480, 259] + ZOrder 18 + } + Block { + BlockType Outport + Name "y" + SID "142::5" + Position [460, 101, 480, 119] + ZOrder -5 + IconDisplay "Port number" + } + Line { + ZOrder 9 + SrcBlock "u" + SrcPort 1 + DstBlock " SFunction " + DstPort 1 + } + Line { + Name "y" + ZOrder 10 + Labels [0, 0] + SrcBlock " SFunction " + SrcPort 2 + DstBlock "y" + DstPort 1 + } + Line { + ZOrder 11 + SrcBlock " Demux " + SrcPort 1 + DstBlock " Terminator " + DstPort 1 + } + Line { + ZOrder 12 + SrcBlock " SFunction " + SrcPort 1 + DstBlock " Demux " + DstPort 1 + } + } + } + Block { + BlockType Product + Name "Product1" + SID "143" + Ports [2, 1] + Position [450, 367, 480, 398] + ZOrder 30 + InputSameDT off + OutDataTypeStr "Inherit: Inherit via internal rule" + RndMeth "Floor" + SaturateOnIntegerOverflow off + } + Block { + BlockType Product + Name "Product10" + SID "144" + Ports [2, 1] + Position [555, 602, 585, 633] + ZOrder 49 + InputSameDT off + OutDataTypeStr "Inherit: Inherit via internal rule" + RndMeth "Floor" + SaturateOnIntegerOverflow off + } + Block { + BlockType Product + Name "Product11" + SID "145" + Ports [2, 1] + Position [555, 662, 585, 693] + ZOrder 50 + InputSameDT off + OutDataTypeStr "Inherit: Inherit via internal rule" + RndMeth "Floor" + SaturateOnIntegerOverflow off + } + Block { + BlockType Product + Name "Product4" + SID "146" + Ports [2, 1] + Position [665, 567, 695, 598] + ZOrder 38 + InputSameDT off + OutDataTypeStr "Inherit: Inherit via internal rule" + RndMeth "Floor" + SaturateOnIntegerOverflow off + } + Block { + BlockType Product + Name "Product8" + SID "147" + Ports [2, 1] + Position [610, 557, 640, 588] + ZOrder 43 + InputSameDT off + OutDataTypeStr "Inherit: Inherit via internal rule" + RndMeth "Floor" + SaturateOnIntegerOverflow off + } + Block { + BlockType Sum + Name "Sum2" + SID "148" + Ports [2, 1] + Position [615, 760, 635, 780] + ZOrder 25 + ShowName off + IconShape "round" + Inputs "|++" + InputSameDT off + OutDataTypeStr "Inherit: Inherit via internal rule" + SaturateOnIntegerOverflow off + } + Block { + BlockType Sum + Name "Sum4" + SID "149" + Ports [2, 1] + Position [395, 450, 415, 470] + ZOrder 27 + ShowName off + IconShape "round" + Inputs "|++" + InputSameDT off + OutDataTypeStr "Inherit: Inherit via internal rule" + SaturateOnIntegerOverflow off + } + Block { + BlockType Sum + Name "Sum5" + SID "150" + Ports [2, 1] + Position [590, 805, 610, 825] + ZOrder 37 + ShowName off + IconShape "round" + Inputs "|+-" + InputSameDT off + OutDataTypeStr "Inherit: Inherit via internal rule" + SaturateOnIntegerOverflow off + } + Block { + BlockType Sum + Name "Sum6" + SID "151" + Ports [2, 1] + Position [610, 610, 630, 630] + ZOrder 48 + ShowName off + IconShape "round" + Inputs "|++" + InputSameDT off + OutDataTypeStr "Inherit: Inherit via internal rule" + SaturateOnIntegerOverflow off + } + Block { + BlockType Reference + Name "Transpose" + SID "152" + Ports [1, 1] + Position [585, 105, 640, 145] + ZOrder 17 + LibraryVersion "1.898" + SourceBlock "dspmtrx3/Transpose" + SourceType "Transpose" + ContentPreviewEnabled off + Hermitian off + overflowFlag off + } + Block { + BlockType Reference + Name "Transpose1" + SID "153" + Ports [1, 1] + Position [360, 355, 415, 395] + ZOrder 29 + LibraryVersion "1.898" + SourceBlock "dspmtrx3/Transpose" + SourceType "Transpose" + ContentPreviewEnabled off + Hermitian off + overflowFlag off + } + Block { + BlockType SubSystem + Name "lambda" + SID "154" + Ports [3, 1] + Position [685, 95, 740, 155] + ZOrder 72 + RequestExecContextInheritance off + System { + Name "lambda" + Location [982, 52, 1909, 1080] + Open off + ModelBrowserVisibility off + ModelBrowserWidth 200 + ScreenColor "white" + PaperOrientation "landscape" + PaperPositionMode "auto" + PaperType "A4" + PaperUnits "centimeters" + TiledPaperMargins [1.270000, 1.270000, 1.270000, 1.270000] + TiledPageScale 1 + ShowPageBoundaries off + ZoomFactor "100" + Block { + BlockType Inport + Name "M" + SID "155" + Position [25, 23, 55, 37] + ZOrder 22 + IconDisplay "Port number" + } + Block { + BlockType Inport + Name "J-T" + SID "156" + Position [155, 118, 185, 132] + ZOrder 23 + Port "2" + IconDisplay "Port number" + } + Block { + BlockType Inport + Name "J-1" + SID "157" + Position [105, 168, 135, 182] + ZOrder 24 + Port "3" + IconDisplay "Port number" + } + Block { + BlockType Product + Name "Product3" + SID "158" + Ports [2, 1] + Position [235, 117, 265, 148] + ZOrder 20 + InputSameDT off + OutDataTypeStr "Inherit: Inherit via internal rule" + RndMeth "Floor" + SaturateOnIntegerOverflow off + } + Block { + BlockType Product + Name "produkt" + SID "159" + Ports [2, 1] + Position [310, 127, 340, 158] + ZOrder 21 + InputSameDT off + OutDataTypeStr "Inherit: Inherit via internal rule" + RndMeth "Floor" + SaturateOnIntegerOverflow off + } + Block { + BlockType Outport + Name "Lambda" + SID "160" + Position [135, 438, 165, 452] + ZOrder 25 + BlockMirror on + IconDisplay "Port number" + } + Line { + ZOrder 1 + SrcBlock "M" + SrcPort 1 + Points [155, 0; 0, 110] + DstBlock "Product3" + DstPort 2 + } + Line { + ZOrder 2 + SrcBlock "J-1" + SrcPort 1 + Points [148, 0; 0, -25] + DstBlock "produkt" + DstPort 2 + } + Line { + ZOrder 3 + SrcBlock "produkt" + SrcPort 1 + Points [9, 0; 0, 300] + DstBlock "Lambda" + DstPort 1 + } + Line { + ZOrder 4 + SrcBlock "Product3" + SrcPort 1 + DstBlock "produkt" + DstPort 1 + } + Line { + ZOrder 5 + SrcBlock "J-T" + SrcPort 1 + DstBlock "Product3" + DstPort 1 + } + } + } + Block { + BlockType SubSystem + Name "mu" + SID "161" + Ports [5, 1] + Position [315, 560, 385, 620] + ZOrder 73 + RequestExecContextInheritance off + System { + Name "mu" + Location [660, 120, 1920, 1072] + Open off + ModelBrowserVisibility off + ModelBrowserWidth 200 + ScreenColor "white" + PaperOrientation "landscape" + PaperPositionMode "auto" + PaperType "A4" + PaperUnits "centimeters" + TiledPaperMargins [1.270000, 1.270000, 1.270000, 1.270000] + TiledPageScale 1 + ShowPageBoundaries off + ZoomFactor "100" + Block { + BlockType Inport + Name "M" + SID "162" + Position [390, 20, 420, 35] + ZOrder 37 + BlockRotation 270 + BlockMirror on + IconDisplay "Port number" + } + Block { + BlockType Inport + Name "J-1" + SID "163" + Position [470, 165, 500, 180] + ZOrder 38 + BlockRotation 270 + BlockMirror on + Port "2" + IconDisplay "Port number" + } + Block { + BlockType Inport + Name "JD" + SID "164" + Position [190, 190, 220, 205] + ZOrder 39 + BlockRotation 270 + BlockMirror on + Port "3" + IconDisplay "Port number" + } + Block { + BlockType Inport + Name "JDT" + SID "165" + Position [380, 365, 410, 380] + ZOrder 40 + BlockRotation 270 + BlockMirror on + Port "4" + IconDisplay "Port number" + } + Block { + BlockType Inport + Name "tauC" + SID "166" + Position [20, 408, 50, 422] + ZOrder 41 + Port "5" + IconDisplay "Port number" + } + Block { + BlockType Product + Name "Product5" + SID "167" + Ports [2, 1] + Position [340, 492, 370, 523] + ZOrder 33 + InputSameDT off + OutDataTypeStr "Inherit: Inherit via internal rule" + RndMeth "Floor" + SaturateOnIntegerOverflow off + } + Block { + BlockType Product + Name "Product6" + SID "168" + Ports [2, 1] + Position [240, 552, 270, 583] + ZOrder 35 + InputSameDT off + OutDataTypeStr "Inherit: Inherit via internal rule" + RndMeth "Floor" + SaturateOnIntegerOverflow off + } + Block { + BlockType Product + Name "Product7" + SID "169" + Ports [2, 1] + Position [180, 577, 210, 608] + ZOrder 36 + InputSameDT off + OutDataTypeStr "Inherit: Inherit via internal rule" + RndMeth "Floor" + SaturateOnIntegerOverflow off + } + Block { + BlockType Sum + Name "Sum3" + SID "170" + Ports [2, 1] + Position [270, 505, 290, 525] + ZOrder 26 + ShowName off + IconShape "round" + Inputs "|+-" + InputSameDT off + OutDataTypeStr "Inherit: Inherit via internal rule" + SaturateOnIntegerOverflow off + } + Block { + BlockType Product + Name "mu" + SID "171" + Ports [2, 1] + Position [420, 502, 450, 533] + ZOrder 32 + InputSameDT off + OutDataTypeStr "Inherit: Inherit via internal rule" + RndMeth "Floor" + SaturateOnIntegerOverflow off + } + Block { + BlockType Outport + Name "mu(x,xD)" + SID "172" + Position [635, 488, 665, 502] + ZOrder 42 + IconDisplay "Port number" + } + Line { + ZOrder 1 + SrcBlock "JDT" + SrcPort 1 + Points [0, 93; -104, 0; 0, 22] + DstBlock "Product5" + DstPort 1 + } + Line { + ZOrder 2 + SrcBlock "M" + SrcPort 1 + Points [0, 61; -380, 0; 0, 484] + DstBlock "Product7" + DstPort 1 + } + Line { + ZOrder 3 + SrcBlock "Product5" + SrcPort 1 + DstBlock "mu" + DstPort 1 + } + Line { + ZOrder 4 + SrcBlock "mu" + SrcPort 1 + Points [104, 0; 0, -25] + DstBlock "mu(x,xD)" + DstPort 1 + } + Line { + ZOrder 5 + SrcBlock "tauC" + SrcPort 1 + Points [181, 0; 0, 100] + DstBlock "Sum3" + DstPort 1 + } + Line { + ZOrder 6 + SrcBlock "Product7" + SrcPort 1 + Points [9, 0; 0, -35] + DstBlock "Product6" + DstPort 1 + } + Line { + ZOrder 7 + SrcBlock "Product6" + SrcPort 1 + Points [5, 0] + DstBlock "Sum3" + DstPort 2 + } + Line { + ZOrder 8 + SrcBlock "Sum3" + SrcPort 1 + DstBlock "Product5" + DstPort 2 + } + Line { + ZOrder 9 + SrcBlock "J-1" + SrcPort 1 + Points [0, 450; -74, 0] + Branch { + ZOrder 10 + Points [0, -110] + DstBlock "mu" + DstPort 2 + } + Branch { + ZOrder 11 + Points [-255, 0; 0, -35] + DstBlock "Product7" + DstPort 2 + } + } + Line { + ZOrder 12 + SrcBlock "JD" + SrcPort 1 + Points [0, 335; 13, 0; 0, 30] + DstBlock "Product6" + DstPort 2 + } + } + } + Block { + BlockType SubSystem + Name "xD und xDD" + SID "174" + Ports [4, 2] + Position [125, 157, 165, 218] + ZOrder 74 + RequestExecContextInheritance off + System { + Name "xD und xDD" + Location [81, 30, 1920, 1080] + Open off + ModelBrowserVisibility off + ModelBrowserWidth 200 + ScreenColor "white" + PaperOrientation "landscape" + PaperPositionMode "auto" + PaperType "A4" + PaperUnits "centimeters" + TiledPaperMargins [1.270000, 1.270000, 1.270000, 1.270000] + TiledPageScale 1 + ShowPageBoundaries off + ZoomFactor "100" + Block { + BlockType Inport + Name "J" + SID "175" + Position [175, 23, 205, 37] + ZOrder 17 + IconDisplay "Port number" + } + Block { + BlockType Inport + Name "qD" + SID "176" + Position [20, 78, 50, 92] + ZOrder 18 + Port "2" + IconDisplay "Port number" + } + Block { + BlockType Inport + Name "qDD" + SID "177" + Position [20, 153, 50, 167] + ZOrder 20 + Port "3" + IconDisplay "Port number" + } + Block { + BlockType Inport + Name "JD" + SID "178" + Position [170, 173, 200, 187] + ZOrder 21 + Port "4" + IconDisplay "Port number" + } + Block { + BlockType Product + Name "Product" + SID "179" + Ports [2, 1] + Position [240, 112, 270, 143] + ZOrder 10 + InputSameDT off + OutDataTypeStr "Inherit: Inherit via internal rule" + RndMeth "Floor" + SaturateOnIntegerOverflow off + } + Block { + BlockType Product + Name "Product2" + SID "180" + Ports [2, 1] + Position [240, 172, 270, 203] + ZOrder 16 + InputSameDT off + OutDataTypeStr "Inherit: Inherit via internal rule" + RndMeth "Floor" + SaturateOnIntegerOverflow off + } + Block { + BlockType Sum + Name "Sum1" + SID "181" + Ports [2, 1] + Position [305, 120, 325, 140] + ZOrder 14 + ShowName off + IconShape "round" + Inputs "|++" + InputSameDT off + OutDataTypeStr "Inherit: Inherit via internal rule" + SaturateOnIntegerOverflow off + } + Block { + BlockType Product + Name "iwas" + SID "182" + Ports [2, 1] + Position [240, 22, 270, 53] + ZOrder 15 + InputSameDT off + OutDataTypeStr "Inherit: Inherit via internal rule" + RndMeth "Floor" + SaturateOnIntegerOverflow off + } + Block { + BlockType Outport + Name "XDD" + SID "183" + Position [425, 198, 455, 212] + ZOrder 22 + IconDisplay "Port number" + } + Block { + BlockType Outport + Name "xD" + SID "184" + Position [115, 468, 145, 482] + ZOrder 23 + Port "2" + IconDisplay "Port number" + } + Line { + ZOrder 1 + SrcBlock "JD" + SrcPort 1 + DstBlock "Product2" + DstPort 1 + } + Line { + ZOrder 2 + SrcBlock "J" + SrcPort 1 + Points [4, 0] + Branch { + ZOrder 3 + Points [0, 90] + DstBlock "Product" + DstPort 1 + } + Branch { + ZOrder 4 + DstBlock "iwas" + DstPort 1 + } + } + Line { + ZOrder 5 + SrcBlock "Product" + SrcPort 1 + DstBlock "Sum1" + DstPort 1 + } + Line { + ZOrder 6 + SrcBlock "qDD" + SrcPort 1 + Points [165, 0; 0, -25] + DstBlock "Product" + DstPort 2 + } + Line { + ZOrder 7 + SrcBlock "Sum1" + SrcPort 1 + Points [0, 83; 44, 0; 0, -8] + DstBlock "XDD" + DstPort 1 + } + Line { + ZOrder 8 + SrcBlock "qD" + SrcPort 1 + Points [42, 0] + Branch { + ZOrder 9 + Points [0, 137; 123, 0; 0, -27] + DstBlock "Product2" + DstPort 2 + } + Branch { + ZOrder 10 + Points [122, 0; 0, -40] + DstBlock "iwas" + DstPort 2 + } + } + Line { + ZOrder 11 + SrcBlock "iwas" + SrcPort 1 + Points [6, 0; 0, 340; -215, 0; 0, 95] + DstBlock "xD" + DstPort 1 + } + Line { + ZOrder 12 + SrcBlock "Product2" + SrcPort 1 + Points [40, 0] + DstBlock "Sum1" + DstPort 2 + } + } + } + Block { + BlockType Sum + Name "xtilde" + SID "185" + Ports [2, 1] + Position [130, 477, 160, 508] + ZOrder 41 + Inputs "+-" + InputSameDT off + OutDataTypeStr "Inherit: Inherit via internal rule" + SaturateOnIntegerOverflow off + } + Block { + BlockType Sum + Name "xtildeD" + SID "186" + Ports [2, 1] + Position [130, 532, 160, 563] + ZOrder 42 + Inputs "+-" + InputSameDT off + OutDataTypeStr "Inherit: Inherit via internal rule" + SaturateOnIntegerOverflow off + } + Block { + BlockType Outport + Name "tau" + SID "187" + Position [825, 763, 855, 777] + ZOrder 70 + IconDisplay "Port number" + } + Line { + ZOrder 1 + SrcBlock "DDD" + SrcPort 1 + Points [9, 0; 0, -160] + DstBlock "Product11" + DstPort 1 + } + Line { + ZOrder 2 + SrcBlock "Product10" + SrcPort 1 + DstBlock "Sum6" + DstPort 1 + } + Line { + ZOrder 3 + SrcBlock "Product8" + SrcPort 1 + DstBlock "Product4" + DstPort 1 + } + Line { + ZOrder 4 + SrcBlock "xdD" + SrcPort 1 + DstBlock "xtildeD" + DstPort 1 + } + Line { + ZOrder 5 + SrcBlock "Transpose1" + SrcPort 1 + Points [4, 0] + Branch { + ZOrder 6 + Points [0, 190] + Branch { + ZOrder 7 + DstBlock "Product8" + DstPort 1 + } + Branch { + ZOrder 8 + Points [0, 69; -128, 0; 0, -34] + DstBlock "mu" + DstPort 4 + } + } + Branch { + ZOrder 9 + DstBlock "Product1" + DstPort 1 + } + } + Line { + ZOrder 10 + SrcBlock "Product4" + SrcPort 1 + Points [66, 0; 0, 268; -166, 0] + DstBlock "Sum5" + DstPort 2 + } + Line { + ZOrder 11 + SrcBlock "Product11" + SrcPort 1 + Points [30, 0] + DstBlock "Sum6" + DstPort 2 + } + Line { + ZOrder 12 + SrcBlock "Sum2" + SrcPort 1 + DstBlock "tau" + DstPort 1 + } + Line { + ZOrder 13 + SrcBlock "Inverse" + SrcPort 1 + Points [7, 0] + Branch { + ZOrder 14 + Points [0, 110] + Branch { + ZOrder 15 + Points [0, 190; -245, 0; 0, 155] + DstBlock "mu" + DstPort 2 + } + Branch { + ZOrder 16 + Points [123, 0] + DstBlock "lambda" + DstPort 3 + } + } + Branch { + ZOrder 17 + DstBlock "Transpose" + DstPort 1 + } + } + Line { + ZOrder 18 + SrcBlock "g" + SrcPort 1 + DstBlock "Sum2" + DstPort 1 + } + Line { + ZOrder 19 + SrcBlock "Sum6" + SrcPort 1 + Points [15, 0] + DstBlock "Product4" + DstPort 2 + } + Line { + ZOrder 20 + SrcBlock "M" + SrcPort 1 + Points [58, 0] + Branch { + ZOrder 21 + Points [0, 47; -126, 0; 0, 433] + DstBlock "mu" + DstPort 1 + } + Branch { + ZOrder 22 + Points [230, 0; 0, 15] + DstBlock "lambda" + DstPort 1 + } + } + Line { + ZOrder 23 + SrcBlock "MATLAB J" + SrcPort 1 + Points [15, 0; 0, 100] + Branch { + ZOrder 24 + Points [0, 135] + Branch { + ZOrder 25 + Points [-172, 0; 0, -95] + DstBlock "xD und xDD" + DstPort 1 + } + Branch { + ZOrder 26 + Points [0, 115] + DstBlock "Transpose1" + DstPort 1 + } + } + Branch { + ZOrder 27 + DstBlock "Inverse" + DstPort 1 + } + } + Line { + ZOrder 28 + SrcBlock "xd" + SrcPort 1 + Points [16, 0; 0, -15] + DstBlock "xtilde" + DstPort 1 + } + Line { + ZOrder 29 + SrcBlock "xtilde" + SrcPort 1 + Points [355, 0; 0, 130] + DstBlock "Product10" + DstPort 2 + } + Line { + ZOrder 30 + SrcBlock "MATLAB JD" + SrcPort 1 + Points [6, 0; 0, 162; -26, 0] + Branch { + ZOrder 31 + Points [0, 288] + DstBlock "mu" + DstPort 3 + } + Branch { + ZOrder 32 + Points [-184, 0; 0, -92] + DstBlock "xD und xDD" + DstPort 4 + } + } + Line { + ZOrder 33 + SrcBlock "Sum4" + SrcPort 1 + Points [0, -70] + DstBlock "Product1" + DstPort 2 + } + Line { + ZOrder 34 + SrcBlock "Sum5" + SrcPort 1 + Points [10, 0] + DstBlock "Sum2" + DstPort 2 + } + Line { + ZOrder 35 + SrcBlock "Lambda1" + SrcPort 1 + DstBlock "Sum4" + DstPort 1 + } + Line { + ZOrder 36 + SrcBlock "xdDD" + SrcPort 1 + Points [76, 0; 0, -135] + DstBlock "Lambda1" + DstPort 2 + } + Line { + ZOrder 37 + SrcBlock "q" + SrcPort 1 + Points [30, 0] + Branch { + ZOrder 38 + Points [37, 0] + Branch { + ZOrder 39 + Points [0, -20; 8, 0] + DstBlock "MATLAB J" + DstPort 1 + } + Branch { + ZOrder 40 + Points [0, 30] + DstBlock "MATLAB JD" + DstPort 1 + } + } + Branch { + ZOrder 41 + Points [0, 33; -102, 0; 0, 310; 97, 0] + DstBlock "xtilde" + DstPort 2 + } + } + Line { + ZOrder 42 + SrcBlock "xtildeD" + SrcPort 1 + Points [17, 0; 0, -33; 348, 0; 0, 168] + DstBlock "Product11" + DstPort 2 + } + Line { + ZOrder 43 + SrcBlock "Product1" + SrcPort 1 + Points [20, 0; 0, 430] + DstBlock "Sum5" + DstPort 1 + } + Line { + ZOrder 44 + SrcBlock "lambda" + SrcPort 1 + Points [9, 0; 0, 380; -458, 0; 0, -55] + DstBlock "Lambda1" + DstPort 1 + } + Line { + ZOrder 45 + SrcBlock "Transpose" + SrcPort 1 + DstBlock "lambda" + DstPort 2 + } + Line { + ZOrder 46 + SrcBlock "tauC" + SrcPort 1 + Points [1, 0; 0, 145] + DstBlock "mu" + DstPort 5 + } + Line { + ZOrder 47 + SrcBlock "mu" + SrcPort 1 + Points [15, 0] + DstBlock "Sum4" + DstPort 2 + } + Line { + ZOrder 48 + SrcBlock "qD" + SrcPort 1 + Points [2, 0; 0, 15] + DstBlock "xD und xDD" + DstPort 2 + } + Line { + ZOrder 49 + SrcBlock "qDD" + SrcPort 1 + DstBlock "xD und xDD" + DstPort 3 + } + Line { + ZOrder 50 + SrcBlock "xD und xDD" + SrcPort 2 + Points [173, 0; 0, 236; -131, 0; 0, 148; -101, 0; 0, -34] + DstBlock "xtildeD" + DstPort 2 + } + Line { + ZOrder 51 + SrcBlock "Kd" + SrcPort 1 + Points [26, 0] + Branch { + ZOrder 52 + Points [0, -132; 10, 0; 0, -30; 202, 0; 0, -43] + DstBlock "Product10" + DstPort 1 + } + Branch { + ZOrder 53 + DstBlock "DDD" + DstPort 1 + } + } + Line { + ZOrder 54 + SrcBlock "D_epsilon" + SrcPort 1 + DstBlock "DDD" + DstPort 2 + } + Annotation { + SID "190" + Name "[1] Verweis" + Position [913, 61, 964, 78] + InternalMargins [0, 0, 0, 0] + FixedHeight off + FixedWidth off + HorizontalAlignment "left" + VerticalAlignment "top" + ZOrder -1 + } + } + } + Block { + BlockType SubSystem + Name "atlas5_leg_joint_impctrl_sqrt_damping" + SID "665" + Ports [8, 3] + Position [295, 680, 515, 920] + ZOrder 699 + LibraryVersion "*1.360" + TreatAsAtomicUnit on + SystemSampleTime "T" + RequestExecContextInheritance off + Object { + $PropName "MaskObject" + $ObjectID 17 + $ClassName "Simulink.Mask" + Type "Atlas Joint Impedance Controller" + Description "Hardware dependent full impedance controller block with matrix\nsquareroot damping design for the atlas" + " robot. For a better\ntesting, all partial momentums can be individually scaled.\nCoulomb-, viscous friction and Stri" + "beck stiction is taken into\naccount for friction compensation." + Array { + Type "Simulink.MaskParameter" + Dimension 27 + Object { + $ObjectID 18 + Type "edit" + Name "K_d" + Prompt "K_d (desired stiffness)" + Value "K_d" + } + Object { + $ObjectID 19 + Type "edit" + Name "D" + Prompt "D (diagonal matrix with desired damping coefficients)" + Value "D" + } + Object { + $ObjectID 20 + Type "edit" + Name "K_tau_g" + Prompt "K_tau_g (gain of gravity compensation)" + Value "K_tau_g" + } + Object { + $ObjectID 21 + Type "edit" + Name "K_tau_c" + Prompt "K_tau_c (gain of corriolis- and inertia compensation)" + Value "K_tau_c" + } + Object { + $ObjectID 22 + Type "edit" + Name "K_tau_K" + Prompt "K_tau_K (gain of stiffness component)" + Value "K_tau_K" + } + Object { + $ObjectID 23 + Type "edit" + Name "K_tau_D" + Prompt "K_tau_D (gain of damping component)" + Value "K_tau_D" + } + Object { + $ObjectID 24 + Type "edit" + Name "K_tau_a" + Prompt "K_tau_a (gain of acceleration component)" + Value "K_tau_a" + } + Object { + $ObjectID 25 + Type "edit" + Name "K_tau_f" + Prompt "K_tau_f (gain of friction compensation)" + Value "K_tau_f" + } + Object { + $ObjectID 26 + Type "edit" + Name "K_tau_e" + Prompt "K_tau_e (gain of external torque)" + Value "K_tau_e" + } + Object { + $ObjectID 27 + Type "edit" + Name "K_tau_o" + Prompt "K_tau_o (gain of compensation of disturbance observer torques)" + Value "K_tau_o" + } + Object { + $ObjectID 28 + Type "edit" + Name "K_qD_d" + Prompt "K_qD_d (gain of desired velocity)" + Value "K_qD_d" + } + Object { + $ObjectID 29 + Type "edit" + Name "K_qDD_d" + Prompt "K_qDD_d (gain of desired acceleration)" + Value "K_qDD_d" + } + Object { + $ObjectID 30 + Type "edit" + Name "K_ext_c" + Prompt "K_ext_c (input gain to deside, wether to trigger friction compensation via the measured external tor" + "que)" + Value "K_ext_c" + } + Object { + $ObjectID 31 + Type "edit" + Name "K_obs_c" + Prompt "K_obs_c (input gain to deside, wether to trigger friction compensation via the observed torque)" + Value "K_obs_c" + } + Object { + $ObjectID 32 + Type "edit" + Name "K_fri_o" + Prompt "K_fri_o (input gain of friction model torques for observer)" + Value "K_fri_o" + } + Object { + $ObjectID 33 + Type "edit" + Name "K_ext_o" + Prompt "K_ext_o (input gain of external torque for observer)" + Value "K_ext_o" + } + Object { + $ObjectID 34 + Type "edit" + Name "tau_obs_max" + Prompt "tau_obs_max (limit for observed disturbance torque)" + Value "30*ones(6,1)" + } + Object { + $ObjectID 35 + Type "edit" + Name "MPV_leg_damp" + Prompt "MPV_damp (base parameter vector for damping calculation)" + Value "MPV_leg_damp" + } + Object { + $ObjectID 36 + Type "edit" + Name "MPV_leg_model" + Prompt "MPV_model (base parameter vector for dynamic model calculation)" + Value "MPV_leg_model" + } + Object { + $ObjectID 37 + Type "edit" + Name "tau_c" + Prompt "tau_c (vector with coulomb friction momentums for all joints)" + Value "tau_c" + } + Object { + $ObjectID 38 + Type "edit" + Name "B" + Prompt "B (vector with viscous friction coefficients of all joints)" + Value "B" + } + Object { + $ObjectID 39 + Type "edit" + Name "qD_th" + Prompt "qD_th (vector with theshold velocities for stiction)" + Value "qD_th" + } + Object { + $ObjectID 40 + Type "edit" + Name "tau_th" + Prompt "tau_th (vector with kick-in momentums for stiction compensation)" + Value "tau_th" + } + Object { + $ObjectID 41 + Type "edit" + Name "K_O" + Prompt "K_O (friction observer gain)" + Value "K_O" + } + Object { + $ObjectID 42 + Type "edit" + Name "T" + Prompt "T (sample time (important for friction observer))" + Value "T" + } + Object { + $ObjectID 43 + Type "edit" + Name "atlas_leg_lr" + Prompt "atlas_leg_lr (left/right flag)" + Value "atlas_leg_lr" + } + Object { + $ObjectID 44 + Type "edit" + Name "T1" + Prompt "T1 (low pass filter time constant for inertia matrix)" + Value "T1" + } + PropName "Parameters" + } + } + System { + Name "atlas5_leg_joint_impctrl_sqrt_damping" + Location [49, 24, 1920, 1080] + Open off + ModelBrowserVisibility off + ModelBrowserWidth 200 + ScreenColor "white" + PaperOrientation "landscape" + PaperPositionMode "auto" + PaperType "A4" + PaperUnits "centimeters" + TiledPaperMargins [1.270000, 1.270000, 1.270000, 1.270000] + TiledPageScale 1 + ShowPageBoundaries off + ZoomFactor "200" + Block { + BlockType Inport + Name "q" + SID "666" + Position [25, 73, 55, 87] + ZOrder 176 + IconDisplay "Port number" + OutDataTypeStr "double" + PortDimensions "6" + VarSizeSig "No" + SignalType "real" + } + Block { + BlockType Inport + Name "qD" + SID "667" + Position [25, 183, 55, 197] + ZOrder 177 + Port "2" + IconDisplay "Port number" + OutDataTypeStr "double" + PortDimensions "6" + VarSizeSig "No" + SignalType "real" + } + Block { + BlockType Inport + Name "q_d" + SID "668" + Position [25, 348, 55, 362] + ZOrder 178 + Port "3" + IconDisplay "Port number" + OutDataTypeStr "double" + PortDimensions "6" + VarSizeSig "No" + SignalType "real" + } + Block { + BlockType Inport + Name "qD_d" + SID "669" + Position [25, 438, 55, 452] + ZOrder 179 + Port "4" + IconDisplay "Port number" + OutDataTypeStr "double" + PortDimensions "6" + VarSizeSig "No" + SignalType "real" + } + Block { + BlockType Inport + Name "qDD_d" + SID "670" + Position [25, 528, 55, 542] + ZOrder 180 + Port "5" + IconDisplay "Port number" + OutDataTypeStr "double" + PortDimensions "6" + VarSizeSig "No" + SignalType "real" + } + Block { + BlockType Inport + Name "g" + SID "671" + Position [25, 718, 55, 732] + ZOrder 189 + Port "6" + IconDisplay "Port number" + OutDataTypeStr "double" + PortDimensions "[3 1]" + VarSizeSig "No" + SignalType "real" + } + Block { + BlockType Inport + Name "tau_J" + SID "672" + Position [25, 868, 55, 882] + ZOrder 233 + Port "7" + IconDisplay "Port number" + OutDataTypeStr "double" + PortDimensions "6" + VarSizeSig "No" + SignalType "real" + } + Block { + BlockType Inport + Name "F_ext" + SID "673" + Position [25, 918, 55, 932] + ZOrder 234 + Port "8" + IconDisplay "Port number" + OutDataTypeStr "double" + PortDimensions "6" + VarSizeSig "No" + SignalType "real" + } + Block { + BlockType Gain + Name "Gain1" + SID "734" + Position [600, 1045, 655, 1085] + ZOrder 288 + Gain "K_fri_o" + ParamDataTypeStr "Inherit: Inherit via internal rule" + OutDataTypeStr "Inherit: Inherit via internal rule" + SaturateOnIntegerOverflow off + } + Block { + BlockType Gain + Name "Gain4" + SID "674" + Position [485, 895, 540, 935] + ZOrder 259 + Gain "K_ext_o" + ParamDataTypeStr "Inherit: Inherit via internal rule" + OutDataTypeStr "Inherit: Inherit via internal rule" + SaturateOnIntegerOverflow off + } + Block { + BlockType Product + Name "Product" + SID "675" + Ports [2, 1] + Position [335, 887, 375, 938] + ZOrder 258 + Multiplication "Matrix(*)" + InputSameDT off + OutDataTypeStr "Inherit: Inherit via internal rule" + RndMeth "Floor" + SaturateOnIntegerOverflow off + } + Block { + BlockType Math + Name "Transpose" + SID "676" + Ports [1, 1] + Position [220, 795, 275, 835] + ZOrder 256 + Operator "transpose" + } + Block { + BlockType Reference + Name "atlas5_leg_coriolis_vec_minvarpar" + SID "687" + Ports [2, 1] + Position [460, 597, 530, 648] + ZOrder 280 + LibraryVersion "1.228" + SourceBlock "atlas_dynamic_library/atlas_leg_coriolis_vec_minvarpar" + SourceType "" + ContentPreviewEnabled off + atlas_arm_lr "atlas_leg_lr" + atlas_version "uint8(5)" + MPV "MPV_leg_model" + } + Block { + BlockType Reference + Name "atlas5_leg_gravload_minvarpar" + SID "688" + Ports [2, 1] + Position [460, 687, 530, 738] + ZOrder 281 + LibraryVersion "1.228" + SourceBlock "atlas_dynamic_library/atlas_leg_gravload_minvarpar" + SourceType "" + ContentPreviewEnabled off + atlas_arm_lr "atlas_leg_lr" + atlas_version "uint8(5)" + MPV "MPV_leg_model" + } + Block { + BlockType Reference + Name "atlas5_leg_jacobig" + SID "686" + Ports [1, 1] + Position [115, 790, 185, 840] + ZOrder 278 + LibraryVersion "1.228" + SourceBlock "atlas_dynamic_library/atlas_leg_jacobig" + SourceType "" + ContentPreviewEnabled off + atlas_version "uint8(5)" + atlas_leg_lr "atlas_leg_lr" + } + Block { + BlockType Reference + Name "atlas_friction_model" + SID "681" + Ports [1, 1] + Position [440, 1027, 540, 1103] + ZOrder 261 + LibraryVersion "1.366" + SourceBlock "atlas_impctrl_library/atlas_friction_model" + SourceType "" + ContentPreviewEnabled off + tau_c "tau_c" + B "B" + } + Block { + BlockType Reference + Name "atlas_joint_impctrl_sqrt_damping_base" + SID "682" + Ports [11, 1] + Position [840, 114, 1055, 1136] + ZOrder 188 + LibraryVersion "1.366" + SourceBlock "atlas_impctrl_library/atlas_joint_impctrl_sqrt_damping_base" + SourceType "Joint Impedance Controller Base" + ContentPreviewEnabled off + K_d "K_d" + D "D" + K_tau_g "K_tau_g" + K_tau_c "K_tau_c" + K_tau_K "K_tau_K" + K_tau_D "K_tau_D" + K_tau_a "K_tau_a" + K_tau_f "K_tau_f" + K_tau_e "K_tau_e" + K_tau_o "K_tau_o" + K_qD_d "K_qD_d" + K_qDD_d "K_qDD_d" + K_ext_c "K_ext_c" + K_obs_c "K_obs_c" + tau_c "tau_c" + B "B" + qD_th "qD_th" + tau_th "tau_th" + } + Block { + BlockType Reference + Name "atlas_leg_inertia_minvarpar" + SID "689" + Ports [1, 1] + Position [460, 781, 530, 829] + ZOrder 282 + LibraryVersion "1.228" + SourceBlock "atlas_dynamic_library/atlas_leg_inertia_minvarpar" + SourceType "" + ContentPreviewEnabled off + atlas_arm_lr "atlas_leg_lr" + atlas_version "uint8(5)" + MPV "MPV_leg_damp" + } + Block { + BlockType Reference + Name "momentum_based_friction_observer" + SID "710" + Ports [7, 1] + Position [670, 862, 735, 1088] + ZOrder 286 + LibraryVersion "1.366" + SourceBlock "atlas_impctrl_library/momentum_based_friction_observer" + SourceType "" + ContentPreviewEnabled off + K_O "K_O" + T "T" + T1 "T1" + tau_out_max "tau_obs_max" + } + Block { + BlockType Outport + Name "tau" + SID "684" + Position [1110, 618, 1140, 632] + ZOrder 185 + IconDisplay "Port number" + OutDataTypeStr "double" + PortDimensions "6" + VarSizeSig "No" + SignalType "real" + } + Block { + BlockType Outport + Name "tau_fr_obs" + SID "685" + Position [1110, 1153, 1140, 1167] + ZOrder 235 + Port "2" + IconDisplay "Port number" + OutDataTypeStr "double" + PortDimensions "6" + VarSizeSig "No" + SignalType "real" + } + Block { + BlockType Outport + Name "tau_ext_mes" + SID "733" + Position [1110, 1228, 1140, 1242] + ZOrder 287 + Port "3" + IconDisplay "Port number" + OutDataTypeStr "double" + PortDimensions "6" + VarSizeSig "No" + SignalType "real" + } + Line { + ZOrder 1 + SrcBlock "atlas_joint_impctrl_sqrt_damping_base" + SrcPort 1 + DstBlock "tau" + DstPort 1 + } + Line { + ZOrder 2 + SrcBlock "atlas_leg_inertia_minvarpar" + SrcPort 1 + Points [33, 0; 0, 1] + Branch { + ZOrder 3 + Points [-1, 0; 6, -1] + DstBlock "atlas_joint_impctrl_sqrt_damping_base" + DstPort 8 + } + Branch { + ZOrder 4 + Points [0, 229] + DstBlock "momentum_based_friction_observer" + DstPort 6 + } + } + Line { + ZOrder 5 + SrcBlock "q" + SrcPort 1 + Points [21, 0] + Branch { + ZOrder 6 + Points [271, 0] + Branch { + ZOrder 7 + Points [27, 0] + Branch { + ZOrder 8 + Points [57, 0; 0, 95] + Branch { + ZOrder 9 + DstBlock "atlas_joint_impctrl_sqrt_damping_base" + DstPort 1 + } + Branch { + ZOrder 10 + Points [0, 435] + DstBlock "atlas5_leg_coriolis_vec_minvarpar" + DstPort 1 + } + } + Branch { + ZOrder 11 + Points [0, 620] + DstBlock "atlas5_leg_gravload_minvarpar" + DstPort 1 + } + } + Branch { + ZOrder 12 + Points [0, 725] + DstBlock "atlas_leg_inertia_minvarpar" + DstPort 1 + } + } + Branch { + ZOrder 13 + Points [0, 735] + DstBlock "atlas5_leg_jacobig" + DstPort 1 + } + } + Line { + ZOrder 14 + SrcBlock "qD" + SrcPort 1 + Points [348, 0; 0, 75] + Branch { + ZOrder 15 + DstBlock "atlas_joint_impctrl_sqrt_damping_base" + DstPort 2 + } + Branch { + ZOrder 16 + Points [0, 370] + Branch { + ZOrder 17 + DstBlock "atlas5_leg_coriolis_vec_minvarpar" + DstPort 2 + } + Branch { + ZOrder 18 + Points [0, 370] + Branch { + ZOrder 19 + DstBlock "momentum_based_friction_observer" + DstPort 5 + } + Branch { + ZOrder 20 + Points [0, 60] + DstBlock "atlas_friction_model" + DstPort 1 + } + } + } + } + Line { + ZOrder 21 + SrcBlock "q_d" + SrcPort 1 + DstBlock "atlas_joint_impctrl_sqrt_damping_base" + DstPort 3 + } + Line { + ZOrder 22 + SrcBlock "atlas5_leg_coriolis_vec_minvarpar" + SrcPort 1 + Points [65, 0] + Branch { + ZOrder 23 + DstBlock "atlas_joint_impctrl_sqrt_damping_base" + DstPort 6 + } + Branch { + ZOrder 24 + Points [0, 350] + DstBlock "momentum_based_friction_observer" + DstPort 4 + } + } + Line { + ZOrder 25 + SrcBlock "qD_d" + SrcPort 1 + DstBlock "atlas_joint_impctrl_sqrt_damping_base" + DstPort 4 + } + Line { + ZOrder 26 + SrcBlock "atlas5_leg_gravload_minvarpar" + SrcPort 1 + Points [46, 0] + Branch { + ZOrder 27 + DstBlock "atlas_joint_impctrl_sqrt_damping_base" + DstPort 7 + } + Branch { + ZOrder 28 + Points [0, 230] + DstBlock "momentum_based_friction_observer" + DstPort 3 + } + } + Line { + ZOrder 29 + SrcBlock "qDD_d" + SrcPort 1 + DstBlock "atlas_joint_impctrl_sqrt_damping_base" + DstPort 5 + } + Line { + ZOrder 30 + SrcBlock "g" + SrcPort 1 + DstBlock "atlas5_leg_gravload_minvarpar" + DstPort 2 + } + Line { + ZOrder 31 + SrcBlock "momentum_based_friction_observer" + SrcPort 1 + Points [61, 0] + Branch { + ZOrder 32 + Points [0, 185] + DstBlock "tau_fr_obs" + DstPort 1 + } + Branch { + ZOrder 33 + Points [0, -80] + DstBlock "atlas_joint_impctrl_sqrt_damping_base" + DstPort 9 + } + } + Line { + ZOrder 34 + SrcBlock "tau_J" + SrcPort 1 + Points [595, 0] + DstBlock "momentum_based_friction_observer" + DstPort 1 + } + Line { + ZOrder 35 + SrcBlock "atlas5_leg_jacobig" + SrcPort 1 + DstBlock "Transpose" + DstPort 1 + } + Line { + ZOrder 36 + SrcBlock "Transpose" + SrcPort 1 + Points [25, 0; 0, 85] + DstBlock "Product" + DstPort 1 + } + Line { + ZOrder 37 + SrcBlock "F_ext" + SrcPort 1 + DstBlock "Product" + DstPort 2 + } + Line { + ZOrder 38 + SrcBlock "Product" + SrcPort 1 + Points [12, 0] + Branch { + ZOrder 50 + Points [0, 320; 399, 0] + Branch { + ZOrder 57 + Points [0, -160] + DstBlock "atlas_joint_impctrl_sqrt_damping_base" + DstPort 11 + } + Branch { + ZOrder 56 + DstBlock "tau_ext_mes" + DstPort 1 + } + } + Branch { + ZOrder 48 + DstBlock "Gain4" + DstPort 1 + } + } + Line { + ZOrder 39 + SrcBlock "Gain4" + SrcPort 1 + DstBlock "momentum_based_friction_observer" + DstPort 2 + } + Line { + ZOrder 42 + SrcBlock "atlas_friction_model" + SrcPort 1 + Points [35, 0] + Branch { + ZOrder 54 + Points [0, 68; 228, 0; 0, -148] + DstBlock "atlas_joint_impctrl_sqrt_damping_base" + DstPort 10 + } + Branch { + ZOrder 43 + DstBlock "Gain1" + DstPort 1 + } + } + Line { + ZOrder 52 + SrcBlock "Gain1" + SrcPort 1 + DstBlock "momentum_based_friction_observer" + DstPort 7 + } + } + } + Block { + BlockType SubSystem + Name "atlas_friction_model" + SID "651" + Ports [1, 1] + Position [985, 1287, 1085, 1363] + ZOrder 241 + TreatAsAtomicUnit on + RequestExecContextInheritance off + Object { + $PropName "MaskObject" + $ObjectID 45 + $ClassName "Simulink.Mask" + Array { + Type "Simulink.MaskParameter" + Dimension 2 + Object { + $ObjectID 46 + Type "edit" + Name "tau_c" + Prompt "tau_c (vector with coulomb friction momentums for all joints)" + Value "tau_c" + } + Object { + $ObjectID 47 + Type "edit" + Name "B" + Prompt "B (vector with viscous friction coefficients of all joints)" + Value "B" + } + PropName "Parameters" + } + } + System { + Name "atlas_friction_model" + Location [65, 78, 1920, 1093] + Open off + ModelBrowserVisibility off + ModelBrowserWidth 200 + ScreenColor "white" + PaperOrientation "landscape" + PaperPositionMode "auto" + PaperType "usletter" + PaperUnits "inches" + TiledPaperMargins [0.500000, 0.500000, 0.500000, 0.500000] + TiledPageScale 1 + ShowPageBoundaries off + ZoomFactor "100" + Block { + BlockType Inport + Name "qD" + SID "653" + Position [15, 63, 45, 77] + ZOrder 131 + IconDisplay "Port number" + } + Block { + BlockType SubSystem + Name "atlas_friction_model" + SID "655" + Ports [1, 1] + Position [70, 32, 175, 108] + ZOrder 130 + ErrorFcn "Stateflow.Translate.translate" + PermitHierarchicalResolution "ExplicitOnly" + TreatAsAtomicUnit on + RequestExecContextInheritance off + SFBlockType "MATLAB Function" + System { + Name "atlas_friction_model" + Location [223, 338, 826, 833] + Open off + ModelBrowserVisibility off + ModelBrowserWidth 200 + ScreenColor "white" + PaperOrientation "landscape" + PaperPositionMode "auto" + PaperType "usletter" + PaperUnits "inches" + TiledPaperMargins [0.500000, 0.500000, 0.500000, 0.500000] + TiledPageScale 1 + ShowPageBoundaries off + ZoomFactor "100" + SIDHighWatermark "135" + SIDPrevWatermark "91" + Block { + BlockType Inport + Name "qD" + SID "655::21" + Position [20, 101, 40, 119] + ZOrder 7 + IconDisplay "Port number" + } + Block { + BlockType Demux + Name " Demux " + SID "655::119" + Ports [1, 1] + Position [270, 230, 320, 270] + ZOrder 44 + Outputs "1" + } + Block { + BlockType S-Function + Name " SFunction " + SID "655::118" + Tag "Stateflow S-Function atlas_impctrl_library 26" + Ports [1, 2] + Position [180, 100, 230, 160] + ZOrder 43 + FunctionName "sf_sfun" + Parameters "B,tau_c" + PortCounts "[1 2]" + Port { + PortNumber 2 + Name "tau_fr_model" + RTWStorageClass "Auto" + DataLoggingNameMode "SignalName" + } + } + Block { + BlockType Terminator + Name " Terminator " + SID "655::120" + Position [460, 241, 480, 259] + ZOrder 45 + } + Block { + BlockType Outport + Name "tau_fr_model" + SID "655::27" + Position [460, 101, 480, 119] + ZOrder 13 + IconDisplay "Port number" + } + Line { + ZOrder 15 + SrcBlock "qD" + SrcPort 1 + DstBlock " SFunction " + DstPort 1 + } + Line { + Name "tau_fr_model" + ZOrder 16 + Labels [0, 0] + SrcBlock " SFunction " + SrcPort 2 + DstBlock "tau_fr_model" + DstPort 1 + } + Line { + ZOrder 17 + SrcBlock " Demux " + SrcPort 1 + DstBlock " Terminator " + DstPort 1 + } + Line { + ZOrder 18 + SrcBlock " SFunction " + SrcPort 1 + DstBlock " Demux " + DstPort 1 + } + } + } + Block { + BlockType Outport + Name "tau_fr_model" + SID "656" + Position [210, 63, 240, 77] + ZOrder 132 + IconDisplay "Port number" + } + Line { + ZOrder 1 + SrcBlock "qD" + SrcPort 1 + DstBlock "atlas_friction_model" + DstPort 1 + } + Line { + ZOrder 2 + SrcBlock "atlas_friction_model" + SrcPort 1 + DstBlock "tau_fr_model" + DstPort 1 + } + } + } + Block { + BlockType SubSystem + Name "atlas_friction_model_atan" + SID "727" + Ports [1, 1] + Position [1050, 952, 1150, 1028] + ZOrder 244 + TreatAsAtomicUnit on + RequestExecContextInheritance off + Object { + $PropName "MaskObject" + $ObjectID 48 + $ClassName "Simulink.Mask" + Array { + Type "Simulink.MaskParameter" + Dimension 2 + Object { + $ObjectID 49 + Type "edit" + Name "tau_c" + Prompt "tau_c (vector with coulomb friction momentums for all joints)" + Value "tau_c" + } + Object { + $ObjectID 50 + Type "edit" + Name "B" + Prompt "B (vector with viscous friction coefficients of all joints)" + Value "B" + } + PropName "Parameters" + } + } + System { + Name "atlas_friction_model_atan" + Location [65, 78, 1920, 1093] + Open off + ModelBrowserVisibility off + ModelBrowserWidth 200 + ScreenColor "white" + PaperOrientation "landscape" + PaperPositionMode "auto" + PaperType "A4" + PaperUnits "centimeters" + TiledPaperMargins [1.270000, 1.270000, 1.270000, 1.270000] + TiledPageScale 1 + ShowPageBoundaries off + ZoomFactor "100" + Block { + BlockType Inport + Name "qD" + SID "728" + Position [15, 63, 45, 77] + ZOrder 131 + IconDisplay "Port number" + } + Block { + BlockType SubSystem + Name "atlas_friction_model_atan" + SID "729" + Ports [1, 1] + Position [70, 32, 175, 108] + ZOrder 130 + ErrorFcn "Stateflow.Translate.translate" + PermitHierarchicalResolution "ExplicitOnly" + TreatAsAtomicUnit on + RequestExecContextInheritance off + SFBlockType "MATLAB Function" + System { + Name "atlas_friction_model_atan" + Location [223, 338, 826, 833] + Open off + ModelBrowserVisibility off + ModelBrowserWidth 200 + ScreenColor "white" + PaperOrientation "landscape" + PaperPositionMode "auto" + PaperType "A4" + PaperUnits "centimeters" + TiledPaperMargins [1.270000, 1.270000, 1.270000, 1.270000] + TiledPageScale 1 + ShowPageBoundaries off + ZoomFactor "100" + SIDHighWatermark "128" + SIDPrevWatermark "91" + Block { + BlockType Inport + Name "qD" + SID "729::21" + Position [20, 101, 40, 119] + ZOrder 7 + IconDisplay "Port number" + } + Block { + BlockType Demux + Name " Demux " + SID "729::122" + Ports [1, 1] + Position [270, 230, 320, 270] + ZOrder 47 + Outputs "1" + } + Block { + BlockType S-Function + Name " SFunction " + SID "729::121" + Tag "Stateflow S-Function atlas_impctrl_library 13" + Ports [1, 2] + Position [180, 100, 230, 160] + ZOrder 46 + FunctionName "sf_sfun" + Parameters "B,tau_c" + PortCounts "[1 2]" + Port { + PortNumber 2 + Name "tau_fr_model" + RTWStorageClass "Auto" + DataLoggingNameMode "SignalName" + } + } + Block { + BlockType Terminator + Name " Terminator " + SID "729::123" + Position [460, 241, 480, 259] + ZOrder 48 + } + Block { + BlockType Outport + Name "tau_fr_model" + SID "729::27" + Position [460, 101, 480, 119] + ZOrder 13 + IconDisplay "Port number" + } + Line { + ZOrder 5 + SrcBlock "qD" + SrcPort 1 + DstBlock " SFunction " + DstPort 1 + } + Line { + Name "tau_fr_model" + ZOrder 6 + Labels [0, 0] + SrcBlock " SFunction " + SrcPort 2 + DstBlock "tau_fr_model" + DstPort 1 + } + Line { + ZOrder 7 + SrcBlock " Demux " + SrcPort 1 + DstBlock " Terminator " + DstPort 1 + } + Line { + ZOrder 8 + SrcBlock " SFunction " + SrcPort 1 + DstBlock " Demux " + DstPort 1 + } + } + } + Block { + BlockType Outport + Name "tau_fr_model" + SID "730" + Position [210, 63, 240, 77] + ZOrder 132 + IconDisplay "Port number" + } + Line { + ZOrder 1 + SrcBlock "qD" + SrcPort 1 + DstBlock "atlas_friction_model_atan" + DstPort 1 + } + Line { + ZOrder 2 + SrcBlock "atlas_friction_model_atan" + SrcPort 1 + DstBlock "tau_fr_model" + DstPort 1 + } + } + } + Block { + BlockType SubSystem + Name "atlas_joint_impctrl" + SID "450" + Ports [6, 1] + Position [635, 400, 855, 640] + ZOrder 183 + TreatAsAtomicUnit on + RequestExecContextInheritance off + Object { + $PropName "MaskObject" + $ObjectID 51 + $ClassName "Simulink.Mask" + Type "Atlas Joint Impedance Controller" + Description "Hardware dependent full impedance controller block with matrix\ndouble diagonalization damping design f" + "or the atlas robot. For\na better testing, all partial momentums can be individually\nscaled. Coulomb-, viscous frict" + "ion and Stribeck stiction is taken\ninto account for friction compensation." + Array { + Type "Simulink.MaskParameter" + Dimension 16 + Object { + $ObjectID 52 + Type "edit" + Name "K_d" + Prompt "K_d (desired stiffness)" + Value "K_d" + } + Object { + $ObjectID 53 + Type "edit" + Name "D" + Prompt "D (diagonal matrix with desired damping coefficients)" + Value "D" + } + Object { + $ObjectID 54 + Type "edit" + Name "tau_c" + Prompt "tau_c (vector with coulomb friction momentums for all joints)" + Value "tau_c" + } + Object { + $ObjectID 55 + Type "edit" + Name "B" + Prompt "B (vector with viscous friction coefficients of all joints)" + Value "B" + } + Object { + $ObjectID 56 + Type "edit" + Name "tau_s" + Prompt "tau_s (vector with sticition momentums of all joints)" + Value "tau_s" + } + Object { + $ObjectID 57 + Type "edit" + Name "qD_s" + Prompt "qD_s (vector with Stribeck velocities of all joints)" + Value "qD_s" + } + Object { + $ObjectID 58 + Type "edit" + Name "delta_s" + Prompt "delta_s (vector with stiction exponents for all joints)" + Value "delta_s" + } + Object { + $ObjectID 59 + Type "edit" + Name "qD_th" + Prompt "qD_th (vector with theshold velocities for stiction)" + Value "qD_th" + } + Object { + $ObjectID 60 + Type "edit" + Name "tau_th" + Prompt "tau_th (vector with kick-in momentums for stiction compensation)" + Value "tau_th" + } + Object { + $ObjectID 61 + Type "edit" + Name "K_tau_g" + Prompt "K_tau_g (gain of gravity compensation)" + Value "K_tau_g" + } + Object { + $ObjectID 62 + Type "edit" + Name "K_tau_c" + Prompt "K_tau_c (gain of corriolis- and inertia compensation)" + Value "K_tau_c" + } + Object { + $ObjectID 63 + Type "edit" + Name "K_tau_F" + Prompt "K_tau_F (gain of friction compensation)" + Value "K_tau_F" + } + Object { + $ObjectID 64 + Type "edit" + Name "K_tau_K" + Prompt "K_tau_K (gain of stiffness component)" + Value "K_tau_K" + } + Object { + $ObjectID 65 + Type "edit" + Name "K_tau_D" + Prompt "K_tau_D (gain of damping component)" + Value "K_tau_D" + } + Object { + $ObjectID 66 + Type "edit" + Name "K_tau_a" + Prompt "K_tau_a (gain of acceleration component)" + Value "K_tau_a" + } + Object { + $ObjectID 67 + Type "edit" + Name "MPV" + Prompt "MPV (vector of minimal parameters)" + Value "MPV" + } + PropName "Parameters" + } + } + System { + Name "atlas_joint_impctrl" + Location [-8, -8, 1928, 1168] + Open off + ModelBrowserVisibility off + ModelBrowserWidth 200 + ScreenColor "white" + PaperOrientation "landscape" + PaperPositionMode "auto" + PaperType "usletter" + PaperUnits "inches" + TiledPaperMargins [0.500000, 0.500000, 0.500000, 0.500000] + TiledPageScale 1 + ShowPageBoundaries off + ZoomFactor "100" + Block { + BlockType Inport + Name "q" + SID "463" + Position [25, 48, 55, 62] + ZOrder 176 + IconDisplay "Port number" + } + Block { + BlockType Inport + Name "qD" + SID "464" + Position [25, 123, 55, 137] + ZOrder 177 + Port "2" + IconDisplay "Port number" + } + Block { + BlockType Inport + Name "q_d" + SID "465" + Position [25, 198, 55, 212] + ZOrder 178 + Port "3" + IconDisplay "Port number" + } + Block { + BlockType Inport + Name "qD_d" + SID "466" + Position [25, 273, 55, 287] + ZOrder 179 + Port "4" + IconDisplay "Port number" + } + Block { + BlockType Inport + Name "qDD_d" + SID "467" + Position [25, 348, 55, 362] + ZOrder 180 + Port "5" + IconDisplay "Port number" + } + Block { + BlockType Inport + Name "g" + SID "468" + Position [25, 508, 55, 522] + ZOrder 189 + Port "6" + IconDisplay "Port number" + } + Block { + BlockType Reference + Name "atlas_arm_coriolis_vec_minvarpar" + SID "469" + Ports [2, 1] + Position [165, 402, 235, 453] + ZOrder 193 + LibraryVersion "1.228" + SourceBlock "atlas_dynamic_library/atlas_arm_coriolis_vec_minvarpar" + SourceType "" + ContentPreviewEnabled off + atlas_arm_lr "atlas_arm_lr" + atlas_version "atlas_version" + MPV "MPV" + } + Block { + BlockType Reference + Name "atlas_arm_gravload_minvarpar" + SID "470" + Ports [2, 1] + Position [165, 477, 235, 528] + ZOrder 191 + LibraryVersion "1.228" + SourceBlock "atlas_dynamic_library/atlas_arm_gravload_minvarpar" + SourceType "" + ContentPreviewEnabled off + atlas_arm_lr "atlas_arm_lr" + atlas_version "atlas_version" + MPV "MPV" + } + Block { + BlockType Reference + Name "atlas_arm_inertia_minvarpar" + SID "471" + Ports [1, 1] + Position [165, 556, 235, 604] + ZOrder 192 + LibraryVersion "1.228" + SourceBlock "atlas_dynamic_library/atlas_arm_inertia_minvarpar" + SourceType "" + ContentPreviewEnabled off + atlas_arm_lr "atlas_arm_lr" + atlas_version "atlas_version" + MPV "MPV" + } + Block { + BlockType Reference + Name "atlas_joint_impctrl_base" + SID "475" + Ports [8, 1] + Position [275, 18, 485, 617] + ZOrder 194 + LibraryVersion "1.359" + SourceBlock "atlas_impctrl_library/atlas_joint_impctrl_base" + SourceType "Joint Impedance Controller Base" + ContentPreviewEnabled off + K_d "K_d" + D "D" + tau_c "tau_c" + B "B" + tau_s "tau_s" + qD_s "qD_s" + delta_s "delta_s" + qD_th "qD_th" + tau_th "tau_th" + K_tau_g "K_tau_g" + K_tau_c "K_tau_c" + K_tau_F "K_tau_F" + K_tau_K "K_tau_K" + K_tau_D "K_tau_D" + K_tau_a "K_tau_a" + } + Block { + BlockType Outport + Name "tau" + SID "473" + Position [515, 313, 545, 327] + ZOrder 185 + IconDisplay "Port number" + } + Line { + ZOrder 27 + SrcBlock "atlas_joint_impctrl_base" + SrcPort 1 + DstBlock "tau" + DstPort 1 + } + Line { + ZOrder 26 + SrcBlock "atlas_arm_inertia_minvarpar" + SrcPort 1 + DstBlock "atlas_joint_impctrl_base" + DstPort 8 + } + Line { + ZOrder 3 + SrcBlock "q" + SrcPort 1 + Points [20, 0] + Branch { + ZOrder 4 + Points [0, 525] + DstBlock "atlas_arm_inertia_minvarpar" + DstPort 1 + } + Branch { + ZOrder 5 + Points [30, 0] + Branch { + ZOrder 6 + Points [0, 435] + DstBlock "atlas_arm_gravload_minvarpar" + DstPort 1 + } + Branch { + ZOrder 7 + Points [41, 0] + Branch { + ZOrder 19 + DstBlock "atlas_joint_impctrl_base" + DstPort 1 + } + Branch { + ZOrder 8 + Points [0, 360] + DstBlock "atlas_arm_coriolis_vec_minvarpar" + DstPort 1 + } + } + } + } + Line { + ZOrder 10 + SrcBlock "qD" + SrcPort 1 + Points [76, 0] + Branch { + ZOrder 20 + DstBlock "atlas_joint_impctrl_base" + DstPort 2 + } + Branch { + ZOrder 11 + Points [0, 310] + DstBlock "atlas_arm_coriolis_vec_minvarpar" + DstPort 2 + } + } + Line { + ZOrder 21 + SrcBlock "q_d" + SrcPort 1 + DstBlock "atlas_joint_impctrl_base" + DstPort 3 + } + Line { + ZOrder 24 + SrcBlock "atlas_arm_coriolis_vec_minvarpar" + SrcPort 1 + DstBlock "atlas_joint_impctrl_base" + DstPort 6 + } + Line { + ZOrder 22 + SrcBlock "qD_d" + SrcPort 1 + DstBlock "atlas_joint_impctrl_base" + DstPort 4 + } + Line { + ZOrder 25 + SrcBlock "atlas_arm_gravload_minvarpar" + SrcPort 1 + DstBlock "atlas_joint_impctrl_base" + DstPort 7 + } + Line { + ZOrder 23 + SrcBlock "qDD_d" + SrcPort 1 + DstBlock "atlas_joint_impctrl_base" + DstPort 5 + } + Line { + ZOrder 18 + SrcBlock "g" + SrcPort 1 + DstBlock "atlas_arm_gravload_minvarpar" + DstPort 2 + } + } + } + Block { + BlockType SubSystem + Name "atlas_joint_impctrl_base" + SID "396" + Ports [8, 1] + Position [635, 98, 855, 367] + ZOrder 182 + TreatAsAtomicUnit on + RequestExecContextInheritance off + Object { + $PropName "MaskObject" + $ObjectID 68 + $ClassName "Simulink.Mask" + Type "Joint Impedance Controller Base" + Description "Hardware independent impedance controller base block with mdouble\ndiagonalization damping design. For " + "a better testing, all partial \nmomentums can be individually scaled. Coulomb-, viscous friction\nand Stribeck sticti" + "on is taken into account for friction compen-\nsation." + Array { + Type "Simulink.MaskParameter" + Dimension 15 + Object { + $ObjectID 69 + Type "edit" + Name "K_d" + Prompt "K_d (desired stiffness)" + Value "K_d" + } + Object { + $ObjectID 70 + Type "edit" + Name "D" + Prompt "D (diagonal matrix with desired damping coefficients)" + Value "D" + } + Object { + $ObjectID 71 + Type "edit" + Name "tau_c" + Prompt "tau_c (vector with coulomb friction momentums for all joints)" + Value "tau_c" + } + Object { + $ObjectID 72 + Type "edit" + Name "B" + Prompt "B (vector with viscous friction coefficients of all joints)" + Value "B" + } + Object { + $ObjectID 73 + Type "edit" + Name "tau_s" + Prompt "tau_s (vector with sticition momentums of all joints)" + Value "tau_s" + } + Object { + $ObjectID 74 + Type "edit" + Name "qD_s" + Prompt "qD_s (vector with Stribeck velocities of all joints)" + Value "qD_s" + } + Object { + $ObjectID 75 + Type "edit" + Name "delta_s" + Prompt "delta_s (vector with stiction exponents for all joints)" + Value "delta_s" + } + Object { + $ObjectID 76 + Type "edit" + Name "qD_th" + Prompt "qD_th (vector with theshold velocities for stiction)" + Value "qD_th" + } + Object { + $ObjectID 77 + Type "edit" + Name "tau_th" + Prompt "tau_th (vector with kick-in momentums for stiction compensation)" + Value "tau_th" + } + Object { + $ObjectID 78 + Type "edit" + Name "K_tau_g" + Prompt "K_tau_g (gain of gravity compensation)" + Value "K_tau_g" + } + Object { + $ObjectID 79 + Type "edit" + Name "K_tau_c" + Prompt "K_tau_c (gain of corriolis- and inertia compensation)" + Value "K_tau_c" + } + Object { + $ObjectID 80 + Type "edit" + Name "K_tau_F" + Prompt "K_tau_F (gain of friction compensation)" + Value "K_tau_F" + } + Object { + $ObjectID 81 + Type "edit" + Name "K_tau_K" + Prompt "K_tau_K (gain of stiffness component)" + Value "K_tau_K" + } + Object { + $ObjectID 82 + Type "edit" + Name "K_tau_D" + Prompt "K_tau_D (gain of damping component)" + Value "K_tau_D" + } + Object { + $ObjectID 83 + Type "edit" + Name "K_tau_a" + Prompt "K_tau_a (gain of acceleration component)" + Value "K_tau_a" + } + PropName "Parameters" + } + Array { + Type "Simulink.dialog.Group" + Dimension 2 + Object { + $ObjectID 84 + Prompt "%" + Object { + $PropName "DialogControls" + $ObjectID 85 + $ClassName "Simulink.dialog.Text" + Prompt "%" + WordWrap "off" + Name "DescTextVar" + } + Name "DescGroupVar" + } + Object { + $ObjectID 86 + Prompt "Simulink:studio:ToolBarParametersMenu" + Array { + Type "Simulink.dialog.parameter.Edit" + Dimension 15 + Object { + $ObjectID 87 + Name "K_d" + } + Object { + $ObjectID 88 + Name "D" + } + Object { + $ObjectID 89 + Name "tau_c" + } + Object { + $ObjectID 90 + Name "B" + } + Object { + $ObjectID 91 + Name "tau_s" + } + Object { + $ObjectID 92 + Name "qD_s" + } + Object { + $ObjectID 93 + Name "delta_s" + } + Object { + $ObjectID 94 + Name "qD_th" + } + Object { + $ObjectID 95 + Name "tau_th" + } + Object { + $ObjectID 96 + Name "K_tau_g" + } + Object { + $ObjectID 97 + Name "K_tau_c" + } + Object { + $ObjectID 98 + Name "K_tau_F" + } + Object { + $ObjectID 99 + Name "K_tau_K" + } + Object { + $ObjectID 100 + Name "K_tau_D" + } + Object { + $ObjectID 101 + Name "K_tau_a" + } + PropName "DialogControls" + } + Name "ParameterGroupVar" + } + PropName "DialogControls" + } + } + System { + Name "atlas_joint_impctrl_base" + Location [-8, -8, 1928, 1168] + Open off + ModelBrowserVisibility off + ModelBrowserWidth 200 + ScreenColor "white" + PaperOrientation "landscape" + PaperPositionMode "auto" + PaperType "usletter" + PaperUnits "inches" + TiledPaperMargins [0.500000, 0.500000, 0.500000, 0.500000] + TiledPageScale 1 + ShowPageBoundaries off + ZoomFactor "100" + Block { + BlockType Inport + Name "q" + SID "397" + Position [5, 298, 35, 312] + ZOrder 148 + IconDisplay "Port number" + } + Block { + BlockType Inport + Name "qD" + SID "398" + Position [5, 383, 35, 397] + ZOrder 149 + Port "2" + IconDisplay "Port number" + } + Block { + BlockType Inport + Name "q_d" + SID "399" + Position [5, 333, 35, 347] + ZOrder 151 + Port "3" + IconDisplay "Port number" + } + Block { + BlockType Inport + Name "qD_d" + SID "400" + Position [5, 418, 35, 432] + ZOrder 152 + Port "4" + IconDisplay "Port number" + } + Block { + BlockType Inport + Name "qDD_d" + SID "401" + Position [5, 463, 35, 477] + ZOrder 153 + Port "5" + IconDisplay "Port number" + } + Block { + BlockType Inport + Name "tau_c" + SID "402" + Position [255, 58, 285, 72] + ZOrder 154 + Port "6" + IconDisplay "Port number" + } + Block { + BlockType Inport + Name "tau_g" + SID "403" + Position [255, 138, 285, 152] + ZOrder 155 + Port "7" + IconDisplay "Port number" + } + Block { + BlockType Inport + Name "M" + SID "404" + Position [5, 173, 35, 187] + ZOrder 158 + Port "8" + IconDisplay "Port number" + } + Block { + BlockType Sum + Name "Add" + SID "405" + Ports [6, 1] + Position [635, 19, 680, 511] + ZOrder 165 + Inputs "+++--+" + InputSameDT off + OutDataTypeStr "Inherit: Inherit via internal rule" + SaturateOnIntegerOverflow off + } + Block { + BlockType Sum + Name "Add1" + SID "406" + Ports [3, 1] + Position [370, 164, 400, 246] + ZOrder 188 + Inputs "--+" + InputSameDT off + OutDataTypeStr "Inherit: Inherit via internal rule" + SaturateOnIntegerOverflow off + } + Block { + BlockType Gain + Name "Gain" + SID "407" + Position [555, 45, 610, 85] + ZOrder 182 + Gain "K_tau_c" + ParamDataTypeStr "Inherit: Inherit via internal rule" + OutDataTypeStr "Inherit: Inherit via internal rule" + SaturateOnIntegerOverflow off + } + Block { + BlockType Gain + Name "Gain1" + SID "408" + Position [555, 125, 610, 165] + ZOrder 183 + Gain "K_tau_g" + ParamDataTypeStr "Inherit: Inherit via internal rule" + OutDataTypeStr "Inherit: Inherit via internal rule" + SaturateOnIntegerOverflow off + } + Block { + BlockType Gain + Name "Gain2" + SID "409" + Position [555, 285, 610, 325] + ZOrder 184 + Gain "K_tau_K" + ParamDataTypeStr "Inherit: Inherit via internal rule" + OutDataTypeStr "Inherit: Inherit via internal rule" + SaturateOnIntegerOverflow off + } + Block { + BlockType Gain + Name "Gain3" + SID "410" + Position [555, 365, 610, 405] + ZOrder 185 + Gain "K_tau_D" + ParamDataTypeStr "Inherit: Inherit via internal rule" + OutDataTypeStr "Inherit: Inherit via internal rule" + SaturateOnIntegerOverflow off + } + Block { + BlockType Gain + Name "Gain4" + SID "411" + Position [555, 445, 610, 485] + ZOrder 186 + Gain "K_tau_a" + ParamDataTypeStr "Inherit: Inherit via internal rule" + OutDataTypeStr "Inherit: Inherit via internal rule" + SaturateOnIntegerOverflow off + } + Block { + BlockType Gain + Name "Gain5" + SID "412" + Position [555, 205, 610, 245] + ZOrder 187 + Gain "K_tau_F" + ParamDataTypeStr "Inherit: Inherit via internal rule" + OutDataTypeStr "Inherit: Inherit via internal rule" + SaturateOnIntegerOverflow off + } + Block { + BlockType Gain + Name "K_d" + SID "413" + Position [255, 280, 300, 330] + ZOrder 172 + Gain "K_d" + Multiplication "Matrix(K*u)" + ParamDataTypeStr "Inherit: Inherit via internal rule" + OutDataTypeStr "Inherit: Inherit via internal rule" + SaturateOnIntegerOverflow off + } + Block { + BlockType Product + Name "Product1" + SID "414" + Ports [2, 1] + Position [255, 367, 295, 398] + ZOrder 163 + Multiplication "Matrix(*)" + InputSameDT off + OutDataTypeStr "Inherit: Inherit via internal rule" + RndMeth "Floor" + SaturateOnIntegerOverflow off + } + Block { + BlockType Product + Name "Product2" + SID "415" + Ports [2, 1] + Position [255, 447, 295, 478] + ZOrder 164 + Multiplication "Matrix(*)" + InputSameDT off + OutDataTypeStr "Inherit: Inherit via internal rule" + RndMeth "Floor" + SaturateOnIntegerOverflow off + } + Block { + BlockType Sum + Name "Sum" + SID "416" + Ports [2, 1] + Position [65, 295, 85, 315] + ZOrder 160 + ShowName off + IconShape "round" + Inputs "|+-" + InputSameDT off + OutDataTypeStr "Inherit: Inherit via internal rule" + SaturateOnIntegerOverflow off + Port { + PortNumber 1 + Name "q~" + RTWStorageClass "Auto" + DataLoggingNameMode "SignalName" + } + } + Block { + BlockType Sum + Name "Sum1" + SID "417" + Ports [2, 1] + Position [65, 380, 85, 400] + ZOrder 161 + ShowName off + IconShape "round" + Inputs "|+-" + InputSameDT off + OutDataTypeStr "Inherit: Inherit via internal rule" + SaturateOnIntegerOverflow off + Port { + PortNumber 1 + Name "qD~" + RTWStorageClass "Auto" + DataLoggingNameMode "SignalName" + } + } + Block { + BlockType Reference + Name "double_diag" + SID "445" + Ports [1, 1] + Position [130, 157, 200, 203] + ZOrder 191 + LibraryVersion "1.359" + SourceBlock "atlas_impctrl_library/double_diag" + SourceType "" + ContentPreviewEnabled off + K_d "K_d" + D "D" + } + Block { + BlockType Reference + Name "friction_compensation" + SID "418" + Ports [2, 1] + Position [430, 187, 530, 263] + ZOrder 190 + LibraryVersion "1.359" + SourceBlock "atlas_impctrl_library/friction_compensation" + SourceType "" + ContentPreviewEnabled off + tau_c "tau_c" + B "B" + qD_th "qD_th" + tau_th "tau_th" + } + Block { + BlockType Outport + Name "tau" + SID "420" + Position [725, 258, 755, 272] + ZOrder 166 + IconDisplay "Port number" + } + Line { + ZOrder 1 + SrcBlock "M" + SrcPort 1 + Points [60, 0] + Branch { + ZOrder 35 + DstBlock "double_diag" + DstPort 1 + } + Branch { + ZOrder 3 + Points [0, 275] + DstBlock "Product2" + DstPort 1 + } + } + Line { + ZOrder 4 + SrcBlock "q" + SrcPort 1 + DstBlock "Sum" + DstPort 1 + } + Line { + ZOrder 5 + SrcBlock "q_d" + SrcPort 1 + Points [35, 0] + DstBlock "Sum" + DstPort 2 + } + Line { + ZOrder 6 + SrcBlock "qD" + SrcPort 1 + Points [7, 0] + Branch { + ZOrder 7 + Points [0, -33; 367, 0; 0, -112] + DstBlock "friction_compensation" + DstPort 2 + } + Branch { + ZOrder 8 + DstBlock "Sum1" + DstPort 1 + } + } + Line { + ZOrder 9 + SrcBlock "qD_d" + SrcPort 1 + Points [35, 0] + DstBlock "Sum1" + DstPort 2 + } + Line { + Name "qD~" + ZOrder 10 + Labels [1, 1] + SrcBlock "Sum1" + SrcPort 1 + DstBlock "Product1" + DstPort 2 + } + Line { + Name "q~" + ZOrder 11 + Labels [1, 1] + SrcBlock "Sum" + SrcPort 1 + DstBlock "K_d" + DstPort 1 + } + Line { + ZOrder 12 + SrcBlock "qDD_d" + SrcPort 1 + DstBlock "Product2" + DstPort 2 + } + Line { + ZOrder 36 + SrcBlock "double_diag" + SrcPort 1 + Points [21, 0; 0, 195] + DstBlock "Product1" + DstPort 1 + } + Line { + ZOrder 14 + SrcBlock "Add" + SrcPort 1 + DstBlock "tau" + DstPort 1 + } + Line { + ZOrder 15 + SrcBlock "K_d" + SrcPort 1 + Points [3, 0] + Branch { + ZOrder 16 + Points [0, -125] + DstBlock "Add1" + DstPort 1 + } + Branch { + ZOrder 17 + DstBlock "Gain2" + DstPort 1 + } + } + Line { + ZOrder 18 + SrcBlock "tau_g" + SrcPort 1 + DstBlock "Gain1" + DstPort 1 + } + Line { + ZOrder 19 + SrcBlock "tau_c" + SrcPort 1 + DstBlock "Gain" + DstPort 1 + } + Line { + ZOrder 20 + SrcBlock "Product1" + SrcPort 1 + Points [28, 0] + Branch { + ZOrder 21 + Points [0, -180] + DstBlock "Add1" + DstPort 2 + } + Branch { + ZOrder 22 + DstBlock "Gain3" + DstPort 1 + } + } + Line { + ZOrder 23 + SrcBlock "Product2" + SrcPort 1 + Points [49, 0] + Branch { + ZOrder 24 + Points [0, -235] + DstBlock "Add1" + DstPort 3 + } + Branch { + ZOrder 25 + DstBlock "Gain4" + DstPort 1 + } + } + Line { + ZOrder 26 + SrcBlock "Gain" + SrcPort 1 + DstBlock "Add" + DstPort 1 + } + Line { + ZOrder 27 + SrcBlock "Gain1" + SrcPort 1 + DstBlock "Add" + DstPort 2 + } + Line { + ZOrder 28 + SrcBlock "Gain2" + SrcPort 1 + DstBlock "Add" + DstPort 4 + } + Line { + ZOrder 29 + SrcBlock "Gain3" + SrcPort 1 + DstBlock "Add" + DstPort 5 + } + Line { + ZOrder 30 + SrcBlock "Gain4" + SrcPort 1 + DstBlock "Add" + DstPort 6 + } + Line { + ZOrder 31 + SrcBlock "Gain5" + SrcPort 1 + DstBlock "Add" + DstPort 3 + } + Line { + ZOrder 32 + SrcBlock "friction_compensation" + SrcPort 1 + DstBlock "Gain5" + DstPort 1 + } + Line { + ZOrder 33 + SrcBlock "Add1" + SrcPort 1 + DstBlock "friction_compensation" + DstPort 1 + } + } + } + Block { + BlockType SubSystem + Name "atlas_joint_impctrl_const_damping" + SID "451" + Ports [6, 1] + Position [1190, 400, 1410, 640] + ZOrder 184 + TreatAsAtomicUnit on + RequestExecContextInheritance off + Object { + $PropName "MaskObject" + $ObjectID 102 + $ClassName "Simulink.Mask" + Type "Atlas Joint Impedance Controller" + Description "Hardware dependent full impedance controller block with\nconstant damping design for the atlas robot. F" + "or a better\ntesting, all partial momentums can be individually scaled.\nCoulomb-, viscous friction and Stribeck stic" + "tion is taken into\naccount for friction compensation." + Array { + Type "Simulink.MaskParameter" + Dimension 16 + Object { + $ObjectID 103 + Type "edit" + Name "K_d" + Prompt "K_d (desired stiffness)" + Value "K_d" + } + Object { + $ObjectID 104 + Type "edit" + Name "D" + Prompt "D (diagonal matrix with desired damping coefficients)" + Value "D" + } + Object { + $ObjectID 105 + Type "edit" + Name "tau_c" + Prompt "tau_c (vector with coulomb friction momentums for all joints)" + Value "tau_c" + } + Object { + $ObjectID 106 + Type "edit" + Name "B" + Prompt "B (vector with viscous friction coefficients of all joints)" + Value "B" + } + Object { + $ObjectID 107 + Type "edit" + Name "tau_s" + Prompt "tau_s (vector with sticition momentums of all joints)" + Value "tau_s" + } + Object { + $ObjectID 108 + Type "edit" + Name "qD_s" + Prompt "qD_s (vector with Stribeck velocities of all joints)" + Value "qD_s" + } + Object { + $ObjectID 109 + Type "edit" + Name "delta_s" + Prompt "delta_s (vector with stiction exponents for all joints)" + Value "delta_s" + } + Object { + $ObjectID 110 + Type "edit" + Name "qD_th" + Prompt "qD_th (vector with theshold velocities for stiction)" + Value "qD_th" + } + Object { + $ObjectID 111 + Type "edit" + Name "tau_th" + Prompt "tau_th (vector with kick-in momentums for stiction compensation)" + Value "tau_th" + } + Object { + $ObjectID 112 + Type "edit" + Name "K_tau_g" + Prompt "K_tau_g (gain of gravity compensation)" + Value "K_tau_g" + } + Object { + $ObjectID 113 + Type "edit" + Name "K_tau_c" + Prompt "K_tau_c (gain of corriolis- and inertia compensation)" + Value "K_tau_c" + } + Object { + $ObjectID 114 + Type "edit" + Name "K_tau_F" + Prompt "K_tau_F (gain of friction compensation)" + Value "K_tau_F" + } + Object { + $ObjectID 115 + Type "edit" + Name "K_tau_K" + Prompt "K_tau_K (gain of stiffness component)" + Value "K_tau_K" + } + Object { + $ObjectID 116 + Type "edit" + Name "K_tau_D" + Prompt "K_tau_D (gain of damping component)" + Value "K_tau_D" + } + Object { + $ObjectID 117 + Type "edit" + Name "K_tau_a" + Prompt "K_tau_a (gain of acceleration component)" + Value "K_tau_a" + } + Object { + $ObjectID 118 + Type "edit" + Name "MPV" + Prompt "MPV (vector of minimal parameters)" + Value "MPV" + } + PropName "Parameters" + } + } + System { + Name "atlas_joint_impctrl_const_damping" + Location [-8, -8, 1928, 1168] + Open off + ModelBrowserVisibility off + ModelBrowserWidth 200 + ScreenColor "white" + PaperOrientation "landscape" + PaperPositionMode "auto" + PaperType "usletter" + PaperUnits "inches" + TiledPaperMargins [0.500000, 0.500000, 0.500000, 0.500000] + TiledPageScale 1 + ShowPageBoundaries off + ZoomFactor "100" + Block { + BlockType Inport + Name "q" + SID "452" + Position [25, 48, 55, 62] + ZOrder 176 + IconDisplay "Port number" + } + Block { + BlockType Inport + Name "qD" + SID "453" + Position [25, 123, 55, 137] + ZOrder 177 + Port "2" + IconDisplay "Port number" + } + Block { + BlockType Inport + Name "q_d" + SID "454" + Position [25, 198, 55, 212] + ZOrder 178 + Port "3" + IconDisplay "Port number" + } + Block { + BlockType Inport + Name "qD_d" + SID "455" + Position [25, 273, 55, 287] + ZOrder 179 + Port "4" + IconDisplay "Port number" + } + Block { + BlockType Inport + Name "qDD_d" + SID "456" + Position [25, 348, 55, 362] + ZOrder 180 + Port "5" + IconDisplay "Port number" + } + Block { + BlockType Inport + Name "g" + SID "457" + Position [25, 508, 55, 522] + ZOrder 189 + Port "6" + IconDisplay "Port number" + } + Block { + BlockType Reference + Name "atlas_arm_coriolis_vec_minvarpar" + SID "458" + Ports [2, 1] + Position [165, 402, 235, 453] + ZOrder 193 + LibraryVersion "1.228" + SourceBlock "atlas_dynamic_library/atlas_arm_coriolis_vec_minvarpar" + SourceType "" + ContentPreviewEnabled off + atlas_arm_lr "atlas_arm_lr" + atlas_version "atlas_version" + MPV "MPV" + } + Block { + BlockType Reference + Name "atlas_arm_gravload_minvarpar" + SID "459" + Ports [2, 1] + Position [165, 477, 235, 528] + ZOrder 191 + LibraryVersion "1.228" + SourceBlock "atlas_dynamic_library/atlas_arm_gravload_minvarpar" + SourceType "" + ContentPreviewEnabled off + atlas_arm_lr "atlas_arm_lr" + atlas_version "atlas_version" + MPV "MPV" + } + Block { + BlockType Reference + Name "atlas_arm_inertia_minvarpar" + SID "460" + Ports [1, 1] + Position [165, 556, 235, 604] + ZOrder 192 + LibraryVersion "1.228" + SourceBlock "atlas_dynamic_library/atlas_arm_inertia_minvarpar" + SourceType "" + ContentPreviewEnabled off + atlas_arm_lr "atlas_arm_lr" + atlas_version "atlas_version" + MPV "MPV" + } + Block { + BlockType Reference + Name "atlas_joint_impctrl_const_damping_base" + SID "474" + Ports [8, 1] + Position [275, 19, 485, 616] + ZOrder 194 + LibraryVersion "1.359" + SourceBlock "atlas_impctrl_library/atlas_joint_impctrl_const_damping_base" + SourceType "Joint Impedance Controller Base" + ContentPreviewEnabled off + K_d "K_d" + D "D" + tau_c "tau_c" + B "B" + tau_s "tau_s" + qD_s "qD_s" + delta_s "delta_s" + qD_th "qD_th" + tau_th "tau_th" + K_tau_g "K_tau_g" + K_tau_c "K_tau_c" + K_tau_F "K_tau_F" + K_tau_K "K_tau_K" + K_tau_D "K_tau_D" + K_tau_a "K_tau_a" + } + Block { + BlockType Outport + Name "tau" + SID "462" + Position [515, 313, 545, 327] + ZOrder 185 + IconDisplay "Port number" + } + Line { + ZOrder 27 + SrcBlock "atlas_joint_impctrl_const_damping_base" + SrcPort 1 + DstBlock "tau" + DstPort 1 + } + Line { + ZOrder 26 + SrcBlock "atlas_arm_inertia_minvarpar" + SrcPort 1 + DstBlock "atlas_joint_impctrl_const_damping_base" + DstPort 8 + } + Line { + ZOrder 3 + SrcBlock "q" + SrcPort 1 + Points [20, 0] + Branch { + ZOrder 4 + Points [0, 525] + DstBlock "atlas_arm_inertia_minvarpar" + DstPort 1 + } + Branch { + ZOrder 5 + Points [30, 0] + Branch { + ZOrder 6 + Points [0, 435] + DstBlock "atlas_arm_gravload_minvarpar" + DstPort 1 + } + Branch { + ZOrder 7 + Points [41, 0] + Branch { + ZOrder 19 + DstBlock "atlas_joint_impctrl_const_damping_base" + DstPort 1 + } + Branch { + ZOrder 8 + Points [0, 360] + DstBlock "atlas_arm_coriolis_vec_minvarpar" + DstPort 1 + } + } + } + } + Line { + ZOrder 10 + SrcBlock "qD" + SrcPort 1 + Points [76, 0] + Branch { + ZOrder 20 + DstBlock "atlas_joint_impctrl_const_damping_base" + DstPort 2 + } + Branch { + ZOrder 11 + Points [0, 310] + DstBlock "atlas_arm_coriolis_vec_minvarpar" + DstPort 2 + } + } + Line { + ZOrder 21 + SrcBlock "q_d" + SrcPort 1 + DstBlock "atlas_joint_impctrl_const_damping_base" + DstPort 3 + } + Line { + ZOrder 24 + SrcBlock "atlas_arm_coriolis_vec_minvarpar" + SrcPort 1 + DstBlock "atlas_joint_impctrl_const_damping_base" + DstPort 6 + } + Line { + ZOrder 22 + SrcBlock "qD_d" + SrcPort 1 + DstBlock "atlas_joint_impctrl_const_damping_base" + DstPort 4 + } + Line { + ZOrder 25 + SrcBlock "atlas_arm_gravload_minvarpar" + SrcPort 1 + DstBlock "atlas_joint_impctrl_const_damping_base" + DstPort 7 + } + Line { + ZOrder 23 + SrcBlock "qDD_d" + SrcPort 1 + DstBlock "atlas_joint_impctrl_const_damping_base" + DstPort 5 + } + Line { + ZOrder 18 + SrcBlock "g" + SrcPort 1 + DstBlock "atlas_arm_gravload_minvarpar" + DstPort 2 + } + } + } + Block { + BlockType SubSystem + Name "atlas_joint_impctrl_const_damping_base" + SID "395" + Ports [8, 1] + Position [1190, 98, 1410, 367] + ZOrder 181 + TreatAsAtomicUnit on + RequestExecContextInheritance off + Object { + $PropName "MaskObject" + $ObjectID 119 + $ClassName "Simulink.Mask" + Type "Joint Impedance Controller Base" + Description "Hardware independent impedance controller base block with constant\ndamping design. For a better testin" + "g, all partial momentums can be\nindividually scaled. Coulomb-, viscous friction and Stribeck stiction\nis taken into" + " account for friction compensation." + Array { + Type "Simulink.MaskParameter" + Dimension 15 + Object { + $ObjectID 120 + Type "edit" + Name "K_d" + Prompt "K_d (desired stiffness)" + Value "K_d" + } + Object { + $ObjectID 121 + Type "edit" + Name "D" + Prompt "D (diagonal matrix with desired damping coefficients)" + Value "D" + } + Object { + $ObjectID 122 + Type "edit" + Name "tau_c" + Prompt "tau_c (vector with coulomb friction momentums for all joints)" + Value "tau_c" + } + Object { + $ObjectID 123 + Type "edit" + Name "B" + Prompt "B (vector with viscous friction coefficients of all joints)" + Value "B" + } + Object { + $ObjectID 124 + Type "edit" + Name "tau_s" + Prompt "tau_s (vector with sticition momentums of all joints)" + Value "tau_s" + } + Object { + $ObjectID 125 + Type "edit" + Name "qD_s" + Prompt "qD_s (vector with Stribeck velocities of all joints)" + Value "qD_s" + } + Object { + $ObjectID 126 + Type "edit" + Name "delta_s" + Prompt "delta_s (vector with stiction exponents for all joints)" + Value "delta_s" + } + Object { + $ObjectID 127 + Type "edit" + Name "qD_th" + Prompt "qD_th (vector with theshold velocities for stiction)" + Value "qD_th" + } + Object { + $ObjectID 128 + Type "edit" + Name "tau_th" + Prompt "tau_th (vector with kick-in momentums for stiction compensation)" + Value "tau_th" + } + Object { + $ObjectID 129 + Type "edit" + Name "K_tau_g" + Prompt "K_tau_g (gain of gravity compensation)" + Value "K_tau_g" + } + Object { + $ObjectID 130 + Type "edit" + Name "K_tau_c" + Prompt "K_tau_c (gain of corriolis- and inertia compensation)" + Value "K_tau_c" + } + Object { + $ObjectID 131 + Type "edit" + Name "K_tau_F" + Prompt "K_tau_F (gain of friction compensation)" + Value "K_tau_F" + } + Object { + $ObjectID 132 + Type "edit" + Name "K_tau_K" + Prompt "K_tau_K (gain of stiffness component)" + Value "K_tau_K" + } + Object { + $ObjectID 133 + Type "edit" + Name "K_tau_D" + Prompt "K_tau_D (gain of damping component)" + Value "K_tau_D" + } + Object { + $ObjectID 134 + Type "edit" + Name "K_tau_a" + Prompt "K_tau_a (gain of acceleration component)" + Value "K_tau_a" + } + PropName "Parameters" + } + Array { + Type "Simulink.dialog.Group" + Dimension 2 + Object { + $ObjectID 135 + Prompt "%" + Object { + $PropName "DialogControls" + $ObjectID 136 + $ClassName "Simulink.dialog.Text" + Prompt "%" + WordWrap "off" + Name "DescTextVar" + } + Name "DescGroupVar" + } + Object { + $ObjectID 137 + Prompt "Simulink:studio:ToolBarParametersMenu" + Array { + Type "Simulink.dialog.parameter.Edit" + Dimension 15 + Object { + $ObjectID 138 + Name "K_d" + } + Object { + $ObjectID 139 + Name "D" + } + Object { + $ObjectID 140 + Name "tau_c" + } + Object { + $ObjectID 141 + Name "B" + } + Object { + $ObjectID 142 + Name "tau_s" + } + Object { + $ObjectID 143 + Name "qD_s" + } + Object { + $ObjectID 144 + Name "delta_s" + } + Object { + $ObjectID 145 + Name "qD_th" + } + Object { + $ObjectID 146 + Name "tau_th" + } + Object { + $ObjectID 147 + Name "K_tau_g" + } + Object { + $ObjectID 148 + Name "K_tau_c" + } + Object { + $ObjectID 149 + Name "K_tau_F" + } + Object { + $ObjectID 150 + Name "K_tau_K" + } + Object { + $ObjectID 151 + Name "K_tau_D" + } + Object { + $ObjectID 152 + Name "K_tau_a" + } + PropName "DialogControls" + } + Name "ParameterGroupVar" + } + PropName "DialogControls" + } + } + System { + Name "atlas_joint_impctrl_const_damping_base" + Location [-8, -8, 1928, 1168] + Open off + ModelBrowserVisibility off + ModelBrowserWidth 200 + ScreenColor "white" + PaperOrientation "landscape" + PaperPositionMode "auto" + PaperType "usletter" + PaperUnits "inches" + TiledPaperMargins [0.500000, 0.500000, 0.500000, 0.500000] + TiledPageScale 1 + ShowPageBoundaries off + ZoomFactor "100" + Block { + BlockType Inport + Name "q" + SID "421" + Position [5, 298, 35, 312] + ZOrder 148 + IconDisplay "Port number" + } + Block { + BlockType Inport + Name "qD" + SID "422" + Position [5, 378, 35, 392] + ZOrder 149 + Port "2" + IconDisplay "Port number" + } + Block { + BlockType Inport + Name "q_d" + SID "423" + Position [5, 333, 35, 347] + ZOrder 151 + Port "3" + IconDisplay "Port number" + } + Block { + BlockType Inport + Name "qD_d" + SID "424" + Position [5, 413, 35, 427] + ZOrder 152 + Port "4" + IconDisplay "Port number" + } + Block { + BlockType Inport + Name "qDD_d" + SID "425" + Position [5, 473, 35, 487] + ZOrder 153 + Port "5" + IconDisplay "Port number" + } + Block { + BlockType Inport + Name "tau_c" + SID "426" + Position [255, 58, 285, 72] + ZOrder 154 + Port "6" + IconDisplay "Port number" + } + Block { + BlockType Inport + Name "tau_g" + SID "427" + Position [255, 138, 285, 152] + ZOrder 155 + Port "7" + IconDisplay "Port number" + } + Block { + BlockType Inport + Name "M" + SID "428" + Position [5, 443, 35, 457] + ZOrder 158 + Port "8" + IconDisplay "Port number" + } + Block { + BlockType Sum + Name "Add" + SID "429" + Ports [6, 1] + Position [635, 19, 680, 511] + ZOrder 165 + Inputs "+++--+" + InputSameDT off + OutDataTypeStr "Inherit: Inherit via internal rule" + SaturateOnIntegerOverflow off + } + Block { + BlockType Sum + Name "Add1" + SID "430" + Ports [3, 1] + Position [370, 164, 400, 246] + ZOrder 188 + Inputs "--+" + InputSameDT off + OutDataTypeStr "Inherit: Inherit via internal rule" + SaturateOnIntegerOverflow off + } + Block { + BlockType Gain + Name "Gain" + SID "431" + Position [555, 45, 610, 85] + ZOrder 182 + Gain "K_tau_c" + ParamDataTypeStr "Inherit: Inherit via internal rule" + OutDataTypeStr "Inherit: Inherit via internal rule" + SaturateOnIntegerOverflow off + } + Block { + BlockType Gain + Name "Gain1" + SID "432" + Position [555, 125, 610, 165] + ZOrder 183 + Gain "K_tau_g" + ParamDataTypeStr "Inherit: Inherit via internal rule" + OutDataTypeStr "Inherit: Inherit via internal rule" + SaturateOnIntegerOverflow off + } + Block { + BlockType Gain + Name "Gain2" + SID "433" + Position [555, 285, 610, 325] + ZOrder 184 + Gain "K_tau_K" + ParamDataTypeStr "Inherit: Inherit via internal rule" + OutDataTypeStr "Inherit: Inherit via internal rule" + SaturateOnIntegerOverflow off + } + Block { + BlockType Gain + Name "Gain3" + SID "434" + Position [555, 365, 610, 405] + ZOrder 185 + Gain "K_tau_D" + ParamDataTypeStr "Inherit: Inherit via internal rule" + OutDataTypeStr "Inherit: Inherit via internal rule" + SaturateOnIntegerOverflow off + } + Block { + BlockType Gain + Name "Gain4" + SID "435" + Position [555, 445, 610, 485] + ZOrder 186 + Gain "K_tau_a" + ParamDataTypeStr "Inherit: Inherit via internal rule" + OutDataTypeStr "Inherit: Inherit via internal rule" + SaturateOnIntegerOverflow off + } + Block { + BlockType Gain + Name "Gain5" + SID "436" + Position [555, 205, 610, 245] + ZOrder 187 + Gain "K_tau_F" + ParamDataTypeStr "Inherit: Inherit via internal rule" + OutDataTypeStr "Inherit: Inherit via internal rule" + SaturateOnIntegerOverflow off + } + Block { + BlockType Gain + Name "K_d" + SID "437" + Position [255, 280, 300, 330] + ZOrder 172 + Gain "K_d" + Multiplication "Matrix(K*u)" + ParamDataTypeStr "Inherit: Inherit via internal rule" + OutDataTypeStr "Inherit: Inherit via internal rule" + SaturateOnIntegerOverflow off + } + Block { + BlockType Gain + Name "K_d1" + SID "446" + Position [255, 360, 300, 410] + ZOrder 191 + Gain "D" + Multiplication "Matrix(K*u)" + ParamDataTypeStr "Inherit: Inherit via internal rule" + OutDataTypeStr "Inherit: Inherit via internal rule" + SaturateOnIntegerOverflow off + } + Block { + BlockType Product + Name "Product2" + SID "439" + Ports [2, 1] + Position [255, 436, 295, 494] + ZOrder 164 + Multiplication "Matrix(*)" + InputSameDT off + OutDataTypeStr "Inherit: Inherit via internal rule" + RndMeth "Floor" + SaturateOnIntegerOverflow off + } + Block { + BlockType Sum + Name "Sum" + SID "440" + Ports [2, 1] + Position [65, 295, 85, 315] + ZOrder 160 + ShowName off + IconShape "round" + Inputs "|+-" + InputSameDT off + OutDataTypeStr "Inherit: Inherit via internal rule" + SaturateOnIntegerOverflow off + Port { + PortNumber 1 + Name "q~" + RTWStorageClass "Auto" + DataLoggingNameMode "SignalName" + } + } + Block { + BlockType Sum + Name "Sum1" + SID "441" + Ports [2, 1] + Position [65, 375, 85, 395] + ZOrder 161 + ShowName off + IconShape "round" + Inputs "|+-" + InputSameDT off + OutDataTypeStr "Inherit: Inherit via internal rule" + SaturateOnIntegerOverflow off + Port { + PortNumber 1 + Name "qD~" + RTWStorageClass "Auto" + DataLoggingNameMode "SignalName" + } + } + Block { + BlockType Reference + Name "friction_compensation" + SID "442" + Ports [2, 1] + Position [430, 187, 530, 263] + ZOrder 190 + LibraryVersion "1.359" + SourceBlock "atlas_impctrl_library/friction_compensation" + SourceType "" + ContentPreviewEnabled off + tau_c "tau_c" + B "B" + qD_th "qD_th" + tau_th "tau_th" + } + Block { + BlockType Outport + Name "tau" + SID "444" + Position [725, 258, 755, 272] + ZOrder 166 + IconDisplay "Port number" + } + Line { + ZOrder 1 + SrcBlock "M" + SrcPort 1 + DstBlock "Product2" + DstPort 1 + } + Line { + ZOrder 4 + SrcBlock "q" + SrcPort 1 + DstBlock "Sum" + DstPort 1 + } + Line { + ZOrder 5 + SrcBlock "q_d" + SrcPort 1 + Points [35, 0] + DstBlock "Sum" + DstPort 2 + } + Line { + ZOrder 6 + SrcBlock "qD" + SrcPort 1 + Points [7, 0] + Branch { + ZOrder 7 + Points [0, -28; 367, 0; 0, -112] + DstBlock "friction_compensation" + DstPort 2 + } + Branch { + ZOrder 8 + DstBlock "Sum1" + DstPort 1 + } + } + Line { + ZOrder 9 + SrcBlock "qD_d" + SrcPort 1 + Points [35, 0] + DstBlock "Sum1" + DstPort 2 + } + Line { + Name "qD~" + ZOrder 35 + Labels [1, 1] + SrcBlock "Sum1" + SrcPort 1 + DstBlock "K_d1" + DstPort 1 + } + Line { + Name "q~" + ZOrder 11 + Labels [1, 1] + SrcBlock "Sum" + SrcPort 1 + DstBlock "K_d" + DstPort 1 + } + Line { + ZOrder 12 + SrcBlock "qDD_d" + SrcPort 1 + DstBlock "Product2" + DstPort 2 + } + Line { + ZOrder 14 + SrcBlock "Add" + SrcPort 1 + DstBlock "tau" + DstPort 1 + } + Line { + ZOrder 15 + SrcBlock "K_d" + SrcPort 1 + Points [3, 0] + Branch { + ZOrder 16 + Points [0, -125] + DstBlock "Add1" + DstPort 1 + } + Branch { + ZOrder 17 + DstBlock "Gain2" + DstPort 1 + } + } + Line { + ZOrder 18 + SrcBlock "tau_g" + SrcPort 1 + DstBlock "Gain1" + DstPort 1 + } + Line { + ZOrder 19 + SrcBlock "tau_c" + SrcPort 1 + DstBlock "Gain" + DstPort 1 + } + Line { + ZOrder 34 + SrcBlock "K_d1" + SrcPort 1 + Points [23, 0] + Branch { + ZOrder 21 + Points [0, -180] + DstBlock "Add1" + DstPort 2 + } + Branch { + ZOrder 22 + DstBlock "Gain3" + DstPort 1 + } + } + Line { + ZOrder 23 + SrcBlock "Product2" + SrcPort 1 + Points [49, 0] + Branch { + ZOrder 37 + Points [0, -235] + DstBlock "Add1" + DstPort 3 + } + Branch { + ZOrder 36 + DstBlock "Gain4" + DstPort 1 + } + } + Line { + ZOrder 26 + SrcBlock "Gain" + SrcPort 1 + DstBlock "Add" + DstPort 1 + } + Line { + ZOrder 27 + SrcBlock "Gain1" + SrcPort 1 + DstBlock "Add" + DstPort 2 + } + Line { + ZOrder 28 + SrcBlock "Gain2" + SrcPort 1 + DstBlock "Add" + DstPort 4 + } + Line { + ZOrder 29 + SrcBlock "Gain3" + SrcPort 1 + DstBlock "Add" + DstPort 5 + } + Line { + ZOrder 30 + SrcBlock "Gain4" + SrcPort 1 + DstBlock "Add" + DstPort 6 + } + Line { + ZOrder 31 + SrcBlock "Gain5" + SrcPort 1 + DstBlock "Add" + DstPort 3 + } + Line { + ZOrder 32 + SrcBlock "friction_compensation" + SrcPort 1 + DstBlock "Gain5" + DstPort 1 + } + Line { + ZOrder 33 + SrcBlock "Add1" + SrcPort 1 + DstBlock "friction_compensation" + DstPort 1 + } + } + } + Block { + BlockType SubSystem + Name "atlas_joint_impctrl_const_damping_v5" + SID "574" + Ports [6, 1] + Position [1190, 675, 1410, 915] + ZOrder 235 + TreatAsAtomicUnit on + RequestExecContextInheritance off + Object { + $PropName "MaskObject" + $ObjectID 153 + $ClassName "Simulink.Mask" + Type "Atlas Joint Impedance Controller" + Description "Hardware dependent full impedance controller block with\nconstant damping design for the atlas robot. F" + "or a better\ntesting, all partial momentums can be individually scaled.\nCoulomb-, viscous friction and Stribeck stic" + "tion is taken into\naccount for friction compensation." + Array { + Type "Simulink.MaskParameter" + Dimension 16 + Object { + $ObjectID 154 + Type "edit" + Name "K_d" + Prompt "K_d (desired stiffness)" + Value "K_d" + } + Object { + $ObjectID 155 + Type "edit" + Name "D" + Prompt "D (diagonal matrix with desired damping coefficients)" + Value "D" + } + Object { + $ObjectID 156 + Type "edit" + Name "tau_c" + Prompt "tau_c (vector with coulomb friction momentums for all joints)" + Value "tau_c" + } + Object { + $ObjectID 157 + Type "edit" + Name "B" + Prompt "B (vector with viscous friction coefficients of all joints)" + Value "B" + } + Object { + $ObjectID 158 + Type "edit" + Name "tau_s" + Prompt "tau_s (vector with sticition momentums of all joints)" + Value "tau_s" + } + Object { + $ObjectID 159 + Type "edit" + Name "qD_s" + Prompt "qD_s (vector with Stribeck velocities of all joints)" + Value "qD_s" + } + Object { + $ObjectID 160 + Type "edit" + Name "delta_s" + Prompt "delta_s (vector with stiction exponents for all joints)" + Value "delta_s" + } + Object { + $ObjectID 161 + Type "edit" + Name "qD_th" + Prompt "qD_th (vector with theshold velocities for stiction)" + Value "qD_th" + } + Object { + $ObjectID 162 + Type "edit" + Name "tau_th" + Prompt "tau_th (vector with kick-in momentums for stiction compensation)" + Value "tau_th" + } + Object { + $ObjectID 163 + Type "edit" + Name "K_tau_g" + Prompt "K_tau_g (gain of gravity compensation)" + Value "K_tau_g" + } + Object { + $ObjectID 164 + Type "edit" + Name "K_tau_c" + Prompt "K_tau_c (gain of corriolis- and inertia compensation)" + Value "K_tau_c" + } + Object { + $ObjectID 165 + Type "edit" + Name "K_tau_F" + Prompt "K_tau_F (gain of friction compensation)" + Value "K_tau_F" + } + Object { + $ObjectID 166 + Type "edit" + Name "K_tau_K" + Prompt "K_tau_K (gain of stiffness component)" + Value "K_tau_K" + } + Object { + $ObjectID 167 + Type "edit" + Name "K_tau_D" + Prompt "K_tau_D (gain of damping component)" + Value "K_tau_D" + } + Object { + $ObjectID 168 + Type "edit" + Name "K_tau_a" + Prompt "K_tau_a (gain of acceleration component)" + Value "K_tau_a" + } + Object { + $ObjectID 169 + Type "edit" + Name "MPV" + Prompt "MPV (vector of minimal parameters)" + Value "MPV" + } + PropName "Parameters" + } + } + System { + Name "atlas_joint_impctrl_const_damping_v5" + Location [-8, -8, 1928, 1168] + Open off + ModelBrowserVisibility off + ModelBrowserWidth 200 + ScreenColor "white" + PaperOrientation "landscape" + PaperPositionMode "auto" + PaperType "A4" + PaperUnits "centimeters" + TiledPaperMargins [1.270000, 1.270000, 1.270000, 1.270000] + TiledPageScale 1 + ShowPageBoundaries off + ZoomFactor "100" + Block { + BlockType Inport + Name "q" + SID "576" + Position [25, 48, 55, 62] + ZOrder 176 + IconDisplay "Port number" + } + Block { + BlockType Inport + Name "qD" + SID "577" + Position [25, 123, 55, 137] + ZOrder 177 + Port "2" + IconDisplay "Port number" + } + Block { + BlockType Inport + Name "q_d" + SID "578" + Position [25, 198, 55, 212] + ZOrder 178 + Port "3" + IconDisplay "Port number" + } + Block { + BlockType Inport + Name "qD_d" + SID "579" + Position [25, 273, 55, 287] + ZOrder 179 + Port "4" + IconDisplay "Port number" + } + Block { + BlockType Inport + Name "qDD_d" + SID "580" + Position [25, 348, 55, 362] + ZOrder 180 + Port "5" + IconDisplay "Port number" + } + Block { + BlockType Inport + Name "g" + SID "581" + Position [25, 508, 55, 522] + ZOrder 189 + Port "6" + IconDisplay "Port number" + } + Block { + BlockType Reference + Name "atlas_arm_coriolis_vec_minvarpar" + SID "582" + Ports [2, 1] + Position [165, 402, 235, 453] + ZOrder 193 + LibraryVersion "1.228" + SourceBlock "atlas_dynamic_library/atlas_arm_coriolis_vec_minvarpar" + SourceType "" + ContentPreviewEnabled off + atlas_arm_lr "atlas_arm_lr" + atlas_version "atlas_version" + MPV "MPV" + } + Block { + BlockType Reference + Name "atlas_arm_gravload_minvarpar" + SID "583" + Ports [2, 1] + Position [165, 477, 235, 528] + ZOrder 191 + LibraryVersion "1.228" + SourceBlock "atlas_dynamic_library/atlas_arm_gravload_minvarpar" + SourceType "" + ContentPreviewEnabled off + atlas_arm_lr "atlas_arm_lr" + atlas_version "atlas_version" + MPV "MPV" + } + Block { + BlockType Reference + Name "atlas_arm_inertia_minvarpar" + SID "584" + Ports [1, 1] + Position [165, 556, 235, 604] + ZOrder 192 + LibraryVersion "1.228" + SourceBlock "atlas_dynamic_library/atlas_arm_inertia_minvarpar" + SourceType "" + ContentPreviewEnabled off + atlas_arm_lr "atlas_arm_lr" + atlas_version "atlas_version" + MPV "MPV" + } + Block { + BlockType Reference + Name "atlas_joint_impctrl_const_damping_base" + SID "585" + Ports [8, 1] + Position [275, 19, 485, 616] + ZOrder 194 + LibraryVersion "1.359" + SourceBlock "atlas_impctrl_library/atlas_joint_impctrl_const_damping_base" + SourceType "Joint Impedance Controller Base" + ContentPreviewEnabled off + K_d "K_d" + D "D" + tau_c "tau_c" + B "B" + tau_s "tau_s" + qD_s "qD_s" + delta_s "delta_s" + qD_th "qD_th" + tau_th "tau_th" + K_tau_g "K_tau_g" + K_tau_c "K_tau_c" + K_tau_F "K_tau_F" + K_tau_K "K_tau_K" + K_tau_D "K_tau_D" + K_tau_a "K_tau_a" + } + Block { + BlockType Outport + Name "tau" + SID "586" + Position [515, 313, 545, 327] + ZOrder 185 + IconDisplay "Port number" + } + Line { + ZOrder 1 + SrcBlock "atlas_joint_impctrl_const_damping_base" + SrcPort 1 + DstBlock "tau" + DstPort 1 + } + Line { + ZOrder 2 + SrcBlock "atlas_arm_inertia_minvarpar" + SrcPort 1 + DstBlock "atlas_joint_impctrl_const_damping_base" + DstPort 8 + } + Line { + ZOrder 3 + SrcBlock "q" + SrcPort 1 + Points [20, 0] + Branch { + ZOrder 4 + Points [0, 525] + DstBlock "atlas_arm_inertia_minvarpar" + DstPort 1 + } + Branch { + ZOrder 5 + Points [30, 0] + Branch { + ZOrder 6 + Points [0, 435] + DstBlock "atlas_arm_gravload_minvarpar" + DstPort 1 + } + Branch { + ZOrder 7 + Points [41, 0] + Branch { + ZOrder 8 + DstBlock "atlas_joint_impctrl_const_damping_base" + DstPort 1 + } + Branch { + ZOrder 9 + Points [0, 360] + DstBlock "atlas_arm_coriolis_vec_minvarpar" + DstPort 1 + } + } + } + } + Line { + ZOrder 10 + SrcBlock "qD" + SrcPort 1 + Points [76, 0] + Branch { + ZOrder 11 + DstBlock "atlas_joint_impctrl_const_damping_base" + DstPort 2 + } + Branch { + ZOrder 12 + Points [0, 310] + DstBlock "atlas_arm_coriolis_vec_minvarpar" + DstPort 2 + } + } + Line { + ZOrder 13 + SrcBlock "q_d" + SrcPort 1 + DstBlock "atlas_joint_impctrl_const_damping_base" + DstPort 3 + } + Line { + ZOrder 14 + SrcBlock "atlas_arm_coriolis_vec_minvarpar" + SrcPort 1 + DstBlock "atlas_joint_impctrl_const_damping_base" + DstPort 6 + } + Line { + ZOrder 15 + SrcBlock "qD_d" + SrcPort 1 + DstBlock "atlas_joint_impctrl_const_damping_base" + DstPort 4 + } + Line { + ZOrder 16 + SrcBlock "atlas_arm_gravload_minvarpar" + SrcPort 1 + DstBlock "atlas_joint_impctrl_const_damping_base" + DstPort 7 + } + Line { + ZOrder 17 + SrcBlock "qDD_d" + SrcPort 1 + DstBlock "atlas_joint_impctrl_const_damping_base" + DstPort 5 + } + Line { + ZOrder 18 + SrcBlock "g" + SrcPort 1 + DstBlock "atlas_arm_gravload_minvarpar" + DstPort 2 + } + } + } + Block { + BlockType SubSystem + Name "atlas_joint_impctrl_sqrt_damping" + SID "348" + Ports [8, 2] + Position [915, 400, 1135, 640] + ZOrder 223 + LibraryVersion "*1.179" + TreatAsAtomicUnit on + RequestExecContextInheritance off + Object { + $PropName "MaskObject" + $ObjectID 170 + $ClassName "Simulink.Mask" + Type "Atlas Joint Impedance Controller" + Description "Hardware dependent full impedance controller block with matrix\nsquareroot damping design for the atlas" + " robot. For a better\ntesting, all partial momentums can be individually scaled.\nCoulomb-, viscous friction and Stri" + "beck stiction is taken into\naccount for friction compensation." + Array { + Type "Simulink.MaskParameter" + Dimension 12 + Object { + $ObjectID 171 + Type "edit" + Name "K_d" + Prompt "K_d (desired stiffness)" + Value "K_d" + } + Object { + $ObjectID 172 + Type "edit" + Name "D" + Prompt "D (diagonal matrix with desired damping coefficients)" + Value "D" + } + Object { + $ObjectID 173 + Type "edit" + Name "K_tau_g" + Prompt "K_tau_g (gain of gravity compensation)" + Value "K_tau_g" + } + Object { + $ObjectID 174 + Type "edit" + Name "K_tau_c" + Prompt "K_tau_c (gain of corriolis- and inertia compensation)" + Value "K_tau_c" + } + Object { + $ObjectID 175 + Type "edit" + Name "K_tau_K" + Prompt "K_tau_K (gain of stiffness component)" + Value "K_tau_K" + } + Object { + $ObjectID 176 + Type "edit" + Name "K_tau_D" + Prompt "K_tau_D (gain of damping component)" + Value "K_tau_D" + } + Object { + $ObjectID 177 + Type "edit" + Name "K_tau_a" + Prompt "K_tau_a (gain of acceleration component)" + Value "K_tau_a" + } + Object { + $ObjectID 178 + Type "edit" + Name "K_qD_d" + Prompt "K_qD_d (gain of desired velocity)" + Value "K_qD_d" + } + Object { + $ObjectID 179 + Type "edit" + Name "K_qDD_d" + Prompt "K_qDD_d (gain of desired acceleration)" + Value "K_qDD_d" + } + Object { + $ObjectID 180 + Type "edit" + Name "MPV" + Prompt "MPV (vector of minimal parameters)" + Value "MPV" + } + Object { + $ObjectID 181 + Type "edit" + Name "K_O" + Prompt "K_O (friction observer gain)" + Value "K_O" + } + Object { + $ObjectID 182 + Type "edit" + Name "T" + Prompt "T (sample time (important for friction observer))" + Value "T" + } + PropName "Parameters" + } + } + System { + Name "atlas_joint_impctrl_sqrt_damping" + Location [-8, -8, 1928, 1168] + Open off + ModelBrowserVisibility off + ModelBrowserWidth 200 + ScreenColor "white" + PaperOrientation "landscape" + PaperPositionMode "auto" + PaperType "usletter" + PaperUnits "inches" + TiledPaperMargins [0.500000, 0.500000, 0.500000, 0.500000] + TiledPageScale 1 + ShowPageBoundaries off + ZoomFactor "100" + Block { + BlockType Inport + Name "q" + SID "349" + Position [25, 73, 55, 87] + ZOrder 176 + IconDisplay "Port number" + } + Block { + BlockType Inport + Name "qD" + SID "350" + Position [25, 183, 55, 197] + ZOrder 177 + Port "2" + IconDisplay "Port number" + } + Block { + BlockType Inport + Name "q_d" + SID "351" + Position [25, 293, 55, 307] + ZOrder 178 + Port "3" + IconDisplay "Port number" + } + Block { + BlockType Inport + Name "qD_d" + SID "352" + Position [25, 403, 55, 417] + ZOrder 179 + Port "4" + IconDisplay "Port number" + } + Block { + BlockType Inport + Name "qDD_d" + SID "353" + Position [25, 513, 55, 527] + ZOrder 180 + Port "5" + IconDisplay "Port number" + } + Block { + BlockType Inport + Name "g" + SID "363" + Position [25, 743, 55, 757] + ZOrder 189 + Port "6" + IconDisplay "Port number" + } + Block { + BlockType Inport + Name "tau_J" + SID "498" + Position [25, 878, 55, 892] + ZOrder 233 + Port "7" + IconDisplay "Port number" + } + Block { + BlockType Inport + Name "tau_ext" + SID "499" + Position [25, 908, 55, 922] + ZOrder 234 + Port "8" + IconDisplay "Port number" + } + Block { + BlockType Reference + Name "atlas_arm_coriolis_vec_minvarpar" + SID "447" + Ports [2, 1] + Position [230, 602, 300, 653] + ZOrder 193 + LibraryVersion "1.228" + SourceBlock "atlas_dynamic_library/atlas_arm_coriolis_vec_minvarpar" + SourceType "" + ContentPreviewEnabled off + atlas_arm_lr "atlas_arm_lr" + atlas_version "atlas_version" + MPV "MPV" + } + Block { + BlockType Reference + Name "atlas_arm_gravload_minvarpar" + SID "448" + Ports [2, 1] + Position [230, 712, 300, 763] + ZOrder 191 + LibraryVersion "1.228" + SourceBlock "atlas_dynamic_library/atlas_arm_gravload_minvarpar" + SourceType "" + ContentPreviewEnabled off + atlas_arm_lr "atlas_arm_lr" + atlas_version "atlas_version" + MPV "MPV" + } + Block { + BlockType Reference + Name "atlas_arm_inertia_minvarpar" + SID "449" + Ports [1, 1] + Position [230, 826, 300, 874] + ZOrder 192 + LibraryVersion "1.228" + SourceBlock "atlas_dynamic_library/atlas_arm_inertia_minvarpar" + SourceType "" + ContentPreviewEnabled off + atlas_arm_lr "atlas_arm_lr" + atlas_version "atlas_version" + MPV "MPV" + } + Block { + BlockType Reference + Name "atlas_joint_impctrl_sqrt_damping_base" + SID "359" + Ports [11, 1] + Position [560, 27, 765, 1013] + ZOrder 188 + LibraryVersion "1.359" + SourceBlock "atlas_impctrl_library/atlas_joint_impctrl_sqrt_damping_base" + SourceType "Joint Impedance Controller Base" + ContentPreviewEnabled off + K_d "K_d" + D "D" + K_tau_g "K_tau_g" + K_tau_c "K_tau_c" + K_tau_K "K_tau_K" + K_tau_D "K_tau_D" + K_tau_a "K_tau_a" + K_tau_f "K_tau_F" + K_tau_e "K_tau_e" + K_tau_o "K_tau_o" + K_qD_d "K_qD_d" + K_qDD_d "K_qDD_d" + K_ext_c "K_ext_c" + K_obs_c "K_obs_c" + tau_c "tau_c" + B "B" + qD_th "qD_th" + tau_th "tau_th" + } + Block { + BlockType Reference + Name "momentum_based_friction_observer" + SID "572" + Ports [7, 1] + Position [395, 865, 515, 1055] + ZOrder 251 + LibraryVersion "1.359" + SourceBlock "atlas_impctrl_library/momentum_based_friction_observer" + SourceType "" + ContentPreviewEnabled off + K_O "K_O" + T "T" + T1 "T1" + tau_out_max "30*ones(7,1)" + } + Block { + BlockType Outport + Name "tau" + SID "358" + Position [825, 513, 855, 527] + ZOrder 185 + IconDisplay "Port number" + } + Block { + BlockType Outport + Name "tau_fr_obs" + SID "502" + Position [825, 1038, 855, 1052] + ZOrder 235 + Port "2" + IconDisplay "Port number" + } + Line { + ZOrder 1 + SrcBlock "atlas_joint_impctrl_sqrt_damping_base" + SrcPort 1 + DstBlock "tau" + DstPort 1 + } + Line { + ZOrder 2 + SrcBlock "atlas_arm_inertia_minvarpar" + SrcPort 1 + Points [33, 0] + Branch { + ZOrder 263 + Points [0, 185] + DstBlock "momentum_based_friction_observer" + DstPort 6 + } + Branch { + ZOrder 4 + DstBlock "atlas_joint_impctrl_sqrt_damping_base" + DstPort 8 + } + } + Line { + ZOrder 5 + SrcBlock "q" + SrcPort 1 + Points [75, 0] + Branch { + ZOrder 6 + Points [30, 0] + Branch { + ZOrder 7 + Points [0, 645] + DstBlock "atlas_arm_gravload_minvarpar" + DstPort 1 + } + Branch { + ZOrder 8 + Points [41, 0] + Branch { + ZOrder 9 + Points [0, 535] + DstBlock "atlas_arm_coriolis_vec_minvarpar" + DstPort 1 + } + Branch { + ZOrder 10 + DstBlock "atlas_joint_impctrl_sqrt_damping_base" + DstPort 1 + } + } + } + Branch { + ZOrder 11 + Points [0, 770] + DstBlock "atlas_arm_inertia_minvarpar" + DstPort 1 + } + } + Line { + ZOrder 12 + SrcBlock "qD" + SrcPort 1 + Points [131, 0] + Branch { + ZOrder 13 + Points [0, 450] + Branch { + ZOrder 264 + Points [-13, 0; 0, 365] + DstBlock "momentum_based_friction_observer" + DstPort 5 + } + Branch { + ZOrder 15 + DstBlock "atlas_arm_coriolis_vec_minvarpar" + DstPort 2 + } + } + Branch { + ZOrder 16 + DstBlock "atlas_joint_impctrl_sqrt_damping_base" + DstPort 2 + } + } + Line { + ZOrder 17 + SrcBlock "q_d" + SrcPort 1 + DstBlock "atlas_joint_impctrl_sqrt_damping_base" + DstPort 3 + } + Line { + ZOrder 18 + SrcBlock "atlas_arm_coriolis_vec_minvarpar" + SrcPort 1 + Points [26, 0] + Branch { + ZOrder 261 + Points [0, 17; 39, 0; 0, 328] + DstBlock "momentum_based_friction_observer" + DstPort 4 + } + Branch { + ZOrder 19 + DstBlock "atlas_joint_impctrl_sqrt_damping_base" + DstPort 6 + } + } + Line { + ZOrder 21 + SrcBlock "qD_d" + SrcPort 1 + DstBlock "atlas_joint_impctrl_sqrt_damping_base" + DstPort 4 + } + Line { + ZOrder 22 + SrcBlock "atlas_arm_gravload_minvarpar" + SrcPort 1 + Points [46, 0] + Branch { + ZOrder 259 + Points [0, 205] + DstBlock "momentum_based_friction_observer" + DstPort 3 + } + Branch { + ZOrder 23 + DstBlock "atlas_joint_impctrl_sqrt_damping_base" + DstPort 7 + } + } + Line { + ZOrder 25 + SrcBlock "qDD_d" + SrcPort 1 + DstBlock "atlas_joint_impctrl_sqrt_damping_base" + DstPort 5 + } + Line { + ZOrder 26 + SrcBlock "g" + SrcPort 1 + DstBlock "atlas_arm_gravload_minvarpar" + DstPort 2 + } + Line { + ZOrder 265 + SrcBlock "momentum_based_friction_observer" + SrcPort 1 + Points [11, 0] + Branch { + ZOrder 28 + DstBlock "atlas_joint_impctrl_sqrt_damping_base" + DstPort 9 + } + Branch { + ZOrder 29 + Points [0, 85] + DstBlock "tau_fr_obs" + DstPort 1 + } + } + Line { + ZOrder 260 + SrcBlock "tau_J" + SrcPort 1 + Points [92, 0; 0, 12; 213, 0; 0, -12] + DstBlock "momentum_based_friction_observer" + DstPort 1 + } + Line { + ZOrder 262 + SrcBlock "tau_ext" + SrcPort 1 + DstBlock "momentum_based_friction_observer" + DstPort 2 + } + } + } + Block { + BlockType SubSystem + Name "atlas_joint_impctrl_sqrt_damping_base" + SID "259" + Ports [11, 1] + Position [915, 99, 1135, 371] + ZOrder 188 + LibraryVersion "*1.151" + TreatAsAtomicUnit on + RequestExecContextInheritance off + Object { + $PropName "MaskObject" + $ObjectID 183 + $ClassName "Simulink.Mask" + Type "Joint Impedance Controller Base" + Description "Hardware independent impedance controller base block with matrix\nsquareroot damping design. For a bett" + "er testing, all partial mo-\nmentums can be individually scaled. Coulomb-, viscous friction\nand Stribeck stiction is" + " taken into account for friction compen-\nsation." + Array { + Type "Simulink.MaskParameter" + Dimension 18 + Object { + $ObjectID 184 + Type "edit" + Name "K_d" + Prompt "K_d (desired stiffness)" + Value "K_d" + } + Object { + $ObjectID 185 + Type "edit" + Name "D" + Prompt "D (diagonal matrix with desired damping coefficients)" + Value "D" + } + Object { + $ObjectID 186 + Type "edit" + Name "K_tau_g" + Prompt "K_tau_g (gain of gravity compensation)" + Value "K_tau_g" + } + Object { + $ObjectID 187 + Type "edit" + Name "K_tau_c" + Prompt "K_tau_c (gain of corriolis- and inertia compensation)" + Value "K_tau_c" + } + Object { + $ObjectID 188 + Type "edit" + Name "K_tau_K" + Prompt "K_tau_K (gain of stiffness component)" + Value "K_tau_K" + } + Object { + $ObjectID 189 + Type "edit" + Name "K_tau_D" + Prompt "K_tau_D (gain of damping component)" + Value "K_tau_D" + } + Object { + $ObjectID 190 + Type "edit" + Name "K_tau_a" + Prompt "K_tau_a (gain of acceleration component)" + Value "K_tau_a" + } + Object { + $ObjectID 191 + Type "edit" + Name "K_tau_f" + Prompt "K_tau_f (gain of model based friction compensation)" + Value "K_tau_f" + } + Object { + $ObjectID 192 + Type "edit" + Name "K_tau_e" + Prompt "K_tau_e (gain of compensation of external torque measurd via hand sensor)" + Value "K_tau_e" + } + Object { + $ObjectID 193 + Type "edit" + Name "K_tau_o" + Prompt "K_tau_o (gain of compensation of disturbance observer torques)" + Value "K_tau_o" + } + Object { + $ObjectID 194 + Type "edit" + Name "K_qD_d" + Prompt "K_qD_d (gain of desired velocity)" + Value "K_qD_d" + } + Object { + $ObjectID 195 + Type "edit" + Name "K_qDD_d" + Prompt "K_qDD_d (gain of desired acceleration)" + Value "K_qDD_d" + } + Object { + $ObjectID 196 + Type "edit" + Name "K_ext_c" + Prompt "K_ext_c (input gain to deside, wether to trigger friction compensation via the measured external tor" + "que)" + Value "K_ext_c" + } + Object { + $ObjectID 197 + Type "edit" + Name "K_obs_c" + Prompt "K_obs_c (input gain to deside, wether to trigger friction compensation via the observed torque)" + Value "K_obs_c" + } + Object { + $ObjectID 198 + Type "edit" + Name "tau_c" + Prompt "tau_c (vector with coulomb friction momentums for all joints)" + Value "tau_c" + } + Object { + $ObjectID 199 + Type "edit" + Name "B" + Prompt "B (vector with viscous friction coefficients of all joints)" + Value "B" + } + Object { + $ObjectID 200 + Type "edit" + Name "qD_th" + Prompt "qD_th (vector with theshold velocities for stiction)" + Value "qD_th" + } + Object { + $ObjectID 201 + Type "edit" + Name "tau_th" + Prompt "tau_th (vector with kick-in momentums for stiction compensation)" + Value "tau_th" + } + PropName "Parameters" + } + Array { + Type "Simulink.dialog.Group" + Dimension 2 + Object { + $ObjectID 202 + Prompt "%" + Object { + $PropName "DialogControls" + $ObjectID 203 + $ClassName "Simulink.dialog.Text" + Prompt "%" + WordWrap "off" + Name "DescTextVar" + } + Name "DescGroupVar" + } + Object { + $ObjectID 204 + Prompt "Simulink:studio:ToolBarParametersMenu" + Array { + Type "Simulink.dialog.parameter.Edit" + Dimension 18 + Object { + $ObjectID 205 + Name "K_d" + } + Object { + $ObjectID 206 + Name "D" + } + Object { + $ObjectID 207 + Name "K_tau_g" + } + Object { + $ObjectID 208 + Name "K_tau_c" + } + Object { + $ObjectID 209 + Name "K_tau_K" + } + Object { + $ObjectID 210 + Name "K_tau_D" + } + Object { + $ObjectID 211 + Name "K_tau_a" + } + Object { + $ObjectID 212 + Name "K_tau_f" + } + Object { + $ObjectID 213 + Name "K_tau_e" + } + Object { + $ObjectID 214 + Name "K_tau_o" + } + Object { + $ObjectID 215 + Name "K_qD_d" + } + Object { + $ObjectID 216 + Name "K_qDD_d" + } + Object { + $ObjectID 217 + Name "K_ext_c" + } + Object { + $ObjectID 218 + Name "K_obs_c" + } + Object { + $ObjectID 219 + Name "tau_c" + } + Object { + $ObjectID 220 + Name "B" + } + Object { + $ObjectID 221 + Name "qD_th" + } + Object { + $ObjectID 222 + Name "tau_th" + } + PropName "DialogControls" + } + Name "ParameterGroupVar" + } + PropName "DialogControls" + } + } + System { + Name "atlas_joint_impctrl_sqrt_damping_base" + Location [984, 52, 1919, 1080] + Open off + ModelBrowserVisibility off + ModelBrowserWidth 200 + ScreenColor "white" + PaperOrientation "landscape" + PaperPositionMode "auto" + PaperType "usletter" + PaperUnits "inches" + TiledPaperMargins [0.500000, 0.500000, 0.500000, 0.500000] + TiledPageScale 1 + ShowPageBoundaries off + ZoomFactor "125" + Block { + BlockType Inport + Name "q" + SID "260" + Position [20, 458, 50, 472] + ZOrder 148 + IconDisplay "Port number" + } + Block { + BlockType Inport + Name "qD" + SID "261" + Position [20, 543, 50, 557] + ZOrder 149 + Port "2" + IconDisplay "Port number" + } + Block { + BlockType Inport + Name "q_d" + SID "262" + Position [20, 493, 50, 507] + ZOrder 151 + Port "3" + IconDisplay "Port number" + } + Block { + BlockType Inport + Name "qD_d" + SID "263" + Position [20, 578, 50, 592] + ZOrder 152 + Port "4" + IconDisplay "Port number" + } + Block { + BlockType Inport + Name "qDD_d" + SID "264" + Position [20, 623, 50, 637] + ZOrder 153 + Port "5" + IconDisplay "Port number" + } + Block { + BlockType Inport + Name "tau_c" + SID "265" + Position [455, 58, 485, 72] + ZOrder 154 + Port "6" + IconDisplay "Port number" + } + Block { + BlockType Inport + Name "tau_g" + SID "266" + Position [455, 138, 485, 152] + ZOrder 155 + Port "7" + IconDisplay "Port number" + } + Block { + BlockType Inport + Name "M" + SID "269" + Position [20, 413, 50, 427] + ZOrder 158 + Port "8" + IconDisplay "Port number" + } + Block { + BlockType Inport + Name "tau_obs" + SID "495" + Position [455, 218, 485, 232] + ZOrder 190 + Port "9" + IconDisplay "Port number" + } + Block { + BlockType Inport + Name "tau_fr_model" + SID "662" + Position [800, 403, 830, 417] + ZOrder 243 + Port "10" + IconDisplay "Port number" + } + Block { + BlockType Inport + Name "tau_ext_mes" + SID "720" + Position [455, 303, 485, 317] + ZOrder 245 + Port "11" + IconDisplay "Port number" + } + Block { + BlockType Sum + Name "Add" + SID "270" + Ports [8, 1] + Position [1110, 31, 1150, 659] + ZOrder 165 + Inputs "+++++--+" + InputSameDT off + OutDataTypeStr "Inherit: Inherit via internal rule" + SaturateOnIntegerOverflow off + } + Block { + BlockType Sum + Name "Add1" + SID "661" + Ports [3, 1] + Position [615, 358, 625, 462] + ZOrder 242 + Inputs "--+" + InputSameDT off + OutDataTypeStr "Inherit: Inherit via internal rule" + SaturateOnIntegerOverflow off + } + Block { + BlockType Sum + Name "Add2" + SID "724" + Ports [3, 1] + Position [760, 282, 770, 438] + ZOrder 248 + Inputs "+++" + InputSameDT off + OutDataTypeStr "Inherit: Inherit via internal rule" + SaturateOnIntegerOverflow off + } + Block { + BlockType Gain + Name "Gain" + SID "376" + Position [995, 45, 1050, 85] + ZOrder 182 + Gain "K_tau_c" + ParamDataTypeStr "Inherit: Inherit via internal rule" + OutDataTypeStr "Inherit: Inherit via internal rule" + SaturateOnIntegerOverflow off + } + Block { + BlockType Gain + Name "Gain1" + SID "377" + Position [995, 125, 1050, 165] + ZOrder 183 + Gain "K_tau_g" + ParamDataTypeStr "Inherit: Inherit via internal rule" + OutDataTypeStr "Inherit: Inherit via internal rule" + SaturateOnIntegerOverflow off + } + Block { + BlockType Gain + Name "Gain10" + SID "725" + Position [680, 340, 735, 380] + ZOrder 249 + Gain "K_obs_c" + ParamDataTypeStr "Inherit: Inherit via internal rule" + OutDataTypeStr "Inherit: Inherit via internal rule" + SaturateOnIntegerOverflow off + } + Block { + BlockType Gain + Name "Gain11" + SID "726" + Position [680, 290, 735, 330] + ZOrder 250 + Gain "K_ext_c" + ParamDataTypeStr "Inherit: Inherit via internal rule" + OutDataTypeStr "Inherit: Inherit via internal rule" + SaturateOnIntegerOverflow off + } + Block { + BlockType Gain + Name "Gain2" + SID "378" + Position [995, 445, 1050, 485] + ZOrder 184 + Gain "K_tau_K" + ParamDataTypeStr "Inherit: Inherit via internal rule" + OutDataTypeStr "Inherit: Inherit via internal rule" + SaturateOnIntegerOverflow off + } + Block { + BlockType Gain + Name "Gain3" + SID "379" + Position [995, 525, 1050, 565] + ZOrder 185 + Gain "K_tau_D" + ParamDataTypeStr "Inherit: Inherit via internal rule" + OutDataTypeStr "Inherit: Inherit via internal rule" + SaturateOnIntegerOverflow off + } + Block { + BlockType Gain + Name "Gain4" + SID "380" + Position [995, 605, 1050, 645] + ZOrder 186 + Gain "K_tau_a" + ParamDataTypeStr "Inherit: Inherit via internal rule" + OutDataTypeStr "Inherit: Inherit via internal rule" + SaturateOnIntegerOverflow off + } + Block { + BlockType Gain + Name "Gain5" + SID "496" + Position [995, 365, 1050, 405] + ZOrder 191 + Gain "K_tau_f" + ParamDataTypeStr "Inherit: Inherit via internal rule" + OutDataTypeStr "Inherit: Inherit via internal rule" + SaturateOnIntegerOverflow off + } + Block { + BlockType Gain + Name "Gain6" + SID "500" + Position [200, 610, 260, 650] + ZOrder 192 + Gain "K_qDD_d" + ParamDataTypeStr "Inherit: Inherit via internal rule" + OutDataTypeStr "Inherit: Inherit via internal rule" + SaturateOnIntegerOverflow off + } + Block { + BlockType Gain + Name "Gain7" + SID "501" + Position [125, 565, 180, 605] + ZOrder 193 + Gain "K_qD_d" + ParamDataTypeStr "Inherit: Inherit via internal rule" + OutDataTypeStr "Inherit: Inherit via internal rule" + SaturateOnIntegerOverflow off + } + Block { + BlockType Gain + Name "Gain8" + SID "721" + Position [995, 205, 1050, 245] + ZOrder 246 + Gain "K_tau_o" + ParamDataTypeStr "Inherit: Inherit via internal rule" + OutDataTypeStr "Inherit: Inherit via internal rule" + SaturateOnIntegerOverflow off + } + Block { + BlockType Gain + Name "Gain9" + SID "722" + Position [995, 285, 1050, 325] + ZOrder 247 + Gain "K_tau_e" + ParamDataTypeStr "Inherit: Inherit via internal rule" + OutDataTypeStr "Inherit: Inherit via internal rule" + SaturateOnIntegerOverflow off + } + Block { + BlockType Gain + Name "K_d" + SID "297" + Position [455, 440, 500, 490] + ZOrder 172 + Gain "K_d" + Multiplication "Matrix(K*u)" + ParamDataTypeStr "Inherit: Inherit via internal rule" + OutDataTypeStr "Inherit: Inherit via internal rule" + SaturateOnIntegerOverflow off + } + Block { + BlockType Product + Name "Product1" + SID "273" + Ports [2, 1] + Position [445, 527, 485, 558] + ZOrder 163 + Multiplication "Matrix(*)" + InputSameDT off + OutDataTypeStr "Inherit: Inherit via internal rule" + RndMeth "Floor" + SaturateOnIntegerOverflow off + } + Block { + BlockType Product + Name "Product2" + SID "274" + Ports [2, 1] + Position [445, 607, 485, 638] + ZOrder 164 + Multiplication "Matrix(*)" + InputSameDT off + OutDataTypeStr "Inherit: Inherit via internal rule" + RndMeth "Floor" + SaturateOnIntegerOverflow off + } + Block { + BlockType Sum + Name "Sum" + SID "275" + Ports [2, 1] + Position [255, 455, 275, 475] + ZOrder 160 + ShowName off + IconShape "round" + Inputs "|+-" + InputSameDT off + OutDataTypeStr "Inherit: Inherit via internal rule" + SaturateOnIntegerOverflow off + Port { + PortNumber 1 + Name "q~" + RTWStorageClass "Auto" + DataLoggingNameMode "SignalName" + } + } + Block { + BlockType Sum + Name "Sum1" + SID "276" + Ports [2, 1] + Position [255, 540, 275, 560] + ZOrder 161 + ShowName off + IconShape "round" + Inputs "|+-" + InputSameDT off + OutDataTypeStr "Inherit: Inherit via internal rule" + SaturateOnIntegerOverflow off + Port { + PortNumber 1 + Name "qD~" + RTWStorageClass "Auto" + DataLoggingNameMode "SignalName" + } + } + Block { + BlockType Terminator + Name "Terminator" + SID "732" + Position [935, 295, 955, 315] + ZOrder 252 + } + Block { + BlockType Reference + Name "atlas_friction_model_atan" + SID "731" + Ports [1, 1] + Position [790, 567, 875, 603] + ZOrder 251 + LibraryVersion "1.361" + SourceBlock "atlas_impctrl_library/atlas_friction_model_atan" + SourceType "" + ContentPreviewEnabled off + tau_c "tau_c" + B "B" + } + Block { + BlockType Reference + Name "fr_comp_w_obs" + SID "660" + Ports [3, 1] + Position [855, 347, 955, 423] + ZOrder 241 + LibraryVersion "1.361" + SourceBlock "atlas_impctrl_library/fr_comp_w_obs" + SourceType "" + ContentPreviewEnabled off + tau_c "tau_c" + B "B" + qD_th "qD_th" + tau_th "tau_th" + } + Block { + BlockType Reference + Name "sqrt_damping" + SID "292" + Ports [1, 1] + Position [320, 396, 390, 444] + ZOrder 167 + LibraryVersion "1.361" + SourceBlock "atlas_impctrl_library/sqrt_damping" + SourceType "" + ContentPreviewEnabled off + K_d "K_d" + D "D" + } + Block { + BlockType Outport + Name "tau" + SID "277" + Position [1185, 338, 1215, 352] + ZOrder 166 + IconDisplay "Port number" + } + Line { + ZOrder 34 + SrcBlock "Gain6" + SrcPort 1 + DstBlock "Product2" + DstPort 2 + } + Line { + ZOrder 36 + SrcBlock "Gain7" + SrcPort 1 + Points [80, 0] + Branch { + ZOrder 169 + DstBlock "Sum1" + DstPort 2 + } + Branch { + ZOrder 168 + DstBlock "atlas_friction_model_atan" + DstPort 1 + } + } + Line { + ZOrder 3 + SrcBlock "q_d" + SrcPort 1 + Points [210, 0] + DstBlock "Sum" + DstPort 2 + } + Line { + ZOrder 4 + SrcBlock "M" + SrcPort 1 + Points [235, 0] + Branch { + ZOrder 68 + Points [0, 195] + DstBlock "Product2" + DstPort 1 + } + Branch { + ZOrder 5 + DstBlock "sqrt_damping" + DstPort 1 + } + } + Line { + ZOrder 7 + SrcBlock "q" + SrcPort 1 + DstBlock "Sum" + DstPort 1 + } + Line { + ZOrder 8 + SrcBlock "qD" + SrcPort 1 + Points [107, 0] + Branch { + ZOrder 71 + Points [0, -34; 620, 0; 0, -131] + DstBlock "fr_comp_w_obs" + DstPort 2 + } + Branch { + ZOrder 70 + DstBlock "Sum1" + DstPort 1 + } + } + Line { + ZOrder 35 + SrcBlock "qD_d" + SrcPort 1 + DstBlock "Gain7" + DstPort 1 + } + Line { + Name "qD~" + ZOrder 10 + Labels [1, 1] + SrcBlock "Sum1" + SrcPort 1 + DstBlock "Product1" + DstPort 2 + } + Line { + Name "q~" + ZOrder 11 + Labels [1, 1] + SrcBlock "Sum" + SrcPort 1 + DstBlock "K_d" + DstPort 1 + } + Line { + ZOrder 33 + SrcBlock "qDD_d" + SrcPort 1 + DstBlock "Gain6" + DstPort 1 + } + Line { + ZOrder 13 + SrcBlock "sqrt_damping" + SrcPort 1 + Points [21, 0; 0, 115] + DstBlock "Product1" + DstPort 1 + } + Line { + ZOrder 14 + SrcBlock "Add" + SrcPort 1 + DstBlock "tau" + DstPort 1 + } + Line { + ZOrder 15 + SrcBlock "K_d" + SrcPort 1 + Points [12, 0] + Branch { + ZOrder 137 + DstBlock "Gain2" + DstPort 1 + } + Branch { + ZOrder 112 + Points [0, -90] + DstBlock "Add1" + DstPort 1 + } + } + Line { + ZOrder 16 + SrcBlock "tau_g" + SrcPort 1 + DstBlock "Gain1" + DstPort 1 + } + Line { + ZOrder 17 + SrcBlock "tau_c" + SrcPort 1 + DstBlock "Gain" + DstPort 1 + } + Line { + ZOrder 18 + SrcBlock "Product1" + SrcPort 1 + Points [61, 0] + Branch { + ZOrder 138 + DstBlock "Gain3" + DstPort 1 + } + Branch { + ZOrder 75 + Points [0, -135] + DstBlock "Add1" + DstPort 2 + } + } + Line { + ZOrder 19 + SrcBlock "Product2" + SrcPort 1 + Points [95, 0] + Branch { + ZOrder 141 + DstBlock "Gain4" + DstPort 1 + } + Branch { + ZOrder 73 + Points [0, -180] + DstBlock "Add1" + DstPort 3 + } + } + Line { + ZOrder 20 + SrcBlock "Gain" + SrcPort 1 + DstBlock "Add" + DstPort 1 + } + Line { + ZOrder 21 + SrcBlock "Gain1" + SrcPort 1 + DstBlock "Add" + DstPort 2 + } + Line { + ZOrder 171 + SrcBlock "fr_comp_w_obs" + SrcPort 1 + Points [15, 0; 0, -47; -64, 0; 0, -33] + DstBlock "Terminator" + DstPort 1 + } + Line { + ZOrder 107 + SrcBlock "tau_obs" + SrcPort 1 + Points [144, 0] + Branch { + ZOrder 149 + DstBlock "Gain8" + DstPort 1 + } + Branch { + ZOrder 148 + Points [0, 135] + DstBlock "Gain10" + DstPort 1 + } + } + Line { + ZOrder 66 + SrcBlock "tau_fr_model" + SrcPort 1 + DstBlock "fr_comp_w_obs" + DstPort 3 + } + Line { + ZOrder 102 + SrcBlock "Gain5" + SrcPort 1 + DstBlock "Add" + DstPort 5 + } + Line { + ZOrder 104 + SrcBlock "Gain2" + SrcPort 1 + DstBlock "Add" + DstPort 6 + } + Line { + ZOrder 105 + SrcBlock "Gain3" + SrcPort 1 + DstBlock "Add" + DstPort 7 + } + Line { + ZOrder 106 + SrcBlock "Gain4" + SrcPort 1 + DstBlock "Add" + DstPort 8 + } + Line { + ZOrder 108 + SrcBlock "Gain8" + SrcPort 1 + DstBlock "Add" + DstPort 3 + } + Line { + ZOrder 109 + SrcBlock "tau_ext_mes" + SrcPort 1 + Points [162, 0] + Branch { + ZOrder 146 + Points [0, -42; 323, 0; 0, 37] + DstBlock "Gain9" + DstPort 1 + } + Branch { + ZOrder 145 + DstBlock "Gain11" + DstPort 1 + } + } + Line { + ZOrder 110 + SrcBlock "Gain9" + SrcPort 1 + DstBlock "Add" + DstPort 4 + } + Line { + ZOrder 139 + SrcBlock "Add2" + SrcPort 1 + DstBlock "fr_comp_w_obs" + DstPort 1 + } + Line { + ZOrder 140 + SrcBlock "Add1" + SrcPort 1 + DstBlock "Add2" + DstPort 3 + } + Line { + ZOrder 142 + SrcBlock "Gain10" + SrcPort 1 + DstBlock "Add2" + DstPort 2 + } + Line { + ZOrder 143 + SrcBlock "Gain11" + SrcPort 1 + DstBlock "Add2" + DstPort 1 + } + Line { + ZOrder 172 + SrcBlock "atlas_friction_model_atan" + SrcPort 1 + Points [100, 0] + DstBlock "Gain5" + DstPort 1 + } + } + } + Block { + BlockType SubSystem + Name "atlas_joint_impctrl_sqrt_damping_v5" + SID "575" + Ports [8, 3] + Position [915, 675, 1135, 915] + ZOrder 236 + TreatAsAtomicUnit on + SystemSampleTime "T" + RequestExecContextInheritance off + Object { + $PropName "MaskObject" + $ObjectID 223 + $ClassName "Simulink.Mask" + Type "Atlas Joint Impedance Controller" + Description "Hardware dependent full impedance controller block with matrix\nsquareroot damping design for the atlas" + " robot. For a better\ntesting, all partial momentums can be individually scaled.\nCoulomb-, viscous friction and Stri" + "beck stiction is taken into\naccount for friction compensation." + Array { + Type "Simulink.MaskParameter" + Dimension 27 + Object { + $ObjectID 224 + Type "edit" + Name "K_d" + Prompt "K_d (desired stiffness)" + Value "K_d" + } + Object { + $ObjectID 225 + Type "edit" + Name "D" + Prompt "D (diagonal matrix with desired damping coefficients)" + Value "D" + } + Object { + $ObjectID 226 + Type "edit" + Name "K_tau_g" + Prompt "K_tau_g (gain of gravity compensation)" + Value "K_tau_g" + } + Object { + $ObjectID 227 + Type "edit" + Name "K_tau_c" + Prompt "K_tau_c (gain of corriolis- and inertia compensation)" + Value "K_tau_c" + } + Object { + $ObjectID 228 + Type "edit" + Name "K_tau_K" + Prompt "K_tau_K (gain of stiffness component)" + Value "K_tau_K" + } + Object { + $ObjectID 229 + Type "edit" + Name "K_tau_D" + Prompt "K_tau_D (gain of damping component)" + Value "K_tau_D" + } + Object { + $ObjectID 230 + Type "edit" + Name "K_tau_a" + Prompt "K_tau_a (gain of acceleration component)" + Value "K_tau_a" + } + Object { + $ObjectID 231 + Type "edit" + Name "K_tau_f" + Prompt "K_tau_f (gain of model based friction compensation)" + Value "K_tau_f" + } + Object { + $ObjectID 232 + Type "edit" + Name "K_tau_e" + Prompt "K_tau_e (gain of compensation of external torque measurd via hand sensor)" + Value "K_tau_e" + } + Object { + $ObjectID 233 + Type "edit" + Name "K_tau_o" + Prompt "K_tau_o (gain of compensation of disturbance observer torques)" + Value "K_tau_o" + } + Object { + $ObjectID 234 + Type "edit" + Name "K_qD_d" + Prompt "K_qD_d (gain of desired velocity)" + Value "K_qD_d" + } + Object { + $ObjectID 235 + Type "edit" + Name "K_qDD_d" + Prompt "K_qDD_d (gain of desired acceleration)" + Value "K_qDD_d" + } + Object { + $ObjectID 236 + Type "edit" + Name "K_ext_c" + Prompt "K_ext_c (input gain to deside, wether to trigger friction compensation via the measured external tor" + "que)" + Value "K_ext_c" + } + Object { + $ObjectID 237 + Type "edit" + Name "K_obs_c" + Prompt "K_obs_c (input gain to deside, wether to trigger friction compensation via the observed torque)" + Value "K_obs_c" + } + Object { + $ObjectID 238 + Type "edit" + Name "K_fri_o" + Prompt "K_fri_o (input gain of friction model torques for observer)" + Value "K_fri_o" + } + Object { + $ObjectID 239 + Type "edit" + Name "K_ext_o" + Prompt "K_ext_o (input gain of external torque for observer)" + Value "K_ext_o" + } + Object { + $ObjectID 240 + Type "edit" + Name "tau_obs_max" + Prompt "tau_obs_max (limit for observed disturbance torque)" + Value "30*ones(7,1)" + } + Object { + $ObjectID 241 + Type "edit" + Name "MPV_arm_damp" + Prompt "MPV_damp (base parameter vector for damping calculation)" + Value "MPV_arm_damp" + } + Object { + $ObjectID 242 + Type "edit" + Name "MPV_arm_model" + Prompt "MPV_model (base parameter vector for dynamic model calculation)" + Value "MPV_arm_model" + } + Object { + $ObjectID 243 + Type "edit" + Name "tau_c" + Prompt "tau_c (vector with coulomb friction momentums for all joints)" + Value "tau_c" + } + Object { + $ObjectID 244 + Type "edit" + Name "B" + Prompt "B (vector with viscous friction coefficients of all joints)" + Value "B" + } + Object { + $ObjectID 245 + Type "edit" + Name "qD_th" + Prompt "qD_th (vector with theshold velocities for stiction)" + Value "qD_th" + } + Object { + $ObjectID 246 + Type "edit" + Name "tau_th" + Prompt "tau_th (vector with kick-in momentums for stiction compensation)" + Value "tau_th" + } + Object { + $ObjectID 247 + Type "edit" + Name "K_O" + Prompt "K_O (friction observer gain)" + Value "K_O" + } + Object { + $ObjectID 248 + Type "edit" + Name "T" + Prompt "T (sample time (important for friction observer))" + Value "T" + } + Object { + $ObjectID 249 + Type "edit" + Name "atlas_arm_lr" + Prompt "atlas_arm_lr (flag for left or right side)" + Value "atlas_arm_lr" + } + Object { + $ObjectID 250 + Type "edit" + Name "T1" + Prompt "T1 (low pass filter time constant for inertia matrix)" + Value "T1" + } + PropName "Parameters" + } + } + System { + Name "atlas_joint_impctrl_sqrt_damping_v5" + Location [49, 24, 1920, 1080] + Open off + ModelBrowserVisibility off + ModelBrowserWidth 200 + ScreenColor "white" + PaperOrientation "landscape" + PaperPositionMode "auto" + PaperType "A4" + PaperUnits "centimeters" + TiledPaperMargins [1.270000, 1.270000, 1.270000, 1.270000] + TiledPageScale 1 + ShowPageBoundaries off + ZoomFactor "100" + Block { + BlockType Inport + Name "q" + SID "587" + Position [25, 73, 55, 87] + ZOrder 176 + IconDisplay "Port number" + OutDataTypeStr "double" + PortDimensions "7" + VarSizeSig "No" + SignalType "real" + } + Block { + BlockType Inport + Name "qD" + SID "588" + Position [25, 183, 55, 197] + ZOrder 177 + Port "2" + IconDisplay "Port number" + OutDataTypeStr "double" + PortDimensions "7" + VarSizeSig "No" + SignalType "real" + } + Block { + BlockType Inport + Name "q_d" + SID "589" + Position [25, 293, 55, 307] + ZOrder 178 + Port "3" + IconDisplay "Port number" + OutDataTypeStr "double" + PortDimensions "7" + VarSizeSig "No" + SignalType "real" + } + Block { + BlockType Inport + Name "qD_d" + SID "590" + Position [25, 403, 55, 417] + ZOrder 179 + Port "4" + IconDisplay "Port number" + OutDataTypeStr "double" + PortDimensions "7" + VarSizeSig "No" + SignalType "real" + } + Block { + BlockType Inport + Name "qDD_d" + SID "591" + Position [25, 513, 55, 527] + ZOrder 180 + Port "5" + IconDisplay "Port number" + OutDataTypeStr "double" + PortDimensions "7" + VarSizeSig "No" + SignalType "real" + } + Block { + BlockType Inport + Name "g" + SID "592" + Position [25, 743, 55, 757] + ZOrder 189 + Port "6" + IconDisplay "Port number" + OutDataTypeStr "double" + PortDimensions "3" + VarSizeSig "No" + SignalType "real" + } + Block { + BlockType Inport + Name "tau_J" + SID "593" + Position [25, 868, 55, 882] + ZOrder 233 + Port "7" + IconDisplay "Port number" + OutDataTypeStr "double" + PortDimensions "7" + VarSizeSig "No" + SignalType "real" + } + Block { + BlockType Inport + Name "F_ext" + SID "594" + Position [25, 918, 55, 932] + ZOrder 234 + Port "8" + IconDisplay "Port number" + OutDataTypeStr "double" + PortDimensions "6" + VarSizeSig "No" + SignalType "real" + } + Block { + BlockType Gain + Name "Gain1" + SID "719" + Position [615, 1095, 670, 1135] + ZOrder 263 + Gain "K_fri_o" + ParamDataTypeStr "Inherit: Inherit via internal rule" + OutDataTypeStr "Inherit: Inherit via internal rule" + SaturateOnIntegerOverflow off + } + Block { + BlockType Gain + Name "Gain4" + SID "645" + Position [615, 895, 670, 935] + ZOrder 259 + Gain "K_ext_o" + ParamDataTypeStr "Inherit: Inherit via internal rule" + OutDataTypeStr "Inherit: Inherit via internal rule" + SaturateOnIntegerOverflow off + } + Block { + BlockType Product + Name "Product" + SID "644" + Ports [2, 1] + Position [325, 887, 365, 938] + ZOrder 258 + Multiplication "Matrix(*)" + InputSameDT off + OutDataTypeStr "Inherit: Inherit via internal rule" + RndMeth "Floor" + SaturateOnIntegerOverflow off + } + Block { + BlockType Math + Name "Transpose" + SID "642" + Ports [1, 1] + Position [220, 795, 275, 835] + ZOrder 256 + Operator "transpose" + } + Block { + BlockType Reference + Name "atlas5_arm_coriolis_vec_minvarpar" + SID "613" + Ports [2, 1] + Position [460, 602, 530, 653] + ZOrder 254 + LibraryVersion "1.228" + SourceBlock "atlas_dynamic_library/atlas5_arm_coriolis_vec_minvarpar" + SourceType "" + ContentPreviewEnabled off + atlas_arm_lr "atlas_arm_lr" + MPV "MPV_arm_model" + } + Block { + BlockType Reference + Name "atlas5_arm_gravload_minvarpar" + SID "615" + Ports [2, 1] + Position [460, 712, 530, 763] + ZOrder 253 + LibraryVersion "1.228" + SourceBlock "atlas_dynamic_library/atlas5_arm_gravload_minvarpar" + SourceType "" + ContentPreviewEnabled off + atlas_arm_lr "atlas_arm_lr" + MPV "MPV_arm_model" + } + Block { + BlockType Reference + Name "atlas5_arm_inertia_minvarpar" + SID "616" + Ports [1, 1] + Position [460, 791, 530, 839] + ZOrder 255 + LibraryVersion "1.228" + SourceBlock "atlas_dynamic_library/atlas5_arm_inertia_minvarpar" + SourceType "" + ContentPreviewEnabled off + atlas_arm_lr "atlas_arm_lr" + MPV "MPV_arm_damp" + } + Block { + BlockType Reference + Name "atlas5_arm_jacobig" + SID "643" + Ports [1, 1] + Position [115, 790, 185, 840] + ZOrder 257 + LibraryVersion "1.228" + SourceBlock "atlas_dynamic_library/atlas5_arm_jacobig" + SourceType "SubSystem" + ContentPreviewEnabled off + } + Block { + BlockType Reference + Name "atlas_friction_model" + SID "664" + Ports [1, 1] + Position [440, 1077, 540, 1153] + ZOrder 261 + LibraryVersion "1.365" + SourceBlock "atlas_impctrl_library/atlas_friction_model" + SourceType "" + ContentPreviewEnabled off + tau_c "tau_c" + B "B" + } + Block { + BlockType Reference + Name "atlas_joint_impctrl_sqrt_damping_base" + SID "598" + Ports [11, 1] + Position [955, 29, 1165, 1231] + ZOrder 188 + LibraryVersion "1.365" + SourceBlock "atlas_impctrl_library/atlas_joint_impctrl_sqrt_damping_base" + SourceType "Joint Impedance Controller Base" + ContentPreviewEnabled off + K_d "K_d" + D "D" + K_tau_g "K_tau_g" + K_tau_c "K_tau_c" + K_tau_K "K_tau_K" + K_tau_D "K_tau_D" + K_tau_a "K_tau_a" + K_tau_f "K_tau_f" + K_tau_e "K_tau_e" + K_tau_o "K_tau_o" + K_qD_d "K_qD_d" + K_qDD_d "K_qDD_d" + K_ext_c "K_ext_c" + K_obs_c "K_obs_c" + tau_c "tau_c" + B "B" + qD_th "qD_th" + tau_th "tau_th" + } + Block { + BlockType Reference + Name "momentum_based_friction_observer" + SID "599" + Ports [7, 1] + Position [755, 859, 865, 1131] + ZOrder 251 + LibraryVersion "1.365" + SourceBlock "atlas_impctrl_library/momentum_based_friction_observer" + SourceType "" + ContentPreviewEnabled off + K_O "K_O" + T "T" + T1 "T1" + tau_out_max "tau_obs_max" + } + Block { + BlockType Outport + Name "tau" + SID "600" + Position [1225, 623, 1255, 637] + ZOrder 185 + IconDisplay "Port number" + OutDataTypeStr "double" + PortDimensions "7" + VarSizeSig "No" + SignalType "real" + } + Block { + BlockType Outport + Name "tau_obs" + SID "601" + Position [1210, 1278, 1240, 1292] + ZOrder 235 + Port "2" + IconDisplay "Port number" + OutDataTypeStr "double" + PortDimensions "7" + VarSizeSig "No" + SignalType "real" + } + Block { + BlockType Outport + Name "tau_ext_mes" + SID "723" + Position [1210, 1318, 1240, 1332] + ZOrder 264 + Port "3" + IconDisplay "Port number" + OutDataTypeStr "double" + PortDimensions "7" + VarSizeSig "No" + SignalType "real" + } + Line { + ZOrder 1 + SrcBlock "atlas_joint_impctrl_sqrt_damping_base" + SrcPort 1 + DstBlock "tau" + DstPort 1 + } + Line { + ZOrder 38 + SrcBlock "atlas5_arm_inertia_minvarpar" + SrcPort 1 + Points [158, 0; 0, 35] + Branch { + ZOrder 3 + Points [0, 225] + DstBlock "momentum_based_friction_observer" + DstPort 6 + } + Branch { + ZOrder 4 + DstBlock "atlas_joint_impctrl_sqrt_damping_base" + DstPort 8 + } + } + Line { + ZOrder 5 + SrcBlock "q" + SrcPort 1 + Points [21, 0] + Branch { + ZOrder 81 + Points [0, 735] + DstBlock "atlas5_arm_jacobig" + DstPort 1 + } + Branch { + ZOrder 80 + Points [298, 0] + Branch { + ZOrder 36 + Points [0, 645] + DstBlock "atlas5_arm_gravload_minvarpar" + DstPort 1 + } + Branch { + ZOrder 8 + Points [57, 0] + Branch { + ZOrder 33 + Points [0, 535] + DstBlock "atlas5_arm_coriolis_vec_minvarpar" + DstPort 1 + } + Branch { + ZOrder 10 + DstBlock "atlas_joint_impctrl_sqrt_damping_base" + DstPort 1 + } + } + } + } + Line { + ZOrder 12 + SrcBlock "qD" + SrcPort 1 + Points [348, 0] + Branch { + ZOrder 72 + DstBlock "atlas_joint_impctrl_sqrt_damping_base" + DstPort 2 + } + Branch { + ZOrder 13 + Points [0, 450] + Branch { + ZOrder 73 + DstBlock "atlas5_arm_coriolis_vec_minvarpar" + DstPort 2 + } + Branch { + ZOrder 70 + Points [0, 395] + Branch { + ZOrder 167 + Points [0, 80] + DstBlock "atlas_friction_model" + DstPort 1 + } + Branch { + ZOrder 113 + DstBlock "momentum_based_friction_observer" + DstPort 5 + } + } + } + } + Line { + ZOrder 17 + SrcBlock "q_d" + SrcPort 1 + Points [291, 0] + Branch { + ZOrder 207 + Points [0, 515] + DstBlock "atlas5_arm_inertia_minvarpar" + DstPort 1 + } + Branch { + ZOrder 206 + DstBlock "atlas_joint_impctrl_sqrt_damping_base" + DstPort 3 + } + } + Line { + ZOrder 32 + SrcBlock "atlas5_arm_coriolis_vec_minvarpar" + SrcPort 1 + Points [190, 0] + Branch { + ZOrder 19 + Points [0, 365] + DstBlock "momentum_based_friction_observer" + DstPort 4 + } + Branch { + ZOrder 20 + DstBlock "atlas_joint_impctrl_sqrt_damping_base" + DstPort 6 + } + } + Line { + ZOrder 21 + SrcBlock "qD_d" + SrcPort 1 + DstBlock "atlas_joint_impctrl_sqrt_damping_base" + DstPort 4 + } + Line { + ZOrder 37 + SrcBlock "atlas5_arm_gravload_minvarpar" + SrcPort 1 + Points [171, 0] + Branch { + ZOrder 23 + Points [0, 215] + DstBlock "momentum_based_friction_observer" + DstPort 3 + } + Branch { + ZOrder 24 + DstBlock "atlas_joint_impctrl_sqrt_damping_base" + DstPort 7 + } + } + Line { + ZOrder 25 + SrcBlock "qDD_d" + SrcPort 1 + DstBlock "atlas_joint_impctrl_sqrt_damping_base" + DstPort 5 + } + Line { + ZOrder 35 + SrcBlock "g" + SrcPort 1 + DstBlock "atlas5_arm_gravload_minvarpar" + DstPort 2 + } + Line { + ZOrder 27 + SrcBlock "momentum_based_friction_observer" + SrcPort 1 + Points [56, 0] + Branch { + ZOrder 141 + Points [0, 290] + DstBlock "tau_obs" + DstPort 1 + } + Branch { + ZOrder 140 + Points [0, -35] + DstBlock "atlas_joint_impctrl_sqrt_damping_base" + DstPort 9 + } + } + Line { + ZOrder 30 + SrcBlock "tau_J" + SrcPort 1 + DstBlock "momentum_based_friction_observer" + DstPort 1 + } + Line { + ZOrder 77 + SrcBlock "atlas5_arm_jacobig" + SrcPort 1 + DstBlock "Transpose" + DstPort 1 + } + Line { + ZOrder 82 + SrcBlock "Transpose" + SrcPort 1 + Points [25, 0; 0, 85] + DstBlock "Product" + DstPort 1 + } + Line { + ZOrder 83 + SrcBlock "F_ext" + SrcPort 1 + DstBlock "Product" + DstPort 2 + } + Line { + ZOrder 84 + SrcBlock "Product" + SrcPort 1 + Points [17, 0] + Branch { + ZOrder 196 + Points [0, 265; 509, 0] + Branch { + ZOrder 198 + Points [0, 145] + DstBlock "tau_ext_mes" + DstPort 1 + } + Branch { + ZOrder 197 + DstBlock "atlas_joint_impctrl_sqrt_damping_base" + DstPort 11 + } + } + Branch { + ZOrder 195 + DstBlock "Gain4" + DstPort 1 + } + } + Line { + ZOrder 168 + SrcBlock "atlas_friction_model" + SrcPort 1 + Points [26, 0] + Branch { + ZOrder 148 + Points [0, 45; 325, 0; 0, -90] + DstBlock "atlas_joint_impctrl_sqrt_damping_base" + DstPort 10 + } + Branch { + ZOrder 147 + DstBlock "Gain1" + DstPort 1 + } + } + Line { + ZOrder 194 + SrcBlock "Gain4" + SrcPort 1 + DstBlock "momentum_based_friction_observer" + DstPort 2 + } + Line { + ZOrder 192 + SrcBlock "Gain1" + SrcPort 1 + DstBlock "momentum_based_friction_observer" + DstPort 7 + } + } + } + Block { + BlockType SubSystem + Name "atlas_joint_impctrl_v5" + SID "573" + Ports [6, 1] + Position [635, 675, 855, 915] + ZOrder 234 + TreatAsAtomicUnit on + RequestExecContextInheritance off + Object { + $PropName "MaskObject" + $ObjectID 251 + $ClassName "Simulink.Mask" + Type "Atlas Joint Impedance Controller" + Description "Hardware dependent full impedance controller block with matrix\ndouble diagonalization damping design f" + "or the atlas robot. For\na better testing, all partial momentums can be individually\nscaled. Coulomb-, viscous frict" + "ion and Stribeck stiction is taken\ninto account for friction compensation." + Array { + Type "Simulink.MaskParameter" + Dimension 16 + Object { + $ObjectID 252 + Type "edit" + Name "K_d" + Prompt "K_d (desired stiffness)" + Value "K_d" + } + Object { + $ObjectID 253 + Type "edit" + Name "D" + Prompt "D (diagonal matrix with desired damping coefficients)" + Value "D" + } + Object { + $ObjectID 254 + Type "edit" + Name "tau_c" + Prompt "tau_c (vector with coulomb friction momentums for all joints)" + Value "tau_c" + } + Object { + $ObjectID 255 + Type "edit" + Name "B" + Prompt "B (vector with viscous friction coefficients of all joints)" + Value "B" + } + Object { + $ObjectID 256 + Type "edit" + Name "tau_s" + Prompt "tau_s (vector with sticition momentums of all joints)" + Value "tau_s" + } + Object { + $ObjectID 257 + Type "edit" + Name "qD_s" + Prompt "qD_s (vector with Stribeck velocities of all joints)" + Value "qD_s" + } + Object { + $ObjectID 258 + Type "edit" + Name "delta_s" + Prompt "delta_s (vector with stiction exponents for all joints)" + Value "delta_s" + } + Object { + $ObjectID 259 + Type "edit" + Name "qD_th" + Prompt "qD_th (vector with theshold velocities for stiction)" + Value "qD_th" + } + Object { + $ObjectID 260 + Type "edit" + Name "tau_th" + Prompt "tau_th (vector with kick-in momentums for stiction compensation)" + Value "tau_th" + } + Object { + $ObjectID 261 + Type "edit" + Name "K_tau_g" + Prompt "K_tau_g (gain of gravity compensation)" + Value "K_tau_g" + } + Object { + $ObjectID 262 + Type "edit" + Name "K_tau_c" + Prompt "K_tau_c (gain of corriolis- and inertia compensation)" + Value "K_tau_c" + } + Object { + $ObjectID 263 + Type "edit" + Name "K_tau_F" + Prompt "K_tau_F (gain of friction compensation)" + Value "K_tau_F" + } + Object { + $ObjectID 264 + Type "edit" + Name "K_tau_K" + Prompt "K_tau_K (gain of stiffness component)" + Value "K_tau_K" + } + Object { + $ObjectID 265 + Type "edit" + Name "K_tau_D" + Prompt "K_tau_D (gain of damping component)" + Value "K_tau_D" + } + Object { + $ObjectID 266 + Type "edit" + Name "K_tau_a" + Prompt "K_tau_a (gain of acceleration component)" + Value "K_tau_a" + } + Object { + $ObjectID 267 + Type "edit" + Name "MPV" + Prompt "MPV (vector of minimal parameters)" + Value "MPV" + } + PropName "Parameters" + } + } + System { + Name "atlas_joint_impctrl_v5" + Location [-8, -8, 1928, 1168] + Open off + ModelBrowserVisibility off + ModelBrowserWidth 200 + ScreenColor "white" + PaperOrientation "landscape" + PaperPositionMode "auto" + PaperType "A4" + PaperUnits "centimeters" + TiledPaperMargins [1.270000, 1.270000, 1.270000, 1.270000] + TiledPageScale 1 + ShowPageBoundaries off + ZoomFactor "100" + Block { + BlockType Inport + Name "q" + SID "602" + Position [25, 48, 55, 62] + ZOrder 176 + IconDisplay "Port number" + } + Block { + BlockType Inport + Name "qD" + SID "603" + Position [25, 123, 55, 137] + ZOrder 177 + Port "2" + IconDisplay "Port number" + } + Block { + BlockType Inport + Name "q_d" + SID "604" + Position [25, 198, 55, 212] + ZOrder 178 + Port "3" + IconDisplay "Port number" + } + Block { + BlockType Inport + Name "qD_d" + SID "605" + Position [25, 273, 55, 287] + ZOrder 179 + Port "4" + IconDisplay "Port number" + } + Block { + BlockType Inport + Name "qDD_d" + SID "606" + Position [25, 348, 55, 362] + ZOrder 180 + Port "5" + IconDisplay "Port number" + } + Block { + BlockType Inport + Name "g" + SID "607" + Position [25, 508, 55, 522] + ZOrder 189 + Port "6" + IconDisplay "Port number" + } + Block { + BlockType Reference + Name "atlas_arm_coriolis_vec_minvarpar" + SID "608" + Ports [2, 1] + Position [165, 402, 235, 453] + ZOrder 193 + LibraryVersion "1.228" + SourceBlock "atlas_dynamic_library/atlas_arm_coriolis_vec_minvarpar" + SourceType "" + ContentPreviewEnabled off + atlas_arm_lr "atlas_arm_lr" + atlas_version "atlas_version" + MPV "MPV" + } + Block { + BlockType Reference + Name "atlas_arm_gravload_minvarpar" + SID "609" + Ports [2, 1] + Position [165, 477, 235, 528] + ZOrder 191 + LibraryVersion "1.228" + SourceBlock "atlas_dynamic_library/atlas_arm_gravload_minvarpar" + SourceType "" + ContentPreviewEnabled off + atlas_arm_lr "atlas_arm_lr" + atlas_version "atlas_version" + MPV "MPV" + } + Block { + BlockType Reference + Name "atlas_arm_inertia_minvarpar" + SID "610" + Ports [1, 1] + Position [165, 556, 235, 604] + ZOrder 192 + LibraryVersion "1.228" + SourceBlock "atlas_dynamic_library/atlas_arm_inertia_minvarpar" + SourceType "" + ContentPreviewEnabled off + atlas_arm_lr "atlas_arm_lr" + atlas_version "atlas_version" + MPV "MPV" + } + Block { + BlockType Reference + Name "atlas_joint_impctrl_base" + SID "611" + Ports [8, 1] + Position [275, 18, 485, 617] + ZOrder 194 + LibraryVersion "1.359" + SourceBlock "atlas_impctrl_library/atlas_joint_impctrl_base" + SourceType "Joint Impedance Controller Base" + ContentPreviewEnabled off + K_d "K_d" + D "D" + tau_c "tau_c" + B "B" + tau_s "tau_s" + qD_s "qD_s" + delta_s "delta_s" + qD_th "qD_th" + tau_th "tau_th" + K_tau_g "K_tau_g" + K_tau_c "K_tau_c" + K_tau_F "K_tau_F" + K_tau_K "K_tau_K" + K_tau_D "K_tau_D" + K_tau_a "K_tau_a" + } + Block { + BlockType Outport + Name "tau" + SID "612" + Position [515, 313, 545, 327] + ZOrder 185 + IconDisplay "Port number" + } + Line { + ZOrder 1 + SrcBlock "atlas_joint_impctrl_base" + SrcPort 1 + DstBlock "tau" + DstPort 1 + } + Line { + ZOrder 2 + SrcBlock "atlas_arm_inertia_minvarpar" + SrcPort 1 + DstBlock "atlas_joint_impctrl_base" + DstPort 8 + } + Line { + ZOrder 3 + SrcBlock "q" + SrcPort 1 + Points [20, 0] + Branch { + ZOrder 4 + Points [0, 525] + DstBlock "atlas_arm_inertia_minvarpar" + DstPort 1 + } + Branch { + ZOrder 5 + Points [30, 0] + Branch { + ZOrder 6 + Points [0, 435] + DstBlock "atlas_arm_gravload_minvarpar" + DstPort 1 + } + Branch { + ZOrder 7 + Points [41, 0] + Branch { + ZOrder 8 + DstBlock "atlas_joint_impctrl_base" + DstPort 1 + } + Branch { + ZOrder 9 + Points [0, 360] + DstBlock "atlas_arm_coriolis_vec_minvarpar" + DstPort 1 + } + } + } + } + Line { + ZOrder 10 + SrcBlock "qD" + SrcPort 1 + Points [76, 0] + Branch { + ZOrder 11 + DstBlock "atlas_joint_impctrl_base" + DstPort 2 + } + Branch { + ZOrder 12 + Points [0, 310] + DstBlock "atlas_arm_coriolis_vec_minvarpar" + DstPort 2 + } + } + Line { + ZOrder 13 + SrcBlock "q_d" + SrcPort 1 + DstBlock "atlas_joint_impctrl_base" + DstPort 3 + } + Line { + ZOrder 14 + SrcBlock "atlas_arm_coriolis_vec_minvarpar" + SrcPort 1 + DstBlock "atlas_joint_impctrl_base" + DstPort 6 + } + Line { + ZOrder 15 + SrcBlock "qD_d" + SrcPort 1 + DstBlock "atlas_joint_impctrl_base" + DstPort 4 + } + Line { + ZOrder 16 + SrcBlock "atlas_arm_gravload_minvarpar" + SrcPort 1 + DstBlock "atlas_joint_impctrl_base" + DstPort 7 + } + Line { + ZOrder 17 + SrcBlock "qDD_d" + SrcPort 1 + DstBlock "atlas_joint_impctrl_base" + DstPort 5 + } + Line { + ZOrder 18 + SrcBlock "g" + SrcPort 1 + DstBlock "atlas_arm_gravload_minvarpar" + DstPort 2 + } + } + } + Block { + BlockType SubSystem + Name "compensate_hand_mass_and_offset" + SID "636" + Ports [2, 1] + Position [915, 952, 1015, 1028] + ZOrder 239 + TreatAsAtomicUnit on + RequestExecContextInheritance off + Object { + $PropName "MaskObject" + $ObjectID 268 + $ClassName "Simulink.Mask" + Array { + Type "Simulink.MaskParameter" + Dimension 2 + Object { + $ObjectID 269 + Type "edit" + Name "mr" + Prompt "mr (mass (1) and com (2-4) of the hand in hand frame)" + Value "mr" + } + Object { + $ObjectID 270 + Type "edit" + Name "Parameter2offsets" + Prompt "offsets (sensor offsets of F/T-sensor)" + Value "offsets" + } + PropName "Parameters" + } + } + System { + Name "compensate_hand_mass_and_offset" + Location [-8, -8, 1928, 1168] + Open off + ModelBrowserVisibility off + ModelBrowserWidth 200 + ScreenColor "white" + PaperOrientation "landscape" + PaperPositionMode "auto" + PaperType "A4" + PaperUnits "centimeters" + TiledPaperMargins [1.270000, 1.270000, 1.270000, 1.270000] + TiledPageScale 1 + ShowPageBoundaries off + ZoomFactor "100" + Block { + BlockType Inport + Name "W_raw" + SID "637" + Position [20, 38, 50, 52] + ZOrder 239 + IconDisplay "Port number" + } + Block { + BlockType Inport + Name "g_hand" + SID "638" + Position [20, 78, 50, 92] + ZOrder 240 + Port "2" + IconDisplay "Port number" + } + Block { + BlockType SubSystem + Name "compensate_hand_mass_and_offset" + SID "635" + Ports [2, 1] + Position [80, 23, 210, 107] + ZOrder 238 + LibraryVersion "1.32" + ErrorFcn "Stateflow.Translate.translate" + PermitHierarchicalResolution "ExplicitOnly" + TreatAsAtomicUnit on + RequestExecContextInheritance off + SFBlockType "MATLAB Function" + System { + Name "compensate_hand_mass_and_offset" + Location [223, 338, 826, 833] + Open off + ModelBrowserVisibility off + ModelBrowserWidth 200 + ScreenColor "white" + PaperOrientation "landscape" + PaperPositionMode "auto" + PaperType "A4" + PaperUnits "centimeters" + TiledPaperMargins [1.270000, 1.270000, 1.270000, 1.270000] + TiledPageScale 1 + ShowPageBoundaries off + ZoomFactor "100" + SIDHighWatermark "24" + Block { + BlockType Inport + Name "W_raw" + SID "635::1" + Position [20, 101, 40, 119] + ZOrder -1 + IconDisplay "Port number" + } + Block { + BlockType Inport + Name "g_hand" + SID "635::19" + Position [20, 136, 40, 154] + ZOrder 10 + Port "2" + IconDisplay "Port number" + } + Block { + BlockType Demux + Name " Demux " + SID "635::23" + Ports [1, 1] + Position [270, 230, 320, 270] + ZOrder 12 + Outputs "1" + } + Block { + BlockType S-Function + Name " SFunction " + SID "635::22" + Tag "Stateflow S-Function atlas_impctrl_library 10" + Ports [2, 2] + Position [180, 100, 230, 160] + ZOrder 11 + FunctionName "sf_sfun" + Parameters "mr,offsets" + PortCounts "[2 2]" + Port { + PortNumber 2 + Name "W_comp" + RTWStorageClass "Auto" + DataLoggingNameMode "SignalName" + } + } + Block { + BlockType Terminator + Name " Terminator " + SID "635::24" + Position [460, 241, 480, 259] + ZOrder 13 + } + Block { + BlockType Outport + Name "W_comp" + SID "635::5" + Position [460, 101, 480, 119] + ZOrder -5 + IconDisplay "Port number" + } + Line { + ZOrder 38 + SrcBlock "W_raw" + SrcPort 1 + Points [120, 0] + DstBlock " SFunction " + DstPort 1 + } + Line { + ZOrder 39 + SrcBlock "g_hand" + SrcPort 1 + DstBlock " SFunction " + DstPort 2 + } + Line { + Name "W_comp" + ZOrder 40 + Labels [0, 0] + SrcBlock " SFunction " + SrcPort 2 + DstBlock "W_comp" + DstPort 1 + } + Line { + ZOrder 41 + SrcBlock " Demux " + SrcPort 1 + DstBlock " Terminator " + DstPort 1 + } + Line { + ZOrder 42 + SrcBlock " SFunction " + SrcPort 1 + DstBlock " Demux " + DstPort 1 + } + } + } + Block { + BlockType Outport + Name "W_comp" + SID "641" + Position [240, 58, 270, 72] + ZOrder 243 + IconDisplay "Port number" + } + Line { + ZOrder 6 + SrcBlock "W_raw" + SrcPort 1 + DstBlock "compensate_hand_mass_and_offset" + DstPort 1 + } + Line { + ZOrder 7 + SrcBlock "g_hand" + SrcPort 1 + DstBlock "compensate_hand_mass_and_offset" + DstPort 2 + } + Line { + ZOrder 10 + SrcBlock "compensate_hand_mass_and_offset" + SrcPort 1 + DstBlock "W_comp" + DstPort 1 + } + } + } + Block { + BlockType SubSystem + Name "continous_momentum_based_friction_observer" + SID "528" + Ports [6, 1] + Position [1190, 1175, 1310, 1365] + ZOrder 233 + TreatAsAtomicUnit on + RequestExecContextInheritance off + Object { + $PropName "MaskObject" + $ObjectID 271 + $ClassName "Simulink.Mask" + Object { + $PropName "Parameters" + $ObjectID 272 + $ClassName "Simulink.MaskParameter" + Type "edit" + Name "K_O" + Prompt "K_O (Observer gain)" + Value "K_O" + } + } + System { + Name "continous_momentum_based_friction_observer" + Location [61, 65, 991, 1080] + Open off + ModelBrowserVisibility off + ModelBrowserWidth 200 + ScreenColor "white" + PaperOrientation "landscape" + PaperPositionMode "auto" + PaperType "usletter" + PaperUnits "inches" + TiledPaperMargins [0.500000, 0.500000, 0.500000, 0.500000] + TiledPageScale 1 + ShowPageBoundaries off + ZoomFactor "100" + Block { + BlockType Inport + Name "tau_J" + SID "529" + Position [50, 38, 80, 52] + ZOrder 231 + IconDisplay "Port number" + } + Block { + BlockType Inport + Name "tau_ext" + SID "530" + Position [620, 218, 650, 232] + ZOrder 239 + Port "2" + IconDisplay "Port number" + } + Block { + BlockType Inport + Name "tau_g" + SID "531" + Position [50, 103, 80, 117] + ZOrder 232 + Port "3" + IconDisplay "Port number" + } + Block { + BlockType Inport + Name "tau_c" + SID "532" + Position [50, 168, 80, 182] + ZOrder 233 + Port "4" + IconDisplay "Port number" + } + Block { + BlockType Inport + Name "qD" + SID "533" + Position [50, 428, 80, 442] + ZOrder 234 + Port "5" + IconDisplay "Port number" + } + Block { + BlockType Inport + Name "M" + SID "534" + Position [50, 358, 80, 372] + ZOrder 235 + Port "6" + IconDisplay "Port number" + } + Block { + BlockType Sum + Name "Add" + SID "547" + Ports [5, 1] + Position [365, 10, 405, 340] + ZOrder 249 + Inputs "+--+-" + InputSameDT off + OutDataTypeStr "Inherit: Inherit via internal rule" + SaturateOnIntegerOverflow off + } + Block { + BlockType Sum + Name "Add1" + SID "551" + Ports [2, 1] + Position [540, 61, 580, 514] + ZOrder 253 + Inputs "+-" + InputSameDT off + OutDataTypeStr "Inherit: Inherit via internal rule" + SaturateOnIntegerOverflow off + } + Block { + BlockType Sum + Name "Add2" + SID "556" + Ports [2, 1] + Position [725, 194, 760, 321] + ZOrder 257 + InputSameDT off + OutDataTypeStr "Inherit: Inherit via internal rule" + SaturateOnIntegerOverflow off + } + Block { + BlockType Derivative + Name "Derivative" + SID "548" + Position [155, 210, 185, 240] + ZOrder 250 + } + Block { + BlockType Gain + Name "Gain" + SID "554" + Position [605, 265, 665, 315] + ZOrder 256 + Gain "K_O" + Multiplication "Matrix(K*u)" + ParamDataTypeStr "Inherit: Inherit via internal rule" + OutDataTypeStr "Inherit: Inherit via internal rule" + SaturateOnIntegerOverflow off + } + Block { + BlockType Integrator + Name "Integrator" + SID "549" + Ports [1, 1] + Position [450, 160, 480, 190] + ZOrder 251 + } + Block { + BlockType Product + Name "Product" + SID "546" + Ports [2, 1] + Position [445, 329, 485, 471] + ZOrder 248 + Multiplication "Matrix(*)" + InputSameDT off + OutDataTypeStr "Inherit: Inherit via internal rule" + RndMeth "Floor" + SaturateOnIntegerOverflow off + } + Block { + BlockType Product + Name "Product1" + SID "552" + Ports [2, 1] + Position [255, 211, 290, 264] + ZOrder 254 + Multiplication "Matrix(*)" + InputSameDT off + OutDataTypeStr "Inherit: Inherit via internal rule" + RndMeth "Floor" + SaturateOnIntegerOverflow off + } + Block { + BlockType Outport + Name "tau_fr" + SID "553" + Position [820, 253, 850, 267] + ZOrder 255 + IconDisplay "Port number" + } + Line { + ZOrder 25 + SrcBlock "Add" + SrcPort 1 + DstBlock "Integrator" + DstPort 1 + } + Line { + ZOrder 26 + SrcBlock "Integrator" + SrcPort 1 + DstBlock "Add1" + DstPort 1 + } + Line { + ZOrder 27 + SrcBlock "Product" + SrcPort 1 + DstBlock "Add1" + DstPort 2 + } + Line { + ZOrder 28 + SrcBlock "M" + SrcPort 1 + Points [27, 0] + Branch { + ZOrder 41 + Points [0, -140] + DstBlock "Derivative" + DstPort 1 + } + Branch { + ZOrder 34 + DstBlock "Product" + DstPort 1 + } + } + Line { + ZOrder 29 + SrcBlock "qD" + SrcPort 1 + Points [111, 0] + Branch { + ZOrder 32 + Points [0, -185] + DstBlock "Product1" + DstPort 2 + } + Branch { + ZOrder 31 + DstBlock "Product" + DstPort 2 + } + } + Line { + ZOrder 33 + SrcBlock "Derivative" + SrcPort 1 + DstBlock "Product1" + DstPort 1 + } + Line { + ZOrder 42 + SrcBlock "Add1" + SrcPort 1 + DstBlock "Gain" + DstPort 1 + } + Line { + ZOrder 61 + SrcBlock "Gain" + SrcPort 1 + Points [7, 0] + Branch { + ZOrder 68 + Points [0, 253; -379, 0; 0, -238] + DstBlock "Add" + DstPort 5 + } + Branch { + ZOrder 67 + DstBlock "Add2" + DstPort 2 + } + } + Line { + ZOrder 60 + SrcBlock "Product1" + SrcPort 1 + DstBlock "Add" + DstPort 4 + } + Line { + ZOrder 62 + SrcBlock "tau_J" + SrcPort 1 + DstBlock "Add" + DstPort 1 + } + Line { + ZOrder 63 + SrcBlock "tau_g" + SrcPort 1 + DstBlock "Add" + DstPort 2 + } + Line { + ZOrder 64 + SrcBlock "tau_c" + SrcPort 1 + DstBlock "Add" + DstPort 3 + } + Line { + ZOrder 69 + SrcBlock "Add2" + SrcPort 1 + DstBlock "tau_fr" + DstPort 1 + } + Line { + ZOrder 76 + SrcBlock "tau_ext" + SrcPort 1 + DstBlock "Add2" + DstPort 1 + } + } + } + Block { + BlockType SubSystem + Name "double_diag" + SID "279" + Ports [1, 1] + Position [635, 952, 735, 1028] + ZOrder 161 + TreatAsAtomicUnit on + RequestExecContextInheritance off + Object { + $PropName "MaskObject" + $ObjectID 273 + $ClassName "Simulink.Mask" + Array { + Type "Simulink.MaskParameter" + Dimension 2 + Object { + $ObjectID 274 + Type "edit" + Name "K_d" + Prompt "K_d" + Value "K_d" + } + Object { + $ObjectID 275 + Type "edit" + Name "D" + Prompt "D" + Value "D" + } + PropName "Parameters" + } + } + System { + Name "double_diag" + Location [59, 65, 1226, 1080] + Open off + ModelBrowserVisibility off + ModelBrowserWidth 200 + ScreenColor "white" + PaperOrientation "landscape" + PaperPositionMode "auto" + PaperType "A4" + PaperUnits "centimeters" + TiledPaperMargins [1.270000, 1.270000, 1.270000, 1.270000] + TiledPageScale 1 + ShowPageBoundaries off + ZoomFactor "100" + Block { + BlockType Inport + Name "M" + SID "281" + Position [20, 58, 50, 72] + ZOrder 162 + IconDisplay "Port number" + } + Block { + BlockType SubSystem + Name "MATLAB double_diag" + SID "278" + Ports [1, 1] + Position [70, 40, 150, 90] + ZOrder 160 + LibraryVersion "1.73" + ErrorFcn "Stateflow.Translate.translate" + PermitHierarchicalResolution "ExplicitOnly" + TreatAsAtomicUnit on + RequestExecContextInheritance off + SFBlockType "MATLAB Function" + System { + Name "MATLAB double_diag" + Location [223, 338, 826, 833] + Open off + ModelBrowserVisibility off + ModelBrowserWidth 200 + ScreenColor "white" + PaperOrientation "landscape" + PaperPositionMode "auto" + PaperType "A4" + PaperUnits "centimeters" + TiledPaperMargins [1.270000, 1.270000, 1.270000, 1.270000] + TiledPageScale 1 + ShowPageBoundaries off + ZoomFactor "100" + SIDHighWatermark "34" + Block { + BlockType Inport + Name "M" + SID "278::19" + Position [20, 101, 40, 119] + ZOrder 10 + IconDisplay "Port number" + } + Block { + BlockType Demux + Name " Demux " + SID "278::33" + Ports [1, 1] + Position [270, 230, 320, 270] + ZOrder 17 + Outputs "1" + } + Block { + BlockType S-Function + Name " SFunction " + SID "278::32" + Tag "Stateflow S-Function atlas_impctrl_library 1" + Ports [1, 2] + Position [180, 100, 230, 160] + ZOrder 16 + FunctionName "sf_sfun" + Parameters "D,K_d" + PortCounts "[1 2]" + Port { + PortNumber 2 + Name "D_d" + RTWStorageClass "Auto" + DataLoggingNameMode "SignalName" + } + } + Block { + BlockType Terminator + Name " Terminator " + SID "278::34" + Position [460, 241, 480, 259] + ZOrder 18 + } + Block { + BlockType Outport + Name "D_d" + SID "278::5" + Position [460, 101, 480, 119] + ZOrder -5 + IconDisplay "Port number" + } + Line { + ZOrder 22 + SrcBlock "M" + SrcPort 1 + DstBlock " SFunction " + DstPort 1 + } + Line { + Name "D_d" + ZOrder 23 + Labels [0, 0] + SrcBlock " SFunction " + SrcPort 2 + DstBlock "D_d" + DstPort 1 + } + Line { + ZOrder 24 + SrcBlock " Demux " + SrcPort 1 + DstBlock " Terminator " + DstPort 1 + } + Line { + ZOrder 25 + SrcBlock " SFunction " + SrcPort 1 + DstBlock " Demux " + DstPort 1 + } + } + } + Block { + BlockType Outport + Name "D_d" + SID "283" + Position [175, 58, 205, 72] + ZOrder 164 + IconDisplay "Port number" + } + Line { + ZOrder 6 + SrcBlock "M" + SrcPort 1 + DstBlock "MATLAB double_diag" + DstPort 1 + } + Line { + ZOrder 8 + SrcBlock "MATLAB double_diag" + SrcPort 1 + DstBlock "D_d" + DstPort 1 + } + } + } + Block { + BlockType SubSystem + Name "fr_comp_w_obs" + SID "646" + Ports [3, 1] + Position [985, 1187, 1085, 1263] + ZOrder 240 + TreatAsAtomicUnit on + RequestExecContextInheritance off + Object { + $PropName "MaskObject" + $ObjectID 276 + $ClassName "Simulink.Mask" + Array { + Type "Simulink.MaskParameter" + Dimension 4 + Object { + $ObjectID 277 + Type "edit" + Name "tau_c" + Prompt "tau_c (vector with coulomb friction momentums for all joints)" + Value "tau_c" + } + Object { + $ObjectID 278 + Type "edit" + Name "B" + Prompt "B (vector with viscous friction coefficients of all joints)" + Value "B" + } + Object { + $ObjectID 279 + Type "edit" + Name "qD_th" + Prompt "qD_th (vector with theshold velocities for stiction)" + Value "qD_th" + } + Object { + $ObjectID 280 + Type "edit" + Name "tau_th" + Prompt "tau_th (vector with kick-in momentums for stiction compensation)" + Value "tau_th" + } + PropName "Parameters" + } + } + System { + Name "fr_comp_w_obs" + Location [59, 30, 1920, 1080] + Open off + ModelBrowserVisibility off + ModelBrowserWidth 200 + ScreenColor "white" + PaperOrientation "landscape" + PaperPositionMode "auto" + PaperType "usletter" + PaperUnits "inches" + TiledPaperMargins [0.500000, 0.500000, 0.500000, 0.500000] + TiledPageScale 1 + ShowPageBoundaries off + ZoomFactor "100" + Block { + BlockType Inport + Name "tau_imp" + SID "647" + Position [20, 43, 50, 57] + ZOrder 167 + IconDisplay "Port number" + } + Block { + BlockType Inport + Name "qD" + SID "648" + Position [20, 78, 50, 92] + ZOrder 164 + Port "2" + IconDisplay "Port number" + } + Block { + BlockType Inport + Name "tau_fr_model" + SID "652" + Position [20, 113, 50, 127] + ZOrder 168 + Port "3" + IconDisplay "Port number" + } + Block { + BlockType SubSystem + Name "MATLAB fr_comp_w_obs" + SID "649" + Ports [3, 1] + Position [95, 34, 240, 136] + ZOrder 162 + LibraryVersion "1.74" + ErrorFcn "Stateflow.Translate.translate" + PermitHierarchicalResolution "ExplicitOnly" + TreatAsAtomicUnit on + RequestExecContextInheritance off + SFBlockType "MATLAB Function" + System { + Name "MATLAB fr_comp_w_obs" + Location [223, 338, 826, 833] + Open off + ModelBrowserVisibility off + ModelBrowserWidth 200 + ScreenColor "white" + PaperOrientation "landscape" + PaperPositionMode "auto" + PaperType "usletter" + PaperUnits "inches" + TiledPaperMargins [0.500000, 0.500000, 0.500000, 0.500000] + TiledPageScale 1 + ShowPageBoundaries off + ZoomFactor "100" + SIDHighWatermark "51" + Block { + BlockType Inport + Name "tau_imp" + SID "649::44" + Position [20, 101, 40, 119] + ZOrder 28 + IconDisplay "Port number" + } + Block { + BlockType Inport + Name "qD" + SID "649::19" + Position [20, 136, 40, 154] + ZOrder 10 + Port "2" + IconDisplay "Port number" + } + Block { + BlockType Inport + Name "tau_fr_model" + SID "649::48" + Position [20, 171, 40, 189] + ZOrder 32 + Port "3" + IconDisplay "Port number" + } + Block { + BlockType Demux + Name " Demux " + SID "649::50" + Ports [1, 1] + Position [270, 230, 320, 270] + ZOrder 34 + Outputs "1" + } + Block { + BlockType S-Function + Name " SFunction " + SID "649::49" + Tag "Stateflow S-Function atlas_impctrl_library 12" + Ports [3, 2] + Position [180, 100, 230, 180] + ZOrder 33 + FunctionName "sf_sfun" + Parameters "qD_th,tau_c,tau_th" + PortCounts "[3 2]" + Port { + PortNumber 2 + Name "tau_F" + RTWStorageClass "Auto" + DataLoggingNameMode "SignalName" + } + } + Block { + BlockType Terminator + Name " Terminator " + SID "649::51" + Position [460, 241, 480, 259] + ZOrder 35 + } + Block { + BlockType Outport + Name "tau_F" + SID "649::5" + Position [460, 101, 480, 119] + ZOrder -5 + IconDisplay "Port number" + } + Line { + ZOrder 17 + SrcBlock "tau_imp" + SrcPort 1 + DstBlock " SFunction " + DstPort 1 + } + Line { + ZOrder 18 + SrcBlock "qD" + SrcPort 1 + DstBlock " SFunction " + DstPort 2 + } + Line { + ZOrder 19 + SrcBlock "tau_fr_model" + SrcPort 1 + DstBlock " SFunction " + DstPort 3 + } + Line { + Name "tau_F" + ZOrder 20 + Labels [0, 0] + SrcBlock " SFunction " + SrcPort 2 + DstBlock "tau_F" + DstPort 1 + } + Line { + ZOrder 21 + SrcBlock " Demux " + SrcPort 1 + DstBlock " Terminator " + DstPort 1 + } + Line { + ZOrder 22 + SrcBlock " SFunction " + SrcPort 1 + Points [20, 0] + DstBlock " Demux " + DstPort 1 + } + } + } + Block { + BlockType Outport + Name "tau_F" + SID "650" + Position [290, 78, 320, 92] + ZOrder 166 + IconDisplay "Port number" + } + Line { + ZOrder 1 + SrcBlock "qD" + SrcPort 1 + DstBlock "MATLAB fr_comp_w_obs" + DstPort 2 + } + Line { + ZOrder 2 + SrcBlock "MATLAB fr_comp_w_obs" + SrcPort 1 + DstBlock "tau_F" + DstPort 1 + } + Line { + ZOrder 3 + SrcBlock "tau_imp" + SrcPort 1 + DstBlock "MATLAB fr_comp_w_obs" + DstPort 1 + } + Line { + ZOrder 4 + SrcBlock "tau_fr_model" + SrcPort 1 + DstBlock "MATLAB fr_comp_w_obs" + DstPort 3 + } + } + } + Block { + BlockType SubSystem + Name "friction_compensation" + SID "389" + Ports [2, 1] + Position [985, 1087, 1085, 1163] + ZOrder 180 + TreatAsAtomicUnit on + RequestExecContextInheritance off + Object { + $PropName "MaskObject" + $ObjectID 281 + $ClassName "Simulink.Mask" + Array { + Type "Simulink.MaskParameter" + Dimension 4 + Object { + $ObjectID 282 + Type "edit" + Name "tau_c" + Prompt "tau_c (vector with coulomb friction momentums for all joints)" + Value "tau_c" + } + Object { + $ObjectID 283 + Type "edit" + Name "B" + Prompt "B (vector with viscous friction coefficients of all joints)" + Value "B" + } + Object { + $ObjectID 284 + Type "edit" + Name "qD_th" + Prompt "qD_th (vector with theshold velocities for stiction)" + Value "qD_th" + } + Object { + $ObjectID 285 + Type "edit" + Name "tau_th" + Prompt "tau_th (vector with kick-in momentums for stiction compensation)" + Value "tau_th" + } + PropName "Parameters" + } + } + System { + Name "friction_compensation" + Location [59, 65, 1920, 1080] + Open off + ModelBrowserVisibility off + ModelBrowserWidth 200 + ScreenColor "white" + PaperOrientation "landscape" + PaperPositionMode "auto" + PaperType "usletter" + PaperUnits "inches" + TiledPaperMargins [0.500000, 0.500000, 0.500000, 0.500000] + TiledPageScale 1 + ShowPageBoundaries off + ZoomFactor "100" + Block { + BlockType Inport + Name "tau_imp" + SID "393" + Position [20, 58, 50, 72] + ZOrder 167 + IconDisplay "Port number" + } + Block { + BlockType Inport + Name "qD" + SID "390" + Position [20, 93, 50, 107] + ZOrder 164 + Port "2" + IconDisplay "Port number" + } + Block { + BlockType SubSystem + Name "MATLAB sqrt_damping" + SID "391" + Ports [2, 1] + Position [95, 45, 245, 120] + ZOrder 162 + LibraryVersion "1.74" + ErrorFcn "Stateflow.Translate.translate" + PermitHierarchicalResolution "ExplicitOnly" + TreatAsAtomicUnit on + RequestExecContextInheritance off + SFBlockType "MATLAB Function" + System { + Name "MATLAB sqrt_damping" + Location [223, 338, 826, 833] + Open off + ModelBrowserVisibility off + ModelBrowserWidth 200 + ScreenColor "white" + PaperOrientation "landscape" + PaperPositionMode "auto" + PaperType "usletter" + PaperUnits "inches" + TiledPaperMargins [0.500000, 0.500000, 0.500000, 0.500000] + TiledPageScale 1 + ShowPageBoundaries off + ZoomFactor "100" + SIDHighWatermark "47" + Block { + BlockType Inport + Name "tau_imp" + SID "391::44" + Position [20, 101, 40, 119] + ZOrder 28 + IconDisplay "Port number" + } + Block { + BlockType Inport + Name "qD" + SID "391::19" + Position [20, 136, 40, 154] + ZOrder 10 + Port "2" + IconDisplay "Port number" + } + Block { + BlockType Demux + Name " Demux " + SID "391::46" + Ports [1, 1] + Position [270, 230, 320, 270] + ZOrder 30 + Outputs "1" + } + Block { + BlockType S-Function + Name " SFunction " + SID "391::45" + Tag "Stateflow S-Function atlas_impctrl_library 8" + Ports [2, 2] + Position [180, 100, 230, 160] + ZOrder 29 + FunctionName "sf_sfun" + Parameters "B,qD_th,tau_c,tau_th" + PortCounts "[2 2]" + Port { + PortNumber 2 + Name "tau_F" + RTWStorageClass "Auto" + DataLoggingNameMode "SignalName" + } + } + Block { + BlockType Terminator + Name " Terminator " + SID "391::47" + Position [460, 241, 480, 259] + ZOrder 31 + } + Block { + BlockType Outport + Name "tau_F" + SID "391::5" + Position [460, 101, 480, 119] + ZOrder -5 + IconDisplay "Port number" + } + Line { + ZOrder 123 + SrcBlock "tau_imp" + SrcPort 1 + Points [120, 0] + DstBlock " SFunction " + DstPort 1 + } + Line { + ZOrder 124 + SrcBlock "qD" + SrcPort 1 + DstBlock " SFunction " + DstPort 2 + } + Line { + Name "tau_F" + ZOrder 125 + Labels [0, 0] + SrcBlock " SFunction " + SrcPort 2 + DstBlock "tau_F" + DstPort 1 + } + Line { + ZOrder 126 + SrcBlock " Demux " + SrcPort 1 + DstBlock " Terminator " + DstPort 1 + } + Line { + ZOrder 127 + SrcBlock " SFunction " + SrcPort 1 + DstBlock " Demux " + DstPort 1 + } + } + } + Block { + BlockType Outport + Name "tau_F" + SID "392" + Position [290, 78, 320, 92] + ZOrder 166 + IconDisplay "Port number" + } + Line { + ZOrder 1 + SrcBlock "qD" + SrcPort 1 + DstBlock "MATLAB sqrt_damping" + DstPort 2 + } + Line { + ZOrder 2 + SrcBlock "MATLAB sqrt_damping" + SrcPort 1 + DstBlock "tau_F" + DstPort 1 + } + Line { + ZOrder 3 + SrcBlock "tau_imp" + SrcPort 1 + DstBlock "MATLAB sqrt_damping" + DstPort 1 + } + } + } + Block { + BlockType SubSystem + Name "momentum_based_friction_observer" + SID "617" + Ports [7, 1] + Position [1350, 955, 1470, 1145] + ZOrder 286 + LibraryVersion "*1.360" + TreatAsAtomicUnit on + SystemSampleTime "T" + RequestExecContextInheritance off + Object { + $PropName "MaskObject" + $ObjectID 286 + $ClassName "Simulink.Mask" + Array { + Type "Simulink.MaskParameter" + Dimension 4 + Object { + $ObjectID 287 + Type "edit" + Name "K_O" + Prompt "K_O (Observer gain)" + Value "K_O" + } + Object { + $ObjectID 288 + Type "edit" + Name "T" + Prompt "T (sampletime)" + Value "T" + } + Object { + $ObjectID 289 + Type "edit" + Name "T1" + Prompt "T1 (low pass differentiator time constant)" + Value "T1" + } + Object { + $ObjectID 290 + Type "edit" + Name "tau_out_max" + Prompt "tau_out_max (safety limit for output, output will be limited to lie in between -tau_out_max and tau_" + "out_max)" + Value "30*ones(6,1)" + } + PropName "Parameters" + } + } + System { + Name "momentum_based_friction_observer" + Location [1959, -14, 3850, 1090] + Open off + ModelBrowserVisibility off + ModelBrowserWidth 200 + ScreenColor "white" + PaperOrientation "landscape" + PaperPositionMode "auto" + PaperType "A4" + PaperUnits "centimeters" + TiledPaperMargins [1.270000, 1.270000, 1.270000, 1.270000] + TiledPageScale 1 + ShowPageBoundaries off + ZoomFactor "100" + Block { + BlockType Inport + Name "tau_J" + SID "618" + Position [75, 38, 105, 52] + ZOrder 231 + IconDisplay "Port number" + OutDataTypeStr "double" + VarSizeSig "No" + SignalType "real" + } + Block { + BlockType Inport + Name "tau_ext" + SID "619" + Position [75, 203, 105, 217] + ZOrder 239 + Port "2" + IconDisplay "Port number" + OutDataTypeStr "double" + VarSizeSig "No" + SignalType "real" + } + Block { + BlockType Inport + Name "tau_g" + SID "620" + Position [75, 93, 105, 107] + ZOrder 232 + Port "3" + IconDisplay "Port number" + OutDataTypeStr "double" + VarSizeSig "No" + SignalType "real" + } + Block { + BlockType Inport + Name "tau_c" + SID "621" + Position [75, 148, 105, 162] + ZOrder 233 + Port "4" + IconDisplay "Port number" + OutDataTypeStr "double" + VarSizeSig "No" + SignalType "real" + } + Block { + BlockType Inport + Name "qD" + SID "622" + Position [75, 368, 105, 382] + ZOrder 234 + Port "5" + IconDisplay "Port number" + OutDataTypeStr "double" + VarSizeSig "No" + SignalType "real" + } + Block { + BlockType Inport + Name "M" + SID "623" + Position [75, 478, 105, 492] + ZOrder 235 + Port "6" + IconDisplay "Port number" + OutDataTypeStr "double" + VarSizeSig "No" + SignalType "real" + } + Block { + BlockType Inport + Name "tau_fr_model" + SID "658" + Position [75, 643, 105, 657] + ZOrder 250 + Port "7" + IconDisplay "Port number" + OutDataTypeStr "double" + VarSizeSig "No" + SignalType "real" + } + Block { + BlockType SubSystem + Name "MATLAB Function" + SID "624" + Ports [12, 3] + Position [220, 20, 330, 675] + ZOrder 230 + LibraryVersion "1.32" + ErrorFcn "Stateflow.Translate.translate" + PermitHierarchicalResolution "ExplicitOnly" + TreatAsAtomicUnit on + RequestExecContextInheritance off + SFBlockType "MATLAB Function" + System { + Name "MATLAB Function" + Location [223, 338, 826, 833] + Open off + ModelBrowserVisibility off + ModelBrowserWidth 200 + ScreenColor "white" + PaperOrientation "landscape" + PaperPositionMode "auto" + PaperType "A4" + PaperUnits "centimeters" + TiledPaperMargins [1.270000, 1.270000, 1.270000, 1.270000] + TiledPageScale 1 + ShowPageBoundaries off + ZoomFactor "100" + SIDHighWatermark "52" + Block { + BlockType Inport + Name "tau_J_old" + SID "624::1" + Position [20, 101, 40, 119] + ZOrder -1 + IconDisplay "Port number" + } + Block { + BlockType Inport + Name "tau_g_old" + SID "624::19" + Position [20, 136, 40, 154] + ZOrder 10 + Port "2" + IconDisplay "Port number" + } + Block { + BlockType Inport + Name "tau_c_old" + SID "624::20" + Position [20, 171, 40, 189] + ZOrder 11 + Port "3" + IconDisplay "Port number" + } + Block { + BlockType Inport + Name "tau_ext_old" + SID "624::38" + Position [20, 206, 40, 224] + ZOrder 29 + Port "4" + IconDisplay "Port number" + } + Block { + BlockType Inport + Name "tau_fr_obs_old" + SID "624::28" + Position [20, 246, 40, 264] + ZOrder 19 + Port "5" + IconDisplay "Port number" + } + Block { + BlockType Inport + Name "tau_int_old" + SID "624::21" + Position [20, 281, 40, 299] + ZOrder 12 + Port "6" + IconDisplay "Port number" + } + Block { + BlockType Inport + Name "qD" + SID "624::22" + Position [20, 316, 40, 334] + ZOrder 13 + Port "7" + IconDisplay "Port number" + } + Block { + BlockType Inport + Name "qD_old" + SID "624::37" + Position [20, 351, 40, 369] + ZOrder 28 + Port "8" + IconDisplay "Port number" + } + Block { + BlockType Inport + Name "M" + SID "624::23" + Position [20, 386, 40, 404] + ZOrder 14 + Port "9" + IconDisplay "Port number" + } + Block { + BlockType Inport + Name "M_old" + SID "624::34" + Position [20, 426, 40, 444] + ZOrder 25 + Port "10" + IconDisplay "Port number" + } + Block { + BlockType Inport + Name "MD_old" + SID "624::35" + Position [20, 461, 40, 479] + ZOrder 26 + Port "11" + IconDisplay "Port number" + } + Block { + BlockType Inport + Name "tau_fr_model_old" + SID "624::42" + Position [20, 496, 40, 514] + ZOrder 33 + Port "12" + IconDisplay "Port number" + } + Block { + BlockType Demux + Name " Demux " + SID "624::51" + Ports [1, 1] + Position [270, 245, 320, 285] + ZOrder 41 + Outputs "1" + } + Block { + BlockType S-Function + Name " SFunction " + SID "624::50" + Tag "Stateflow S-Function atlas_impctrl_library 11" + Ports [12, 4] + Position [180, 95, 230, 355] + ZOrder 40 + FunctionName "sf_sfun" + Parameters "K_O,T,T1,tau_out_max" + PortCounts "[12 4]" + Port { + PortNumber 2 + Name "tau_fr" + RTWStorageClass "Auto" + DataLoggingNameMode "SignalName" + } + Port { + PortNumber 3 + Name "tau_int" + RTWStorageClass "Auto" + DataLoggingNameMode "SignalName" + } + Port { + PortNumber 4 + Name "MD" + RTWStorageClass "Auto" + DataLoggingNameMode "SignalName" + } + } + Block { + BlockType Terminator + Name " Terminator " + SID "624::52" + Position [460, 256, 480, 274] + ZOrder 42 + } + Block { + BlockType Outport + Name "tau_fr" + SID "624::5" + Position [460, 101, 480, 119] + ZOrder -5 + IconDisplay "Port number" + } + Block { + BlockType Outport + Name "tau_int" + SID "624::27" + Position [460, 136, 480, 154] + ZOrder 18 + Port "2" + IconDisplay "Port number" + } + Block { + BlockType Outport + Name "MD" + SID "624::36" + Position [460, 171, 480, 189] + ZOrder 27 + Port "3" + IconDisplay "Port number" + } + Line { + ZOrder 18 + SrcBlock "tau_J_old" + SrcPort 1 + DstBlock " SFunction " + DstPort 1 + } + Line { + ZOrder 19 + SrcBlock "tau_g_old" + SrcPort 1 + DstBlock " SFunction " + DstPort 2 + } + Line { + ZOrder 20 + SrcBlock "tau_c_old" + SrcPort 1 + DstBlock " SFunction " + DstPort 3 + } + Line { + ZOrder 21 + SrcBlock "tau_ext_old" + SrcPort 1 + DstBlock " SFunction " + DstPort 4 + } + Line { + ZOrder 22 + SrcBlock "tau_fr_obs_old" + SrcPort 1 + DstBlock " SFunction " + DstPort 5 + } + Line { + ZOrder 23 + SrcBlock "tau_int_old" + SrcPort 1 + DstBlock " SFunction " + DstPort 6 + } + Line { + ZOrder 24 + SrcBlock "qD" + SrcPort 1 + DstBlock " SFunction " + DstPort 7 + } + Line { + ZOrder 25 + SrcBlock "qD_old" + SrcPort 1 + DstBlock " SFunction " + DstPort 8 + } + Line { + ZOrder 26 + SrcBlock "M" + SrcPort 1 + DstBlock " SFunction " + DstPort 9 + } + Line { + ZOrder 27 + SrcBlock "M_old" + SrcPort 1 + DstBlock " SFunction " + DstPort 10 + } + Line { + ZOrder 28 + SrcBlock "MD_old" + SrcPort 1 + DstBlock " SFunction " + DstPort 11 + } + Line { + ZOrder 29 + SrcBlock "tau_fr_model_old" + SrcPort 1 + DstBlock " SFunction " + DstPort 12 + } + Line { + Name "tau_fr" + ZOrder 30 + Labels [0, 0] + SrcBlock " SFunction " + SrcPort 2 + DstBlock "tau_fr" + DstPort 1 + } + Line { + Name "tau_int" + ZOrder 31 + Labels [0, 0] + SrcBlock " SFunction " + SrcPort 3 + DstBlock "tau_int" + DstPort 1 + } + Line { + Name "MD" + ZOrder 32 + Labels [0, 0] + SrcBlock " SFunction " + SrcPort 4 + DstBlock "MD" + DstPort 1 + } + Line { + ZOrder 33 + SrcBlock " Demux " + SrcPort 1 + DstBlock " Terminator " + DstPort 1 + } + Line { + ZOrder 34 + SrcBlock " SFunction " + SrcPort 1 + DstBlock " Demux " + DstPort 1 + } + } + } + Block { + BlockType UnitDelay + Name "Unit Delay" + SID "625" + Position [255, 843, 290, 877] + ZOrder 228 + BlockMirror on + InputProcessing "Elements as channels (sample based)" + SampleTime "-1" + } + Block { + BlockType UnitDelay + Name "Unit Delay1" + SID "626" + Position [255, 778, 290, 812] + ZOrder 240 + BlockMirror on + InputProcessing "Elements as channels (sample based)" + SampleTime "-1" + } + Block { + BlockType UnitDelay + Name "Unit Delay2" + SID "627" + Position [145, 523, 180, 557] + ZOrder 241 + InputProcessing "Elements as channels (sample based)" + SampleTime "-1" + } + Block { + BlockType UnitDelay + Name "Unit Delay3" + SID "628" + Position [255, 713, 290, 747] + ZOrder 242 + BlockMirror on + InputProcessing "Elements as channels (sample based)" + SampleTime "-1" + } + Block { + BlockType UnitDelay + Name "Unit Delay4" + SID "629" + Position [145, 28, 180, 62] + ZOrder 243 + InputProcessing "Elements as channels (sample based)" + SampleTime "-1" + } + Block { + BlockType UnitDelay + Name "Unit Delay5" + SID "630" + Position [145, 193, 180, 227] + ZOrder 249 + InputProcessing "Elements as channels (sample based)" + SampleTime "-1" + } + Block { + BlockType UnitDelay + Name "Unit Delay6" + SID "631" + Position [145, 83, 180, 117] + ZOrder 245 + InputProcessing "Elements as channels (sample based)" + SampleTime "-1" + } + Block { + BlockType UnitDelay + Name "Unit Delay7" + SID "632" + Position [145, 138, 180, 172] + ZOrder 246 + InputProcessing "Elements as channels (sample based)" + SampleTime "-1" + } + Block { + BlockType UnitDelay + Name "Unit Delay8" + SID "633" + Position [145, 413, 180, 447] + ZOrder 247 + InputProcessing "Elements as channels (sample based)" + SampleTime "-1" + } + Block { + BlockType UnitDelay + Name "Unit Delay9" + SID "659" + Position [145, 633, 180, 667] + ZOrder 251 + InputProcessing "Elements as channels (sample based)" + SampleTime "-1" + } + Block { + BlockType Outport + Name "tau_fr" + SID "634" + Position [455, 128, 485, 142] + ZOrder 238 + IconDisplay "Port number" + OutDataTypeStr "double" + VarSizeSig "No" + SignalType "real" + } + Line { + ZOrder 1 + SrcBlock "Unit Delay" + SrcPort 1 + Points [-231, 0; 0, -595] + DstBlock "MATLAB Function" + DstPort 5 + } + Line { + ZOrder 2 + SrcBlock "tau_g" + SrcPort 1 + DstBlock "Unit Delay6" + DstPort 1 + } + Line { + ZOrder 3 + SrcBlock "tau_J" + SrcPort 1 + DstBlock "Unit Delay4" + DstPort 1 + } + Line { + ZOrder 4 + SrcBlock "M" + SrcPort 1 + Points [10, 0] + Branch { + ZOrder 5 + Points [0, 55] + DstBlock "Unit Delay2" + DstPort 1 + } + Branch { + ZOrder 6 + DstBlock "MATLAB Function" + DstPort 9 + } + } + Line { + ZOrder 7 + SrcBlock "qD" + SrcPort 1 + Points [15, 0] + Branch { + ZOrder 8 + Points [0, 55] + DstBlock "Unit Delay8" + DstPort 1 + } + Branch { + ZOrder 9 + DstBlock "MATLAB Function" + DstPort 7 + } + } + Line { + ZOrder 10 + SrcBlock "tau_c" + SrcPort 1 + DstBlock "Unit Delay7" + DstPort 1 + } + Line { + ZOrder 11 + SrcBlock "MATLAB Function" + SrcPort 2 + Points [33, 0; 0, 445] + DstBlock "Unit Delay1" + DstPort 1 + } + Line { + ZOrder 12 + SrcBlock "Unit Delay1" + SrcPort 1 + Points [-212, 0; 0, -475] + DstBlock "MATLAB Function" + DstPort 6 + } + Line { + ZOrder 13 + SrcBlock "Unit Delay2" + SrcPort 1 + DstBlock "MATLAB Function" + DstPort 10 + } + Line { + ZOrder 14 + SrcBlock "MATLAB Function" + SrcPort 3 + Points [9, 0; 0, 160] + DstBlock "Unit Delay3" + DstPort 1 + } + Line { + ZOrder 15 + SrcBlock "Unit Delay3" + SrcPort 1 + Points [-197, 0; 0, -135] + DstBlock "MATLAB Function" + DstPort 11 + } + Line { + ZOrder 16 + SrcBlock "Unit Delay4" + SrcPort 1 + DstBlock "MATLAB Function" + DstPort 1 + } + Line { + ZOrder 17 + SrcBlock "Unit Delay6" + SrcPort 1 + DstBlock "MATLAB Function" + DstPort 2 + } + Line { + ZOrder 18 + SrcBlock "Unit Delay7" + SrcPort 1 + DstBlock "MATLAB Function" + DstPort 3 + } + Line { + ZOrder 19 + SrcBlock "Unit Delay8" + SrcPort 1 + DstBlock "MATLAB Function" + DstPort 8 + } + Line { + ZOrder 20 + SrcBlock "MATLAB Function" + SrcPort 1 + Points [50, 0; 0, 5] + Branch { + ZOrder 21 + Points [0, 725] + DstBlock "Unit Delay" + DstPort 1 + } + Branch { + ZOrder 22 + DstBlock "tau_fr" + DstPort 1 + } + } + Line { + ZOrder 23 + SrcBlock "tau_ext" + SrcPort 1 + DstBlock "Unit Delay5" + DstPort 1 + } + Line { + ZOrder 24 + SrcBlock "Unit Delay5" + SrcPort 1 + DstBlock "MATLAB Function" + DstPort 4 + } + Line { + ZOrder 25 + SrcBlock "tau_fr_model" + SrcPort 1 + DstBlock "Unit Delay9" + DstPort 1 + } + Line { + ZOrder 26 + SrcBlock "Unit Delay9" + SrcPort 1 + DstBlock "MATLAB Function" + DstPort 12 + } + } + } + Block { + BlockType SubSystem + Name "sqrt_damping" + SID "287" + Ports [1, 1] + Position [775, 952, 875, 1028] + ZOrder 163 + TreatAsAtomicUnit on + RequestExecContextInheritance off + Object { + $PropName "MaskObject" + $ObjectID 291 + $ClassName "Simulink.Mask" + Array { + Type "Simulink.MaskParameter" + Dimension 2 + Object { + $ObjectID 292 + Type "edit" + Name "K_d" + Prompt "K_d" + Value "K_d" + } + Object { + $ObjectID 293 + Type "edit" + Name "D" + Prompt "D" + Value "D" + } + PropName "Parameters" + } + } + System { + Name "sqrt_damping" + Location [0, 0, 960, 1160] + Open off + ModelBrowserVisibility off + ModelBrowserWidth 200 + ScreenColor "white" + PaperOrientation "landscape" + PaperPositionMode "auto" + PaperType "A4" + PaperUnits "centimeters" + TiledPaperMargins [1.270000, 1.270000, 1.270000, 1.270000] + TiledPageScale 1 + ShowPageBoundaries off + ZoomFactor "100" + Block { + BlockType Inport + Name "M" + SID "289" + Position [20, 58, 50, 72] + ZOrder 164 + IconDisplay "Port number" + } + Block { + BlockType SubSystem + Name "MATLAB sqrt_damping" + SID "286" + Ports [1, 1] + Position [75, 37, 165, 93] + ZOrder 162 + LibraryVersion "1.74" + ErrorFcn "Stateflow.Translate.translate" + PermitHierarchicalResolution "ExplicitOnly" + TreatAsAtomicUnit on + RequestExecContextInheritance off + SFBlockType "MATLAB Function" + System { + Name "MATLAB sqrt_damping" + Location [223, 338, 826, 833] + Open off + ModelBrowserVisibility off + ModelBrowserWidth 200 + ScreenColor "white" + PaperOrientation "landscape" + PaperPositionMode "auto" + PaperType "A4" + PaperUnits "centimeters" + TiledPaperMargins [1.270000, 1.270000, 1.270000, 1.270000] + TiledPageScale 1 + ShowPageBoundaries off + ZoomFactor "100" + SIDHighWatermark "52" + Block { + BlockType Inport + Name "M" + SID "286::19" + Position [20, 101, 40, 119] + ZOrder 10 + IconDisplay "Port number" + } + Block { + BlockType Demux + Name " Demux " + SID "286::51" + Ports [1, 1] + Position [270, 230, 320, 270] + ZOrder 20 + Outputs "1" + } + Block { + BlockType S-Function + Name " SFunction " + SID "286::50" + Tag "Stateflow S-Function atlas_impctrl_library 3" + Ports [1, 2] + Position [180, 100, 230, 160] + ZOrder 19 + FunctionName "sf_sfun" + Parameters "D,K_d" + PortCounts "[1 2]" + Port { + PortNumber 2 + Name "D_d" + RTWStorageClass "Auto" + DataLoggingNameMode "SignalName" + } + } + Block { + BlockType Terminator + Name " Terminator " + SID "286::52" + Position [460, 241, 480, 259] + ZOrder 21 + } + Block { + BlockType Outport + Name "D_d" + SID "286::5" + Position [460, 101, 480, 119] + ZOrder -5 + IconDisplay "Port number" + } + Line { + ZOrder 22 + SrcBlock "M" + SrcPort 1 + DstBlock " SFunction " + DstPort 1 + } + Line { + Name "D_d" + ZOrder 23 + Labels [0, 0] + SrcBlock " SFunction " + SrcPort 2 + DstBlock "D_d" + DstPort 1 + } + Line { + ZOrder 24 + SrcBlock " Demux " + SrcPort 1 + DstBlock " Terminator " + DstPort 1 + } + Line { + ZOrder 25 + SrcBlock " SFunction " + SrcPort 1 + DstBlock " Demux " + DstPort 1 + } + } + } + Block { + BlockType Outport + Name "D_d" + SID "291" + Position [185, 58, 215, 72] + ZOrder 166 + IconDisplay "Port number" + } + Line { + ZOrder 10 + SrcBlock "M" + SrcPort 1 + DstBlock "MATLAB sqrt_damping" + DstPort 1 + } + Line { + ZOrder 12 + SrcBlock "MATLAB sqrt_damping" + SrcPort 1 + DstBlock "D_d" + DstPort 1 + } + } + } + Block { + BlockType SubSystem + Name "velocity_based_friction_observer" + SID "485" + Ports [6, 1] + Position [1190, 955, 1310, 1145] + ZOrder 231 + TreatAsAtomicUnit on + RequestExecContextInheritance off + Object { + $PropName "MaskObject" + $ObjectID 294 + $ClassName "Simulink.Mask" + Array { + Type "Simulink.MaskParameter" + Dimension 2 + Object { + $ObjectID 295 + Type "edit" + Name "K_O" + Prompt "K_O (Observer gain)" + Value "K_O" + } + Object { + $ObjectID 296 + Type "edit" + Name "T" + Prompt "T (sampletime)" + Value "T" + } + PropName "Parameters" + } + } + System { + Name "velocity_based_friction_observer" + Location [61, 65, 991, 1080] + Open off + ModelBrowserVisibility off + ModelBrowserWidth 200 + ScreenColor "white" + PaperOrientation "landscape" + PaperPositionMode "auto" + PaperType "usletter" + PaperUnits "inches" + TiledPaperMargins [0.500000, 0.500000, 0.500000, 0.500000] + TiledPageScale 1 + ShowPageBoundaries off + ZoomFactor "100" + Block { + BlockType Inport + Name "tau_J" + SID "486" + Position [15, 58, 45, 72] + ZOrder 231 + IconDisplay "Port number" + } + Block { + BlockType Inport + Name "tau_ext" + SID "494" + Position [305, 73, 335, 87] + ZOrder 239 + Port "2" + IconDisplay "Port number" + } + Block { + BlockType Inport + Name "tau_g" + SID "487" + Position [15, 103, 45, 117] + ZOrder 232 + Port "3" + IconDisplay "Port number" + } + Block { + BlockType Inport + Name "tau_c" + SID "488" + Position [15, 148, 45, 162] + ZOrder 233 + Port "4" + IconDisplay "Port number" + } + Block { + BlockType Inport + Name "qD" + SID "489" + Position [100, 283, 130, 297] + ZOrder 234 + Port "5" + IconDisplay "Port number" + } + Block { + BlockType Inport + Name "M" + SID "490" + Position [100, 328, 130, 342] + ZOrder 235 + Port "6" + IconDisplay "Port number" + } + Block { + BlockType Sum + Name "Add" + SID "561" + Ports [2, 1] + Position [370, 57, 400, 148] + ZOrder 244 + Inputs "-+" + InputSameDT off + OutDataTypeStr "Inherit: Inherit via internal rule" + SaturateOnIntegerOverflow off + } + Block { + BlockType SubSystem + Name "MATLAB Function" + SID "484" + Ports [7, 2] + Position [165, 44, 285, 356] + ZOrder 230 + LibraryVersion "1.32" + ErrorFcn "Stateflow.Translate.translate" + PermitHierarchicalResolution "ExplicitOnly" + TreatAsAtomicUnit on + RequestExecContextInheritance off + SFBlockType "MATLAB Function" + System { + Name "MATLAB Function" + Location [223, 338, 826, 833] + Open off + ModelBrowserVisibility off + ModelBrowserWidth 200 + ScreenColor "white" + PaperOrientation "landscape" + PaperPositionMode "auto" + PaperType "usletter" + PaperUnits "inches" + TiledPaperMargins [0.500000, 0.500000, 0.500000, 0.500000] + TiledPageScale 1 + ShowPageBoundaries off + ZoomFactor "100" + SIDHighWatermark "31" + Block { + BlockType Inport + Name "tau_J_old" + SID "484::1" + Position [20, 101, 40, 119] + ZOrder -1 + IconDisplay "Port number" + } + Block { + BlockType Inport + Name "tau_g_old" + SID "484::19" + Position [20, 136, 40, 154] + ZOrder 10 + Port "2" + IconDisplay "Port number" + } + Block { + BlockType Inport + Name "tau_c_old" + SID "484::20" + Position [20, 171, 40, 189] + ZOrder 11 + Port "3" + IconDisplay "Port number" + } + Block { + BlockType Inport + Name "tau_fr_old" + SID "484::28" + Position [20, 206, 40, 224] + ZOrder 19 + Port "4" + IconDisplay "Port number" + } + Block { + BlockType Inport + Name "tau_int_alt" + SID "484::21" + Position [20, 246, 40, 264] + ZOrder 12 + Port "5" + IconDisplay "Port number" + } + Block { + BlockType Inport + Name "qD" + SID "484::22" + Position [20, 281, 40, 299] + ZOrder 13 + Port "6" + IconDisplay "Port number" + } + Block { + BlockType Inport + Name "M" + SID "484::23" + Position [20, 316, 40, 334] + ZOrder 14 + Port "7" + IconDisplay "Port number" + } + Block { + BlockType Demux + Name " Demux " + SID "484::30" + Ports [1, 1] + Position [270, 230, 320, 270] + ZOrder 21 + Outputs "1" + } + Block { + BlockType S-Function + Name " SFunction " + SID "484::29" + Tag "Stateflow S-Function atlas_impctrl_library 9" + Ports [7, 3] + Position [180, 100, 230, 260] + ZOrder 20 + FunctionName "sf_sfun" + Parameters "K_O,T" + PortCounts "[7 3]" + Port { + PortNumber 2 + Name "tau_fr" + RTWStorageClass "Auto" + DataLoggingNameMode "SignalName" + } + Port { + PortNumber 3 + Name "tau_int" + RTWStorageClass "Auto" + DataLoggingNameMode "SignalName" + } + } + Block { + BlockType Terminator + Name " Terminator " + SID "484::31" + Position [460, 241, 480, 259] + ZOrder 22 + } + Block { + BlockType Outport + Name "tau_fr" + SID "484::5" + Position [460, 101, 480, 119] + ZOrder -5 + IconDisplay "Port number" + } + Block { + BlockType Outport + Name "tau_int" + SID "484::27" + Position [460, 136, 480, 154] + ZOrder 18 + Port "2" + IconDisplay "Port number" + } + Line { + ZOrder 162 + SrcBlock "tau_J_old" + SrcPort 1 + DstBlock " SFunction " + DstPort 1 + } + Line { + ZOrder 163 + SrcBlock "tau_g_old" + SrcPort 1 + DstBlock " SFunction " + DstPort 2 + } + Line { + ZOrder 164 + SrcBlock "tau_c_old" + SrcPort 1 + DstBlock " SFunction " + DstPort 3 + } + Line { + ZOrder 165 + SrcBlock "tau_fr_old" + SrcPort 1 + DstBlock " SFunction " + DstPort 4 + } + Line { + ZOrder 166 + SrcBlock "tau_int_alt" + SrcPort 1 + DstBlock " SFunction " + DstPort 5 + } + Line { + ZOrder 167 + SrcBlock "qD" + SrcPort 1 + DstBlock " SFunction " + DstPort 6 + } + Line { + ZOrder 168 + SrcBlock "M" + SrcPort 1 + DstBlock " SFunction " + DstPort 7 + } + Line { + Name "tau_fr" + ZOrder 169 + Labels [0, 0] + SrcBlock " SFunction " + SrcPort 2 + DstBlock "tau_fr" + DstPort 1 + } + Line { + Name "tau_int" + ZOrder 170 + Labels [0, 0] + SrcBlock " SFunction " + SrcPort 3 + DstBlock "tau_int" + DstPort 1 + } + Line { + ZOrder 171 + SrcBlock " Demux " + SrcPort 1 + DstBlock " Terminator " + DstPort 1 + } + Line { + ZOrder 172 + SrcBlock " SFunction " + SrcPort 1 + DstBlock " Demux " + DstPort 1 + } + } + } + Block { + BlockType UnitDelay + Name "Unit Delay" + SID "482" + Position [195, 468, 230, 502] + ZOrder 228 + BlockMirror on + InputProcessing "Elements as channels (sample based)" + SampleTime "-1" + } + Block { + BlockType UnitDelay + Name "Unit Delay1" + SID "503" + Position [195, 403, 230, 437] + ZOrder 240 + BlockMirror on + InputProcessing "Elements as channels (sample based)" + SampleTime "-1" + } + Block { + BlockType UnitDelay + Name "Unit Delay2" + SID "558" + Position [85, 48, 120, 82] + ZOrder 241 + InputProcessing "Elements as channels (sample based)" + SampleTime "-1" + } + Block { + BlockType UnitDelay + Name "Unit Delay3" + SID "559" + Position [85, 93, 120, 127] + ZOrder 242 + InputProcessing "Elements as channels (sample based)" + SampleTime "-1" + } + Block { + BlockType UnitDelay + Name "Unit Delay4" + SID "560" + Position [85, 138, 120, 172] + ZOrder 243 + InputProcessing "Elements as channels (sample based)" + SampleTime "-1" + } + Block { + BlockType Outport + Name "tau_fr" + SID "493" + Position [435, 98, 465, 112] + ZOrder 238 + IconDisplay "Port number" + } + Line { + ZOrder 1 + SrcBlock "MATLAB Function" + SrcPort 1 + Points [22, 0] + Branch { + ZOrder 52 + DstBlock "Add" + DstPort 2 + } + Branch { + ZOrder 51 + Points [0, 360] + DstBlock "Unit Delay" + DstPort 1 + } + } + Line { + ZOrder 36 + SrcBlock "Unit Delay" + SrcPort 1 + Points [-124, 0; 0, -285] + DstBlock "MATLAB Function" + DstPort 4 + } + Line { + ZOrder 11 + SrcBlock "tau_g" + SrcPort 1 + DstBlock "Unit Delay3" + DstPort 1 + } + Line { + ZOrder 10 + SrcBlock "tau_J" + SrcPort 1 + DstBlock "Unit Delay2" + DstPort 1 + } + Line { + ZOrder 14 + SrcBlock "M" + SrcPort 1 + DstBlock "MATLAB Function" + DstPort 7 + } + Line { + ZOrder 13 + SrcBlock "qD" + SrcPort 1 + DstBlock "MATLAB Function" + DstPort 6 + } + Line { + ZOrder 12 + SrcBlock "tau_c" + SrcPort 1 + DstBlock "Unit Delay4" + DstPort 1 + } + Line { + ZOrder 50 + SrcBlock "tau_ext" + SrcPort 1 + DstBlock "Add" + DstPort 1 + } + Line { + ZOrder 33 + SrcBlock "MATLAB Function" + SrcPort 2 + Points [9, 0; 0, 140] + DstBlock "Unit Delay1" + DstPort 1 + } + Line { + ZOrder 37 + SrcBlock "Unit Delay1" + SrcPort 1 + Points [-104, 0; 0, -175] + DstBlock "MATLAB Function" + DstPort 5 + } + Line { + ZOrder 46 + SrcBlock "Unit Delay2" + SrcPort 1 + DstBlock "MATLAB Function" + DstPort 1 + } + Line { + ZOrder 47 + SrcBlock "Unit Delay3" + SrcPort 1 + DstBlock "MATLAB Function" + DstPort 2 + } + Line { + ZOrder 48 + SrcBlock "Unit Delay4" + SrcPort 1 + DstBlock "MATLAB Function" + DstPort 3 + } + Line { + ZOrder 49 + SrcBlock "Add" + SrcPort 1 + DstBlock "tau_fr" + DstPort 1 + } + } + } + } +} +#Finite State Machines +# +# Stateflow 80000005 +# +# +Stateflow { + machine { + id 1 + name "atlas_impctrl_library" + created "18-Dec-2014 15:32:22" + isLibrary 1 + firstTarget 149 + sfVersion 80000005 + } + chart { + id 2 + name "double_diag/MATLAB double_diag" + windowPosition [422 539.941 189 413] + viewLimits [0 156.75 0 153.75] + screen [1 1 3600 1200 1.180555555555556] + treeNode [0 3 0 0] + firstTransition 9 + firstJunction 8 + viewObj 2 + machine 1 + toolbarMode LIBRARY_TOOLBAR + ssIdHighWaterMark 8 + decomposition CLUSTER_CHART + type EML_CHART + firstData 4 + chartFileNumber 1 + disableImplicitCasting 1 + eml { + name "double_diag" + } + } + state { + id 3 + labelString "eML_blk_kernel()" + position [18 64.5 118 66] + fontSize 12 + chart 2 + treeNode [2 0 0 0] + superState SUBCHART + subviewer 2 + ssIdNumber 1 + type FUNC_STATE + decomposition CLUSTER_STATE + eml { + isEML 1 + script "function D_d=double_diag(M,K_d,D)\n%#codegen\n[V,K0]=eig(K_d,M);\n% Q=inv(V)';\n% D_d_=2*Q*D*sqrt" + "(K0)*Q';\nQD=V'\\D;\nY=2*QD*sqrt(K0);\nD_d_=Y/V;\nassert(max(max(abs(imag(D_d_))))==0);\nD_d=real(D_d_);" + editorLayout "100 M4x1[10 5 700 500]" + } + } + data { + id 4 + ssIdNumber 6 + name "M" + linkNode [2 0 5] + scope INPUT_DATA + machine 1 + props { + array { + size "-1" + } + type { + method SF_INHERITED_TYPE + primitive SF_DOUBLE_TYPE + isSigned 1 + wordLength "16" + } + complexity SF_COMPLEX_INHERITED + frame SF_FRAME_INHERITED + } + dataType "Inherit: Same as Simulink" + } + data { + id 5 + ssIdNumber 4 + name "K_d" + linkNode [2 4 6] + scope PARAMETER_DATA + paramIndexForInitFromWorkspace 1 + machine 1 + props { + array { + size "-1" + } + type { + method SF_INHERITED_TYPE + primitive SF_DOUBLE_TYPE + } + complexity SF_COMPLEX_INHERITED + } + dataType "Inherit: Same as Simulink" + } + data { + id 6 + ssIdNumber 5 + name "D_d" + linkNode [2 5 7] + scope OUTPUT_DATA + machine 1 + props { + array { + size "-1" + } + type { + method SF_INHERITED_TYPE + primitive SF_DOUBLE_TYPE + } + complexity SF_COMPLEX_INHERITED + frame SF_FRAME_NO + } + dataType "Inherit: Same as Simulink" + } + data { + id 7 + ssIdNumber 8 + name "D" + linkNode [2 6 0] + scope PARAMETER_DATA + machine 1 + props { + array { + size "-1" + } + type { + method SF_INHERITED_TYPE + primitive SF_DOUBLE_TYPE + isSigned 1 + wordLength "16" + } + complexity SF_COMPLEX_INHERITED + frame SF_FRAME_INHERITED + } + dataType "Inherit: Same as Simulink" + } + junction { + id 8 + position [23.5747 49.5747 7] + chart 2 + linkNode [2 0 0] + subviewer 2 + ssIdNumber 3 + type CONNECTIVE_JUNCTION + } + transition { + id 9 + labelString "{eML_blk_kernel();}" + labelPosition [28.125 13.875 102.544 14.964] + fontSize 12 + src { + intersection [0 0 1 0 23.5747 14.625 0 0] + } + dst { + id 8 + intersection [1 0 -1 0 23.5747 42.5747 0 0] + } + midPoint [23.5747 24.9468] + chart 2 + linkNode [2 0 0] + dataLimits [21.175 25.975 14.625 42.575] + subviewer 2 + drawStyle SMART + slide { + sticky BOTH_STICK + } + executionOrder 1 + ssIdNumber 2 + } + instance { + id 10 + name "double_diag/MATLAB double_diag" + machine 1 + chart 2 + } + chart { + id 11 + name "atlas3_cart_impctrl/DDD/Eigenvalue" + windowPosition [422 539.941 189 413] + viewLimits [0 156.75 0 153.75] + screen [1 1 3600 1200 1.180555555555556] + treeNode [0 12 0 0] + firstTransition 18 + firstJunction 17 + viewObj 11 + machine 1 + toolbarMode LIBRARY_TOOLBAR + ssIdHighWaterMark 7 + decomposition CLUSTER_CHART + type EML_CHART + firstData 13 + chartFileNumber 2 + disableImplicitCasting 1 + eml { + name "fcn" + } + } + state { + id 12 + labelString "eML_blk_kernel()" + position [18 64.5 118 66] + fontSize 12 + chart 11 + treeNode [11 0 0 0] + superState SUBCHART + subviewer 11 + ssIdNumber 1 + type FUNC_STATE + decomposition CLUSTER_STATE + eml { + isEML 1 + script "function [V,E,D] = fcn(A)\n\nE=eig(A);\n[V,D]=eig(A);\n" + editorLayout "100 M4x1[10 5 700 500]" + } + } + data { + id 13 + ssIdNumber 4 + name "A" + linkNode [11 0 14] + scope INPUT_DATA + machine 1 + props { + array { + size "-1" + } + type { + method SF_INHERITED_TYPE + primitive SF_DOUBLE_TYPE + } + complexity SF_COMPLEX_INHERITED + } + dataType "Inherit: Same as Simulink" + } + data { + id 14 + ssIdNumber 5 + name "V" + linkNode [11 13 15] + scope OUTPUT_DATA + machine 1 + props { + array { + size "-1" + } + type { + method SF_INHERITED_TYPE + primitive SF_DOUBLE_TYPE + } + complexity SF_COMPLEX_INHERITED + frame SF_FRAME_NO + } + dataType "Inherit: Same as Simulink" + } + data { + id 15 + ssIdNumber 6 + name "E" + linkNode [11 14 16] + scope OUTPUT_DATA + machine 1 + props { + array { + size "-1" + } + type { + method SF_INHERITED_TYPE + primitive SF_DOUBLE_TYPE + isSigned 1 + wordLength "16" + } + complexity SF_COMPLEX_INHERITED + frame SF_FRAME_NO + } + dataType "Inherit: Same as Simulink" + } + data { + id 16 + ssIdNumber 7 + name "D" + linkNode [11 15 0] + scope OUTPUT_DATA + machine 1 + props { + array { + size "-1" + } + type { + method SF_INHERITED_TYPE + primitive SF_DOUBLE_TYPE + isSigned 1 + wordLength "16" + } + complexity SF_COMPLEX_INHERITED + frame SF_FRAME_NO + } + dataType "Inherit: Same as Simulink" + } + junction { + id 17 + position [23.5747 49.5747 7] + chart 11 + linkNode [11 0 0] + subviewer 11 + ssIdNumber 3 + type CONNECTIVE_JUNCTION + } + transition { + id 18 + labelString "{eML_blk_kernel();}" + labelPosition [28.125 13.875 102.544 14.964] + fontSize 12 + src { + intersection [0 0 1 0 23.5747 14.625 0 0] + } + dst { + id 17 + intersection [1 0 -1 0 23.5747 42.5747 0 0] + } + midPoint [23.5747 24.9468] + chart 11 + linkNode [11 0 0] + dataLimits [21.175 25.975 14.625 42.575] + subviewer 11 + drawStyle SMART + slide { + sticky BOTH_STICK + } + executionOrder 1 + ssIdNumber 2 + } + instance { + id 19 + name "atlas3_cart_impctrl/DDD/Eigenvalue" + machine 1 + chart 11 + } + chart { + id 20 + name "sqrt_damping/MATLAB sqrt_damping" + windowPosition [422 539.941 189 413] + viewLimits [0 156.75 0 153.75] + screen [1 1 3600 1200 1.180555555555556] + treeNode [0 21 0 0] + firstTransition 27 + firstJunction 26 + viewObj 20 + machine 1 + toolbarMode LIBRARY_TOOLBAR + ssIdHighWaterMark 8 + decomposition CLUSTER_CHART + type EML_CHART + firstData 22 + chartFileNumber 3 + disableImplicitCasting 1 + eml { + name "sqrt_damping" + } + } + state { + id 21 + labelString "eML_blk_kernel()" + position [18 64.5 118 66] + fontSize 12 + chart 20 + treeNode [20 0 0 0] + superState SUBCHART + subviewer 20 + ssIdNumber 1 + type FUNC_STATE + decomposition CLUSTER_STATE + eml { + isEML 1 + script "function D_d=sqrt_damping(M,K_d,D)\n%#codegen\nK_d1=sqrtm(K_d);\nM1=sqrtm(M);\nD_d_=K_d1*D*M1+M1*" + "D*K_d1;\nassert(max(max(abs(imag(D_d_))))==0);\nD_d=real(D_d_);" + editorLayout "100 M4x1[10 5 700 500]" + } + } + data { + id 22 + ssIdNumber 6 + name "M" + linkNode [20 0 23] + scope INPUT_DATA + machine 1 + props { + array { + size "-1" + } + type { + method SF_INHERITED_TYPE + primitive SF_DOUBLE_TYPE + isSigned 1 + wordLength "16" + } + complexity SF_COMPLEX_INHERITED + frame SF_FRAME_INHERITED + } + dataType "Inherit: Same as Simulink" + } + data { + id 23 + ssIdNumber 4 + name "K_d" + linkNode [20 22 24] + scope PARAMETER_DATA + paramIndexForInitFromWorkspace 1 + machine 1 + props { + array { + size "-1" + } + type { + method SF_INHERITED_TYPE + primitive SF_DOUBLE_TYPE + } + complexity SF_COMPLEX_INHERITED + } + dataType "Inherit: Same as Simulink" + } + data { + id 24 + ssIdNumber 5 + name "D_d" + linkNode [20 23 25] + scope OUTPUT_DATA + machine 1 + props { + array { + size "-1" + } + type { + method SF_INHERITED_TYPE + primitive SF_DOUBLE_TYPE + } + complexity SF_COMPLEX_INHERITED + frame SF_FRAME_NO + } + dataType "Inherit: Same as Simulink" + } + data { + id 25 + ssIdNumber 8 + name "D" + linkNode [20 24 0] + scope PARAMETER_DATA + machine 1 + props { + array { + size "-1" + } + type { + method SF_INHERITED_TYPE + primitive SF_DOUBLE_TYPE + isSigned 1 + wordLength "16" + } + complexity SF_COMPLEX_INHERITED + frame SF_FRAME_INHERITED + } + dataType "Inherit: Same as Simulink" + } + junction { + id 26 + position [23.5747 49.5747 7] + chart 20 + linkNode [20 0 0] + subviewer 20 + ssIdNumber 3 + type CONNECTIVE_JUNCTION + } + transition { + id 27 + labelString "{eML_blk_kernel();}" + labelPosition [28.125 13.875 102.544 14.964] + fontSize 12 + src { + intersection [0 0 1 0 23.5747 14.625 0 0] + } + dst { + id 26 + intersection [1 0 -1 0 23.5747 42.5747 0 0] + } + midPoint [23.5747 24.9468] + chart 20 + linkNode [20 0 0] + dataLimits [21.175 25.975 14.625 42.575] + subviewer 20 + drawStyle SMART + slide { + sticky BOTH_STICK + } + executionOrder 1 + ssIdNumber 2 + } + instance { + id 28 + name "sqrt_damping/MATLAB sqrt_damping" + machine 1 + chart 20 + } + chart { + id 29 + name "atlas3_cart_impctrl/MATLAB J" + windowPosition [422 539.941 189 413] + viewLimits [0 156.75 0 153.75] + screen [1 1 3600 1200 1.180555555555556] + treeNode [0 30 0 0] + firstTransition 34 + firstJunction 33 + viewObj 29 + machine 1 + toolbarMode LIBRARY_TOOLBAR + ssIdHighWaterMark 5 + decomposition CLUSTER_CHART + type EML_CHART + firstData 31 + chartFileNumber 4 + disableImplicitCasting 1 + eml { + name "fcn" + } + } + state { + id 30 + labelString "eML_blk_kernel()" + position [18 64.5 118 66] + fontSize 12 + chart 29 + treeNode [29 0 0 0] + superState SUBCHART + subviewer 29 + ssIdNumber 1 + type FUNC_STATE + decomposition CLUSTER_STATE + eml { + isEML 1 + script "function Jg = fcn(qs)\n\nlr = true;\n\nJg = atlas3_arm_jacobig_sym(qs, lr);" + editorLayout "100 M4x1[10 5 700 500]" + } + } + data { + id 31 + ssIdNumber 4 + name "qs" + linkNode [29 0 32] + scope INPUT_DATA + machine 1 + props { + array { + size "-1" + } + type { + method SF_INHERITED_TYPE + primitive SF_DOUBLE_TYPE + } + complexity SF_COMPLEX_INHERITED + } + dataType "Inherit: Same as Simulink" + } + data { + id 32 + ssIdNumber 5 + name "Jg" + linkNode [29 31 0] + scope OUTPUT_DATA + machine 1 + props { + array { + size "-1" + } + type { + method SF_INHERITED_TYPE + primitive SF_DOUBLE_TYPE + } + complexity SF_COMPLEX_INHERITED + frame SF_FRAME_NO + } + dataType "Inherit: Same as Simulink" + } + junction { + id 33 + position [23.5747 49.5747 7] + chart 29 + linkNode [29 0 0] + subviewer 29 + ssIdNumber 3 + type CONNECTIVE_JUNCTION + } + transition { + id 34 + labelString "{eML_blk_kernel();}" + labelPosition [28.125 13.875 102.544 14.964] + fontSize 12 + src { + intersection [0 0 1 0 23.5747 14.625 0 0] + } + dst { + id 33 + intersection [1 0 -1 0 23.5747 42.5747 0 0] + } + midPoint [23.5747 24.9468] + chart 29 + linkNode [29 0 0] + dataLimits [21.175 25.975 14.625 42.575] + subviewer 29 + drawStyle SMART + slide { + sticky BOTH_STICK + } + executionOrder 1 + ssIdNumber 2 + } + instance { + id 35 + name "atlas3_cart_impctrl/MATLAB J" + machine 1 + chart 29 + } + chart { + id 36 + name "atlas3_cart_impctrl/MATLAB JD" + windowPosition [422 539.941 189 413] + viewLimits [0 156.75 0 153.75] + screen [1 1 3600 1200 1.180555555555556] + treeNode [0 37 0 0] + firstTransition 41 + firstJunction 40 + viewObj 36 + machine 1 + ssIdHighWaterMark 5 + decomposition CLUSTER_CHART + type EML_CHART + firstData 38 + chartFileNumber 5 + disableImplicitCasting 1 + eml { + name "fcn" + } + } + state { + id 37 + labelString "eML_blk_kernel()" + position [18 64.5 118 66] + fontSize 12 + chart 36 + treeNode [36 0 0 0] + superState SUBCHART + subviewer 36 + ssIdNumber 1 + type FUNC_STATE + decomposition CLUSTER_STATE + eml { + isEML 1 + script "function y = fcn(u)\n%#codegen\n\ny = u;" + editorLayout "100 M4x1[205 227 1080 733]" + } + } + data { + id 38 + ssIdNumber 4 + name "u" + linkNode [36 0 39] + scope INPUT_DATA + machine 1 + props { + array { + size "-1" + } + type { + method SF_INHERITED_TYPE + primitive SF_DOUBLE_TYPE + } + complexity SF_COMPLEX_INHERITED + } + dataType "Inherit: Same as Simulink" + } + data { + id 39 + ssIdNumber 5 + name "y" + linkNode [36 38 0] + scope OUTPUT_DATA + machine 1 + props { + array { + size "-1" + } + type { + method SF_INHERITED_TYPE + primitive SF_DOUBLE_TYPE + } + complexity SF_COMPLEX_INHERITED + frame SF_FRAME_NO + } + dataType "Inherit: Same as Simulink" + } + junction { + id 40 + position [23.5747 49.5747 7] + chart 36 + linkNode [36 0 0] + subviewer 36 + ssIdNumber 3 + type CONNECTIVE_JUNCTION + } + transition { + id 41 + labelString "{eML_blk_kernel();}" + labelPosition [28.125 13.875 102.544 14.964] + fontSize 12 + src { + intersection [0 0 1 0 23.5747 14.625 0 0] + } + dst { + id 40 + intersection [1 0 -1 0 23.5747 42.5747 0 0] + } + midPoint [23.5747 24.9468] + chart 36 + linkNode [36 0 0] + dataLimits [21.175 25.975 14.625 42.575] + subviewer 36 + drawStyle SMART + slide { + sticky BOTH_STICK + } + executionOrder 1 + ssIdNumber 2 + } + instance { + id 42 + name "atlas3_cart_impctrl/MATLAB JD" + machine 1 + chart 36 + } + chart { + id 43 + name "atlas3_cart_impctrl/DDD/Inverse" + windowPosition [422 539.941 189 413] + viewLimits [0 156.75 0 153.75] + screen [1 1 3600 1200 1.180555555555556] + treeNode [0 44 0 0] + firstTransition 48 + firstJunction 47 + viewObj 43 + machine 1 + ssIdHighWaterMark 5 + decomposition CLUSTER_CHART + type EML_CHART + firstData 45 + chartFileNumber 6 + disableImplicitCasting 1 + eml { + name "fcn" + } + } + state { + id 44 + labelString "eML_blk_kernel()" + position [18 64.5 118 66] + fontSize 12 + chart 43 + treeNode [43 0 0 0] + superState SUBCHART + subviewer 43 + ssIdNumber 1 + type FUNC_STATE + decomposition CLUSTER_STATE + eml { + isEML 1 + script "function y = fcn(u)\n%#codegen\n\ny = inv(u);" + editorLayout "100 M4x1[10 5 700 500]" + } + } + data { + id 45 + ssIdNumber 4 + name "u" + linkNode [43 0 46] + scope INPUT_DATA + machine 1 + props { + array { + size "-1" + } + type { + method SF_INHERITED_TYPE + primitive SF_DOUBLE_TYPE + } + complexity SF_COMPLEX_INHERITED + } + dataType "Inherit: Same as Simulink" + } + data { + id 46 + ssIdNumber 5 + name "y" + linkNode [43 45 0] + scope OUTPUT_DATA + machine 1 + props { + array { + size "-1" + } + type { + method SF_INHERITED_TYPE + primitive SF_DOUBLE_TYPE + } + complexity SF_COMPLEX_INHERITED + frame SF_FRAME_NO + } + dataType "Inherit: Same as Simulink" + } + junction { + id 47 + position [23.5747 49.5747 7] + chart 43 + linkNode [43 0 0] + subviewer 43 + ssIdNumber 3 + type CONNECTIVE_JUNCTION + } + transition { + id 48 + labelString "{eML_blk_kernel();}" + labelPosition [28.125 13.875 102.544 14.964] + fontSize 12 + src { + intersection [0 0 1 0 23.5747 14.625 0 0] + } + dst { + id 47 + intersection [1 0 -1 0 23.5747 42.5747 0 0] + } + midPoint [23.5747 24.9468] + chart 43 + linkNode [43 0 0] + dataLimits [21.175 25.975 14.625 42.575] + subviewer 43 + drawStyle SMART + slide { + sticky BOTH_STICK + } + executionOrder 1 + ssIdNumber 2 + } + instance { + id 49 + name "atlas3_cart_impctrl/DDD/Inverse" + machine 1 + chart 43 + } + chart { + id 50 + name "atlas3_cart_impctrl/Inverse" + windowPosition [422 539.941 189 413] + viewLimits [0 156.75 0 153.75] + screen [1 1 3600 1200 1.180555555555556] + treeNode [0 51 0 0] + firstTransition 55 + firstJunction 54 + viewObj 50 + machine 1 + ssIdHighWaterMark 5 + decomposition CLUSTER_CHART + type EML_CHART + firstData 52 + chartFileNumber 7 + disableImplicitCasting 1 + eml { + name "fcn" + } + } + state { + id 51 + labelString "eML_blk_kernel()" + position [18 64.5 118 66] + fontSize 12 + chart 50 + treeNode [50 0 0 0] + superState SUBCHART + subviewer 50 + ssIdNumber 1 + type FUNC_STATE + decomposition CLUSTER_STATE + eml { + isEML 1 + script "function y = fcn(u)\n%#codegen\n\ny = u;" + editorLayout "100 M4x1[205 227 1080 733]" + } + } + data { + id 52 + ssIdNumber 4 + name "u" + linkNode [50 0 53] + scope INPUT_DATA + machine 1 + props { + array { + size "-1" + } + type { + method SF_INHERITED_TYPE + primitive SF_DOUBLE_TYPE + } + complexity SF_COMPLEX_INHERITED + } + dataType "Inherit: Same as Simulink" + } + data { + id 53 + ssIdNumber 5 + name "y" + linkNode [50 52 0] + scope OUTPUT_DATA + machine 1 + props { + array { + size "-1" + } + type { + method SF_INHERITED_TYPE + primitive SF_DOUBLE_TYPE + } + complexity SF_COMPLEX_INHERITED + frame SF_FRAME_NO + } + dataType "Inherit: Same as Simulink" + } + junction { + id 54 + position [23.5747 49.5747 7] + chart 50 + linkNode [50 0 0] + subviewer 50 + ssIdNumber 3 + type CONNECTIVE_JUNCTION + } + transition { + id 55 + labelString "{eML_blk_kernel();}" + labelPosition [28.125 13.875 102.544 14.964] + fontSize 12 + src { + intersection [0 0 1 0 23.5747 14.625 0 0] + } + dst { + id 54 + intersection [1 0 -1 0 23.5747 42.5747 0 0] + } + midPoint [23.5747 24.9468] + chart 50 + linkNode [50 0 0] + dataLimits [21.175 25.975 14.625 42.575] + subviewer 50 + drawStyle SMART + slide { + sticky BOTH_STICK + } + executionOrder 1 + ssIdNumber 2 + } + instance { + id 56 + name "atlas3_cart_impctrl/Inverse" + machine 1 + chart 50 + } + chart { + id 57 + name "friction_compensation/MATLAB sqrt_damping" + windowPosition [422 539.941 189 413] + viewLimits [0 156.75 0 153.75] + screen [1 1 3600 1200 1.180555555555556] + treeNode [0 58 0 0] + firstTransition 67 + firstJunction 66 + viewObj 57 + machine 1 + toolbarMode LIBRARY_TOOLBAR + ssIdHighWaterMark 14 + decomposition CLUSTER_CHART + type EML_CHART + firstData 59 + chartFileNumber 8 + disableImplicitCasting 1 + eml { + name "sqrt_damping" + } + } + state { + id 58 + labelString "eML_blk_kernel()" + position [18 64.5 118 66] + fontSize 12 + chart 57 + treeNode [57 0 0 0] + superState SUBCHART + subviewer 57 + ssIdNumber 1 + type FUNC_STATE + decomposition CLUSTER_STATE + eml { + isEML 1 + script "function tau_F=sqrt_damping(tau_imp,qD,tau_c,B,qD_th,tau_th)\n%#codegen\ntau_F=zeros(length(tau_i" + "mp),1);\nfor i=1:length(tau_imp)\n % friction compensation only, when significant distance to desired\n % traj" + "ectory\n if (abs(tau_imp(i)) > tau_th(i))\n % when qD qD_th(i) || sign(qD(i))==sign(tau_imp(i)))\n tau_F(i) = tau_c(i)*sign(qD(i)) + B(i)*qD" + "(i);\n else\n tau_F(i) = tau_c(i);\n end\n else\n tau_F(i) = 0;\n end\nend\n " + editorLayout "100 M4x1[10 5 700 500]" + } + } + data { + id 59 + ssIdNumber 4 + name "tau_imp" + linkNode [57 0 60] + scope INPUT_DATA + paramIndexForInitFromWorkspace 5 + machine 1 + props { + array { + size "-1" + } + type { + method SF_INHERITED_TYPE + primitive SF_DOUBLE_TYPE + } + complexity SF_COMPLEX_INHERITED + } + dataType "Inherit: Same as Simulink" + } + data { + id 60 + ssIdNumber 6 + name "qD" + linkNode [57 59 61] + scope INPUT_DATA + machine 1 + props { + array { + size "-1" + } + type { + method SF_INHERITED_TYPE + primitive SF_DOUBLE_TYPE + isSigned 1 + wordLength "16" + } + complexity SF_COMPLEX_INHERITED + frame SF_FRAME_INHERITED + } + dataType "Inherit: Same as Simulink" + } + data { + id 61 + ssIdNumber 5 + name "tau_F" + linkNode [57 60 62] + scope OUTPUT_DATA + machine 1 + props { + array { + size "-1" + } + type { + method SF_INHERITED_TYPE + primitive SF_DOUBLE_TYPE + } + complexity SF_COMPLEX_INHERITED + frame SF_FRAME_NO + } + dataType "Inherit: Same as Simulink" + } + data { + id 62 + ssIdNumber 8 + name "tau_c" + linkNode [57 61 63] + scope PARAMETER_DATA + paramIndexForInitFromWorkspace 2 + machine 1 + props { + array { + size "-1" + } + type { + method SF_INHERITED_TYPE + primitive SF_DOUBLE_TYPE + isSigned 1 + wordLength "16" + } + complexity SF_COMPLEX_INHERITED + frame SF_FRAME_INHERITED + } + dataType "Inherit: Same as Simulink" + } + data { + id 63 + ssIdNumber 9 + name "B" + linkNode [57 62 64] + scope PARAMETER_DATA + machine 1 + props { + array { + size "-1" + } + type { + method SF_INHERITED_TYPE + primitive SF_DOUBLE_TYPE + isSigned 1 + wordLength "16" + } + complexity SF_COMPLEX_INHERITED + frame SF_FRAME_INHERITED + } + dataType "Inherit: Same as Simulink" + } + data { + id 64 + ssIdNumber 12 + name "qD_th" + linkNode [57 63 65] + scope PARAMETER_DATA + paramIndexForInitFromWorkspace 1 + machine 1 + props { + array { + size "-1" + } + type { + method SF_INHERITED_TYPE + primitive SF_DOUBLE_TYPE + isSigned 1 + wordLength "16" + } + complexity SF_COMPLEX_INHERITED + frame SF_FRAME_INHERITED + } + dataType "Inherit: Same as Simulink" + } + data { + id 65 + ssIdNumber 13 + name "tau_th" + linkNode [57 64 0] + scope PARAMETER_DATA + paramIndexForInitFromWorkspace 3 + machine 1 + props { + array { + size "-1" + } + type { + method SF_INHERITED_TYPE + primitive SF_DOUBLE_TYPE + isSigned 1 + wordLength "16" + } + complexity SF_COMPLEX_INHERITED + frame SF_FRAME_INHERITED + } + dataType "Inherit: Same as Simulink" + } + junction { + id 66 + position [23.5747 49.5747 7] + chart 57 + linkNode [57 0 0] + subviewer 57 + ssIdNumber 3 + type CONNECTIVE_JUNCTION + } + transition { + id 67 + labelString "{eML_blk_kernel();}" + labelPosition [28.125 13.875 102.544 14.964] + fontSize 12 + src { + intersection [0 0 1 0 23.5747 14.625 0 0] + } + dst { + id 66 + intersection [1 0 -1 0 23.5747 42.5747 0 0] + } + midPoint [23.5747 24.9468] + chart 57 + linkNode [57 0 0] + dataLimits [21.175 25.975 14.625 42.575] + subviewer 57 + drawStyle SMART + slide { + sticky BOTH_STICK + } + executionOrder 1 + ssIdNumber 2 + } + instance { + id 68 + name "friction_compensation/MATLAB sqrt_damping" + machine 1 + chart 57 + } + chart { + id 69 + name "velocity_based_friction_observer/MATLAB Function" + windowPosition [422 539.941 189 413] + viewLimits [0 156.75 0 153.75] + screen [1 1 3600 1200 1.180555555555556] + treeNode [0 70 0 0] + firstTransition 83 + firstJunction 82 + viewObj 69 + machine 1 + toolbarMode LIBRARY_TOOLBAR + ssIdHighWaterMark 15 + decomposition CLUSTER_CHART + type EML_CHART + firstData 71 + chartFileNumber 9 + disableImplicitCasting 1 + eml { + name "fcn" + } + } + state { + id 70 + labelString "eML_blk_kernel()" + position [18 64.5 118 66] + fontSize 12 + chart 69 + treeNode [69 0 0 0] + superState SUBCHART + subviewer 69 + ssIdNumber 1 + type FUNC_STATE + decomposition CLUSTER_STATE + eml { + isEML 1 + script "function [tau_fr, tau_int] = fcn(tau_J_old, tau_g_old, tau_c_old, tau_fr_old, tau_int_alt, qD, M," + " K_O, T)\n%#codegen\n\ntau_int = tau_int_alt + T*K_O*(M\\(tau_J_old-tau_g_old-tau_c_old-tau_fr_old));\ntau_fr =" + " tau_int - K_O*qD;" + editorLayout "100 M4x1[10 5 700 500]" + } + } + data { + id 71 + ssIdNumber 4 + name "tau_J_old" + linkNode [69 0 72] + scope INPUT_DATA + machine 1 + props { + array { + size "-1" + } + type { + method SF_INHERITED_TYPE + primitive SF_DOUBLE_TYPE + } + complexity SF_COMPLEX_INHERITED + } + dataType "Inherit: Same as Simulink" + } + data { + id 72 + ssIdNumber 5 + name "tau_fr" + linkNode [69 71 73] + scope OUTPUT_DATA + machine 1 + props { + array { + size "-1" + } + type { + method SF_INHERITED_TYPE + primitive SF_DOUBLE_TYPE + } + complexity SF_COMPLEX_INHERITED + frame SF_FRAME_NO + } + dataType "Inherit: Same as Simulink" + } + data { + id 73 + ssIdNumber 6 + name "tau_g_old" + linkNode [69 72 74] + scope INPUT_DATA + machine 1 + props { + array { + size "-1" + } + type { + method SF_INHERITED_TYPE + primitive SF_DOUBLE_TYPE + isSigned 1 + wordLength "16" + } + complexity SF_COMPLEX_INHERITED + frame SF_FRAME_INHERITED + } + dataType "Inherit: Same as Simulink" + } + data { + id 74 + ssIdNumber 7 + name "tau_c_old" + linkNode [69 73 75] + scope INPUT_DATA + machine 1 + props { + array { + size "-1" + } + type { + method SF_INHERITED_TYPE + primitive SF_DOUBLE_TYPE + isSigned 1 + wordLength "16" + } + complexity SF_COMPLEX_INHERITED + frame SF_FRAME_INHERITED + } + dataType "Inherit: Same as Simulink" + } + data { + id 75 + ssIdNumber 15 + name "tau_fr_old" + linkNode [69 74 76] + scope INPUT_DATA + machine 1 + props { + array { + size "-1" + } + type { + method SF_INHERITED_TYPE + primitive SF_DOUBLE_TYPE + isSigned 1 + wordLength "16" + } + complexity SF_COMPLEX_INHERITED + frame SF_FRAME_INHERITED + } + dataType "Inherit: Same as Simulink" + } + data { + id 76 + ssIdNumber 8 + name "tau_int_alt" + linkNode [69 75 77] + scope INPUT_DATA + machine 1 + props { + array { + size "-1" + } + type { + method SF_INHERITED_TYPE + primitive SF_DOUBLE_TYPE + isSigned 1 + wordLength "16" + } + complexity SF_COMPLEX_INHERITED + frame SF_FRAME_INHERITED + } + dataType "Inherit: Same as Simulink" + } + data { + id 77 + ssIdNumber 9 + name "qD" + linkNode [69 76 78] + scope INPUT_DATA + machine 1 + props { + array { + size "-1" + } + type { + method SF_INHERITED_TYPE + primitive SF_DOUBLE_TYPE + isSigned 1 + wordLength "16" + } + complexity SF_COMPLEX_INHERITED + frame SF_FRAME_INHERITED + } + dataType "Inherit: Same as Simulink" + } + data { + id 78 + ssIdNumber 10 + name "M" + linkNode [69 77 79] + scope INPUT_DATA + machine 1 + props { + array { + size "-1" + } + type { + method SF_INHERITED_TYPE + primitive SF_DOUBLE_TYPE + isSigned 1 + wordLength "16" + } + complexity SF_COMPLEX_INHERITED + frame SF_FRAME_INHERITED + } + dataType "Inherit: Same as Simulink" + } + data { + id 79 + ssIdNumber 11 + name "K_O" + linkNode [69 78 80] + scope PARAMETER_DATA + machine 1 + props { + array { + size "-1" + } + type { + method SF_INHERITED_TYPE + primitive SF_DOUBLE_TYPE + isSigned 1 + wordLength "16" + } + complexity SF_COMPLEX_INHERITED + frame SF_FRAME_INHERITED + } + dataType "Inherit: Same as Simulink" + } + data { + id 80 + ssIdNumber 12 + name "T" + linkNode [69 79 81] + scope PARAMETER_DATA + paramIndexForInitFromWorkspace 1 + machine 1 + props { + array { + size "-1" + } + type { + method SF_INHERITED_TYPE + primitive SF_DOUBLE_TYPE + isSigned 1 + wordLength "16" + } + complexity SF_COMPLEX_INHERITED + frame SF_FRAME_INHERITED + } + dataType "Inherit: Same as Simulink" + } + data { + id 81 + ssIdNumber 14 + name "tau_int" + linkNode [69 80 0] + scope OUTPUT_DATA + machine 1 + props { + array { + size "-1" + } + type { + method SF_INHERITED_TYPE + primitive SF_DOUBLE_TYPE + isSigned 1 + wordLength "16" + } + complexity SF_COMPLEX_INHERITED + frame SF_FRAME_NO + } + dataType "Inherit: Same as Simulink" + } + junction { + id 82 + position [23.5747 49.5747 7] + chart 69 + linkNode [69 0 0] + subviewer 69 + ssIdNumber 3 + type CONNECTIVE_JUNCTION + } + transition { + id 83 + labelString "{eML_blk_kernel();}" + labelPosition [28.125 13.875 102.544 14.964] + fontSize 12 + src { + intersection [0 0 1 0 23.5747 14.625 0 0] + } + dst { + id 82 + intersection [1 0 -1 0 23.5747 42.5747 0 0] + } + midPoint [23.5747 24.9468] + chart 69 + linkNode [69 0 0] + dataLimits [21.175 25.975 14.625 42.575] + subviewer 69 + drawStyle SMART + slide { + sticky BOTH_STICK + } + executionOrder 1 + ssIdNumber 2 + } + instance { + id 84 + name "velocity_based_friction_observer/MATLAB Function" + machine 1 + chart 69 + } + chart { + id 85 + name "compensate_hand_mass_and_offset/compensate_hand_mass_and_offset" + windowPosition [422 539.941 189 413] + viewLimits [0 156.75 0 153.75] + screen [1 1 3600 1200 1.180555555555556] + treeNode [0 86 0 0] + firstTransition 93 + firstJunction 92 + viewObj 85 + machine 1 + toolbarMode LIBRARY_TOOLBAR + ssIdHighWaterMark 8 + decomposition CLUSTER_CHART + type EML_CHART + firstData 87 + chartFileNumber 10 + disableImplicitCasting 1 + eml { + name "fcn" + } + } + state { + id 86 + labelString "eML_blk_kernel()" + position [18 64.5 118 66] + fontSize 12 + chart 85 + treeNode [85 0 0 0] + superState SUBCHART + subviewer 85 + ssIdNumber 1 + type FUNC_STATE + decomposition CLUSTER_STATE + eml { + isEML 1 + script "function W_comp = fcn(W_raw, g_hand, mr, offsets)\n%#codegen\n\n% mr contains the mass (1) and th" + "e coordinates of the com (2-4) of the hand\n% (in hand coordinates), g has to be expressed in hand coordinates\n" + "W_comp = W_raw - offsets;\nW_comp(1:3) = W_comp(1:3) - mr(1)*g;\nW_comp(4:6) = W_comp(4:6) - cross(mr(2:4), mr(1" + ")*g);" + editorLayout "100 M4x1[10 5 700 500]" + } + } + data { + id 87 + ssIdNumber 4 + name "W_raw" + linkNode [85 0 88] + scope INPUT_DATA + machine 1 + props { + array { + size "-1" + } + type { + method SF_INHERITED_TYPE + primitive SF_DOUBLE_TYPE + } + complexity SF_COMPLEX_INHERITED + } + dataType "Inherit: Same as Simulink" + } + data { + id 88 + ssIdNumber 5 + name "W_comp" + linkNode [85 87 89] + scope OUTPUT_DATA + machine 1 + props { + array { + size "-1" + } + type { + method SF_INHERITED_TYPE + primitive SF_DOUBLE_TYPE + } + complexity SF_COMPLEX_INHERITED + frame SF_FRAME_NO + } + dataType "Inherit: Same as Simulink" + } + data { + id 89 + ssIdNumber 6 + name "g_hand" + linkNode [85 88 90] + scope INPUT_DATA + machine 1 + props { + array { + size "-1" + } + type { + method SF_INHERITED_TYPE + primitive SF_DOUBLE_TYPE + isSigned 1 + wordLength "16" + } + complexity SF_COMPLEX_INHERITED + frame SF_FRAME_INHERITED + } + dataType "Inherit: Same as Simulink" + } + data { + id 90 + ssIdNumber 7 + name "mr" + linkNode [85 89 91] + scope PARAMETER_DATA + machine 1 + props { + array { + size "-1" + } + type { + method SF_INHERITED_TYPE + primitive SF_DOUBLE_TYPE + isSigned 1 + wordLength "16" + } + complexity SF_COMPLEX_INHERITED + frame SF_FRAME_INHERITED + } + dataType "Inherit: Same as Simulink" + } + data { + id 91 + ssIdNumber 8 + name "offsets" + linkNode [85 90 0] + scope PARAMETER_DATA + paramIndexForInitFromWorkspace 1 + machine 1 + props { + array { + size "-1" + } + type { + method SF_INHERITED_TYPE + primitive SF_DOUBLE_TYPE + isSigned 1 + wordLength "16" + } + complexity SF_COMPLEX_INHERITED + frame SF_FRAME_INHERITED + } + dataType "Inherit: Same as Simulink" + } + junction { + id 92 + position [23.5747 49.5747 7] + chart 85 + linkNode [85 0 0] + subviewer 85 + ssIdNumber 3 + type CONNECTIVE_JUNCTION + } + transition { + id 93 + labelString "{eML_blk_kernel();}" + labelPosition [28.125 13.875 102.544 14.964] + fontSize 12 + src { + intersection [0 0 1 0 23.5747 14.625 0 0] + } + dst { + id 92 + intersection [1 0 -1 0 23.5747 42.5747 0 0] + } + midPoint [23.5747 24.9468] + chart 85 + linkNode [85 0 0] + dataLimits [21.175 25.975 14.625 42.575] + subviewer 85 + drawStyle SMART + slide { + sticky BOTH_STICK + } + executionOrder 1 + ssIdNumber 2 + } + instance { + id 94 + name "compensate_hand_mass_and_offset/compensate_hand_mass_and_offset" + machine 1 + chart 85 + } + chart { + id 95 + name "momentum_based_friction_observer/MATLAB Function" + windowPosition [422 539.941 189 413] + viewLimits [0 156.75 0 153.75] + screen [1 1 3600 1200 1.180555555555556] + treeNode [0 96 0 0] + firstTransition 117 + firstJunction 116 + viewObj 95 + visible 1 + machine 1 + subviewS { + } + ssIdHighWaterMark 23 + decomposition CLUSTER_CHART + type EML_CHART + firstData 97 + chartFileNumber 11 + disableImplicitCasting 1 + eml { + name "fcn" + } + } + state { + id 96 + labelString "eML_blk_kernel()" + position [18 64.5 118 66] + fontSize 12 + chart 95 + treeNode [95 0 0 0] + superState SUBCHART + subviewer 95 + ssIdNumber 1 + type FUNC_STATE + decomposition CLUSTER_STATE + eml { + isEML 1 + script "function [tau_fr, tau_int, MD] = fcn(tau_J_old, tau_g_old, tau_c_old, tau_ext_old, tau_fr_obs_old" + ", tau_int_old, qD, qD_old, M, M_old, MD_old, tau_fr_model_old, K_O, T1, tau_out_max, T)\n%#codegen\n\nMD = " + "1/(T1+T) * (T1*MD_old + M - M_old);\ntau_int = tau_int_old + T*(tau_J_old-tau_g_old-tau_c_old+tau_ext_old-tau_fr" + "_model_old+MD*qD_old-tau_fr_obs_old);\ntau_fr_MqD = -K_O*M*qD;\ntau_fr = K_O*tau_int + tau_fr_MqD;\n\n% limit ou" + "tput and anti-windup\nfor i=1:length(tau_J_old)\n if tau_fr(i)>tau_out_max(i)\n tau_fr(i)=tau_out_max(i);\n " + " tau_int(i)=1/K_O(i,i)*(tau_out_max(i)-tau_fr_MqD(i));\n elseif tau_fr(i)<-tau_out_max(i)\n tau_fr(i)=-tau" + "_out_max(i);\n tau_int(i)=1/K_O(i,i)*(-tau_out_max(i)-tau_fr_MqD(i));\n end\nend" + editorLayout "100 M4x1[10 5 700 500]" + } + } + data { + id 97 + ssIdNumber 4 + name "tau_J_old" + linkNode [95 0 98] + scope INPUT_DATA + machine 1 + props { + array { + size "-1" + } + type { + primitive SF_DOUBLE_TYPE + } + } + dataType "double" + } + data { + id 98 + ssIdNumber 5 + name "tau_fr" + linkNode [95 97 99] + scope OUTPUT_DATA + machine 1 + props { + array { + size "-1" + } + type { + primitive SF_DOUBLE_TYPE + } + frame SF_FRAME_NO + } + dataType "double" + } + data { + id 99 + ssIdNumber 6 + name "tau_g_old" + linkNode [95 98 100] + scope INPUT_DATA + machine 1 + props { + array { + size "-1" + } + type { + primitive SF_DOUBLE_TYPE + isSigned 1 + wordLength "16" + } + frame SF_FRAME_INHERITED + } + dataType "double" + } + data { + id 100 + ssIdNumber 7 + name "tau_c_old" + linkNode [95 99 101] + scope INPUT_DATA + machine 1 + props { + array { + size "-1" + } + type { + primitive SF_DOUBLE_TYPE + isSigned 1 + wordLength "16" + } + frame SF_FRAME_INHERITED + } + dataType "double" + } + data { + id 101 + ssIdNumber 21 + name "tau_ext_old" + linkNode [95 100 102] + scope INPUT_DATA + machine 1 + props { + array { + size "-1" + } + type { + primitive SF_DOUBLE_TYPE + isSigned 1 + wordLength "16" + } + frame SF_FRAME_INHERITED + } + dataType "double" + } + data { + id 102 + ssIdNumber 15 + name "tau_fr_obs_old" + linkNode [95 101 103] + scope INPUT_DATA + machine 1 + props { + array { + size "-1" + } + type { + primitive SF_DOUBLE_TYPE + isSigned 1 + wordLength "16" + } + frame SF_FRAME_INHERITED + } + dataType "double" + } + data { + id 103 + ssIdNumber 8 + name "tau_int_old" + linkNode [95 102 104] + scope INPUT_DATA + machine 1 + props { + array { + size "-1" + } + type { + primitive SF_DOUBLE_TYPE + isSigned 1 + wordLength "16" + } + frame SF_FRAME_INHERITED + } + dataType "double" + } + data { + id 104 + ssIdNumber 9 + name "qD" + linkNode [95 103 105] + scope INPUT_DATA + machine 1 + props { + array { + size "-1" + } + type { + primitive SF_DOUBLE_TYPE + isSigned 1 + wordLength "16" + } + frame SF_FRAME_INHERITED + } + dataType "double" + } + data { + id 105 + ssIdNumber 20 + name "qD_old" + linkNode [95 104 106] + scope INPUT_DATA + machine 1 + props { + array { + size "-1" + } + type { + primitive SF_DOUBLE_TYPE + isSigned 1 + wordLength "16" + } + frame SF_FRAME_INHERITED + } + dataType "double" + } + data { + id 106 + ssIdNumber 10 + name "M" + linkNode [95 105 107] + scope INPUT_DATA + machine 1 + props { + array { + size "-1" + } + type { + primitive SF_DOUBLE_TYPE + isSigned 1 + wordLength "16" + } + frame SF_FRAME_INHERITED + } + dataType "double" + } + data { + id 107 + ssIdNumber 17 + name "M_old" + linkNode [95 106 108] + scope INPUT_DATA + machine 1 + props { + array { + size "-1" + } + type { + primitive SF_DOUBLE_TYPE + isSigned 1 + wordLength "16" + } + frame SF_FRAME_NO + } + dataType "double" + } + data { + id 108 + ssIdNumber 18 + name "MD_old" + linkNode [95 107 109] + scope INPUT_DATA + machine 1 + props { + array { + size "-1" + } + type { + primitive SF_DOUBLE_TYPE + isSigned 1 + wordLength "16" + } + frame SF_FRAME_INHERITED + } + dataType "double" + } + data { + id 109 + ssIdNumber 22 + name "tau_fr_model_old" + linkNode [95 108 110] + scope INPUT_DATA + machine 1 + props { + array { + size "-1" + } + type { + primitive SF_DOUBLE_TYPE + isSigned 1 + wordLength "16" + } + frame SF_FRAME_INHERITED + } + dataType "double" + } + data { + id 110 + ssIdNumber 11 + name "K_O" + linkNode [95 109 111] + scope PARAMETER_DATA + machine 1 + props { + array { + size "-1" + } + type { + primitive SF_DOUBLE_TYPE + isSigned 1 + wordLength "16" + } + frame SF_FRAME_INHERITED + } + dataType "double" + } + data { + id 111 + ssIdNumber 16 + name "T1" + linkNode [95 110 112] + scope PARAMETER_DATA + paramIndexForInitFromWorkspace 2 + machine 1 + props { + array { + size "[1 1]" + } + type { + primitive SF_DOUBLE_TYPE + isSigned 1 + wordLength "16" + } + frame SF_FRAME_INHERITED + } + dataType "double" + } + data { + id 112 + ssIdNumber 23 + name "tau_out_max" + linkNode [95 111 113] + scope PARAMETER_DATA + paramIndexForInitFromWorkspace 3 + machine 1 + props { + array { + size "-1" + } + type { + primitive SF_DOUBLE_TYPE + isSigned 1 + wordLength "16" + } + frame SF_FRAME_INHERITED + } + dataType "double" + } + data { + id 113 + ssIdNumber 12 + name "T" + linkNode [95 112 114] + scope PARAMETER_DATA + paramIndexForInitFromWorkspace 1 + machine 1 + props { + array { + size "[1 1]" + } + type { + primitive SF_DOUBLE_TYPE + isSigned 1 + wordLength "16" + } + frame SF_FRAME_INHERITED + } + dataType "double" + } + data { + id 114 + ssIdNumber 14 + name "tau_int" + linkNode [95 113 115] + scope OUTPUT_DATA + machine 1 + props { + array { + size "-1" + } + type { + primitive SF_DOUBLE_TYPE + isSigned 1 + wordLength "16" + } + frame SF_FRAME_NO + } + dataType "double" + } + data { + id 115 + ssIdNumber 19 + name "MD" + linkNode [95 114 0] + scope OUTPUT_DATA + machine 1 + props { + array { + size "-1" + } + type { + primitive SF_DOUBLE_TYPE + isSigned 1 + wordLength "16" + } + frame SF_FRAME_NO + } + dataType "double" + } + junction { + id 116 + position [23.5747 49.5747 7] + chart 95 + linkNode [95 0 0] + subviewer 95 + ssIdNumber 3 + type CONNECTIVE_JUNCTION + } + transition { + id 117 + labelString "{eML_blk_kernel();}" + labelPosition [28.125 13.875 102.544 14.964] + fontSize 12 + src { + intersection [0 0 1 0 23.5747 14.625 0 0] + } + dst { + id 116 + intersection [1 0 -1 0 23.5747 42.5747 0 0] + } + midPoint [23.5747 24.9468] + chart 95 + linkNode [95 0 0] + dataLimits [21.175 25.975 14.625 42.575] + subviewer 95 + drawStyle SMART + slide { + sticky BOTH_STICK + } + executionOrder 1 + ssIdNumber 2 + } + instance { + id 118 + name "momentum_based_friction_observer/MATLAB Function" + machine 1 + chart 95 + } + chart { + id 119 + name "fr_comp_w_obs/MATLAB fr_comp_w_obs" + windowPosition [422 539.941 189 413] + viewLimits [0 156.75 0 153.75] + screen [1 1 3600 1200 1.180555555555556] + treeNode [0 120 0 0] + firstTransition 129 + firstJunction 128 + viewObj 119 + machine 1 + ssIdHighWaterMark 14 + decomposition CLUSTER_CHART + type EML_CHART + firstData 121 + chartFileNumber 12 + disableImplicitCasting 1 + eml { + name "fr_comp_w_obs" + } + } + state { + id 120 + labelString "eML_blk_kernel()" + position [18 64.5 118 66] + fontSize 12 + chart 119 + treeNode [119 0 0 0] + superState SUBCHART + subviewer 119 + ssIdNumber 1 + type FUNC_STATE + decomposition CLUSTER_STATE + eml { + isEML 1 + script "function tau_F=fr_comp_w_obs(tau_imp,qD,tau_fr_model,tau_c,qD_th,tau_th)\n%#codegen\ntau_F=zeros(" + "length(tau_imp),1);\nfor i=1:length(tau_imp)\n if (abs(qD(i)) > qD_th(i))\n tau_F(i) = tau_fr_model(i);\n e" + "lse\n % for low speed friction compensation only, when significant distance\n % to desired trajectory\n " + " if (abs(tau_imp(i)) > tau_th(i))\n % when qD" + FullBlockPath "atlas_joint_impctrl_sqrt_damping_test/Bus Selector3" + LogSignal 1 + UseCustomName 1 + LogName "qDD" + MaxPoints 5000 + Decimation 2 + } + TestPointedSignal { + SignalName "" + FullBlockPath "atlas_joint_impctrl_sqrt_damping_test/atlas5_arm_coriolis_vec_minvarpar" + LogSignal 1 + UseCustomName 1 + LogName "tau_c" + MaxPoints 5000 + Decimation 2 + } + TestPointedSignal { + SignalName "" + FullBlockPath "atlas_joint_impctrl_sqrt_damping_test/atlas5_arm_gravload_minvarpar" + LogSignal 1 + UseCustomName 1 + LogName "tau_g" + MaxPoints 5000 + Decimation 2 + } + TestPointedSignal { + SignalName "tau_m" + FullBlockPath "atlas_joint_impctrl_sqrt_damping_test/atlas5_arm_fordyn_rj_damping_minvarpar/tau_m" + LogSignal 1 + MaxPoints 5000 + Decimation 2 + } + TestPointedSignal { + SignalName "qD" + FullBlockPath "atlas_joint_impctrl_sqrt_damping_test/atlas5_arm_fordyn_rj_damping_minvarpar/Integrator" + LogSignal 1 + MaxPoints 5000 + Decimation 2 + } + TestPointedSignal { + SignalName "q" + FullBlockPath "atlas_joint_impctrl_sqrt_damping_test/atlas5_arm_fordyn_rj_damping_minvarpar/Integrator1" + LogSignal 1 + MaxPoints 5000 + Decimation 2 + } + TestPointedSignal { + SignalName "tau_acc" + FullBlockPath "atlas_joint_impctrl_sqrt_damping_test/atlas5_arm_fordyn_rj_damping_minvarpar/Sum3" + LogSignal 1 + MaxPoints 5000 + Decimation 2 + } + } + ScopeRefreshTime 0.035000 + OverrideScopeRefreshTime off + DisableAllScopes off + DataTypeOverride "UseLocalSettings" + DataTypeOverrideAppliesTo "AllNumericTypes" + MinMaxOverflowLogging "UseLocalSettings" + MinMaxOverflowArchiveMode "Overwrite" + FPTRunName "Run 1" + MaxMDLFileLineLength 120 + Object { + $PropName "BdWindowsInfo" + $ObjectID 1 + $ClassName "Simulink.BDWindowsInfo" + Object { + $PropName "WindowsInfo" + $ObjectID 2 + $ClassName "Simulink.WindowInfo" + IsActive [1] + Location [806.0, 144.0, 947.0, 837.0] + Object { + $PropName "ModelBrowserInfo" + $ObjectID 3 + $ClassName "Simulink.ModelBrowserInfo" + Visible [0] + DockPosition "Left" + Width [50] + Height [50] + Filter [59] + } + Object { + $PropName "ExplorerBarInfo" + $ObjectID 4 + $ClassName "Simulink.ExplorerBarInfo" + Visible [1] + } + Object { + $PropName "EditorsInfo" + $ObjectID 5 + $ClassName "Simulink.EditorInfo" + IsActive [1] + ViewObjType "SimulinkTopLevel" + LoadSaveID "0" + Extents [897.0, 663.0] + ZoomFactor [1.0] + Offset [913.6874982714653, 217.0] + } + } + } + Created "Thu Dec 11 11:08:52 2014" + Creator "knoechelmann" + UpdateHistory "UpdateHistoryNever" + ModifiedByFormat "%" + LastModifiedBy "Vorndamme" + ModifiedDateFormat "%" + LastModifiedDate "Mon Apr 11 17:06:38 2016" + RTWModifiedTimeStamp 382295089 + ModelVersionFormat "1.%" + ConfigurationManager "none" + SampleTimeColors off + SampleTimeAnnotations on + LibraryLinkDisplay "all" + WideLines off + ShowLineDimensions on + ShowPortDataTypes off + ShowDesignRanges off + ShowLoopsOnError on + IgnoreBidirectionalLines off + ShowStorageClass off + ShowTestPointIcons on + ShowSignalResolutionIcons on + ShowViewerIcons on + SortedOrder off + ExecutionContextIcon off + ShowLinearizationAnnotations on + ShowMarkup on + BlockNameDataTip off + BlockParametersDataTip off + BlockDescriptionStringDataTip off + ToolBar on + StatusBar on + BrowserShowLibraryLinks on + BrowserLookUnderMasks on + SimulationMode "rapid-accelerator" + PauseTimes "5" + NumberOfSteps 1 + SnapshotBufferSize 10 + SnapshotInterval 10 + NumberOfLastSnapshots 0 + LinearizationMsg "none" + Profile off + ParamWorkspaceSource "MATLABWorkspace" + AccelSystemTargetFile "accel.tlc" + AccelTemplateMakefile "accel_default_tmf" + AccelMakeCommand "make_rtw" + TryForcingSFcnDF off + Object { + $PropName "DataLoggingOverride" + $ObjectID 6 + $ClassName "Simulink.SimulationData.ModelLoggingInfo" + model_ "atlas3_joint_impctrl_test" + overrideMode_ [0.0] + Array { + Type "Cell" + Dimension 1 + Cell "atlas3_joint_impctrl_test" + PropName "logAsSpecifiedByModels_" + } + Array { + Type "Cell" + Dimension 1 + Cell [] + PropName "logAsSpecifiedByModelsSSIDs_" + } + } + RecordCoverage off + CovPath "/" + CovSaveName "covdata" + CovMetricSettings "dw" + CovNameIncrementing off + CovHtmlReporting on + CovForceBlockReductionOff on + CovEnableCumulative on + covSaveCumulativeToWorkspaceVar on + CovSaveSingleToWorkspaceVar on + CovCumulativeVarName "covCumulativeData" + CovCumulativeReport off + CovReportOnPause on + CovModelRefEnable "Off" + CovExternalEMLEnable off + CovSFcnEnable off + CovBoundaryAbsTol 0.000010 + CovBoundaryRelTol 0.010000 + CovUseTimeInterval off + CovStartTime 0 + CovStopTime 0 + ExtModeBatchMode off + ExtModeEnableFloating on + ExtModeTrigType "manual" + ExtModeTrigMode "normal" + ExtModeTrigPort "1" + ExtModeTrigElement "any" + ExtModeTrigDuration 1000 + ExtModeTrigDurationFloating "auto" + ExtModeTrigHoldOff 0 + ExtModeTrigDelay 0 + ExtModeTrigDirection "rising" + ExtModeTrigLevel 0 + ExtModeArchiveMode "off" + ExtModeAutoIncOneShot off + ExtModeIncDirWhenArm off + ExtModeAddSuffixToVar off + ExtModeWriteAllDataToWs off + ExtModeArmWhenConnect on + ExtModeSkipDownloadWhenConnect off + ExtModeLogAll on + ExtModeAutoUpdateStatusClock on + ShowModelReferenceBlockVersion off + ShowModelReferenceBlockIO off + Array { + Type "Handle" + Dimension 1 + Simulink.ConfigSet { + $ObjectID 7 + Version "1.15.0" + Array { + Type "Handle" + Dimension 8 + Simulink.SolverCC { + $ObjectID 8 + Version "1.15.0" + StartTime "0.0" + StopTime "2.0" + AbsTol "auto" + FixedStep "1e-4" + InitialStep "auto" + MaxNumMinSteps "-1" + MaxOrder 5 + ZcThreshold "auto" + ConsecutiveZCsStepRelTol "10*128*eps" + MaxConsecutiveZCs "1000" + ExtrapolationOrder 4 + NumberNewtonIterations 1 + MaxStep "auto" + MinStep "auto" + MaxConsecutiveMinStep "1" + RelTol "1e-3" + SolverMode "Auto" + EnableConcurrentExecution off + ConcurrentTasks off + Solver "ode4" + SolverName "ode4" + SolverJacobianMethodControl "auto" + ShapePreserveControl "DisableAll" + ZeroCrossControl "UseLocalSettings" + ZeroCrossAlgorithm "Nonadaptive" + AlgebraicLoopSolver "TrustRegion" + SolverResetMethod "Fast" + PositivePriorityOrder off + AutoInsertRateTranBlk off + SampleTimeConstraint "Unconstrained" + InsertRTBMode "Whenever possible" + } + Simulink.DataIOCC { + $ObjectID 9 + Version "1.15.0" + Decimation "1" + ExternalInput "[t, u]" + FinalStateName "xFinal" + InitialState "xInitial" + LimitDataPoints off + MaxDataPoints "1000" + LoadExternalInput off + LoadInitialState off + SaveFinalState off + SaveCompleteFinalSimState off + SaveFormat "StructureWithTime" + SignalLoggingSaveFormat "Dataset" + SaveOutput on + SaveState off + SignalLogging on + DSMLogging on + InspectSignalLogs off + VisualizeSimOutput on + SaveTime on + ReturnWorkspaceOutputs off + StateSaveName "xout" + TimeSaveName "tout" + OutputSaveName "yout" + SignalLoggingName "logsout" + DSMLoggingName "dsmout" + OutputOption "RefineOutputTimes" + OutputTimes "[]" + ReturnWorkspaceOutputsName "out" + Refine "1" + } + Simulink.OptimizationCC { + $ObjectID 10 + Version "1.15.0" + Array { + Type "Cell" + Dimension 8 + Cell "BooleansAsBitfields" + Cell "PassReuseOutputArgsAs" + Cell "PassReuseOutputArgsThreshold" + Cell "ZeroExternalMemoryAtStartup" + Cell "ZeroInternalMemoryAtStartup" + Cell "OptimizeModelRefInitCode" + Cell "NoFixptDivByZeroProtection" + Cell "UseSpecifiedMinMax" + PropName "DisabledProps" + } + BlockReduction on + BooleanDataType on + ConditionallyExecuteInputs on + InlineParams off + UseDivisionForNetSlopeComputation "off" + UseFloatMulNetSlope off + DefaultUnderspecifiedDataType "double" + UseSpecifiedMinMax off + InlineInvariantSignals off + OptimizeBlockIOStorage on + BufferReuse on + EnhancedBackFolding off + CachingGlobalReferences off + GlobalBufferReuse on + StrengthReduction off + ExpressionFolding on + BooleansAsBitfields off + BitfieldContainerType "uint_T" + EnableMemcpy on + MemcpyThreshold 64 + PassReuseOutputArgsAs "Structure reference" + PassReuseOutputArgsThreshold 12 + ExpressionDepthLimit 128 + LocalBlockOutputs on + RollThreshold 5 + StateBitsets off + DataBitsets off + ActiveStateOutputEnumStorageType "Native Integer" + ZeroExternalMemoryAtStartup on + ZeroInternalMemoryAtStartup on + InitFltsAndDblsToZero off + NoFixptDivByZeroProtection off + EfficientFloat2IntCast off + EfficientMapNaN2IntZero on + OptimizeModelRefInitCode off + LifeSpan "inf" + MaxStackSize "Inherit from target" + BufferReusableBoundary on + SimCompilerOptimization "off" + AccelVerboseBuild off + } + Simulink.DebuggingCC { + $ObjectID 11 + Version "1.15.0" + RTPrefix "error" + ConsistencyChecking "none" + ArrayBoundsChecking "none" + SignalInfNanChecking "warning" + SignalRangeChecking "warning" + ReadBeforeWriteMsg "UseLocalSettings" + WriteAfterWriteMsg "UseLocalSettings" + WriteAfterReadMsg "UseLocalSettings" + AlgebraicLoopMsg "warning" + ArtificialAlgebraicLoopMsg "warning" + SaveWithDisabledLinksMsg "warning" + SaveWithParameterizedLinksMsg "warning" + CheckSSInitialOutputMsg on + UnderspecifiedInitializationDetection "Simplified" + MergeDetectMultiDrivingBlocksExec "error" + CheckExecutionContextPreStartOutputMsg off + CheckExecutionContextRuntimeOutputMsg off + SignalResolutionControl "UseLocalSettings" + BlockPriorityViolationMsg "warning" + MinStepSizeMsg "warning" + TimeAdjustmentMsg "none" + MaxConsecutiveZCsMsg "error" + MaskedZcDiagnostic "warning" + IgnoredZcDiagnostic "warning" + SolverPrmCheckMsg "warning" + InheritedTsInSrcMsg "warning" + DiscreteInheritContinuousMsg "warning" + MultiTaskDSMMsg "error" + MultiTaskCondExecSysMsg "error" + MultiTaskRateTransMsg "warning" + SingleTaskRateTransMsg "none" + TasksWithSamePriorityMsg "warning" + SigSpecEnsureSampleTimeMsg "warning" + CheckMatrixSingularityMsg "warning" + IntegerOverflowMsg "warning" + Int32ToFloatConvMsg "warning" + ParameterDowncastMsg "error" + ParameterOverflowMsg "error" + ParameterUnderflowMsg "none" + ParameterPrecisionLossMsg "warning" + ParameterTunabilityLossMsg "warning" + FixptConstUnderflowMsg "none" + FixptConstOverflowMsg "none" + FixptConstPrecisionLossMsg "none" + UnderSpecifiedDataTypeMsg "warning" + UnnecessaryDatatypeConvMsg "none" + VectorMatrixConversionMsg "none" + InvalidFcnCallConnMsg "error" + FcnCallInpInsideContextMsg "EnableAllAsError" + SignalLabelMismatchMsg "none" + UnconnectedInputMsg "warning" + UnconnectedOutputMsg "warning" + UnconnectedLineMsg "warning" + SFcnCompatibilityMsg "none" + FrameProcessingCompatibilityMsg "error" + UniqueDataStoreMsg "none" + BusObjectLabelMismatch "warning" + RootOutportRequireBusObject "warning" + AssertControl "UseLocalSettings" + ModelReferenceIOMsg "none" + ModelReferenceMultiInstanceNormalModeStructChecksumCheck "error" + ModelReferenceVersionMismatchMessage "none" + ModelReferenceIOMismatchMessage "none" + UnknownTsInhSupMsg "warning" + ModelReferenceDataLoggingMessage "warning" + ModelReferenceSymbolNameMessage "warning" + ModelReferenceExtraNoncontSigs "error" + StateNameClashWarn "none" + SimStateInterfaceChecksumMismatchMsg "warning" + SimStateOlderReleaseMsg "error" + InitInArrayFormatMsg "warning" + StrictBusMsg "ErrorLevel1" + BusNameAdapt "WarnAndRepair" + NonBusSignalsTreatedAsBus "none" + BlockIODiagnostic "none" + SFUnusedDataAndEventsDiag "warning" + SFUnexpectedBacktrackingDiag "warning" + SFInvalidInputDataAccessInChartInitDiag "warning" + SFNoUnconditionalDefaultTransitionDiag "warning" + SFTransitionOutsideNaturalParentDiag "warning" + SFUnconditionalTransitionShadowingDiag "warning" + SFUndirectedBroadcastEventsDiag "warning" + SFTransitionActionBeforeConditionDiag "warning" + SFOutputUsedAsStateInMooreChartDiag "error" + IntegerSaturationMsg "warning" + } + Simulink.HardwareCC { + $ObjectID 12 + Version "1.15.0" + ProdBitPerChar 8 + ProdBitPerShort 16 + ProdBitPerInt 32 + ProdBitPerLong 32 + ProdBitPerLongLong 64 + ProdBitPerFloat 32 + ProdBitPerDouble 64 + ProdBitPerPointer 32 + ProdLargestAtomicInteger "Char" + ProdLargestAtomicFloat "None" + ProdIntDivRoundTo "Undefined" + ProdEndianess "Unspecified" + ProdWordSize 32 + ProdShiftRightIntArith on + ProdLongLongMode off + ProdHWDeviceType "32-bit Generic" + TargetBitPerChar 8 + TargetBitPerShort 16 + TargetBitPerInt 32 + TargetBitPerLong 32 + TargetBitPerLongLong 64 + TargetBitPerFloat 32 + TargetBitPerDouble 64 + TargetBitPerPointer 32 + TargetLargestAtomicInteger "Char" + TargetLargestAtomicFloat "None" + TargetShiftRightIntArith on + TargetLongLongMode off + TargetIntDivRoundTo "Undefined" + TargetEndianess "Unspecified" + TargetWordSize 32 + TargetPreprocMaxBitsSint 32 + TargetPreprocMaxBitsUint 32 + TargetHWDeviceType "Specified" + TargetUnknown off + ProdEqTarget on + } + Simulink.ModelReferenceCC { + $ObjectID 13 + Version "1.15.0" + UpdateModelReferenceTargets "IfOutOfDateOrStructuralChange" + CheckModelReferenceTargetMessage "error" + EnableParallelModelReferenceBuilds off + ParallelModelReferenceErrorOnInvalidPool on + ParallelModelReferenceMATLABWorkerInit "None" + ModelReferenceNumInstancesAllowed "Multi" + PropagateVarSize "Infer from blocks in model" + ModelReferencePassRootInputsByReference on + ModelReferenceMinAlgLoopOccurrences off + PropagateSignalLabelsOutOfModel off + SupportModelReferenceSimTargetCustomCode off + } + Simulink.SFSimCC { + $ObjectID 14 + Version "1.15.0" + SFSimOverflowDetection on + SFSimEcho on + SimCtrlC on + SimIntegrity on + SimUseLocalCustomCode off + SimParseCustomCode on + SimBuildMode "sf_incremental_build" + SimGenImportedTypeDefs off + } + Simulink.RTWCC { + $BackupClass "Simulink.RTWCC" + $ObjectID 15 + Version "1.15.0" + Array { + Type "Cell" + Dimension 15 + Cell "IncludeHyperlinkInReport" + Cell "GenerateTraceInfo" + Cell "GenerateTraceReport" + Cell "GenerateTraceReportSl" + Cell "GenerateTraceReportSf" + Cell "GenerateTraceReportEml" + Cell "PortableWordSizes" + Cell "GenerateWebview" + Cell "GenerateCodeMetricsReport" + Cell "GenerateCodeReplacementReport" + Cell "GenerateErtSFunction" + Cell "CreateSILPILBlock" + Cell "CodeExecutionProfiling" + Cell "CodeProfilingSaveOptions" + Cell "CodeProfilingInstrumentation" + PropName "DisabledProps" + } + SystemTargetFile "grt.tlc" + TLCOptions "" + GenCodeOnly off + MakeCommand "make_rtw" + GenerateMakefile on + PackageGeneratedCodeAndArtifacts off + PackageName "" + TemplateMakefile "grt_default_tmf" + PostCodeGenCommand "" + Description "" + GenerateReport off + SaveLog off + RTWVerbose on + RetainRTWFile off + ProfileTLC off + TLCDebug off + TLCCoverage off + TLCAssert off + RTWUseLocalCustomCode off + RTWUseSimCustomCode off + CustomSourceCode "" + CustomHeaderCode "" + CustomInclude "" + CustomSource "" + CustomLibrary "" + CustomInitializer "" + CustomTerminator "" + Toolchain "Automatically locate an installed toolchain" + BuildConfiguration "Faster Builds" + IncludeHyperlinkInReport off + LaunchReport off + PortableWordSizes off + CreateSILPILBlock "None" + CodeExecutionProfiling off + CodeExecutionProfileVariable "executionProfile" + CodeProfilingSaveOptions "SummaryOnly" + CodeProfilingInstrumentation off + SILDebugging off + TargetLang "C" + IncludeBusHierarchyInRTWFileBlockHierarchyMap off + GenerateTraceInfo off + GenerateTraceReport off + GenerateTraceReportSl off + GenerateTraceReportSf off + GenerateTraceReportEml off + GenerateWebview off + GenerateCodeMetricsReport off + GenerateCodeReplacementReport off + GenerateMissedCodeReplacementReport off + RTWCompilerOptimization "off" + RTWCustomCompilerOptimizations "" + CheckMdlBeforeBuild "Off" + SharedConstantsCachingThreshold 1024 + Array { + Type "Handle" + Dimension 2 + Simulink.CodeAppCC { + $ObjectID 16 + Version "1.15.0" + Array { + Type "Cell" + Dimension 24 + Cell "IgnoreCustomStorageClasses" + Cell "ParameterTuningSideEffectCode" + Cell "IgnoreTestpoints" + Cell "InsertBlockDesc" + Cell "InsertPolySpaceComments" + Cell "SFDataObjDesc" + Cell "MATLABFcnDesc" + Cell "SimulinkDataObjDesc" + Cell "DefineNamingRule" + Cell "SignalNamingRule" + Cell "ParamNamingRule" + Cell "InternalIdentifier" + Cell "InlinedPrmAccess" + Cell "CustomSymbolStr" + Cell "CustomSymbolStrGlobalVar" + Cell "CustomSymbolStrType" + Cell "CustomSymbolStrField" + Cell "CustomSymbolStrFcn" + Cell "CustomSymbolStrFcnArg" + Cell "CustomSymbolStrBlkIO" + Cell "CustomSymbolStrTmpVar" + Cell "CustomSymbolStrMacro" + Cell "CustomSymbolStrUtil" + Cell "ReqsInCode" + PropName "DisabledProps" + } + ForceParamTrailComments off + GenerateComments on + CommentStyle "Auto" + IgnoreCustomStorageClasses on + IgnoreTestpoints off + IncHierarchyInIds off + MaxIdLength 31 + PreserveName off + PreserveNameWithParent off + ShowEliminatedStatement off + OperatorAnnotations off + IncAutoGenComments off + SimulinkDataObjDesc off + SFDataObjDesc off + MATLABFcnDesc off + IncDataTypeInIds off + MangleLength 1 + CustomSymbolStrGlobalVar "$R$N$M" + CustomSymbolStrType "$N$R$M_T" + CustomSymbolStrField "$N$M" + CustomSymbolStrFcn "$R$N$M$F" + CustomSymbolStrFcnArg "rt$I$N$M" + CustomSymbolStrBlkIO "rtb_$N$M" + CustomSymbolStrTmpVar "$N$M" + CustomSymbolStrMacro "$R$N$M" + CustomSymbolStrUtil "$N$C" + DefineNamingRule "None" + ParamNamingRule "None" + SignalNamingRule "None" + InsertBlockDesc off + InsertPolySpaceComments off + SimulinkBlockComments on + MATLABSourceComments off + EnableCustomComments off + InternalIdentifier "Shortened" + InlinedPrmAccess "Literals" + ReqsInCode off + UseSimReservedNames off + } + Simulink.GRTTargetCC { + $BackupClass "Simulink.TargetCC" + $ObjectID 17 + Version "1.15.0" + Array { + Type "Cell" + Dimension 13 + Cell "GeneratePreprocessorConditionals" + Cell "IncludeMdlTerminateFcn" + Cell "SuppressErrorStatus" + Cell "ERTCustomFileBanners" + Cell "GenerateSampleERTMain" + Cell "GenerateTestInterfaces" + Cell "ModelStepFunctionPrototypeControlCompliant" + Cell "GenerateAllocFcn" + Cell "PurelyIntegerCode" + Cell "SupportComplex" + Cell "SupportAbsoluteTime" + Cell "SupportContinuousTime" + Cell "SupportNonInlinedSFcns" + PropName "DisabledProps" + } + TargetFcnLib "ansi_tfl_table_tmw.mat" + TargetLibSuffix "" + TargetPreCompLibLocation "" + GenFloatMathFcnCalls "NOT IN USE" + TargetLangStandard "C89/C90 (ANSI)" + CodeReplacementLibrary "None" + UtilityFuncGeneration "Auto" + ERTMultiwordTypeDef "System defined" + ERTMultiwordLength 256 + MultiwordLength 2048 + GenerateFullHeader on + InferredTypesCompatibility off + GenerateSampleERTMain off + GenerateTestInterfaces off + ModelReferenceCompliant on + ParMdlRefBuildCompliant on + CompOptLevelCompliant on + ConcurrentExecutionCompliant on + IncludeMdlTerminateFcn on + GeneratePreprocessorConditionals "Disable all" + CombineOutputUpdateFcns on + CombineSignalStateStructs off + SuppressErrorStatus off + ERTFirstTimeCompliant off + IncludeFileDelimiter "Auto" + ERTCustomFileBanners off + SupportAbsoluteTime on + LogVarNameModifier "rt_" + MatFileLogging on + MultiInstanceERTCode off + CodeInterfacePackaging "Nonreusable function" + SupportNonFinite on + SupportComplex on + PurelyIntegerCode off + SupportContinuousTime on + SupportNonInlinedSFcns on + SupportVariableSizeSignals off + ParenthesesLevel "Nominal" + CastingMode "Nominal" + MATLABClassNameForMDSCustomization "Simulink.SoftwareTarget.GRTCustomization" + ModelStepFunctionPrototypeControlCompliant off + CPPClassGenCompliant on + AutosarCompliant off + GRTInterface off + GenerateAllocFcn off + GenerateSharedConstants on + UseMalloc off + ExtMode off + ExtModeStaticAlloc off + ExtModeTesting off + ExtModeStaticAllocSize 1000000 + ExtModeTransport 0 + ExtModeMexFile "ext_comm" + ExtModeIntrfLevel "Level1" + RTWCAPISignals off + RTWCAPIParams off + RTWCAPIStates off + RTWCAPIRootIO off + GenerateASAP2 off + MultiInstanceErrorCode "Error" + } + PropName "Components" + } + } + PropName "Components" + } + Name "Configuration" + ExtraOptions "-aGenerateTraceInfo=0 -aIgnoreTestpoints=0 " + CurrentDlgPage "Solver" + ConfigPrmDlgPosition [ 536, 69, 1858, 888 ] + } + PropName "ConfigurationSets" + } + Simulink.ConfigSet { + $PropName "ActiveConfigurationSet" + $ObjectID 7 + } + Object { + $PropName "DataTransfer" + $ObjectID 18 + $ClassName "Simulink.GlobalDataTransfer" + DefaultTransitionBetweenSyncTasks "Ensure deterministic transfer (maximum delay)" + DefaultTransitionBetweenAsyncTasks "Ensure data integrity only" + DefaultTransitionBetweenContTasks "Ensure deterministic transfer (minimum delay)" + DefaultExtrapolationMethodBetweenContTasks "None" + AutoInsertRateTranBlk [0] + } + ExplicitPartitioning off + BlockDefaults { + ForegroundColor "black" + BackgroundColor "white" + DropShadow off + NamePlacement "normal" + FontName "Helvetica" + FontSize 10 + FontWeight "normal" + FontAngle "normal" + ShowName on + BlockRotation 0 + BlockMirror off + } + AnnotationDefaults { + HorizontalAlignment "center" + VerticalAlignment "middle" + ForegroundColor "black" + BackgroundColor "white" + DropShadow off + FontName "Helvetica" + FontSize 10 + FontWeight "normal" + FontAngle "normal" + UseDisplayTextAsClickCallback off + } + LineDefaults { + FontName "Helvetica" + FontSize 9 + FontWeight "normal" + FontAngle "normal" + } + MaskDefaults { + SelfModifiable "off" + IconFrame "on" + IconOpaque "on" + RunInitForIconRedraw "off" + IconRotate "none" + PortRotate "default" + IconUnits "autoscale" + } + MaskParameterDefaults { + Evaluate "on" + Tunable "on" + NeverSave "off" + Internal "off" + ReadOnly "off" + Enabled "on" + Visible "on" + ToolTip "on" + } + BlockParameterDefaults { + Block { + BlockType BusCreator + Inputs "4" + DisplayOption "none" + OutDataTypeStr "Inherit: auto" + NonVirtualBus off + InheritFromInputs on + } + Block { + BlockType BusSelector + OutputSignals "signal1,signal2,signal3" + OutputAsBus off + } + Block { + BlockType Constant + Value "1" + VectorParams1D on + SamplingMode "Sample based" + OutMin "[]" + OutMax "[]" + OutDataTypeStr "Inherit: Inherit from 'Constant value'" + LockScale off + SampleTime "inf" + FramePeriod "inf" + PreserveConstantTs off + } + Block { + BlockType Demux + Outputs "4" + DisplayOption "none" + BusSelectionMode off + } + Block { + BlockType FromWorkspace + VariableName "simulink_input" + OutDataTypeStr "Inherit: auto" + SampleTime "-1" + Interpolate on + ZeroCross off + OutputAfterFinalValue "Extrapolation" + } + Block { + BlockType Gain + Gain "1" + Multiplication "Element-wise(K.*u)" + ParamMin "[]" + ParamMax "[]" + ParamDataTypeStr "Inherit: Same as input" + OutMin "[]" + OutMax "[]" + OutDataTypeStr "Inherit: Same as input" + LockScale off + RndMeth "Floor" + SaturateOnIntegerOverflow on + SampleTime "-1" + } + Block { + BlockType Inport + Port "1" + OutputFunctionCall off + OutMin "[]" + OutMax "[]" + OutDataTypeStr "Inherit: auto" + LockScale off + BusOutputAsStruct off + PortDimensions "-1" + VarSizeSig "Inherit" + SampleTime "-1" + SignalType "auto" + SamplingMode "auto" + LatchByDelayingOutsideSignal off + LatchInputForFeedbackSignals off + Interpolate on + } + Block { + BlockType ManualSwitch + CurrentSetting "1" + varsize off + SampleTime "-1" + } + Block { + BlockType Math + Operator "exp" + OutputSignalType "auto" + SampleTime "-1" + OutMin "[]" + OutMax "[]" + OutDataTypeStr "Inherit: Same as first input" + LockScale off + RndMeth "Floor" + SaturateOnIntegerOverflow on + IntermediateResultsDataTypeStr "Inherit: Inherit via internal rule" + AlgorithmType "Newton-Raphson" + Iterations "3" + } + Block { + BlockType Mux + Inputs "4" + DisplayOption "none" + UseBusObject off + BusObject "BusObject" + NonVirtualBus off + } + Block { + BlockType Outport + Port "1" + OutMin "[]" + OutMax "[]" + OutDataTypeStr "Inherit: auto" + LockScale off + BusOutputAsStruct off + PortDimensions "-1" + VarSizeSig "Inherit" + SampleTime "-1" + SignalType "auto" + SamplingMode "auto" + SourceOfInitialOutputValue "Dialog" + OutputWhenDisabled "held" + InitialOutput "[]" + } + Block { + BlockType Product + Inputs "2" + Multiplication "Element-wise(.*)" + CollapseMode "All dimensions" + CollapseDim "1" + InputSameDT on + OutMin "[]" + OutMax "[]" + OutDataTypeStr "Inherit: Same as first input" + LockScale off + RndMeth "Zero" + SaturateOnIntegerOverflow on + SampleTime "-1" + } + Block { + BlockType RateTransition + Integrity on + Deterministic on + X0 "0" + OutPortSampleTimeOpt "Specify" + OutPortSampleTimeMultiple "1" + OutPortSampleTime "-1" + } + Block { + BlockType Scope + ModelBased off + TickLabels "OneTimeTick" + ZoomMode "on" + Grid "on" + ShowLegends off + TimeRange "auto" + YMin "-5" + YMax "5" + SaveToWorkspace off + SaveName "ScopeData" + DataFormat "Array" + LimitDataPoints on + MaxDataPoints "5000" + Decimation "1" + SampleInput off + SampleTime "-1" + ScrollMode off + } + Block { + BlockType SignalConversion + ConversionOutput "Signal copy" + OutDataTypeStr "Inherit: auto" + OverrideOpt off + } + Block { + BlockType SubSystem + ShowPortLabels "FromPortIcon" + Permissions "ReadWrite" + PermitHierarchicalResolution "All" + TreatAsAtomicUnit off + MinAlgLoopOccurrences off + PropExecContextOutsideSubsystem off + CheckFcnCallInpInsideContextMsg off + SystemSampleTime "-1" + RTWSystemCode "Auto" + RTWFcnNameOpts "Auto" + RTWFileNameOpts "Auto" + FunctionInterfaceSpec "void_void" + FunctionWithSeparateData off + RTWMemSecFuncInitTerm "Inherit from model" + RTWMemSecFuncExecute "Inherit from model" + RTWMemSecDataConstants "Inherit from model" + RTWMemSecDataInternal "Inherit from model" + RTWMemSecDataParameters "Inherit from model" + SimViewingDevice off + DataTypeOverride "UseLocalSettings" + DataTypeOverrideAppliesTo "AllNumericTypes" + MinMaxOverflowLogging "UseLocalSettings" + Opaque off + MaskHideContents off + SFBlockType "NONE" + Variant off + GeneratePreprocessorConditionals off + ContentPreviewEnabled off + IsWebBlock off + } + Block { + BlockType Sum + IconShape "rectangular" + Inputs "++" + CollapseMode "All dimensions" + CollapseDim "1" + InputSameDT on + AccumDataTypeStr "Inherit: Inherit via internal rule" + OutMin "[]" + OutMax "[]" + OutDataTypeStr "Inherit: Same as first input" + LockScale off + RndMeth "Floor" + SaturateOnIntegerOverflow on + SampleTime "-1" + } + Block { + BlockType TransferFcn + Numerator "[1]" + Denominator "[1 2 1]" + AbsoluteTolerance "auto" + ContinuousStateAttributes "''" + Realization "auto" + } + Block { + BlockType UniformRandomNumber + Minimum "-1" + Maximum "1" + Seed "0" + SampleTime "-1" + VectorParams1D on + } + Block { + BlockType ZeroOrderHold + SampleTime "1" + } + } + System { + Name "atlas_joint_impctrl_sqrt_damping_test" + Location [806, 144, 1753, 981] + Open on + ModelBrowserVisibility off + ModelBrowserWidth 200 + ScreenColor "white" + PaperOrientation "landscape" + PaperPositionMode "auto" + PaperType "A4" + PaperUnits "centimeters" + TiledPaperMargins [1.270000, 1.270000, 1.270000, 1.270000] + TiledPageScale 1 + ShowPageBoundaries off + ZoomFactor "100" + ReportName "simulink-default.rpt" + SIDHighWatermark "271" + Block { + BlockType SubSystem + Name "7D low pass filter1" + SID "211" + Ports [1, 1] + Position [85, 157, 165, 183] + ZOrder 260 + RequestExecContextInheritance off + Object { + $PropName "MaskObject" + $ObjectID 19 + $ClassName "Simulink.Mask" + Object { + $PropName "Parameters" + $ObjectID 20 + $ClassName "Simulink.MaskParameter" + Type "edit" + Name "f" + Prompt "T1" + Value "T1_filter_input" + } + } + System { + Name "7D low pass filter1" + Location [-8, 0, 1928, 1176] + Open off + ModelBrowserVisibility off + ModelBrowserWidth 200 + ScreenColor "white" + PaperOrientation "landscape" + PaperPositionMode "auto" + PaperType "A4" + PaperUnits "centimeters" + TiledPaperMargins [1.270000, 1.270000, 1.270000, 1.270000] + TiledPageScale 1 + ShowPageBoundaries off + ZoomFactor "100" + Block { + BlockType Inport + Name "x" + SID "212" + Position [55, 193, 85, 207] + ZOrder 190 + IconDisplay "Port number" + } + Block { + BlockType Demux + Name "Demux" + SID "213" + Ports [1, 7] + Position [145, 20, 150, 380] + ZOrder 192 + ShowName off + Outputs "7" + DisplayOption "bar" + } + Block { + BlockType Mux + Name "Mux" + SID "214" + Ports [7, 1] + Position [430, 20, 435, 380] + ZOrder 193 + ShowName off + Inputs "7" + DisplayOption "bar" + } + Block { + BlockType TransferFcn + Name "Transfer Fcn" + SID "215" + Position [260, 32, 320, 68] + ZOrder 189 + Denominator "[f 1]" + } + Block { + BlockType TransferFcn + Name "Transfer Fcn1" + SID "216" + Position [260, 132, 320, 168] + ZOrder 200 + Denominator "[f 1]" + } + Block { + BlockType TransferFcn + Name "Transfer Fcn2" + SID "217" + Position [260, 182, 320, 218] + ZOrder 201 + Denominator "[f 1]" + } + Block { + BlockType TransferFcn + Name "Transfer Fcn3" + SID "218" + Position [260, 232, 320, 268] + ZOrder 202 + Denominator "[f 1]" + } + Block { + BlockType TransferFcn + Name "Transfer Fcn4" + SID "219" + Position [260, 282, 320, 318] + ZOrder 203 + Denominator "[f 1]" + } + Block { + BlockType TransferFcn + Name "Transfer Fcn5" + SID "220" + Position [260, 332, 320, 368] + ZOrder 204 + Denominator "[f 1]" + } + Block { + BlockType TransferFcn + Name "Transfer Fcn6" + SID "221" + Position [260, 82, 320, 118] + ZOrder 199 + Denominator "[f 1]" + } + Block { + BlockType Outport + Name "x_lp_filtered" + SID "222" + Position [500, 193, 530, 207] + ZOrder 191 + IconDisplay "Port number" + } + Line { + ZOrder 1 + SrcBlock "x" + SrcPort 1 + DstBlock "Demux" + DstPort 1 + } + Line { + ZOrder 2 + SrcBlock "Mux" + SrcPort 1 + DstBlock "x_lp_filtered" + DstPort 1 + } + Line { + ZOrder 3 + SrcBlock "Demux" + SrcPort 1 + Points [0, 0] + DstBlock "Transfer Fcn" + DstPort 1 + } + Line { + ZOrder 4 + SrcBlock "Transfer Fcn" + SrcPort 1 + DstBlock "Mux" + DstPort 1 + } + Line { + ZOrder 5 + SrcBlock "Demux" + SrcPort 6 + Points [0, 0] + DstBlock "Transfer Fcn4" + DstPort 1 + } + Line { + ZOrder 6 + SrcBlock "Transfer Fcn4" + SrcPort 1 + DstBlock "Mux" + DstPort 6 + } + Line { + ZOrder 7 + SrcBlock "Demux" + SrcPort 2 + Points [0, 0] + DstBlock "Transfer Fcn6" + DstPort 1 + } + Line { + ZOrder 8 + SrcBlock "Transfer Fcn6" + SrcPort 1 + DstBlock "Mux" + DstPort 2 + } + Line { + ZOrder 9 + SrcBlock "Demux" + SrcPort 3 + Points [0, 0] + DstBlock "Transfer Fcn1" + DstPort 1 + } + Line { + ZOrder 10 + SrcBlock "Transfer Fcn1" + SrcPort 1 + DstBlock "Mux" + DstPort 3 + } + Line { + ZOrder 11 + SrcBlock "Demux" + SrcPort 4 + Points [0, 0] + DstBlock "Transfer Fcn2" + DstPort 1 + } + Line { + ZOrder 12 + SrcBlock "Transfer Fcn2" + SrcPort 1 + DstBlock "Mux" + DstPort 4 + } + Line { + ZOrder 13 + SrcBlock "Demux" + SrcPort 5 + Points [0, 0] + DstBlock "Transfer Fcn3" + DstPort 1 + } + Line { + ZOrder 14 + SrcBlock "Transfer Fcn3" + SrcPort 1 + DstBlock "Mux" + DstPort 5 + } + Line { + ZOrder 15 + SrcBlock "Demux" + SrcPort 7 + DstBlock "Transfer Fcn5" + DstPort 1 + } + Line { + ZOrder 16 + SrcBlock "Transfer Fcn5" + SrcPort 1 + DstBlock "Mux" + DstPort 7 + } + } + } + Block { + BlockType SubSystem + Name "7D low pass filter2" + SID "223" + Ports [1, 1] + Position [85, 207, 165, 233] + ZOrder 261 + RequestExecContextInheritance off + Object { + $PropName "MaskObject" + $ObjectID 21 + $ClassName "Simulink.Mask" + Object { + $PropName "Parameters" + $ObjectID 22 + $ClassName "Simulink.MaskParameter" + Type "edit" + Name "f" + Prompt "T1" + Value "T1_filter_input" + } + } + System { + Name "7D low pass filter2" + Location [-8, 0, 1928, 1176] + Open off + ModelBrowserVisibility off + ModelBrowserWidth 200 + ScreenColor "white" + PaperOrientation "landscape" + PaperPositionMode "auto" + PaperType "A4" + PaperUnits "centimeters" + TiledPaperMargins [1.270000, 1.270000, 1.270000, 1.270000] + TiledPageScale 1 + ShowPageBoundaries off + ZoomFactor "100" + Block { + BlockType Inport + Name "x" + SID "224" + Position [55, 193, 85, 207] + ZOrder 190 + IconDisplay "Port number" + } + Block { + BlockType Demux + Name "Demux" + SID "225" + Ports [1, 7] + Position [145, 20, 150, 380] + ZOrder 192 + ShowName off + Outputs "7" + DisplayOption "bar" + } + Block { + BlockType Mux + Name "Mux" + SID "226" + Ports [7, 1] + Position [430, 20, 435, 380] + ZOrder 193 + ShowName off + Inputs "7" + DisplayOption "bar" + } + Block { + BlockType TransferFcn + Name "Transfer Fcn" + SID "227" + Position [260, 32, 320, 68] + ZOrder 189 + Denominator "[f 1]" + } + Block { + BlockType TransferFcn + Name "Transfer Fcn1" + SID "228" + Position [260, 132, 320, 168] + ZOrder 200 + Denominator "[f 1]" + } + Block { + BlockType TransferFcn + Name "Transfer Fcn2" + SID "229" + Position [260, 182, 320, 218] + ZOrder 201 + Denominator "[f 1]" + } + Block { + BlockType TransferFcn + Name "Transfer Fcn3" + SID "230" + Position [260, 232, 320, 268] + ZOrder 202 + Denominator "[f 1]" + } + Block { + BlockType TransferFcn + Name "Transfer Fcn4" + SID "231" + Position [260, 282, 320, 318] + ZOrder 203 + Denominator "[f 1]" + } + Block { + BlockType TransferFcn + Name "Transfer Fcn5" + SID "232" + Position [260, 332, 320, 368] + ZOrder 204 + Denominator "[f 1]" + } + Block { + BlockType TransferFcn + Name "Transfer Fcn6" + SID "233" + Position [260, 82, 320, 118] + ZOrder 199 + Denominator "[f 1]" + } + Block { + BlockType Outport + Name "x_lp_filtered" + SID "234" + Position [500, 193, 530, 207] + ZOrder 191 + IconDisplay "Port number" + } + Line { + ZOrder 1 + SrcBlock "x" + SrcPort 1 + DstBlock "Demux" + DstPort 1 + } + Line { + ZOrder 2 + SrcBlock "Mux" + SrcPort 1 + DstBlock "x_lp_filtered" + DstPort 1 + } + Line { + ZOrder 3 + SrcBlock "Demux" + SrcPort 1 + Points [0, 0] + DstBlock "Transfer Fcn" + DstPort 1 + } + Line { + ZOrder 4 + SrcBlock "Transfer Fcn" + SrcPort 1 + DstBlock "Mux" + DstPort 1 + } + Line { + ZOrder 5 + SrcBlock "Demux" + SrcPort 6 + Points [0, 0] + DstBlock "Transfer Fcn4" + DstPort 1 + } + Line { + ZOrder 6 + SrcBlock "Transfer Fcn4" + SrcPort 1 + DstBlock "Mux" + DstPort 6 + } + Line { + ZOrder 7 + SrcBlock "Demux" + SrcPort 2 + Points [0, 0] + DstBlock "Transfer Fcn6" + DstPort 1 + } + Line { + ZOrder 8 + SrcBlock "Transfer Fcn6" + SrcPort 1 + DstBlock "Mux" + DstPort 2 + } + Line { + ZOrder 9 + SrcBlock "Demux" + SrcPort 3 + Points [0, 0] + DstBlock "Transfer Fcn1" + DstPort 1 + } + Line { + ZOrder 10 + SrcBlock "Transfer Fcn1" + SrcPort 1 + DstBlock "Mux" + DstPort 3 + } + Line { + ZOrder 11 + SrcBlock "Demux" + SrcPort 4 + Points [0, 0] + DstBlock "Transfer Fcn2" + DstPort 1 + } + Line { + ZOrder 12 + SrcBlock "Transfer Fcn2" + SrcPort 1 + DstBlock "Mux" + DstPort 4 + } + Line { + ZOrder 13 + SrcBlock "Demux" + SrcPort 5 + Points [0, 0] + DstBlock "Transfer Fcn3" + DstPort 1 + } + Line { + ZOrder 14 + SrcBlock "Transfer Fcn3" + SrcPort 1 + DstBlock "Mux" + DstPort 5 + } + Line { + ZOrder 15 + SrcBlock "Demux" + SrcPort 7 + DstBlock "Transfer Fcn5" + DstPort 1 + } + Line { + ZOrder 16 + SrcBlock "Transfer Fcn5" + SrcPort 1 + DstBlock "Mux" + DstPort 7 + } + } + } + Block { + BlockType SubSystem + Name "7D low pass filter3" + SID "162" + Ports [1, 1] + Position [920, 402, 1000, 428] + ZOrder 230 + RequestExecContextInheritance off + Object { + $PropName "MaskObject" + $ObjectID 23 + $ClassName "Simulink.Mask" + Object { + $PropName "Parameters" + $ObjectID 24 + $ClassName "Simulink.MaskParameter" + Type "edit" + Name "f" + Prompt "T1" + Value "T1_filter_output" + } + } + System { + Name "7D low pass filter3" + Location [-8, 0, 1928, 1176] + Open off + ModelBrowserVisibility off + ModelBrowserWidth 200 + ScreenColor "white" + PaperOrientation "landscape" + PaperPositionMode "auto" + PaperType "usletter" + PaperUnits "inches" + TiledPaperMargins [0.500000, 0.500000, 0.500000, 0.500000] + TiledPageScale 1 + ShowPageBoundaries off + ZoomFactor "100" + Block { + BlockType Inport + Name "x" + SID "163" + Position [55, 193, 85, 207] + ZOrder 190 + IconDisplay "Port number" + } + Block { + BlockType Demux + Name "Demux" + SID "164" + Ports [1, 7] + Position [145, 20, 150, 380] + ZOrder 192 + ShowName off + Outputs "7" + DisplayOption "bar" + } + Block { + BlockType Mux + Name "Mux" + SID "165" + Ports [7, 1] + Position [430, 20, 435, 380] + ZOrder 193 + ShowName off + Inputs "7" + DisplayOption "bar" + } + Block { + BlockType TransferFcn + Name "Transfer Fcn" + SID "166" + Position [260, 32, 320, 68] + ZOrder 189 + Denominator "[f 1]" + } + Block { + BlockType TransferFcn + Name "Transfer Fcn1" + SID "167" + Position [260, 132, 320, 168] + ZOrder 200 + Denominator "[f 1]" + } + Block { + BlockType TransferFcn + Name "Transfer Fcn2" + SID "168" + Position [260, 182, 320, 218] + ZOrder 201 + Denominator "[f 1]" + } + Block { + BlockType TransferFcn + Name "Transfer Fcn3" + SID "169" + Position [260, 232, 320, 268] + ZOrder 202 + Denominator "[f 1]" + } + Block { + BlockType TransferFcn + Name "Transfer Fcn4" + SID "170" + Position [260, 282, 320, 318] + ZOrder 203 + Denominator "[f 1]" + } + Block { + BlockType TransferFcn + Name "Transfer Fcn5" + SID "210" + Position [260, 332, 320, 368] + ZOrder 204 + Denominator "[f 1]" + } + Block { + BlockType TransferFcn + Name "Transfer Fcn6" + SID "171" + Position [260, 82, 320, 118] + ZOrder 199 + Denominator "[f 1]" + } + Block { + BlockType Outport + Name "x_lp_filtered" + SID "172" + Position [500, 193, 530, 207] + ZOrder 191 + IconDisplay "Port number" + } + Line { + ZOrder 1 + SrcBlock "x" + SrcPort 1 + DstBlock "Demux" + DstPort 1 + } + Line { + ZOrder 2 + SrcBlock "Mux" + SrcPort 1 + DstBlock "x_lp_filtered" + DstPort 1 + } + Line { + ZOrder 3 + SrcBlock "Demux" + SrcPort 1 + Points [0, 0] + DstBlock "Transfer Fcn" + DstPort 1 + } + Line { + ZOrder 4 + SrcBlock "Transfer Fcn" + SrcPort 1 + DstBlock "Mux" + DstPort 1 + } + Line { + ZOrder 5 + SrcBlock "Demux" + SrcPort 6 + Points [0, 0] + DstBlock "Transfer Fcn4" + DstPort 1 + } + Line { + ZOrder 6 + SrcBlock "Transfer Fcn4" + SrcPort 1 + DstBlock "Mux" + DstPort 6 + } + Line { + ZOrder 7 + SrcBlock "Demux" + SrcPort 2 + Points [0, 0] + DstBlock "Transfer Fcn6" + DstPort 1 + } + Line { + ZOrder 8 + SrcBlock "Transfer Fcn6" + SrcPort 1 + DstBlock "Mux" + DstPort 2 + } + Line { + ZOrder 9 + SrcBlock "Demux" + SrcPort 3 + Points [0, 0] + DstBlock "Transfer Fcn1" + DstPort 1 + } + Line { + ZOrder 10 + SrcBlock "Transfer Fcn1" + SrcPort 1 + DstBlock "Mux" + DstPort 3 + } + Line { + ZOrder 11 + SrcBlock "Demux" + SrcPort 4 + Points [0, 0] + DstBlock "Transfer Fcn2" + DstPort 1 + } + Line { + ZOrder 12 + SrcBlock "Transfer Fcn2" + SrcPort 1 + DstBlock "Mux" + DstPort 4 + } + Line { + ZOrder 13 + SrcBlock "Demux" + SrcPort 5 + Points [0, 0] + DstBlock "Transfer Fcn3" + DstPort 1 + } + Line { + ZOrder 14 + SrcBlock "Transfer Fcn3" + SrcPort 1 + DstBlock "Mux" + DstPort 5 + } + Line { + ZOrder 15 + SrcBlock "Demux" + SrcPort 7 + DstBlock "Transfer Fcn5" + DstPort 1 + } + Line { + ZOrder 16 + SrcBlock "Transfer Fcn5" + SrcPort 1 + DstBlock "Mux" + DstPort 7 + } + } + } + Block { + BlockType Sum + Name "Add" + SID "1" + Ports [2, 1] + Position [1565, 350, 1620, 410] + ZOrder 116 + InputSameDT off + OutDataTypeStr "Inherit: Inherit via internal rule" + SaturateOnIntegerOverflow off + Port { + PortNumber 1 + Name "E" + RTWStorageClass "Auto" + DataLogging on + DataLoggingNameMode "SignalName" + DataLoggingName "E" + } + } + Block { + BlockType BusCreator + Name "Bus\nCreator" + SID "190" + Ports [6, 1] + Position [1295, 369, 1300, 481] + ZOrder 238 + ShowName off + Inputs "'q','qD','qDD','tau_fr','tau_m','g'" + DisplayOption "bar" + } + Block { + BlockType BusSelector + Name "Bus\nSelector" + SID "191" + Ports [1, 3] + Position [1390, 351, 1395, 409] + ZOrder 239 + ShowName off + OutputSignals "q,qD,g" + Port { + PortNumber 1 + Name "" + RTWStorageClass "Auto" + DataLoggingNameMode "SignalName" + } + Port { + PortNumber 2 + Name "" + RTWStorageClass "Auto" + DataLoggingNameMode "SignalName" + } + Port { + PortNumber 3 + Name "" + RTWStorageClass "Auto" + DataLoggingNameMode "SignalName" + } + } + Block { + BlockType BusSelector + Name "Bus\nSelector1" + SID "193" + Ports [1, 2] + Position [1390, 781, 1395, 834] + ZOrder 241 + ShowName off + OutputSignals "q,qD" + Port { + PortNumber 1 + Name "" + RTWStorageClass "Auto" + DataLoggingNameMode "SignalName" + } + Port { + PortNumber 2 + Name "" + RTWStorageClass "Auto" + DataLoggingNameMode "SignalName" + } + } + Block { + BlockType BusSelector + Name "Bus\nSelector10" + SID "203" + Ports [1, 2] + Position [40, 144, 45, 246] + ZOrder 253 + ShowName off + OutputSignals "q,qD" + Port { + PortNumber 1 + Name "" + RTWStorageClass "Auto" + DataLoggingNameMode "SignalName" + } + Port { + PortNumber 2 + Name "" + RTWStorageClass "Auto" + DataLoggingNameMode "SignalName" + } + } + Block { + BlockType BusSelector + Name "Bus\nSelector11" + SID "246" + Ports [1, 1] + Position [1070, 590, 1075, 610] + ZOrder 273 + ShowName off + OutputSignals "qD" + Port { + PortNumber 1 + Name "" + RTWStorageClass "Auto" + DataLoggingNameMode "SignalName" + } + } + Block { + BlockType BusSelector + Name "Bus\nSelector2" + SID "194" + Ports [1, 2] + Position [1390, 707, 1395, 758] + ZOrder 242 + ShowName off + OutputSignals "q,g" + Port { + PortNumber 1 + Name "" + RTWStorageClass "Auto" + DataLoggingNameMode "SignalName" + } + Port { + PortNumber 2 + Name "" + RTWStorageClass "Auto" + DataLoggingNameMode "SignalName" + } + } + Block { + BlockType BusSelector + Name "Bus\nSelector3" + SID "195" + Ports [1, 1] + Position [1475, 665, 1480, 685] + ZOrder 243 + ShowName off + OutputSignals "qDD" + Port { + PortNumber 1 + Name "" + RTWStorageClass "Auto" + DataLogging on + DataLoggingNameMode "Custom" + DataLoggingName "qDD" + } + } + Block { + BlockType BusSelector + Name "Bus\nSelector4" + SID "196" + Ports [1, 1] + Position [1475, 605, 1480, 625] + ZOrder 244 + ShowName off + OutputSignals "qD" + Port { + PortNumber 1 + Name "" + RTWStorageClass "Auto" + DataLoggingNameMode "SignalName" + } + } + Block { + BlockType BusSelector + Name "Bus\nSelector5" + SID "197" + Ports [1, 1] + Position [1475, 550, 1480, 570] + ZOrder 245 + ShowName off + OutputSignals "q" + Port { + PortNumber 1 + Name "" + RTWStorageClass "Auto" + DataLoggingNameMode "SignalName" + } + } + Block { + BlockType BusSelector + Name "Bus\nSelector6" + SID "198" + Ports [1, 1] + Position [1375, 110, 1380, 130] + ZOrder 248 + BlockMirror on + ShowName off + OutputSignals "q" + Port { + PortNumber 1 + Name "" + RTWStorageClass "Auto" + DataLoggingNameMode "SignalName" + } + } + Block { + BlockType BusSelector + Name "Bus\nSelector7" + SID "199" + Ports [1, 1] + Position [1445, 475, 1450, 495] + ZOrder 249 + ShowName off + OutputSignals "tau_fr" + Port { + PortNumber 1 + Name "" + RTWStorageClass "Auto" + DataLoggingNameMode "SignalName" + } + } + Block { + BlockType BusSelector + Name "Bus\nSelector8" + SID "201" + Ports [1, 1] + Position [1060, 435, 1065, 455] + ZOrder 251 + ShowName off + OutputSignals "g" + Port { + PortNumber 1 + Name "" + RTWStorageClass "Auto" + DataLoggingNameMode "SignalName" + } + } + Block { + BlockType BusSelector + Name "Bus\nSelector9" + SID "202" + Ports [1, 2] + Position [85, 394, 90, 496] + ZOrder 252 + ShowName off + OutputSignals "g,tau_m" + Port { + PortNumber 1 + Name "" + RTWStorageClass "Auto" + DataLoggingNameMode "SignalName" + } + Port { + PortNumber 2 + Name "" + RTWStorageClass "Auto" + DataLoggingNameMode "SignalName" + } + } + Block { + BlockType FromWorkspace + Name "F0_ext" + SID "248" + Position [1245, 183, 1310, 207] + ZOrder 275 + BlockMirror on + NamePlacement "alternate" + VariableName "simin_F0_ext" + SampleTime "0" + Interpolate off + ZeroCross on + OutputAfterFinalValue "Holding final value" + } + Block { + BlockType UniformRandomNumber + Name "F_ext_noise" + SID "260" + Position [30, 589, 60, 621] + ZOrder 287 + Minimum "-F_ext_noise" + Maximum "F_ext_noise" + Seed "F_ext_noise_seed" + SampleTime "0" + } + Block { + BlockType Gain + Name "Gain" + SID "267" + Position [200, 555, 230, 585] + ZOrder 294 + BlockRotation 270 + Gain "g_noise_switch" + ParamDataTypeStr "Inherit: Inherit via internal rule" + OutDataTypeStr "Inherit: Inherit via internal rule" + SaturateOnIntegerOverflow off + } + Block { + BlockType Gain + Name "Gain1" + SID "268" + Position [155, 555, 185, 585] + ZOrder 295 + BlockRotation 270 + Gain "tau_noise_switch" + ParamDataTypeStr "Inherit: Inherit via internal rule" + OutDataTypeStr "Inherit: Inherit via internal rule" + SaturateOnIntegerOverflow off + } + Block { + BlockType Gain + Name "Gain2" + SID "269" + Position [65, 555, 95, 585] + ZOrder 296 + BlockRotation 270 + Gain "F_ext_noise_switch" + ParamDataTypeStr "Inherit: Inherit via internal rule" + OutDataTypeStr "Inherit: Inherit via internal rule" + SaturateOnIntegerOverflow off + } + Block { + BlockType Gain + Name "Gain3" + SID "270" + Position [215, 110, 245, 140] + ZOrder 297 + BlockRotation 270 + BlockMirror on + Gain "q_noise_switch" + ParamDataTypeStr "Inherit: Inherit via internal rule" + OutDataTypeStr "Inherit: Inherit via internal rule" + SaturateOnIntegerOverflow off + } + Block { + BlockType Gain + Name "Gain4" + SID "271" + Position [180, 110, 210, 140] + ZOrder 298 + BlockRotation 270 + BlockMirror on + Gain "qD_noise_switch" + ParamDataTypeStr "Inherit: Inherit via internal rule" + OutDataTypeStr "Inherit: Inherit via internal rule" + SaturateOnIntegerOverflow off + } + Block { + BlockType ManualSwitch + Name "Manual Switch1" + SID "140" + Position [850, 355, 890, 470] + ZOrder 213 + CurrentSetting "0" + } + Block { + BlockType Mux + Name "Mux" + SID "253" + Ports [3, 1] + Position [1685, 301, 1690, 359] + ZOrder 280 + ShowName off + Inputs "3" + DisplayOption "bar" + } + Block { + BlockType Product + Name "Product" + SID "9" + Ports [2, 1] + Position [1135, 82, 1175, 233] + ZOrder 128 + BlockMirror on + Multiplication "Matrix(*)" + InputSameDT off + OutDataTypeStr "Inherit: Inherit via internal rule" + RndMeth "Floor" + SaturateOnIntegerOverflow off + } + Block { + BlockType RateTransition + Name "Rate Transition" + SID "141" + Position [765, 419, 805, 461] + ZOrder 219 + } + Block { + BlockType RateTransition + Name "Rate Transition1" + SID "142" + Position [645, 419, 685, 461] + ZOrder 220 + } + Block { + BlockType RateTransition + Name "Rate Transition10" + SID "242" + Position [255, 499, 295, 541] + ZOrder 269 + } + Block { + BlockType RateTransition + Name "Rate Transition11" + SID "243" + Position [700, 364, 740, 406] + ZOrder 270 + } + Block { + BlockType RateTransition + Name "Rate Transition12" + SID "244" + Position [725, 529, 765, 571] + ZOrder 271 + } + Block { + BlockType RateTransition + Name "Rate Transition13" + SID "255" + Position [685, 784, 725, 826] + ZOrder 282 + } + Block { + BlockType RateTransition + Name "Rate Transition2" + SID "146" + Position [1205, 479, 1245, 521] + ZOrder 247 + Port { + PortNumber 1 + Name "g" + RTWStorageClass "Auto" + DataLoggingNameMode "SignalName" + } + } + Block { + BlockType RateTransition + Name "Rate Transition3" + SID "235" + Position [255, 149, 295, 191] + ZOrder 262 + } + Block { + BlockType RateTransition + Name "Rate Transition4" + SID "236" + Position [255, 199, 295, 241] + ZOrder 263 + } + Block { + BlockType RateTransition + Name "Rate Transition5" + SID "237" + Position [255, 249, 295, 291] + ZOrder 264 + } + Block { + BlockType RateTransition + Name "Rate Transition6" + SID "238" + Position [255, 299, 295, 341] + ZOrder 265 + } + Block { + BlockType RateTransition + Name "Rate Transition7" + SID "239" + Position [255, 349, 295, 391] + ZOrder 266 + } + Block { + BlockType RateTransition + Name "Rate Transition8" + SID "240" + Position [255, 399, 295, 441] + ZOrder 267 + } + Block { + BlockType RateTransition + Name "Rate Transition9" + SID "241" + Position [255, 449, 295, 491] + ZOrder 268 + } + Block { + BlockType Scope + Name "Scope" + SID "10" + Ports [1] + Position [1710, 389, 1740, 421] + ZOrder 117 + Floating off + Location [60, 59, 1921, 1079] + Open off + NumInputPorts "1" + ZoomMode "yonly" + List { + ListType AxesTitles + axes1 "%" + } + List { + ListType ScopeGraphics + FigureColor "[0.5 0.5 0.5]" + AxesColor "[0 0 0]" + AxesTickColor "[1 1 1]" + LineColors "[1 1 0;1 0 1;0 1 1;1 0 0;0 1 0;0 0 1]" + LineStyles "-|-|-|-|-|-" + LineWidths "[0.5 0.5 0.5 0.5 0.5 0.5]" + MarkerStyles "none|none|none|none|none|none" + } + DataFormat "StructureWithTime" + SampleTime "0" + } + Block { + BlockType Scope + Name "Scope1" + SID "173" + Ports [1] + Position [1610, 544, 1640, 576] + ZOrder 231 + Floating off + Location [60, 94, 1921, 1079] + Open off + NumInputPorts "1" + ZoomMode "yonly" + List { + ListType AxesTitles + axes1 "%" + } + List { + ListType ScopeGraphics + FigureColor "[0.5 0.5 0.5]" + AxesColor "[0 0 0]" + AxesTickColor "[1 1 1]" + LineColors "[1 1 0;1 0 1;0 1 1;1 0 0;0 1 0;0 0 1]" + LineStyles "-|-|-|-|-|-" + LineWidths "[0.5 0.5 0.5 0.5 0.5 0.5]" + MarkerStyles "none|none|none|none|none|none" + } + SaveName "ScopeData1" + DataFormat "StructureWithTime" + SampleTime "0" + } + Block { + BlockType Scope + Name "Scope2" + SID "174" + Ports [1] + Position [1610, 599, 1640, 631] + ZOrder 232 + Floating off + Location [60, 94, 1921, 1079] + Open off + NumInputPorts "1" + ZoomMode "yonly" + List { + ListType AxesTitles + axes1 "%" + } + List { + ListType ScopeGraphics + FigureColor "[0.5 0.5 0.5]" + AxesColor "[0 0 0]" + AxesTickColor "[1 1 1]" + LineColors "[1 1 0;1 0 1;0 1 1;1 0 0;0 1 0;0 0 1]" + LineStyles "-|-|-|-|-|-" + LineWidths "[0.5 0.5 0.5 0.5 0.5 0.5]" + MarkerStyles "none|none|none|none|none|none" + } + SaveName "ScopeData2" + DataFormat "StructureWithTime" + SampleTime "0" + } + Block { + BlockType Scope + Name "Scope3" + SID "175" + Ports [1] + Position [1610, 659, 1640, 691] + ZOrder 233 + Floating off + Location [60, 94, 1921, 1079] + Open off + NumInputPorts "1" + ZoomMode "yonly" + List { + ListType AxesTitles + axes1 "%" + } + List { + ListType ScopeGraphics + FigureColor "[0.5 0.5 0.5]" + AxesColor "[0 0 0]" + AxesTickColor "[1 1 1]" + LineColors "[1 1 0;1 0 1;0 1 1;1 0 0;0 1 0;0 0 1]" + LineStyles "-|-|-|-|-|-" + LineWidths "[0.5 0.5 0.5 0.5 0.5 0.5]" + MarkerStyles "none|none|none|none|none|none" + } + SaveName "ScopeData3" + DataFormat "StructureWithTime" + SampleTime "0" + } + Block { + BlockType Scope + Name "Scope4" + SID "186" + Ports [4] + Position [1610, 453, 1640, 487] + ZOrder 234 + Floating off + Location [66, 91, 1903, 1039] + Open off + NumInputPorts "4" + ZoomMode "yonly" + List { + ListType AxesTitles + axes1 "%" + axes2 "%" + axes3 "%" + axes4 "%" + } + List { + ListType ScopeGraphics + FigureColor "[0.5 0.5 0.5]" + AxesColor "[0 0 0]" + AxesTickColor "[1 1 1]" + LineColors "[1 1 0;1 0 1;0 1 1;1 0 0;0 1 0;0 0 1]" + LineStyles "-|-|-|-|-|-" + LineWidths "[0.5 0.5 0.5 0.5 0.5 0.5]" + MarkerStyles "none|none|none|none|none|none" + } + YMin "-15~-1~-1~-40" + YMax "15~1~1~40" + SaveName "ScopeData4" + DataFormat "StructureWithTime" + LimitDataPoints off + SampleTime "0" + } + Block { + BlockType SignalConversion + Name "Signal Conversion" + SID "147" + Position [140, 399, 180, 441] + ZOrder 225 + } + Block { + BlockType Sum + Name "Sum" + SID "261" + Ports [2, 1] + Position [205, 410, 225, 430] + ZOrder 288 + ShowName off + IconShape "round" + Inputs "|++" + InputSameDT off + OutDataTypeStr "Inherit: Inherit via internal rule" + SaturateOnIntegerOverflow off + } + Block { + BlockType Sum + Name "Sum1" + SID "188" + Ports [2, 1] + Position [1550, 475, 1570, 495] + ZOrder 236 + ShowName off + IconShape "round" + Inputs "|+-" + InputSameDT off + OutDataTypeStr "Inherit: Inherit via internal rule" + SaturateOnIntegerOverflow off + } + Block { + BlockType Sum + Name "Sum2" + SID "247" + Ports [2, 1] + Position [1250, 540, 1270, 560] + ZOrder 274 + ShowName off + IconShape "round" + Inputs "|++" + InputSameDT off + OutDataTypeStr "Inherit: Inherit via internal rule" + SaturateOnIntegerOverflow off + } + Block { + BlockType Sum + Name "Sum3" + SID "262" + Ports [2, 1] + Position [160, 460, 180, 480] + ZOrder 289 + ShowName off + IconShape "round" + Inputs "|++" + InputSameDT off + OutDataTypeStr "Inherit: Inherit via internal rule" + SaturateOnIntegerOverflow off + } + Block { + BlockType Sum + Name "Sum4" + SID "263" + Ports [2, 1] + Position [70, 510, 90, 530] + ZOrder 290 + ShowName off + IconShape "round" + Inputs "|++" + InputSameDT off + OutDataTypeStr "Inherit: Inherit via internal rule" + SaturateOnIntegerOverflow off + } + Block { + BlockType Sum + Name "Sum5" + SID "264" + Ports [2, 1] + Position [185, 210, 205, 230] + ZOrder 291 + ShowName off + IconShape "round" + Inputs "++|" + InputSameDT off + OutDataTypeStr "Inherit: Inherit via internal rule" + SaturateOnIntegerOverflow off + } + Block { + BlockType Sum + Name "Sum6" + SID "265" + Ports [2, 1] + Position [220, 160, 240, 180] + ZOrder 292 + ShowName off + IconShape "round" + Inputs "++|" + InputSameDT off + OutDataTypeStr "Inherit: Inherit via internal rule" + SaturateOnIntegerOverflow off + } + Block { + BlockType Math + Name "Transpose" + SID "189" + Ports [1, 1] + Position [1205, 100, 1260, 140] + ZOrder 237 + BlockMirror on + Operator "transpose" + } + Block { + BlockType ZeroOrderHold + Name "Zero-Order\nHold" + SID "143" + Position [705, 425, 740, 455] + ZOrder 218 + SampleTime "0.001" + } + Block { + BlockType Reference + Name "atlas5_arm_coriolis_vec_minvarpar" + SID "207" + Ports [2, 1] + Position [1425, 782, 1495, 833] + ZOrder 257 + LibraryVersion "1.228" + SourceBlock "atlas_dynamic_library/atlas5_arm_coriolis_vec_minvarpar" + SourceType "" + ContentPreviewEnabled off + atlas_arm_lr "atlas_arm_lr" + MPV "MPV_arm_plant" + Port { + PortNumber 1 + PropagatedSignals "tau_c" + RTWStorageClass "Auto" + DataLogging on + DataLoggingNameMode "Custom" + DataLoggingName "tau_c" + } + } + Block { + BlockType Reference + Name "atlas5_arm_energy_minvarpar" + SID "208" + Ports [3, 2] + Position [1425, 351, 1495, 409] + ZOrder 258 + LibraryVersion "1.228" + SourceBlock "atlas_dynamic_library/atlas5_arm_energy_minvarpar" + SourceType "" + ContentPreviewEnabled off + MPV "MPV_arm_plant" + Port { + PortNumber 1 + Name "T" + RTWStorageClass "Auto" + DataLoggingNameMode "SignalName" + } + Port { + PortNumber 2 + Name "U" + RTWStorageClass "Auto" + DataLoggingNameMode "SignalName" + } + } + Block { + BlockType Reference + Name "atlas5_arm_fordyn_rj_damping_minvarpar" + SID "204" + Ports [3, 5] + Position [1100, 367, 1270, 463] + ZOrder 254 + LibraryVersion "1.228" + SourceBlock "atlas_dynamic_library/atlas5_arm_fordyn_rj_damping_minvarpar" + SourceType "" + ContentPreviewEnabled off + q0 "q0" + qD0 "qD0" + d "d" + muC "muC" + atlas_arm_lr "atlas_arm_lr" + MPV "MPV_arm_plant" + } + Block { + BlockType Reference + Name "atlas5_arm_gravload_minvarpar" + SID "206" + Ports [2, 1] + Position [1425, 707, 1495, 758] + ZOrder 256 + LibraryVersion "1.228" + SourceBlock "atlas_dynamic_library/atlas5_arm_gravload_minvarpar" + SourceType "" + ContentPreviewEnabled off + atlas_arm_lr "atlas_arm_lr" + MPV "MPV_arm_plant" + Port { + PortNumber 1 + PropagatedSignals "tau_g" + RTWStorageClass "Auto" + DataLogging on + DataLoggingNameMode "Custom" + DataLoggingName "tau_g" + } + } + Block { + BlockType Reference + Name "atlas5_arm_jacobig" + SID "205" + Ports [1, 1] + Position [1285, 95, 1355, 145] + ZOrder 255 + BlockMirror on + LibraryVersion "1.228" + SourceBlock "atlas_dynamic_library/atlas5_arm_jacobig" + SourceType "SubSystem" + ContentPreviewEnabled off + } + Block { + BlockType Reference + Name "atlas_friciton_model" + SID "245" + Ports [1, 1] + Position [1100, 562, 1200, 638] + ZOrder 272 + LibraryVersion "1.360" + SourceBlock "atlas_impctrl_library/atlas_friction_model" + SourceType "" + ContentPreviewEnabled off + tau_c "tau_c" + B "B" + } + Block { + BlockType Reference + Name "atlas_joint_impctrl_sqrt_damping_v5" + SID "209" + Ports [8, 3] + Position [355, 140, 580, 550] + ZOrder 259 + ForegroundColor "yellow" + LibraryVersion "1.360" + SourceBlock "atlas_impctrl_library/atlas_joint_impctrl_sqrt_damping_v5" + SourceType "Atlas Joint Impedance Controller" + ContentPreviewEnabled off + K_d "K_d" + D "D" + K_tau_g "K_tau_g" + K_tau_c "K_tau_c" + K_tau_K "K_tau_K" + K_tau_D "K_tau_D" + K_tau_a "K_tau_a" + K_tau_f "K_tau_f" + K_tau_e "K_tau_e" + K_tau_o "K_tau_o" + K_qD_d "K_qD_d" + K_qDD_d "K_qDD_d" + K_ext_c "K_ext_c" + K_obs_c "K_obs_c" + K_fri_o "K_fri_o" + K_ext_o "K_ext_o" + MPV_arm_damp "MPV_arm_damp" + MPV_arm_model "MPV_arm_model" + tau_c "tau_c" + B "B" + qD_th "qD_th" + tau_th "tau_th" + K_O "K_O" + T "T" + atlas_arm_lr "atlas_arm_lr" + T1 "T1" + } + Block { + BlockType Constant + Name "g" + SID "138" + Position [1100, 485, 1175, 515] + ZOrder 246 + Value "[0;0;-9.81]" + } + Block { + BlockType UniformRandomNumber + Name "g_noise" + SID "258" + Position [260, 589, 290, 621] + ZOrder 285 + BlockMirror on + Minimum "-g_noise" + Maximum "g_noise" + Seed "g_noise_seed" + SampleTime "0" + } + Block { + BlockType FromWorkspace + Name "qDD_d" + SID "135" + Position [95, 358, 160, 382] + ZOrder 211 + VariableName "simin_qDD_soll" + SampleTime "0" + ZeroCross on + OutputAfterFinalValue "Holding final value" + } + Block { + BlockType FromWorkspace + Name "qD_d" + SID "136" + Position [95, 308, 160, 332] + ZOrder 210 + VariableName "simin_qD_soll" + SampleTime "0" + ZeroCross on + OutputAfterFinalValue "Holding final value" + } + Block { + BlockType UniformRandomNumber + Name "qD_noise" + SID "257" + Position [145, 74, 175, 106] + ZOrder 284 + Minimum "-qD_noise" + Maximum "qD_noise" + Seed "qD_noise_seed" + SampleTime "0" + } + Block { + BlockType FromWorkspace + Name "q_d" + SID "137" + Position [95, 258, 160, 282] + ZOrder 209 + VariableName "simin_q_soll" + SampleTime "0" + ZeroCross on + OutputAfterFinalValue "Holding final value" + } + Block { + BlockType UniformRandomNumber + Name "q_noise" + SID "256" + Position [260, 74, 290, 106] + ZOrder 283 + BlockMirror on + Minimum "-q_noise" + Maximum "q_noise" + Seed "q_noise_seed" + SampleTime "0" + } + Block { + BlockType UniformRandomNumber + Name "tau_noise" + SID "259" + Position [120, 589, 150, 621] + ZOrder 286 + Minimum "-tau_noise" + Maximum "tau_noise" + Seed "tau_noise_seed" + SampleTime "0" + } + Block { + BlockType Outport + Name "q" + SID "55" + Position [1515, 553, 1545, 567] + ZOrder 168 + IconDisplay "Port number" + } + Block { + BlockType Outport + Name "qD" + SID "56" + Position [1515, 608, 1545, 622] + ZOrder 169 + Port "2" + IconDisplay "Port number" + } + Block { + BlockType Outport + Name "qDD" + SID "57" + Position [1515, 668, 1545, 682] + ZOrder 170 + Port "3" + IconDisplay "Port number" + } + Block { + BlockType Outport + Name "E" + SID "58" + Position [1750, 323, 1780, 337] + ZOrder 171 + Port "4" + IconDisplay "Port number" + } + Block { + BlockType Outport + Name "tau_g" + SID "129" + Position [1570, 728, 1600, 742] + ZOrder 199 + Port "5" + IconDisplay "Port number" + } + Block { + BlockType Outport + Name "tau_c" + SID "131" + Position [1570, 803, 1600, 817] + ZOrder 201 + Port "6" + IconDisplay "Port number" + } + Block { + BlockType Outport + Name "tau_m" + SID "249" + Position [1100, 323, 1130, 337] + ZOrder 276 + Port "7" + IconDisplay "Port number" + } + Block { + BlockType Outport + Name "tau_ext_mes" + SID "250" + Position [760, 798, 790, 812] + ZOrder 277 + Port "8" + IconDisplay "Port number" + } + Block { + BlockType Outport + Name "tau_obs" + SID "251" + Position [900, 728, 930, 742] + ZOrder 278 + Port "9" + IconDisplay "Port number" + } + Block { + BlockType Outport + Name "out_F0_ext" + SID "252" + Position [1515, 263, 1545, 277] + ZOrder 279 + Port "10" + IconDisplay "Port number" + } + Block { + BlockType Outport + Name "tau_ext" + SID "254" + Position [1125, 18, 1155, 32] + ZOrder 281 + Port "11" + IconDisplay "Port number" + } + Line { + Name "T" + ZOrder 1205 + Labels [1, 1] + SrcBlock "atlas5_arm_energy_minvarpar" + SrcPort 1 + Points [38, 0] + Branch { + ZOrder 1566 + Points [0, -55] + DstBlock "Mux" + DstPort 1 + } + Branch { + ZOrder 1565 + DstBlock "Add" + DstPort 1 + } + } + Line { + Name "U" + ZOrder 1203 + Labels [1, 1] + SrcBlock "atlas5_arm_energy_minvarpar" + SrcPort 2 + Points [48, 0] + Branch { + ZOrder 1568 + Points [0, -65] + DstBlock "Mux" + DstPort 2 + } + Branch { + ZOrder 1567 + DstBlock "Add" + DstPort 2 + } + } + Line { + Name "E" + ZOrder 4 + SrcBlock "Add" + SrcPort 1 + Points [4, 0] + Branch { + ZOrder 1571 + Labels [1, 1] + Points [0, 25] + DstBlock "Scope" + DstPort 1 + } + Branch { + ZOrder 1570 + Points [0, -30] + DstBlock "Mux" + DstPort 3 + } + } + Line { + ZOrder 1195 + SrcBlock "atlas5_arm_jacobig" + SrcPort 1 + DstBlock "Transpose" + DstPort 1 + } + Line { + ZOrder 1463 + SrcBlock "Product" + SrcPort 1 + Points [-67, 0] + Branch { + ZOrder 1574 + Points [0, -135] + DstBlock "tau_ext" + DstPort 1 + } + Branch { + ZOrder 1573 + Points [-34, 0; 0, 225] + Branch { + ZOrder 1183 + DstBlock "atlas5_arm_fordyn_rj_damping_minvarpar" + DstPort 1 + } + Branch { + ZOrder 909 + Points [0, 155; 561, 0; 0, -65] + DstBlock "Scope4" + DstPort 3 + } + } + } + Line { + ZOrder 1464 + SrcBlock "F0_ext" + SrcPort 1 + Points [-38, 0] + Branch { + ZOrder 1564 + Points [0, 75] + DstBlock "out_F0_ext" + DstPort 1 + } + Branch { + ZOrder 1563 + Points [-12, 0] + Branch { + ZOrder 1688 + Points [0, -126; -1188, 0; 0, 451] + DstBlock "Sum4" + DstPort 1 + } + Branch { + ZOrder 1312 + DstBlock "Product" + DstPort 2 + } + } + } + Line { + ZOrder 1200 + SrcBlock "atlas5_arm_gravload_minvarpar" + SrcPort 1 + DstBlock "tau_g" + DstPort 1 + } + Line { + ZOrder 1196 + SrcBlock "atlas5_arm_coriolis_vec_minvarpar" + SrcPort 1 + DstBlock "tau_c" + DstPort 1 + } + Line { + ZOrder 1216 + SrcBlock "qD_d" + SrcPort 1 + DstBlock "Rate Transition6" + DstPort 1 + } + Line { + ZOrder 1212 + SrcBlock "qDD_d" + SrcPort 1 + DstBlock "Rate Transition7" + DstPort 1 + } + Line { + ZOrder 1214 + SrcBlock "q_d" + SrcPort 1 + DstBlock "Rate Transition5" + DstPort 1 + } + Line { + ZOrder 709 + SrcBlock "Manual Switch1" + SrcPort 1 + DstBlock "7D low pass filter3" + DstPort 1 + } + Line { + ZOrder 1215 + SrcBlock "atlas_joint_impctrl_sqrt_damping_v5" + SrcPort 1 + Points [33, 0; 0, 175] + Branch { + ZOrder 922 + Points [0, 55] + DstBlock "Rate Transition1" + DstPort 1 + } + Branch { + ZOrder 839 + DstBlock "Rate Transition11" + DstPort 1 + } + } + Line { + ZOrder 600 + SrcBlock "Rate Transition1" + SrcPort 1 + DstBlock "Zero-Order\nHold" + DstPort 1 + } + Line { + ZOrder 601 + SrcBlock "Zero-Order\nHold" + SrcPort 1 + DstBlock "Rate Transition" + DstPort 1 + } + Line { + ZOrder 602 + SrcBlock "Rate Transition" + SrcPort 1 + DstBlock "Manual Switch1" + DstPort 2 + } + Line { + ZOrder 1181 + SrcBlock "7D low pass filter3" + SrcPort 1 + Points [42, 0] + Branch { + ZOrder 1559 + Points [0, -85] + DstBlock "tau_m" + DstPort 1 + } + Branch { + ZOrder 1558 + DstBlock "atlas5_arm_fordyn_rj_damping_minvarpar" + DstPort 2 + } + } + Line { + ZOrder 1211 + SrcBlock "atlas_joint_impctrl_sqrt_damping_v5" + SrcPort 2 + Points [26, 0; 0, 205] + DstBlock "Rate Transition12" + DstPort 1 + } + Line { + ZOrder 940 + SrcBlock "Sum1" + SrcPort 1 + DstBlock "Scope4" + DstPort 4 + } + Line { + ZOrder 950 + SrcBlock "Transpose" + SrcPort 1 + DstBlock "Product" + DstPort 1 + } + Line { + ZOrder 1185 + SrcBlock "atlas5_arm_fordyn_rj_damping_minvarpar" + SrcPort 1 + DstBlock "Bus\nCreator" + DstPort 1 + } + Line { + ZOrder 1186 + SrcBlock "atlas5_arm_fordyn_rj_damping_minvarpar" + SrcPort 2 + DstBlock "Bus\nCreator" + DstPort 2 + } + Line { + ZOrder 1182 + SrcBlock "atlas5_arm_fordyn_rj_damping_minvarpar" + SrcPort 3 + DstBlock "Bus\nCreator" + DstPort 3 + } + Line { + Name "" + ZOrder 1202 + Labels [0, 0] + SrcBlock "Bus\nSelector" + SrcPort 2 + DstBlock "atlas5_arm_energy_minvarpar" + DstPort 2 + } + Line { + Name "" + ZOrder 1204 + Labels [0, 0] + SrcBlock "Bus\nSelector" + SrcPort 1 + DstBlock "atlas5_arm_energy_minvarpar" + DstPort 1 + } + Line { + ZOrder 1051 + SrcBlock "Bus\nCreator" + SrcPort 1 + Points [38, 0] + Branch { + ZOrder 1079 + Points [0, 60] + Branch { + ZOrder 1090 + Points [0, 75] + Branch { + ZOrder 1107 + DstBlock "Bus\nSelector5" + DstPort 1 + } + Branch { + ZOrder 1106 + Points [0, 55] + Branch { + ZOrder 1118 + Points [0, 49] + Branch { + ZOrder 1127 + Points [-300, 0; 0, -15] + Branch { + ZOrder 1129 + Points [0, -49] + Branch { + ZOrder 1406 + Points [0, -155] + DstBlock "Bus\nSelector8" + DstPort 1 + } + Branch { + ZOrder 1405 + DstBlock "Bus\nSelector11" + DstPort 1 + } + } + Branch { + ZOrder 1128 + Points [-1024, 0; 0, -204] + Branch { + ZOrder 1143 + Points [0, -250] + DstBlock "Bus\nSelector10" + DstPort 1 + } + Branch { + ZOrder 1133 + DstBlock "Bus\nSelector9" + DstPort 1 + } + } + } + Branch { + ZOrder 1126 + Points [0, 11] + Branch { + ZOrder 1119 + Points [0, 60] + Branch { + ZOrder 1122 + Points [0, 75] + DstBlock "Bus\nSelector1" + DstPort 1 + } + Branch { + ZOrder 1061 + DstBlock "Bus\nSelector2" + DstPort 1 + } + } + Branch { + ZOrder 1098 + DstBlock "Bus\nSelector3" + DstPort 1 + } + } + } + Branch { + ZOrder 1104 + DstBlock "Bus\nSelector4" + DstPort 1 + } + } + } + Branch { + ZOrder 1089 + DstBlock "Bus\nSelector7" + DstPort 1 + } + } + Branch { + ZOrder 1058 + Points [0, -45] + Branch { + ZOrder 1124 + Points [0, -125; 77, 0; 0, -135] + DstBlock "Bus\nSelector6" + DstPort 1 + } + Branch { + ZOrder 1082 + DstBlock "Bus\nSelector" + DstPort 1 + } + } + } + Line { + Name "" + ZOrder 1198 + Labels [-1, 0] + SrcBlock "Bus\nSelector1" + SrcPort 1 + DstBlock "atlas5_arm_coriolis_vec_minvarpar" + DstPort 1 + } + Line { + Name "" + ZOrder 1197 + Labels [0, 0] + SrcBlock "Bus\nSelector1" + SrcPort 2 + DstBlock "atlas5_arm_coriolis_vec_minvarpar" + DstPort 2 + } + Line { + Name "" + ZOrder 1199 + Labels [0, 0] + SrcBlock "Bus\nSelector2" + SrcPort 1 + DstBlock "atlas5_arm_gravload_minvarpar" + DstPort 1 + } + Line { + ZOrder 1187 + SrcBlock "atlas5_arm_fordyn_rj_damping_minvarpar" + SrcPort 4 + DstBlock "Bus\nCreator" + DstPort 4 + } + Line { + ZOrder 1069 + SrcBlock "g" + SrcPort 1 + DstBlock "Rate Transition2" + DstPort 1 + } + Line { + Name "g" + ZOrder 1077 + Labels [0, 0] + SrcBlock "Rate Transition2" + SrcPort 1 + Points [30, 0] + DstBlock "Bus\nCreator" + DstPort 6 + } + Line { + Name "" + ZOrder 1194 + Labels [0, 0] + SrcBlock "Bus\nSelector6" + SrcPort 1 + DstBlock "atlas5_arm_jacobig" + DstPort 1 + } + Line { + Name "" + ZOrder 1088 + Labels [0, 0] + SrcBlock "Bus\nSelector7" + SrcPort 1 + Points [23, 0] + Branch { + ZOrder 1092 + Points [0, -30] + DstBlock "Scope4" + DstPort 1 + } + Branch { + ZOrder 1091 + DstBlock "Sum1" + DstPort 1 + } + } + Line { + Name "" + ZOrder 1109 + Labels [0, 0] + SrcBlock "Bus\nSelector5" + SrcPort 1 + Points [12, 0] + Branch { + ZOrder 1117 + Points [0, -13; 55, 0; 0, 13] + DstBlock "Scope1" + DstPort 1 + } + Branch { + ZOrder 1116 + DstBlock "q" + DstPort 1 + } + } + Line { + Name "" + ZOrder 1110 + Labels [0, 0] + SrcBlock "Bus\nSelector4" + SrcPort 1 + Points [10, 0] + Branch { + ZOrder 1115 + Points [0, -21; 55, 0; 0, 21] + DstBlock "Scope2" + DstPort 1 + } + Branch { + ZOrder 1114 + DstBlock "qD" + DstPort 1 + } + } + Line { + Name "" + ZOrder 1111 + Labels [0, 0] + SrcBlock "Bus\nSelector3" + SrcPort 1 + Points [9, 0] + Branch { + ZOrder 1113 + Points [0, -21; 60, 0; 0, 21] + DstBlock "Scope3" + DstPort 1 + } + Branch { + ZOrder 1112 + DstBlock "qDD" + DstPort 1 + } + } + Line { + Name "" + ZOrder 1201 + Labels [0, 0] + SrcBlock "Bus\nSelector2" + SrcPort 2 + DstBlock "atlas5_arm_gravload_minvarpar" + DstPort 2 + } + Line { + Name "" + ZOrder 1206 + Labels [0, 0] + SrcBlock "Bus\nSelector" + SrcPort 3 + DstBlock "atlas5_arm_energy_minvarpar" + DstPort 3 + } + Line { + Name "" + ZOrder 1184 + Labels [0, 0] + SrcBlock "Bus\nSelector8" + SrcPort 1 + DstBlock "atlas5_arm_fordyn_rj_damping_minvarpar" + DstPort 3 + } + Line { + Name "" + ZOrder 1131 + Labels [0, 0] + SrcBlock "Bus\nSelector9" + SrcPort 1 + DstBlock "Signal Conversion" + DstPort 1 + } + Line { + Name "" + ZOrder 1217 + Labels [0, 0] + SrcBlock "Bus\nSelector10" + SrcPort 1 + DstBlock "7D low pass filter1" + DstPort 1 + } + Line { + Name "" + ZOrder 1219 + Labels [0, 0] + SrcBlock "Bus\nSelector10" + SrcPort 2 + DstBlock "7D low pass filter2" + DstPort 1 + } + Line { + ZOrder 1188 + SrcBlock "atlas5_arm_fordyn_rj_damping_minvarpar" + SrcPort 5 + DstBlock "Bus\nCreator" + DstPort 5 + } + Line { + ZOrder 1294 + SrcBlock "Rate Transition3" + SrcPort 1 + DstBlock "atlas_joint_impctrl_sqrt_damping_v5" + DstPort 1 + } + Line { + ZOrder 1295 + SrcBlock "Rate Transition4" + SrcPort 1 + DstBlock "atlas_joint_impctrl_sqrt_damping_v5" + DstPort 2 + } + Line { + ZOrder 1296 + SrcBlock "Rate Transition5" + SrcPort 1 + DstBlock "atlas_joint_impctrl_sqrt_damping_v5" + DstPort 3 + } + Line { + ZOrder 1297 + SrcBlock "Rate Transition6" + SrcPort 1 + DstBlock "atlas_joint_impctrl_sqrt_damping_v5" + DstPort 4 + } + Line { + ZOrder 1298 + SrcBlock "Rate Transition7" + SrcPort 1 + DstBlock "atlas_joint_impctrl_sqrt_damping_v5" + DstPort 5 + } + Line { + ZOrder 1299 + SrcBlock "Rate Transition8" + SrcPort 1 + DstBlock "atlas_joint_impctrl_sqrt_damping_v5" + DstPort 6 + } + Line { + ZOrder 1300 + SrcBlock "Rate Transition9" + SrcPort 1 + DstBlock "atlas_joint_impctrl_sqrt_damping_v5" + DstPort 7 + } + Line { + ZOrder 1301 + SrcBlock "Rate Transition10" + SrcPort 1 + DstBlock "atlas_joint_impctrl_sqrt_damping_v5" + DstPort 8 + } + Line { + ZOrder 1302 + SrcBlock "Rate Transition11" + SrcPort 1 + DstBlock "Manual Switch1" + DstPort 1 + } + Line { + ZOrder 1399 + SrcBlock "Rate Transition12" + SrcPort 1 + Points [84, 0] + Branch { + ZOrder 1562 + Points [0, 185] + DstBlock "tau_obs" + DstPort 1 + } + Branch { + ZOrder 1561 + DstBlock "Sum2" + DstPort 1 + } + } + Line { + Name "" + ZOrder 1401 + Labels [0, 0] + SrcBlock "Bus\nSelector11" + SrcPort 1 + DstBlock "atlas_friciton_model" + DstPort 1 + } + Line { + ZOrder 1407 + SrcBlock "atlas_friciton_model" + SrcPort 1 + Points [55, 0] + DstBlock "Sum2" + DstPort 2 + } + Line { + ZOrder 1410 + SrcBlock "Sum2" + SrcPort 1 + Points [47, 0; 0, -85; 192, 0] + Branch { + ZOrder 1415 + Points [0, 51; 46, 0] + DstBlock "Sum1" + DstPort 2 + } + Branch { + ZOrder 1414 + DstBlock "Scope4" + DstPort 2 + } + } + Line { + ZOrder 1560 + SrcBlock "atlas_joint_impctrl_sqrt_damping_v5" + SrcPort 3 + Points [15, 0; 0, 325] + DstBlock "Rate Transition13" + DstPort 1 + } + Line { + ZOrder 1572 + SrcBlock "Mux" + SrcPort 1 + DstBlock "E" + DstPort 1 + } + Line { + ZOrder 1680 + SrcBlock "Rate Transition13" + SrcPort 1 + DstBlock "tau_ext_mes" + DstPort 1 + } + Line { + ZOrder 1681 + SrcBlock "Signal Conversion" + SrcPort 1 + DstBlock "Sum" + DstPort 1 + } + Line { + ZOrder 1682 + SrcBlock "Sum" + SrcPort 1 + DstBlock "Rate Transition8" + DstPort 1 + } + Line { + ZOrder 1683 + SrcBlock "g_noise" + SrcPort 1 + Points [-40, 0] + DstBlock "Gain" + DstPort 1 + } + Line { + Name "" + ZOrder 1684 + Labels [0, 0] + SrcBlock "Bus\nSelector9" + SrcPort 2 + DstBlock "Sum3" + DstPort 1 + } + Line { + ZOrder 1685 + SrcBlock "Sum3" + SrcPort 1 + DstBlock "Rate Transition9" + DstPort 1 + } + Line { + ZOrder 1686 + SrcBlock "tau_noise" + SrcPort 1 + Points [15, 0] + DstBlock "Gain1" + DstPort 1 + } + Line { + ZOrder 1689 + SrcBlock "Sum4" + SrcPort 1 + DstBlock "Rate Transition10" + DstPort 1 + } + Line { + ZOrder 1690 + SrcBlock "F_ext_noise" + SrcPort 1 + Points [15, 0] + DstBlock "Gain2" + DstPort 1 + } + Line { + ZOrder 1691 + SrcBlock "7D low pass filter2" + SrcPort 1 + DstBlock "Sum5" + DstPort 2 + } + Line { + ZOrder 1692 + SrcBlock "Sum5" + SrcPort 1 + DstBlock "Rate Transition4" + DstPort 1 + } + Line { + ZOrder 1693 + SrcBlock "7D low pass filter1" + SrcPort 1 + DstBlock "Sum6" + DstPort 2 + } + Line { + ZOrder 1694 + SrcBlock "Sum6" + SrcPort 1 + DstBlock "Rate Transition3" + DstPort 1 + } + Line { + ZOrder 1695 + SrcBlock "q_noise" + SrcPort 1 + Points [-25, 0] + DstBlock "Gain3" + DstPort 1 + } + Line { + ZOrder 1696 + SrcBlock "qD_noise" + SrcPort 1 + Points [15, 0] + DstBlock "Gain4" + DstPort 1 + } + Line { + ZOrder 1697 + SrcBlock "Gain" + SrcPort 1 + DstBlock "Sum" + DstPort 2 + } + Line { + ZOrder 1698 + SrcBlock "Gain1" + SrcPort 1 + DstBlock "Sum3" + DstPort 2 + } + Line { + ZOrder 1699 + SrcBlock "Gain2" + SrcPort 1 + DstBlock "Sum4" + DstPort 2 + } + Line { + ZOrder 1700 + SrcBlock "Gain3" + SrcPort 1 + DstBlock "Sum6" + DstPort 1 + } + Line { + ZOrder 1701 + SrcBlock "Gain4" + SrcPort 1 + DstBlock "Sum5" + DstPort 1 + } + } +} +#Finite State Machines +# +# Stateflow 80000005 +# +# +Stateflow { + machine { + id 1 + name "atlas_joint_impctrl_sqrt_damping_test" + created "11-Dec-2014 11:16:26" + isLibrary 0 + firstTarget 2 + sfVersion 80000005 + } + target { + id 2 + name "sfun" + description "Default Simulink S-Function Target." + machine 1 + linkNode [1 0 3] + } + target { + id 3 + name "rtw" + machine 1 + linkNode [1 2 0] + } +} diff --git a/simulink/atlas_joint_impctrl_sqrt_damping_test_settings_default.m b/simulink/atlas_joint_impctrl_sqrt_damping_test_settings_default.m new file mode 100644 index 0000000..2b0e252 --- /dev/null +++ b/simulink/atlas_joint_impctrl_sqrt_damping_test_settings_default.m @@ -0,0 +1,157 @@ +% Settings to start the Atlas Arm joint impedance controller +% called by atlas_joint_impctrl_sqrt_damping_test_start.m + +% Jonathan Vorndamme, vorndamme@irt.uni-hannover.de, 2015-01 +% Moritz Schappler, schappler@irt.uni-hannover.de, 2015-09 +% (c) Institut für Regelungstechnik, Universität Hannover + +%% Init + +lrStrings = {'left', 'right'}; + +AS=atlas_const(atlas_version, lr); +if atlas_limb == 1 + q_r=0.5*(AS.q_min(AS.JI_rArm)+AS.q_max(AS.JI_rArm)); + q_l=0.5*(AS.q_min(AS.JI_lArm)+AS.q_max(AS.JI_lArm)); + NJL = AS.NJA; + JI = AS.JI_Arm; + % TODO: Simulink-Modell an Arm v5 umbenennen + sl_Modellname = 'atlas_joint_impctrl_sqrt_damping_test'; + atlas_arm_lr = lr; +else + q_r=0.5*(AS.q_min(AS.JI_rLeg)+AS.q_max(AS.JI_rLeg)); + q_l=0.5*(AS.q_min(AS.JI_lLeg)+AS.q_max(AS.JI_lLeg)); + NJL = AS.NJL; + JI = AS.JI_Leg; + sl_Modellname = 'atlas5_leg_joint_impctrl_sqrt_damping_test'; + atlas_leg_lr = lr; +end + +%% Soll-Trajektorie +q0=q_l; +qD0 = zeros(1,NJL)'; + +q_start = q0'; +q_end = q_start; +q_end(2) = q_start(2)+pi/2; %Drehe q2 um 90° (seitlich ausgestreckt) +% C3-stetige Trapez-Trajektorie fahren +vmax = 2*ones(1,NJL); +amax = 10*ones(1,NJL); +jmax = 100*ones(1,NJL); +zmax = [ (q0(2)+pi/2) ; 2; 10; 100]; + +[~, ~, w_t, w_Q] = traj_trapezN( [q_start; zeros(2,NJL)], ... + [q_end; zeros(2,NJL)], [q_end; vmax; amax; jmax], 1e-3, false); +qsollDaten.q = NaN(length(w_t), NJL); +qsollDaten.qD = NaN(length(w_t), NJL); +qsollDaten.qDD = NaN(length(w_t), NJL); +for i = 1:NJL + qsollDaten.q(:,i) = w_Q(:,1,i); + qsollDaten.qD(:,i) = w_Q(:,2,i); + qsollDaten.qDD(:,i) = w_Q(:,3,i); +end + +qsollDaten.t = w_t; % Zeitbasis ist für alle Achsen gleich. Daher hier keine Anpassung notwendig + +%% Externe Kraft +t_Fext = [0;1;4]; +F_ext = [[0;100;0], zeros(3,5)]; + +%% Simulink-Eingangsdaten +simin_q_soll = struct('time', qsollDaten.t, ... + 'signals', struct('values', qsollDaten.q, 'dimensions', NJL), ... + 'name', 'q_soll'); + +simin_qD_soll = struct('time', qsollDaten.t, ... + 'signals', struct('values', qsollDaten.qD, 'dimensions', NJL), ... + 'name', 'qD_soll'); + +simin_qDD_soll = struct('time', qsollDaten.t, ... + 'signals', struct('values', qsollDaten.qDD, 'dimensions', NJL), ... + 'name', 'qD_soll'); + +simin_F0_ext = struct('time', t_Fext, ... + 'signals', struct('values', F_ext, 'dimensions', 6), ... + 'name', 'F0_ext'); + +%% model parameters +if atlas_limb == 1 + [a_mdh, d_mdh, ~, ~, rSges_mdh_ORIG, m_ORIG,Iges_mdh_ORIG] = atlas_arm_parameter_mdh(atlas_arm_lr, atlas_version); + MPV_ORIG = atlas_arm_convert_par1_MPV(rSges_mdh_ORIG, m_ORIG, Iges_mdh_ORIG, a_mdh, d_mdh, atlas_version); + % Zusatzlast: 1kg mit 100mm Hebelarm, damit Trägheit im Dynamikmodell + % höher wird. + MPV_payload = atlas5_arm_FT_payload_MPV(1, [.1,.1,.1]', [0.1, 0, 0, 0.1, 0, 0.1]', true); + MPV_arm_plant=MPV_ORIG+MPV_payload; % MPV for simulated plant + MPV_arm_model=MPV_ORIG+MPV_payload;% MPV for calculating the gravity model + MPV_arm_damp=MPV_ORIG+MPV_payload; % MPV for calculating the inertia matrix (positive definite) + % set noise levels for simulated measurements + q_noise = 0.01; + qD_noise = 0.01; + tau_noise = 0.5; + F_ext_noise = 3; + g_noise = 0.001; + % set noise seeds for measurement noises + q_noise_seed = 0; + qD_noise_seed = 0; + tau_noise_seed = 0; + F_ext_noise_seed = 0; + g_noise_seed = 0; + % set noise switches for measurement noises (1=on, 0=off) + q_noise_switch = 0; + qD_noise_switch = 0; + tau_noise_switch = 0; + F_ext_noise_switch = 0; + g_noise_switch = 0; +else + [a_mdh, d_mdh, ~, ~, rSges_mdh_ORIG, m_ORIG,Iges_mdh_ORIG] = atlas_leg_parameter_mdh(atlas_leg_lr, atlas_version); + MPV_ORIG = atlas_leg_convert_par1_MPV(rSges_mdh_ORIG, m_ORIG, Iges_mdh_ORIG, a_mdh, d_mdh, atlas_version); + MPV_leg_plant=MPV_ORIG; % MPV for simulated plant + MPV_leg_model=MPV_ORIG;% MPV for calculating the gravity model + MPV_leg_damp=MPV_ORIG; % MPV for calculating the inertia matrix (positive definite) +end + +d = 0.2*ones(NJL,1); +muC = 8*ones(NJL,1); + +% controller parameters and gains +K_d = 150*eye(NJL); +D = 0.7*eye(NJL); +K_O = 5*eye(NJL); +T = 0.001; +T1 = 0; +K_tau_g = 1; +K_tau_c = 1; +K_tau_K = 1; +K_tau_D = 1; +K_tau_a = 1; +K_tau_f = 0; +K_tau_e = 0; +K_tau_o = 0; +K_ext_c = 0; +K_obs_c = 0; +K_fri_o = 1; +K_ext_o = 1; +K_qD_d = 1; +K_qDD_d = 1; +tau_c = muC - 4*ones(NJL,1); +B = d - 0.1*ones(NJL,1); +qD_th = 0.05*ones(NJL,1); +tau_th = 0.02*ones(NJL,1); + +% Filter für Ein- und Ausgänge des Reglers +T1_filter_input = 0; +T1_filter_output = 0; +%% Configure Model + +load_system(sl_Modellname) +configSet = getActiveConfigSet(sl_Modellname); +set_param(configSet, 'Solver', 'ode4'); +set_param(configSet, 'FixedStep', '1e-6'); + +%% Define Inputs +simin_tau_ext = struct('time', 0, ... + 'signals', struct('values', zeros(1,NJL), 'dimensions', NJL), ... + 'name', 'tau_ext'); +simin_tau_m = struct('time', 0, ... + 'signals', struct('values', zeros(1,NJL), 'dimensions', NJL), ... + 'name', 'tau_m'); diff --git a/simulink/results/.gitignore b/simulink/results/.gitignore new file mode 100644 index 0000000..72e8ffc --- /dev/null +++ b/simulink/results/.gitignore @@ -0,0 +1 @@ +*

agnASZZ8+eaZ;H3pi?4m4iv}{5~~@hWm=!dgM4<( z<}93}V6~u>-^`wq0h_Mt2BII~}Fb zoV{aJR1M zC8B3o&S!HV%!pE4ZjPrlAH`)8qP>mGTlY(A?&!Q+dF&TbGLFyjJ3LAUz&neQv9ML; zOjSz8NyPjCBGO%h?pWDTR$9sRbM@#bCiaC{5lBXCk#ZBAa4iW3D@%le5zXAA84!$+ zGAI({kvXJA@oo_??a_g9&H}wjAX=O8WJ&#a!f677*l9yUBew?#bbv+bG#$`tHMvGVo<-UuFvC0=v7s9Xg=F%d6Urok(wh>9Gpkt#NXHtkv%koa;U)eAg{BN;~7z-oGe<@tt&}_9hW@qqBhtG8e61@Ae$g5sc8X zWVCqiqJkj?o0`#KB6hSI=$3g(fd(=o^QNBB*-R?SsxMyd)w`cM0!?wT4ZuG5?83J8 zDYxUgPK-kE2{IxUB`6UG?_T~|IlMPQt6eJ&NGsaJVqif3JX4>eC*;;!GjM2y$@P^3F3+Ei!2vl5>ZKx%*x7Dw3(s5wBYkcy7MN zTS|W$ndeLKf<&^Jr+)tZ2Ycp3bFy5tAhZ~ZrHnJrT;^TgojzG70u663|KV=f*?bdcnW&+(Qjn69n=4ECQ z2zrQT#0>%gS*2eIsZu!4iSAuGH1{5`rGry^M0*mqbTtjLt*NEsOdLXq@1>Fu975SM zyaHFc);15ac2E8Kz^RU6VM>o8YuBnmcf$a=Mr;qVY(9JAqPhq*&U-NQR<@$fcsh}e8ZnkQ>YtmN1&#LS65|EMmc-hEu0HVI zf?Ky!^ARcWJ+HjfBHTJ62N@>W17F87OlztqZ5OHqHOJ%wN zfnfg-yNG^2>%%bwBGvIkxgE)z4}p$EUYpQLlLUQ4nMxy;EuVU=J<)AIAU)nzHK`#F zvWN6EtBRbh23sU^{hCv!UklKNE-I8gdY5;=(RI6AVA^ePimI#FZ92GP?KD8pd*dfGEY(m z$g;TD-GJDFEH|=CNBdP%hwk-xKI8}YsfD2YvkZ#tuWdv|+hhNX-Fwc*gmYu8_OTbW zGxmqo!L4CaKo$>e{VwBE$_BPiam%@u={NR6q&?$3sHNMiO&o(x^XwnP13zed*h%mh zWZ!37fhBrA1r-3X9&uhtBpvN?9Yq08B+lTmBh!)W+pBG$V&qs*P5nrUlZF7j(2iW+ z*rHTnK<1WlrC4dleJoR+p>kC_GJD(iGgTBpNkPDlTj6a_%dY|=ossLQI_fl7j;Eb2 zL+)}*y_yOEvX_z5V*atC$mI3gB^rQGi8@qP$s&P*>y+R`P?VfzgjyGZ zo7$1LOHmlaY3f~c8AOso*}U4S36UuS#0HwkE!+|nacW7_b(tMsu65CMM=Iy<=mSHJ zJdQH~VYkX-zdiSwQLbu6k>qQM){B8{fhPYJSFBMmKDihL2$^9ZOgh6YdD4W({5>z^ z8y+1}D19h9go}sz6L;Aa8jQIw4!8C-bF$)XdHLV*oK7J_Qtzz{$Gn8FUo|fwY%MX& zbG+pPYEM4;9Jx`sevgQzh8Ixk8O4lvBj)56TLFw?()&0H$GbP1?H^6(l-l8nuY%1ELCxQ`#!j#7(Cp^pt6Y7;Ue_FuVo3F z`+9(Eo64TiWn$wk@sS8@0cKr?8zp!DT!l#SZR2wXY^AT=d*N{@cFo=&%}BSnvT#C5 z@A?u&sNXUr_H+)Z?{=wWf8bW#r?^_c=1+Y)Vb;p7GlhMXdqKzHVSRU(Blml6IF2^wtqFI)4$}GI&U?|`q9=X_x z1ER=X%FvAR#PJt@IIL|s?p)YF(of02QOY&cRL9G*y|5 z{=w}GR>Kma?0z7M<)yd?3TL$XVLHF`j>+*9>IG60(QbOxW|qR+SpyQ{TU-UocnsTl z>BG4JH;sDL@w&@YpcDx|_-+OuB)P9Q{`Vj3he(2Qk6Lb*)%JWMhj+ymRMY*&8oj)# zDr#{)=_Lc%j>+j5IclRMs45cGBMg(#Yi2Wo!|*oyIGno#9sWWG~BM+Af+~3p;|lxhp=@E^6iM=@a;pC zT|@60H{>SIVel>*g(*Zd06FDr5u&or86Ru8nTxo-D=PMg>Md4JsL#_KkeB%iBoeQC z1UExuZ-0^%gtj9z6u_fDSICJ(2C^)QJfn!dG|#%0E^Gbn51$jraCA=uI*^EV34`8l zXmR@youR|_Ud@2K_Jrj|AMRBObfTJ4;)n__0I8Nl67N9zGe0*Zl6dF&T$M=TO$@ak zBjHFDp=1RpImO+N=v3W}yZ-$Ry>=gBHpy?%iW_gjLiQsINiBtaWhkKh)b_iSm5rKJ zi4kf(N7#u}2nRyeTQ^b(An6TpC>b(THC-BZ8(9utSyYaBb(TzdR0(^$t<}-N3RpJf zn*npdo^T}jPMMg;A8gtI)g`s@k>uMH@>Ns?h(c#A8q4+3=?6tvqSo_aAseqO8DA0zzcp#LWC3lVjQK+mt zIR};eE?F&swyM(=hOH=;2<&QEkq#iFdQo6X1HZaR+tQ-I;h;EQLB=8K|4A@5Qz|Sq z*p_>-jkII}X&18qmbQd42FBXf0IAXfL}t>kv-bBN?1u>XOekuZX(*M`72H>LDiBiE zCD-|*tfDCE?(iPVGkT=uA)y$f)Iu|J3uG;&j!4SwVsf|JDHyw2Atov?w)qJpVrVi@ zxuXya6IEcbXC#2;ww-vMgOxxb*0V zS!Q)jim+UzhSHg2EJ`Z)ph&0Ey>fjd5amjxLM{--&M<=-o@2_QT_ePA63`Q4HmS6QTW>kD<>0~J=) zuhh^6A`v?Lm$+SC*$ZIHAul=g1w@~_l)^U7wgN~gg84j3+G@570EnVZr%@hOa?mdV zATgLClRzW}bIT{n*D7HkH(Ub|rI5OWK*Z6e<|Ytwv@c{*CCo=B;;^#1RNpV?=LJmX zboGXFdKw&jY zxt$Q7IE!ur!8}OYu(t5f%qVw!7G2oKxzf9e4!o76LzpOP%oY3oNw<+XEf-MdSfQ+C z83aV^YieoEG9AoH#U#{jmH{~}+kwb{{6t7IV~kr6F|^Yv9;KSe$07u?ni1w~VIsI{ zfryYDcJpU_EdOsWSQP7gu9RBrPDT#Qs)-uuSs z{x=LH$5~v!YkVzSN953GZ+p$JYW7=Gt8(HV69z9T`<5g-tdEV8dBh>k=O5T+qWkfG04tw-dp-F+@0xpHQv z*VL}6%*u?6$BKvqpjz_A+9N~xaTE`_WOOErWzykEtvfhe@qt&-1q9hQ}9 zIemP?K8esZakybXZsagtyM7f`p^`E@*&5I5Qqpp!;~|{^b8Z{t!|Kso*N+!jd9KR} zRdeJI$TG852Gm^TNI}`HK(>!UQ7a}oPMS}kAOeuN^L-PMkD*J?n#)-pFY&gV)B)3* zj{UhZsiXb$8xND0+fQAvEdS2eWn(R~$~BuSGdhxI4rIxEw{Tl3(u0}>LnGR@yQ>n# z0F1muqGIh=euRb?PWdQVbasX^}*F0 zgaQvnKZD#4)y#=q1|ST{S1h`X zhz(>yI;rm~_IV>p>L90b>UWCnv*`E-5bF6VX<;(;*9 z2t0oaurAThiVZUnY);mB(C+G*7V!K%(B3Hs`S3lA1Rp+4^;`GhrHT#;us{F)#9uUa zFb%RBSC_rWYyxfbt}F{wu23rF>fs@_T##K^704YBK>-MkNgz7r7OV>F*Ln6U`)3VK zr<}DwI^QsDW*~67Vjkp{UPH-4_?4;vt)Vg$jU8ikALUfEneA>h#0cV+sp<`Kr|cK#(fRZ z50Gi1a|9i=@WvS$2LSPdH$GQz;7D`vz*P@~NhMT@*VN=ThBi3xsT%G;EIp=@E|kC$ zM&LMRx{9{zRI3-~*Z^S81%4y50{~_3VJ71<5wTCE|cUtHzVO9N9WcYhrjdlwQH_ z8_ftD1VFrjmr6*u%#MJq@8FdcO0M8tqy@(1naC*03N<)j(v?odP;v#|Pd5%FR{)Wl zZo%{jtx(02S9A-}j9mkv5XGIt0KeXJ_01Ks^szC0vV)IBQI>HzATZB>SS*ADA5*uq zier(u#O*7c3VHxVSyD5AK)b}-cqPZSXg#7M#Qx^~)f(I?BTd1z40Ov9Sy*c;YRqBk z!))~s;-}J-ZdKi8ZW*Uyw=*h>?A?5BX33GY)en(-Px=#^VlB zCUGe)xhU{iWKjd*34Z9IkWQ_`GivzA z9p_2g;`TgA3VN9R^P#+rhlYl3p}bNKy7Yh1U;H^ zEx0ZYf?NwA;zMRnNhG{lJY~ZUke4hR%_m7xaDiB+`Y)VrTuxNs zV%V{PVNSh`k~X-UN+Qb&xD?(Pir!P1)>0X)CX6pUd1T@ z1l}3muxEa5fOiJT*fRkLNSj)xmecIY)gGhx_=eq^Z>jJBHJVhJ@OVforHpaZGd zB#mIo1{b$B5&}L=n?ymZ2z9RqB6)#A0>!&V!;E1uowbsH&_w82NdyQ5H(DR^Z)Mdy z7E0KM($o0{L=%w?hd{;rst+uq5D2}^BOM|U%Ip9l#|01=y{xyQy|-0|4HN2L?P9T= zi84T1?N3R%IR*HUVgs?o^9Gds@!GLKhF?b(I}lAz zQjho5&jIC!%PY!rm?!f_C4IVxa-(g~*S1baMRkG5F_F~T&7`)ct86o^lYr#MzS7&W zJf+)-W>9fuGHsXLp(l@$U>B_!T%!QrX1>It(^p&xAo5vH)XE-0VQ0A_I}bd>6Y# z)^_qM5IWUYmTCdQgJdn6sz7*xBHfTG-&bK}W-?MB$P-jnKUu z+YFgq?JB_=7QM6bI9T`A&k8ARVb9!VRraA6n;zvN(2U<{@wiTEBjuI9YHH_)SEg5R zH)V043drT+WnZyRB0LKb71kTJ=0w|?JF+Q}<4STl048#vqK9@;8%`I_aw!zv~ z#YlJQN3s5Pn z<(@2x3?}Yg4pm8--tN^@rHoDN?j((xl~{p@bR5nI1S0yuHdT3dXKA>YgAh`T(MqA{ z&T?6xY=y;McTNU+7R*FuR- z^#(dyfw1y=npu0u^UzI11fqxnt3*hi4(D6+wElr0ixn*hv`XRaU|sWYTy76nb%1$F zMPN@SVDwZ@w_JQrt!cF92q$_USU!8&Mrj z;ZD_Li4nm`)j*f}9QU3fZ6IVM0nyG`POcc~^9MqDF-$*g+cib2LL0oT`zV#7AMIc{ zm7*sdV?}_#9q#ufIf32!n_IWOid{&&x0yElDNCWSrQ{TIY3C2J<*sQVv?YY zh8)&A#LB|2EX~7N5+kD~Kq#um`03kpk)uY-;}5hi{YGpS0IY#?VstySp;7%p_8AZ+ zs!}KGM#wZ8S%ZIvQzu4tlmx=eCAh?-3WN@f?tt!%Y^O@}^pXK#rfN@vc5jz#fNZ0$ zW^ZRt^mVe>zha+6m{HMt>XwMDH10^h^mal8V)7#qQhxhP2@jnfzrxT_!2)ErXxMW+<%7b*VLX z&#Fo{Qq&n@*>_81Q5GsalK`urr+I%P>KD|KB26SD^Ccf{q`Q}l{&H`ilxIYE0u0NT z8(G=%L53+2x5v>}xRGG%oAAWkz*bA}=9EApRmi!G8v(hoW4V|p`~yXuq?O!=`T)Uk zT_X|f@|txFZltPV<)spL1h5xt^Nin!dj8aG0e>T1>7}7s#RSM_-LFg3;HPGvfE$_Y z0f593f0Ux`Ju1mXKplw7@X<_!WZJMsOGLQ}GG+;wTps#ORqvit7=lP<)cZ#$Uo5Vr zjO`my^B&kY{U9zTS^RmcYCazJ=f^kf6NozcfElH5pYMeXu%4 zNrd%f(nPuuEv8dBg9r){W6jYVt!aq<+QrEPVR*7lhKi$vTv)=0?ENr53J8HjyPns??2i`e4CKZ2py6`dpd( zOT;heCn0((hN0)Hv3(DawGx19d}mIU9^Mf)Cb{@VGQBWh-B zmJ7+~QyfXJl+J!WSw_)F6B1ruNJcNTj^z9$vNY(f>FlzJ50{aMd5iLZ5+NlrnNc?a zfh9Vhms=OXU?)51M%aUxh&Ku6?mBx08W>-0`a{CS6ue}46G2m1@6W*|)HOLIBqq>E zO&QeL1G|MMfo+5F3qOV#<}?Va=X{qhN_quOXh^GIMuLg!cSPjv<=X9_IUvu&ocS$qk0U18*by znE<(xSsLU;TAi~GrgoB!Q&P$p`l~s$0z)c<5D3u6Z2ice7M%dhk#b-TVlg)k9wI~vq?ZM`} zk(mPxiys6L_;4?s$=*KfhUBd~+1!Ucm4@#U9Omk0O3^f`@mEqKi6Gvy;)tWk>Irxo zStAlt%~{RJxSHGHbDwPu2xCQcYUD^vX-DfJ28R0?&`F z0V3?>L&VyEI!j^bm#1r?p*0`=0_5Pz-LTlWhqZ*gx)wWJ(*?H@AQ?7W<$Zj^u=VaS zSKg;ve+io5bjsC{2*kcj z=;2}d5>!3lkIsFEMvyH|Z-jk(@T-;Au#Zn$Szmz&y@=PD(O`svGhyWmPvaAC zvq=vSFKr}#XfDEU)A{jcHpaM-K^eF*zmUi>lDA=VVJ>#d1{4FP4>7kTam*h`q4X|Dk=tF&tKkld^ZifepS75MbE^JL!MNTHNm>0ct!gea|y z$XXBX^^LH*F#Ewx-=|5SoJ9bnwdW!LLN;II5-h9~DV{gU!Z*StOb)juqfkBLHPs1x zU$IXh?1GJZi<@yHOC;Vb!%0LdMbVTS2uaGz@oOSW>&r5^up+ru-0q3stK${5+X`zO zaiUc$gvin^k)z{AipZhqGrWPSL3D*U2uv*=n?wZ(PFgEgjtcu*=#_Pb0qL4mOI#r4 zQhVaTmeLBFGl3=`zgAJWe;pmRln_-u98x1vjYwYtGQIUZ?wvBla;Jb9)j4hzryx?B ziTeV|&u2mafn~D4lmZ}>F~#208>#ws%}${kp|Z;5ReB;z)2B3gB3p|>LEanbJ`ZLB zL!$FK>lU;q=O_5PR8|&cdqy1*g<0r7vOvC(sYM~j5fO_{Q8jL4OHkIdE(+TL@>jWV zK$Uu5w&=_}9{CdYGASuKRot9ND;8fR5en0zofnX&rhg@%>5Rze50R=RsWal^8}=!r zkLM{?nil2rVf|+~9OZ`%AB2A4kHn~U}o0;L7oMbqe zHCy>|A@MrwxFHe>S5-?L7(`1Cw}fl#w$+?m3ItvqX&XLzfKY*3t{#3PMXMll-)^Kz zzGmhCk>O`~eWCc)r0QiGv%t%wXW29X()29xFo;-Tv*K6a4&D4!iUO41l46>Z+Sy>3 zO)W29vvh9EJhDnxLIg%S4^kCO?2*897|uH%yo4#`+Usl3y+W;6M^qU_%Ju6}paK-C z?IP4~ zIwM-tvjV}Bk{x74706IXu%1gGhA=hF!=^6+hGxz=m{VJk#T>!rw+r*-KfXer0-(D_ zPgSQNnWM|JmwOIKZI3)RB9K)P=TjlD%@?%ep(xP>mstBLlYNWT>A{GWWMn-9B3qWE zSN3F+VgPwm!k}@K)zgLITT4la{@^fi96{~=)uLe9CA~R7s=j!hded%>;^d?o(UL^X zqI@5=EvEOu=N=UePHE~S6wjJ3@5V*vA`ow39P0v9p6f=+PiIY9D=v`N3OP@2PpA+C z><aukA85Jbkcw|-RHz=!dS28%@yF(6OIV>`sqW~@hV2pR!elEr)P9s3jlNwqVK zek1a3?6XDCImP+DIWGI_>N$+oHU(H40tE(~k@2Vn%gUIJ>JeX9Htab;9VqRPS;iV0}xRMzNVk%pCjs}4)n$Nd6*3JAq0 zY`j;Nta(&+xRKKg)@mS-?$WZWCo)wJ!V!VWYD^5p&|Hjv71uSnfx>1!Wu>KU{lCS0D^` zHT#K)Oa-BA<5x66*(9fko<)T5uFUSfk)e3k@f85U2X=2rBdE-QUtLBfdkKT~BHaQA zf?_qx$J|J$^ZCjc6Od3Z^qNoK{5G{`V6ryy5ZNY%# zsikx7A@;gf>*ci)8A5VhAXX!?jP3ASoV%;C4_N?xyT`hbsdnz`tQ`=fIwPfC7Hz7{ z`QvR+e}PZR9fD|WFqrByq=F4Ki1-Kt!iLw&6+3UM_G0|2g&7DpqSe$}#sh(Xiq*53 z%8gWt2G*&Kb9wj5pk~i@$TtF?*dr89B!uMt0|SQvYnAl90nrkiN@8S) zL6XY=#HvZer!ElG73!JjaU<)eSubLS5@}-C*iHm8L?N+BQ$dDZqLAbuHsxZEvjM^A z5F5lUwL0j{=rnC~4T3V_kcbyVqzZ9B7f2^yUvXuplppHEBA~MK`6x%EftxXSNv=6^ zK17wV_#fsrthC@OGGZQV6#|f+qrMR4GGGW+XMvzwNZ&^|jmiCZC?rHkDtS#i)3SJ< zegG18_Sr~aY~fM!9BN=}1rZw~b;Y%)8-d^%J=K38sIWJ( z8rF?ek_A9%vETt=%Osb&6A2-n1T*TWnFvuS@T+qQ zc>9&86?4CSC2GaY(tS5F*z*mE@)p3bo^j_miYYi=Sd#0=TX4L9%(FunH|Bj(Zli)v z;e8x30D=Q^u2i^zYyx)R-b<5G2dg&+u{9a(C{i#i2M3YD0hY?(>)2?hbQAE-wyP_O z1!)GodNy5dK~#FK(^MG>iSH9etybF!cV)!9!zZdPqUDdkD&T3}PTni*lb!beA6a z_tb~6OldM^vZoah^{kl3q1#woQTxHKhggsHgU>6{s8{BH;ZKR7>_K=Vonp~-TZjyO zmYD%tAWPrdr*cEVXYHz%_nF#NJ1vBE8x&n1%4?z(dK~z|vY3HTbVk}(Kqyf5`A{fR zT!`51-(X^BZ8_=ygd!$WkBF@0IgUgqVzzx)AK$P~AXVZtQqcl3gq%Bd3eQ!{Yb62| zZj}^GK)TkB#d51;FW?%BhgQ`d6K=;9iPZA;kt>`P&qZ13i0H3yE0FDFDoNC;YDms3 zQb1&D6VDvhw!FxBzO4*Rv)xK)b`RBS9t$2V>aYH`v{6o2YuoFfHSMC;7KT-$eRZBh z)&-?m-lj_g&Wx*~i~Z2Rb3Gw+(|kl2S(0!ged~=aQ208z!oXY;V$}f%1PB{rYdy7{ z2VKv1-jaFEoJ#<`dRQe9NEF;gLK=PSm(KWVplF=sY{y}&4>wfotVHvBlACnk>;DK6EBw4a=EsQim6 zs5w4tSuY*MN+}Z(g`|*VCM$JqJ^JGthOIZ~nHa}s&+O^#hv|)nJQGNY*Dygllb&kF zI?E)Omabq_8)D<13*?m;#|z9l3PHr-7M5(7x~;#{kXPbmWT-3vf0c4_$SZb|&P7O7Q~5VCy3#t1y-uB(vLjMkd=Lk`uPbm0;W8)HuIj*n4qNzSU!CkSi&~R7W6T zKD!TDnr8Ss^VFV`1{W|O`<^DNn{ULHTQP#He$ymJa31XT3!+yRK) z^2RA#LoSDUly-y~A?oXO^uU-Di?usPj0nUcU*}u{bKoAtxkfIBS~FzOpzG9jL>@x7 zbeNuZiF9*Y!P%J!bmc)f0z-Owb=t#Bq&g8oG7v}?;xmMWedWvcMkj$@pGNt8g+1oI zC}vLto3CUBSz!lxd$)bb$+<8~m5qdz%wg|4`^68AJe;}y75fCD%#2#yZidLzLh!MH zEQGG7IatRoshY6p3532x4oe<}n)SU4`?n2EkJL5hv1+6F&|tax&i!B-9#dwu`n^tB zrCN8EMy?{z{E_PC78P&iX7u9e?uSxGx~>_gFtU8jpyPzar+m#!;c1Qvi%BmbzC?){ zHFFIMBNt5}gtZf)_!t>d12W3{E6Y{D1lO8K=uxH#;sablyo=dYUNe|4SV@IoBlNWr zfl*V#aW3wuBEYj#Yf8@H-?Tge zGXb5yv6YCIfJkg7=mw;Z_aQAMaAkkJ!om2!3g2h{)CpoW2LIXi+a*m-fp(?p8hYM5wmZ3>rZpsJ@Ta zQtL`9E-6i+MqFA0w%>s$zB2MrGowbiNE_2Y_^5J_t=F-iQ*j<;Fz1bxUsSUQFp;H+ zw_eX~^;U^;3grc>Cl0ObK`)h>$kc*!M32g)*R6-%tCIAtbY1lBL~=QcsB22ovd0|A z5Mq;uDUtem)`yr9DRpG-1gszBgO?77NbVm)AzC>p2N37zPaTH2vW3GwzuFQxJGtHr zvPcf(x*c*RSZq<_=RNXkkCM7tt`Wp5%G=69Au0z$z0F3;jpsczNN3;|uy8?yM1stx z&X5xU@y|Gy%=Y$4hTID6grMnvU(#`Wo(y>r>aZaN0K%nab+|&0yoPCq04%zusH>F^ zT743tR;+2Z5-90pd55s=z#fwZXd8$&vvop$s9E#0NEtM%6w;CEIPBj`Pj{$_CbBN^ z%9?UV)OqBe%AvkJoGBkXs=Qt1kQg23B!J`p7Bu-JzJ&h~24Nuvn#buQ6iW|}4) z)z%8b&yGAj944dZRft^}^503*wc@jw;K88z^fg6axSx?P@g(X=L_}+OpObmkFS#0O zKk^vN?5aCAU(;#AK8|hB$Mp1E7@&`>_ct7=XQ!B2BSY=EDwo_3uh2gb?#|40F6bn` zq?I}&49FIei_jfYpp{yXF8L&&vEPR{HX4Eqo4Fsa{pVgyq`I2&H@pv|qPVvknxERJ#lXh6EuR7dvFTt3y*eUPoi zYi|ph%NMJqUQjT5WKY>a4rIvm$W5@TI3O*JdUTF2k`U(6qEEbqrDuM39db4Gt}Q=B zJ)Rymj+e2Q=hqfnqK@RKu$8<%X)eo6&&6XM?9dSAF-~@92r~)(K-PL{&07o$ys(55 zddC+nQ*SLG!*;J8#s2a_tRthFe3hVa@&mfbbDY^^j!2h;wK~a;^AZqNT-i-t>q%8I z3VO#&>Ukdl(3xQ0Bs$0Exv`DNFIGpo3D`?s?gnpJAVY{Lf@~eHId;etjp8qz8{Pqf zZB`^2oA10OW=_BZNPjb?fLNe9e#M6K-6BnZ{1`n=r@=n%K4wcI+sB4h1-i@UI`$Zf z{TTZd-1~xk0ugzlM($%E+ZtT>h2+~9srC)^G@~X{4$`&aoQw`+uBV29CiJsE`9q_u zByxFM1L?L++Ciptq~RZV;buqmg0A$%tI4Yp)H5HV+WG8dKT>HzxA{_@N)`Lo6R^=e z=o;a3t-lQjd07XxJkgQO?BCbqcaa*V5J)U>5HCY)fdPXUF*Eu^vgey zCDUrnyb@)&z54N+L@N^BE=6LO5=Jw`y<5$tW6CB`J8Ru4!UPz$BB4jD7Aq z5f@b$bY{vLEa#eNPm0-q%W?Bpri6|r2T995;@Nwc;L0#mKN z-&l1k+95cgtNqMcOZpT|E|Zq6?TAzrgR;{CZSBckd&z+o)ce{fS9Lu2G4X7T6A7vT}~5(jdWTAX>we9JJ8F`N2Q1%-Aq)u>mW42rZtd( z8U=ii1*Qgrm zHzIdmd&$5dN6MjB492Mx&#=%VcZ*0Ke1j<_M0{Wk(JT0Z2~d9Rv?G9o5PK}y)(n4I zI=~DIe_#UhlJh8w4HH=^P-ZiCOuJQ1G=8A6F&9pL-bsf^ztU71;I?R$q^M#G7%tk9 zF3vC5r;sYdnj(-cTBfts#}q}QpQ!qn@{shC?FgiaU1|#%h>IZ|L>>|*z-j)b+=0EO z(LY2&;rm#znWSX&Qx0N~BcU*uTo7Z)_t)DI1mrfT%2GYoxPDV=Osixt&&ussHG_F} z1pyHOG!MQdo(3M}wa)Sbk5W-Y81Kt|WH%zmN*`yPtdS8(J70z}&*9O?m9fO`K;c{O zBGdp7k<^5O0mDo&(_HLJ?ibVyiSv*3nJeDqxM5?04`Ef#=4BR=d>3YMJWZVJzS{HTHZ-|gl;Wc*m z08u%z6e+<35;}DDxn%3%_PC6Y4+gRH>0gB+;KSu!iEL3m^EkXsEd40u5K4(|k0AkU z$unIa->^?1(}-8$RzJ{@9b<`*?~y6+H^P*X2WJupoG>$6rrk)Rg+8zJgAABqOGJYM zKpM^Zyo3b6?1OM4LzK6}${Tx%M^)0K0@6fm%(1WJYo<^JeN8;Vl)*ca3zk9ztza~U zJfgPpP~cCJ<~*-UL_SHmc@=TjR(cD7EU_s(0w82^WXFmdsr19XQsn2wB$K()v;+_$ zQh5XuRnNqYbZ~uMB5tfJw>6M1B9%85kSQ*h{jL*nCjQ9tIWHxdtSk~oWQa%Qxa+*+ zIDtIU>YoTAi8y3g00a_bWr?~n3yB-d%hn}mPF;Cc@_DXm3b#C%R>_g-NkQMm3OkT zpx})t%LH$jfAf2;Jm+SW*8~iJ7eaR5k+-w5&I_)wI}Zrte;k+ntn#F+Y>h+&%4!@R z)~w7;?km!+2GaHPkxwV(BTkWlS>@l0>osnrrZ90`-yFdqJgTRp0s_g2RUo};Hn~zj z#rAe=a;3zHV*=T_arKXstAh8FB|c$ay??33GB0>#`z~fv77Ex9FC>K6w=!WLX-;$N zH_<|(zMif$l(>F+0-KyG%gNa{pahdRu0$XlRLf+83EgsWa(t#us^`3o{W?G(K*0LY z5jOjEzKqvWr&A-Fa81mPCe1)*{x;%GzO<}v_b;3cjD^VnBT9QDPo|7w} z%d-)uFcJ_CJKtp}Q3PwkUtuUwBu;AT991Il#OZ)^BV!~o^}!ton`|1RNxu#PjftIL zeIKPJVO30DGb!=lXU=Ox-2kWG$I6gvB93Pk$kys|zyh7_4dfu0^ARTm4ZxDYQOr3+ z<$yxwqX>L9Nd^a4(B=LTlIQ8Xa>rO}pHoR6kp+W^#1FaCR|3$o;y7mKls6+z8u3H~ z$Pce85%?}3sK!hLCPN(J&7576Q_~)pAk*?~tW5&wdbq7dAX5*|gK&!M5hpw_r_x8_ zP-x~9*&~k6cYSH6oltPvnfJ0edooD4(X#%Ixzr{Xj!xDln3K>qfchz^K6om7d08{Hp0 zlspp0Gy*dH(RJTYV#ta!%8;J|h&97#XAD+{LP;R6(;#{Z8K>n=b|c_z%=Vk1q>r`F z76!jfLeFMCkQ9TLuMwGJofz^AkvUi+uqFaQgz54Gs?$KHC0G)HA2kloa_&ol=y1q@ ztnqfxY;iZDCqk&pMSRFNp@zW@TgE0V=Ex7-jA zU)I03GesiJSRk4%+hB9cF98W>dA64{%z37CJ9lKI>jwyRu{cW0R;EZCdLodf*Sksr z!%7UVSl4xQ$xL1Uf_(xhbPC2PZVIG#Ya}HR%N=VZ>!KUtrC6&CaOc$a*+Mjl1ucBmR8oURUU{qWpY-P2ZAz2?}N~- z7K+d6RYeSWiS1QM`am{koe5aF+I0tH8M)3i+q>F3q$=YCJJyq2m2tAN&odF58He8T z1;g&ED+h0t14x%m=#O5-1Oaiv8yl2uspK}OR^4enov|wm1?HUY+b*5UUbRhb3b%hY z(q#HNNntTUqh%Yu2`kM$OhO<{rl)sjWBrVkZ4Yjs=Me1+1rid0%@1PXm50^6n(AKQ zK(`EP(FOW5FAfXA&g*C3@ ztnrqIGgi);JQ{|$ACFH12lC`KIf$Vg6;$l=))>lBVfPJ9A<6-0hsW7<@7Sjh`!W1U zk=n02dliqaUD(gU7|K$4Wi|qtZ^?9Ph!3((GTjeVr4C@pOJ#@tg54x9 zl?(l?q0|=W#NJawsVyw&H51uN8T5Xis;+_0>9?EWe!S`xFE%9Cm@MVNrPCZ=d5w}? z)`^h-sd|*_xvVK4#(Eu`lci~KjXfVgwvb$cpw6wg$pCdu?n~RfYbx1gWh+1;yFN3M z*A)BXRkL+50aMB6J}#!xUtTGTKw>`A9M_bmg9RToQiO3D$8LpvEv34wk}C3AN_D}+ zdk&ZQA2jInhD(_(Gux378CpB0l&>WR3GSTFYRcq}G_TfDW(%@e{goFTBy-tmfxnl1 z#0CZ(2d^Z{wdToq_Lg1BV$l~Ops6~)h)e}GhY-ln5UqW#B?`y7PV29)*r$*!-*Zao zP-YAK+?J*&Qmy<+d*Oj>Wn`ag#Q%6z1ppFC-ZT$l(Nn``*`c|j=3Lm6TA}=xSN7|Q zmQ@NIBwW#zXxq=x9?E}N<#iwBzhHIvj6HvQ;Z(x5GF|4W9}A=_%lsgsZOjwX2jZd%c7d)fBFE#y?5=_mkwK`% zt~3gmcz5ppQ!$D>_fUsSA0ZA9%IM7{y5)*PAjZ1`EIKU;hbVw}oObA}tuz-zczk?r zrn$^RIR@Z#;-16YIZV5m<5E`3JT>2dET#B*vxeK&%Y_=TFV3-J$@t z>W-XCl+`kii3Eg!w3dQCii=%LC!j`Q4$I6QlLRzX)+?fjdI8U#r@X8be>M|u6mF!s9o3d zwo~O4MtXmMY+YkUd{mXfm?uvdi0iYM_7PQyC@+x|RmCxC78!`9Jd|0}*ab4RXzcik zCjZ9Fl7G=^3J#wXK&B8M#=$0pKOWV6fHa3}z2}-J6sLyE$2aU#$Z{P7PjVB{VrFOH z8=*r3iqvg5Mj5wlBZFNM2 z5YV+*TiPwrmDPe6{iumh_?)Vu(M`6aGfSwKPsm!x*mU(o#W-p^BdKxWIs{r#=*FnZsGxzOhSboN^nXmN{In zVS5Tft)@eTVFvb0}J?2Ty>#%oPX<+wmTd)v*LrIYOM zh}rW~Idd0?MUK5OF$O$S7H&Ek9n!TOk@GfhyT?9RCp_SkR)a zi8QSx2Zuv_b0~wX53-4uK19B<2p0T$JCTrH;pG;seFr?%-}^WXm28C&m&}Yi?Y%eI zn=URcuFG|0lZI7hW>$q{Zz54BLS$!`nU$=B(us}pAAK%okCZy(JHaQtAF95(gS&MTs$-}Cip@E;&%XnPg!s##N+eZs zmJ@t%^)`IQ$5XW$N0RE#mc&`@v4fAEHqHhf#aVqLJw^8Ox;oUx;RSC>6eZ>ZlIAmfSDvh4S~@P*`*Tm(HX-Fe`jcZUc>%l&GlphVZSkTNd8J^}Z-cp? zIT=a(S;VL%W@D;CEDfG}6vJtitVmo=`iNcO4K-por3%?OIibWs_9eBN8kK%ky_7vx zyuRo5X5mx&mqal|vvbLVg6)#er;^Y|?TSJ(HUPOg2J3s!h6XQ$w<(>ntC`=ORN6w{ zC$|jDYU{=C+`P3<+nPa4vwQE#&`P;J%~pN%$@5@8dt+2qy_5D4cSFrSaxW=uGV?y! zIeq!em?{thJxdlybEkJtx1+H#SgE&Y6xLN^$7eNx-DM{JNzme|R`Tbwx@5F%rD_$0Q#onl;YyxYo$Ly*UX!oCaEbA*7JvUy0n6uQk_sR)^j9eT-wl5q#=`in$daLhw(m7#H)R$Bp0KOgy+J_p0szf&%F~8FE0GDbdo5BGxka` z_0o~Vt3#tP8dEpCi8}YEm0nF`q1eRz5zCEpQij|iRM;q@Eqsy%1?mb7v_FDvu&J$!m5w|P0^0;fWT zslFO>@|9Y>?d$_$?cg~iudOW$1vrM6!cUOdv*teU)V{b|DsFcya% znRIh%U!EeB*3J4~6K_rVNTCi5!|T2HwUnRYjY_=#;zSH>J|;s|%SsME4TSsS0^ zR1F$xV(h^!w!V5j;v{-8L4@X1f+n8yy;aw~C<<2n=mS1Z_4!1HRhYiH54h~&%RITp zqzXB0{JFMbEFU~=sHdEz$7qxZMA7N0hc)c)nfDUCm6dsibB5{YlqJ;z&1d?T-KpBA z7(zWx9t&v}RTqsZ(w%8N#fiDC&q#hUe%75QOE&Fn<-Yi`b+ckJb7HUPo8XQm$g-1Y zS!>Y*qFyIlQBp#h_VWuF0log4%7#lC?1ctCWIUiknu%Wh#+tX(R4q{2;7-3BXJTaW z+xwBL0?|#61iR}8LP&PZh3AF+bT{_(IVW+xk^G=KIX-@T za=!|dwT)Btj2LUOIP|H**Gw2h*fZt3aTJR3DR|uCP(hpA0Nho>?o{l$=Y@P*worCrPDe>F za?%pi?4?^Zl!2&cT3~J}?NYoNNgKk>ajcFTzei&{qq(Mh?8quqNNMMs)F_5F_|b=H zO{f!P{>>YWSlvL9^6N>~CP3A+y$HMU^XWZ0=sC#!q~g5x?q>n*+BcrU;<|AcaI9B% zr}nP0RkO_MV--&^2Go@vk9AViw|Ig1aE^}?w#AcYrTD;GeV^~_f?{Bm!<%&UrKGL( zfEM#-0g0>AbfA^oA@Oz|$&rw;tLt!YYs}LUhH5LrF6Gr~$uK&DgZ4BpzgNJ2v8x{MB!N{d3>~+CXlOAzU9@Gt zK^E-0fSJM*<>f+Wu4m)S4=<06s3}mfb2&vPPN}l$J8JJuxoQY0!eawW+SJ8+&MU1*W z|7}@)OH^%4gnjYIl0%82NhWBNa?qJ);OOMT#kH{ZEeLmEd)>@e2fv6%Gz|$Pg>qdmMF|$Oh`OpIwG)imY74H{K3v zXrBNH(F89%*ZI|fT~JW4fj^enxuNHhTyj8{ z%0rl$FegMnfPyMo93%n)x7Zp!)_uJp*S<*v3rN++%2#hkx@ZiILD{-nY~%OZ;TM1; z{BpF)Yijm^)1|E0+cjG^V{X|6u#`WU<1OEBH}^UJ;mG_3u3&`U@r`stO-FX22Mw0< zie%S#QA<=t`dO^vQe0d;2aI##Zq9zjFnjT6?^{0er#YAKOpI+;f=DklCNW3|+sLwR4_0dK{%@7i}E*fGMVx*sq$W zZTl?Xwk}QM>toZ`4ZqQ`zu$$Moy*}F%}P;Kde)lT<|(3w6SQ-q3I7(=U$~Ry%|Ok{ zzq6y>QRZi%w8c%-hT~TXj7VH*!`eL(|I`krZ^JEsf(qqJT5L(i8%bmq;nbulDCO2j z9;KrRw{dCfH>)^A2b%7V-<4hHlQnU58F?OXL48bgD>@7@a9{6CWEkIp@6j`g8Y6oZ zGlh=u1E{*J-FbQW`q{7!Mc##X$`R6P)=Dyjc-jRz{UGv!NJzQxh~yEE$84`O zISa^Yp$v@$;Wu9T?C3TNsF#~jQ)hD5o(wUMPpgtL@SX}xKl7sbyt-8uqxy(9|LHTN zH0&@jY8D<-pO4D+QU0&5y9gX9m_W6i?;RXARX~IZck7DJeD!Wyx{si6<+i?HqbM=) z;F_E2`^SabM`P3U3fD-~12+muznlf$Z}vdB(kJR*p{stHEU=yX8g{Wr+OVR6GxW1^ ze}TyG$T0-cXs|tAWd@&LOPzzM%)Udru=|pfh3XVo?0{$D%De%)N{3m#NcjflY&U1Q zCC3|>8?Vy!U@L)JhW=(evf5W?8TV2)a{O=4W8$NGUhXt#DA}2>Z-n1aQrHOab;^F< z=asj4>Z7e8I{bLg?r@|AO3>tuF00dUiF-X8r{7Fx7LNC3Ql=M6O9BJNA@QtO@nS-K z|D7ZyZVh(Ju$2@V<7&fd12Sr62=W`vbCP<7TEm)0tFxTgnf^iMX%K>EH+H0FqlG7< z5#@58xU{6SB#`R94eKR1AE=Zf`C9w^6W2XpVlpY|NW4DZ}l{a{)hr>^Ll z57$PaE7>AHP4nG|3>~p&^l_~ys*h~Vm?$n3>zbNqUF+FDUkzOFXe51mjCS6K)i^Fd zV7n-vZW*4dRc_uDVtEm@ZLrEOUL(Z{zFNh@!fO9y(B6pjNoh(WhCif(V zzPna!Lo=zWLycvni}^IH8;}}%H#LVfX7^#o0K4%qmIi0`yyq6xYYmq(WwpbN%%4@Y zNfC=JQd+Pt4Vm?k#IfoGU-P37D(?*BvPsE$LlTQd>FGThjH6STs7;iF;xcqUTA$XN zV;+k9K>@>ggr<}V~{yk0QGg9lS8jkbA#g& zO5g)kpe0;^C8h7?U>jFq;gt!?#^3<|ITV5xA0Cpk>Gn!RH}lUCKwpN-$>1yF__f z@u$9k>sWJ~cwHtqahj_b5dnRKS^UN_M$Q_sBvdkJr(T zp3{{&9Y6?;sF0NsOiL7+$;?}5i9Yv5la577ZzgSY`Rn7_SLM{&!e`lFl`hN@C9aWu zac*b=2pRek!goWp z%{`gY*z!yf%TbDo;of}PS<#j8qvcW^R?!OK%wXC)3QqK8?9TqfI0OqjjdH{)KfPu; zr-m;*_FWz#GRZEvv)3E_g{a<7pw+(HX51&Fdo3cKxn%_BnwKZf$!x%3)0!T+nUBA2 zY`DZUjKed3`E|V7V$~2pQtrd!;BGoIe1_;<U(+bh&V}tc&y}WLbFOpIRCA&hC7f#`CSHDz`u1}X1VmHpWy(F98c)QV% zN9ZKuQxWrJM2UWMWV-fQb6-!s=SL>{;1M(()>J)QEK7cT^Ha0l#5TFE+R^5NZ*(18AAA1D(s0k;ep^UCpC(^ zRm9~z-n)A4dZ%%IG~3V%`i#_Si}(uM?!H%I+5XyF>BER&p@|Rg(NE#L9TZoko((=7 zG1Sl8WE&_>+|4#-peisMBp*cuHMb#&-KnZKk7{dyhIXpAjg4a zcV)g@J5)Sl82>fa@l3A24E3$I12k<4@)8A>5|qulw8^9~rfJnvpIIdmlt2`r>CTJp zORrjv+f<2hR~np3r)_o0$%#M{_p0lt)GS!YhVY z%W;q{7_U;E*gE@-bT5|mO^ZH zwhBDdN-h7H-gcUiJ*s|2#pBN1B(otW3DT4<8<4b;%TBe6-JPoE*cnlJocdCm{!Gj( z!1l%}uOPNd$B(zf>fL%Am@fB1PWff5 z13SyZxYw@PX36Xu??2{XiDIy zm@B`mg>_UltRoOh1zW0GUD}-?hy+&3n^aei1MyspMPAJ8^6fZqa_{AMgT}(AHM)K2 zHlwH8%Fj6ti)se9#VfE!QO$0WaXQrV#|Rr3Jb>OV+21BX?y=R|oHogY$9SPCBV%vW zOOm&CGUy75CxO2^e z7_BU6Uh!~AO5_{fZ#+z#x>1?mpmPvffcT;Ih7GaTgsY?`7c|X7O2~el^Nc!CUn@ z8Y*S}u7?+fywBZv6CHT+s1@(Mo5PB0w_mEBC?dB2!Ht87+}X9=_9n!w>%R&ZkR1v0 zvMG$`o>yDrqTvJ%{!c8wZ}F-?e|+Rrs= zRC~GfeMT2sHLRD066zY)ZNnZ1B@XdWZA1?(-Np1qwWu^YnN3)Il{FLhac2KqYeKeF zFx#}{K2VY|VY?@K^(`fI9UJPsa^k~~YH=uKW#DVtFRN0qE+JPU6_>-S99M?KTgs|w zhOt&*6n-cvFGvhDv#HU#YgM&;nGl!@lPP~4VpZJFx*r>y-0DQ{3Rbd#`nAwPO^2xC zt(@+XTS?32(_ec)dp?*URYC9c)z0;A1&NUZ%MuF^TbGEP1Ql3`XFm}{V_3z+%RD)$ zCN~LnYg`*aRLwU<)IpuZY4v7ndNt5_>gYSr)$*+!CSl^2h7q?h*3ZsBi^&&rCc$kI z?_N6I@N9HXZNIhm6;n5JSN=-S%<)d*_gX#dtMv3U=iT(rA}H8{O-7sLcBuu8Jpo^s_nN=!fh|mJ#J!%LST=Ik84XLL zIa7Axf$`q7MN_};_62lf1IOwV4LAbV=`mkqctiS$;9QP|vW%BKd4aV>oELS0c{gSr z9ziXdEuK8KT>g3`TdvdEx|hXT_hWF4M2#z{*0;_i$&X|wrb`5UCU$n+_jzQ#y`Q-D zsLTH}gn3X-F7f0v0)J#$)t);AtNLv*8oT{oJB=o)#E*Nuj`l7tp@wkKH?;R|!g-+) zS*uROdMszuhdcgAzj>g7S#{lkFY6dnc%J`6mmhbNKNz)j;eOt2YtT-COvAVe(}o_n zxWHGNqF1NjRLiY)F!cdpgr1j*C%znZOndA20gcc2UPr)~i|UHuTx|_CB28KVMmMo8 z5!bjoJsMCc)Ox?sxq*_Vq*wS7ZD4qs?aop_rC8Ej-VCE;TjyC7d-okqJ=}|cr_tjL zcXNlH()x_&3BCU4HRHJo-hQ9<^-I#ES*-|fVfET{pyW5hWXm0ygN2%)2Cq+zUq8!y zRNB67ZhEi_&XoB!ZXLK+bKquah`D_FyyVAmmmF zYqsp9@r4fRkfF@`*3F*VNe8>5LA(2z-;Ozb!N~7_Ydkncp&0pPKWKkJ=3rLl>*v*j z_0h>aYAQ~R9R1T5uJLfel6)z+t_AN8cr`RMc*vnMo=#5eu zJtD|cv+*FczTHc%OxmOvJN+$HW01Oyv`5x^b&Ee_JlQ*2%aaqhMa* z`5h9Be#uvn$%dmQ_}!p`{jV~Oyr)+tb$~ZTO@3SG2AvzTA6*?Mq~yFA9|i^0u|8(=Lj32nl*oRb?g6GJJi;=pZTB2+sy^j;7IgE2aghHL z%B|BU(aG6C+wnG;yIG^klo6HNjrjMh-PZ2|gAPUyh`p-Wg;1_`9(WuIi6I4!ur^Ml z!XOBU@GAlnhC_Z9B7PJ~N`ei1+)&_4NCy;H3uT8!%45Aj<`AG7h7c7L5duMlpn@!VB2yB4z#slC=-gp&#JQ9xr zK?xWDO_Z@fbEwGSiL^8+SOGW(dh`GZ{Ve){F<}S-#*&giZvb|nL-agAU=6gL2gsb1 zfV>{5B?#!jlh7q8(A$ru&_9~~XsLk2BVDi#KfCyWy%q|Ov;%5DK<<&y*Pk5_(EC32 zcf$NJ4N|bqB`pwCTKeZmKj{h(Ku?79a9V$Mb2!Z({pdkqq)-@P9I&1!sp$6uD1sDv zI1jKM6haCm5M1w<<^=E`&E=6EC<5ug8cJr0S}J@7Xbj5ZkeG@n4_h4C4UffvpobIt zjxqrlpf(!kfmd)u;y?&duqN`yv5+v>7;T4l^e`tCf~~2OdlZ5av(_ z|B5&q@h9R?=pUGa5W)o7|I3&3pUYt)1P&d3{{=!6K|tj{LHwu%LH?zOzt_Wsp})`( z1p6)p|3bdQ+TUdFC;bT`@CWh#$_z!cy*&z0O+XjTNdc0f+&s`OSXWXZF|aKbgF#yU z$)H1t`zwbGbk!~?7y%rz`4OAw zhrc4<#qK`}jEE4>_Fo{ri!I?lK~;Z+LLdm{EC|R|xhy zOTHVQe`5)u_Wx59#SmayG|tu&WAB3U{*^O-Wj8_X|1@QX_CXtoLH*s{$pdQ>urvt( zVvGhWVEu{CaXJ`)(z!?5gLa?sDy2k@P90zO< zEQnyND+=s^_6Fk}aVQiR?}Y{XqHtK=!&xb#T~Kfk^l%0EMJazVn*anJg(FM~k5WVd z))xg}_p7m00BfRL9q^7IF%eN|=^qQdcN$6$qp9z3CJ?+|=Xz6ZiM$DTCS}debB5z~ zS09ZY3kE%}y4OaDj<6VcQeCOnuEHy*@X&LWPE%<-+2jmgA1{xBk%S7q5Z?aK#pzLt zmPvnU*($$8($jAYLZ+W>gS0c!=F{fIbZ|TzQSxV$)H=NR=ELrtZMqZx$sj(4r>W># zfS^WPSi}>h9uvVPoO}1A5b1~8H$^guw&ghmq~Y-LJ2cblFsx*N*Hm3ws5Q*u1YPQ`V>$pSesvFks)KbBTiT=OHC^Se2%les(srWB=kU zc#G{Oqgui8yNRRc&#&VBC_R^3@jAJqg@Gn)%_S>^ShPn?l`k2#$MwrSjq2T%#QiU{ zW?$6kV((H#O+0w_yi&DPj=jPb8|kWI&KbomkyFaJ{_!=L_Pf!w#$r-1FQ1odfo_UV z&2Yj{h4Y$<45hzl)WVa@CD@Ql02^FOYdzd(y)K4I7jvG9#lq-Wq}oU2G#qo>dx^Qz z{&*ei=-K&u6!U#4bq|b}BPS*p6RJjMJ&|=2<0F?DuLPdY*rYr@@SH8^q;>NJf#)N4 zB315EEK>Hh=dHafgD25^bYalSd-J4IIbq=A#K*C>Reo!4UO&q#Nd5-92Ntf2^z?Kp z7?=}udlQS7HWBA4T;m0~`C&x0#V(lKyXj-}W-(`GM4`y;Xd0IoY!-`b+p$z9ZDr^c zym=)#K@qljYH9;`vhs(=U>dv!7_PV*QjH#`yEfRMo}J9`E}^wAl&@t|wn~vH#5Z;(fSMPQA*d>OQ@g zQk!xj4iII~R;c>9m&k8N!W(o%WSYnLSB0kZ>K>Jsf5;KIzuFp=cKWy>eUqkHn>R~z z@BL?Q29}z4{nLx|TJx^>Kqgjv@Hc|A-{<-|ydO8E_MT@gAY-x+;==H%*d_BnyCJSb zcTA)Eg9M@BM6@4GE|lA|e4h}qeg-*37ohkOG+BGD&O>|0D$ z&MX~1fs$SbZ+*xjQ>G)BxtOSOVUzMx%Cn~gkLq_Xp5UAOYLNfUX#TUm^@rsYgM&mx z#X!QM@Smm=Fo!?QrYQV3vq?Dp(`Uu^>)(x|#&Y(dqN`+-6qFIC5=d#30W5m(I)?E){<`yh00sEdv^)qQ}g z9(}av-1vQzMtYlJ2mla3_S7ceLFKW(Wh>^}b>do)&nB zWn~Gqe~}zR1-dTp(yu~(HL^;9zVepkC(TAoKY3RVglQI?a%&IC5KYfU$8N4A8&Oe>Eu5e;HJ2|=jC59W3iY`)}8yo+~US@%46P%o&|=DtEtK( zVv};Rf;wov<5Qh+C*hkMZT@K4IWA(QoL=jC$lF)4T#T_V+{O1T%wjU8#~D%}db0*H zZV)3hX7(uyrKl9|Nxh9vz^fjq=}dhL+3VXsT}^7>AG}>dtaluehoxKb1d*n=`3D{((;E>g;>JVJo4bDRmx_)+HVk^{ zXC7S5u8eOO|N7xkoib;XP!*jETcUJdpC5(b1KN_iK{kCI32R|8h&hL&{3_%U%jx+n zmo^&Ka`xb-OB@!&UU_p1^J>ac$oszxvW=gXxJ)z#VNebsu6@f<(Dy1kTYogpd3{OR z=+aWmytG??d)c{1au;F zx?aCVAc))z16ASQVvxIR&104aw(FD*gRU%dt}KZOlYKWDHckf4&m44dJ$u&K_9#1R zHO=~xX?#kC?t^>p3-d19U3Pr*F4ZKCI>S2NvM}piO44meEk{{=aBy%>VsP1=;PBX3 z&P|mQla$@N$7L9zV1bic*Y!7_kdNNp8h55o@-%Kcuxd7%Nbfz*dM6=+b$qnR!H&MZG2peIs^`|=f5$`(y`NyDWbpuAHOS5mr{m*^a5S`|=HcZiS3PETI+oLi zTMpr(+{S)PwdJa^Qfwk@WU%M{^@x$d!Tf2w?xIPVhqeFhz7t>Hd?QZxo9`OiOJ9+g zAG>aQge7G9acDh=lh-hV+f>@eFFNHGJXn$|hSH_Txh)5G6fEt1iaFSIx`C(v#7?JT zeGP;qs8CXvgtx8(8@-Bo>0buZyb*At=!HLojh>F{S@stff3QwV#hSw>mE$&Y zH{O*#V`spdH$S?0+ibXtzvf*!Wy}h3<}3M>Gk2@rVFy#UP9fa~LvvozXPs-?dy(0u z(=u0n$^gcZ;vqP@^<3yfa0R4)aL7Gxa`}ez<9nrC=68^M*$N~rd~s*O)%LuIdF>R{ zPj58z)a==PLm70Quh`GHhp4<>-v8BtEOsWhx4+czoG~k1ME~o}SW-~Oy>ivgUE0ul zW~$e@+~@KT0TCISd(y?w{GBDD(5>Do*Bpaw+nvbclfwIj&gL_E`p!%95XYT;sPaNh$IgqVB~V9u_KMNC zAdnC;uFg8n6^~J2P5!h-edbM<3biKW=G^G;4v%nSsJZmU7Eu5*yp=8RqFV zu3^P<7;g5Ng-oUAB?9bheI!?2zK#-snn~jx;M%Xub;_m=On7v?DdAjEELPT@zs7v! zLwlvQ_v<8T`^W~ei2IKp6xLnj>Xcc&nIC+?4Nt*9w)K#g+!wg%gF^nAu!=~IJ8dQY zAaS05w(-W+ScQ<02i08L$%3xpDtY>}p~{}L;x*3|4d=4aj?;xiQxRrPOu4dbfaq$JbvX#7ils9`C6|BrcX~w=XFki>8*`JH( ztbU>yL?)Vb+Be>Ut}~suM4l@620iuUTQ?KqqF#gZgJC((X&zm*jB)B%O|T9@eqgJz zU*s{{)YwCVtc6QG`dZ|N(qEaS8=Lr3uljDDRL>l%*k=w4eaSPZ$#Id*DPkn4j-s^b z-rOdliigwUOqQd~*TDp)A*Sh?@VC7ON>{jNh%vwmg^8n|2`=$sULi0y4Pz>2FZnJ^ zhrLuZp*;0!7@9pfZhUO7x>rm2ixrV*`MqQgBjLfrEF`m=It6!RgyN2bug4BZat(Zqle%xBnr*oMk?uzWRtOIq@ z_umo;msXvO4Pu)bA2brVUvT!d`-2?quMy6tCeMa{)F-)+tadY4ZZc8}K}oE1D7 z3WGgWIOdzc{-S0OA_ceZvF*)%)p5#C7hc(yW*IQHRMSi82cB+pudO9+-etS6UT;3x z<+yA`lzM+69ydIs9sxDviinccPr4L0->3IRipe%_eCE=xhx4k1Ij}>TI!TGnW ztS)eYv1EHEIGo-O{e8(hOac7r6#YyN{26*N(bD`GcYz{=fQa{xy_uwpx7*<`j2i~XQGmQLF0LNp-csC$O~ip?LNS;dbO?fXmf|+i zx&*>wu`bSNJP0NzCI}UP!udh=I3R-Ng~d68pn}5OK$kc>dvQG=J@dUo;7p3!5s!Bh z2ZO!5yac`Af>@jb7%CiTTibr}2xO!Xw#ydm=ZSqGmR}aBMoCJX& zGZ<|Gh6+N!KL`35%|l~dL4<*kHds%*6t|}*+D_aSDQa&cgn$W%iXlY>pip~=00j65 zz#$?)5YI*!AtVC(Ih@-sX#O@HPyq}G2j~DCi39m3J5O5_PKsOQk|s#S5$l2fo)`fE z>3oC#(|4apdp+CqV3BZVJ0m&14A4MRPCk=x@g#;jC0uY!1R8$;-5Qm8J zL15w#h$Q$gkO1?6rV2m;4~PK%7fpYG{G}-tX8?$VG>?{?fu@{1Kghrl1=2#|9SIWQ z!4Fb%wG{*zp>Q4q28jv^2|@&+Vj{wT$7aE!N5Bs@HO2pl$o+3i ziJk2q2)lXWTn_ci&K8VvK@o8C00adJU~FeAZjZ%bkbrg|-Q0knG(d2yD;SV!ZfQxN z5|0MFSLs9Tm2<&=KX5@4v{Bpz>FOZG?JZ!3vPXKl;JKy2c#Inu?*;>6{x%4EF>6s< zq>wej4rya;BZNX)+lwM>kq8tFhJZl@fh5s)rn#V{zaJcS5B_t=e_-ih5nx0B?t=d? zQPQNK|E16WUPpi0Wgw0w#qC9~x_^tP{gPt+X+U`X$$szxTMB|Y0(>DTB#)vvK|>&7 z5ExVxf;d!UZU}@M00R{M{{rztX?QIDA2ieA58br*587$L3m{@ZkQ$!`62c=2} z0qKZ<+$S9Mc-niv@7_23lI%0vW@rC9JF~NaUR6?>9m2tlOW(Q{o`DMkaf0mcTj2@` zffW&U=4cBL4?s}|OIzBY5l9eN+QtNpkVKf;!x17PxF|FdVPcExn$&Hm6pnc7IC)U$ z+PTqexRY2NY;)n#g=*}3*3M;wH=ez$@4FolU9arr1deK6D}%zAg8PK6L#$Y=1OYm6|d;SH-BSjy0A6(R>kYv7qGf$ zc*$a`+f(-N*5!}=NYT9GN-CP?U%!0Pa6e9P|I(?!C*7OA+p42dQM%rLb&$v)L%VbC zD5o&hosBG7Pl(0uS=+Lz*?ZNZBpbS%Fl}taMj}EY>jRjn)Fzj_(DnruQ^F#&XUM|N z3l!_xvDca^BJ}N0Sm~QEXWbd5uXXfxu7Fdvhn06hhoY<9TpgMYakKy_@3YvC{fp zBDB}bBXBEVcY25S%XmPR&?&ALUctdq>fIJGJniuv>bu`Izm2M#Zhu?hwXQavq@8=0 z1TDGuWbye5ls($GoL8Lw()O0QM05HS_I3YCzgg0xE!hX*cnfUAP6W;De2lB6TZDtA z6wwkK(oCmTSL2_qw=ohtelqXU`+1erJo1Vee zdY-17?$MWJmX4%~R?ozirii@W=tqZAq(&da?c`byXc(AM6l53R8%9l~8{RBusFA3E zI)H`Xfx5$Q@p>g|^jsM__P*d{1TG4bD%y&wvqnnH8Z|#zlF4BDcnIR${(eq96MR)oxzw{nQnQlP={1c(JfuDM!#0ttF+|BR- z8~voJ)sAQAgK*>eLaMJLBJL9p$5eX?9|}#Fj*rWPTke=h@YfCSqy)5IX)2}O- zlVk_J3QZM8o!%_*)D1XM5-gm^uLu~|Of0cxee&2trWWeI+PVJqVXaj~kIwSJVcuvt z^%m8^XsHv^XPr0u?ADVB1r$MpI=0pYr+Mcd>V~K18aE#!r&OZ5o5b5ucZMM+#Z)DG zuC-4DN?U#PxgbxaG~OH*uipL2nrpWMQ*#U}BDEGZ2ydXZ>w<6$^+7l^Q>MbT%l1Wu zk{u6BWa5qS7LJQcL**X4+&5e+Osm{4SG9B(?YX(IsMAmNDJU>7kCd2rVG0+a8_v^` zkYij@;9CqdL_QZ^81H;#2i@ExuBXU06cng#bJ_Cq8{|g(>vS_`MNQq$Z%UG5uLsez zN9JWO#HJ4|s@jzXFFa^lj9qZl)vHp~K2OR5u3Jp()lPKwU)53Ojs8H9_p+^he-W?y zIKjTwRi=A5h3TR4ez#BoM=hM^6R9yVY|c8v(4!rn(<+$@9nxKj$ThQ78p^9}r*#j5 z#6A?dWfkU_aeU+Otwr4jE0m3CEBOXfDSxy`tFX4UsFeZ#gt=3C_5tyAbAw|3<8>Xo z62-)>5hw3)Jf2S9u!F#vz{RTUD|pE`f_g{`G>-+JSyQHrE^V^n1)gejV^%6$4m~uZ zvGAWMtdz!cic2^8nEmaUOxY9PxN%m&DYf*N;@yl`ov@%HzL=qPA%UA%Tl=srC3<&uN^Oa9G4rS+j zvZ!tl;?juTk)fa3ishonydcKd5mlA$v4Fy+q-vut9(u$d{JKx0UejITd6WGut8mB* zN}AahiYgF4mbLoEe&16Jwxdw*BDELTzSB*70*&gh5L&6GdkPXaOrkaET|bh;bT2%6 zdL>CH)7FAQYMVlAP?>;EfLVb{7!>karUTkWMJUCc?Nf(8*}TECCIliHGwcxn^scQx{mPAE0bmh2gIb~3$O7f{|{M34E zzCbLkD-u3QPEFB zK`1wiJT|TFwxe0u?MsAgyV3WcPq6L3IdC_ST*;8Pc5>$Fv!ZvE84sd(Kk!^q3)i0^ z?#e#dGjTN#sU#trk+yFz`}J#i*dHVO? z?bKn{l0H-n(Os!_hy%9I3f522hf-fmDs7(;#JmvSomaDZuNvBO*UegiJypg<#{IG? z|49bg<*R1pt!lc#$xxQv|9yMtFPIJkb1xI zcC`oCZ(K0@jlvV=@fY4xkLGbpCL>pD{RUEkdfH4Qr#`O^vn}HtDhb|kBzfS{9hxrl zru+)>_dVqaF7i>b4EG214%EgYezhIo{p}I|NrM0KO01xyO5Gxj`&X?EVNb%kZD-jf zDqd=y=mYCpS2J5GN_&MFKELzZ_M{h0@v^B4!GBRwAm=wxb~S8~GdffIMJw7!=AqpI ztI=rx6nF|u_qeN&q;c_`UxKI7(Bdf5=wZi+h;gRj66?W{$9s2Ok!;nw?J@@Ad^O+$ z4~hlygIL(OYG+~RSCkl@{DLA8Csrns6o*eO>QWMu%!L-h;X;82HjAT_Sv>v&OV3+B z2*=9^OSA8XT}sN8yPzCRci!}~!O=2=5nvJN$!xV_oog%|nG@GtC@61xMT>Nj>Os+d zL93?~TLG(YV34ygMC~iZ!3~YA^~~1V!`JCa#t(0W@7}QYEY&#<;;s9@>In-a&Megk zT9sJA>=7Mm^KTFX`<-hL%O-aH2k9ZS#<|6`0x7(89juT88+V!L{Kz`AD$G8&3O#tkJMD^vcz!I-t}c=_@=&Y3rPWH@3v1Z6cKa?r zeBA7?c2S{_ScqmYK9W;K^t@;W1;1M#P;pz26<2|4YkFzfL?fZSG3K)`> zD4lwCV$*{@sm0h?Q^uRsy_}Qmc1p@E4U3XBK62=zM)?z@5JT#_z5A(8m}3r9_w zZfj!YEE6}9);L*M%k%oUD4E_rt#@ry4;yHrHN0+jUBG3k#6c^aOJf*sS-Ap!ZR(|t zN!}e)yH&ywL`CCSDd3T0=PCiQnm%%3;RLr=A6a^QXs`gOdE%7vR$Y{A?)Iyv^lT zcdJ*(Wk`gHV5Sxn$vG2TeIvP#6+-y@9rOB%#Ae$z5r?}x=<@!pJC5Y(cA6MCm&gj2IGvl)!$+Bk zXeOU^{c@0Q-nDcw32vI2yr(T0%fm?|f z4B_^AvKu6H*iO1Z6jQ_;DP#2o9SsKU7M7W^HtG1{gn?KH%9_)!9xWjf~y-l-Lc?EQeBbun5;0jCPGFD2oewBq^sN4IkdaLCahV zHq4B{>tLgTEtC@@o)KiZoR24tux}i;EOFILzo9sp*)^*cArqrZ(ZQA~lauJ4Bo3Y- z-wxhfIsD8_?P7i31@f>UFx@7Zw4-pM)zo+DvCQ0r8>_a^>Ri#R+NiFfu=50-aRw?K zXa@7-K4jk3%32X@aMT+Su3`YG%;2uo$J4KTp-)rdU$+-pMQEjUDvy9fIRn1hG)tSMAg(+Fhj0U ztYtLKk5$w@$t#hO@I`-yDDZ0Z3@M42x@XnpQ^-TG5PI#p@0^P+;|4(wID8FVXU(u29f25+Hc z1U~zsi)u%Bkip7qT{32&roBlgJ6^FmcKBI(SDC7awGu7SZ61* zoX(e4rD3uKt%j(g_H>U@aBf+dwMu54)t5|EOk!=gu9b7(hkS1W-6Am$ckA^bfR&hL z%&zvsXOr>=GCP_ohz!+i-R*PB7pLH}d{(#}04Ft1tVZS}n=!4#8Z!`2A47+Btuv~P zpM6I8TS6U4@r>1mKP2R?v(c~Z=bb|)N<909+p(T;eIYNfy=l_pePVC-sARz*G&&Ld z5uP6mCVp`AB_a2wG4aAI>yq`v(hk)D;G%eD7*2Ff&Md|T)wtAs7zRtY)iq9u?D0*X z>nVJFw5mE)$aGLLRakkp*E!t^w?P#i#tjNnGg>XqNmh7N;|vlrB}1tc;=)YcZ1}E} z*90nN#&J?ADu>^VOJVXQ&TrO=O+kvdJ2mb`=Wk>x#ibzMi5(UBte`1~^}Eq4pa4In zVW7zJ$F3mR!K}HO^Ef+0S#v$XDo+^{RI&!}U-uaxRsug!1@~z^yD}RXub`2Y!=kS~ z_?(et@v*-}!tN#g90xiUc@-@=mci%VHF*PU!2`su>XDWCOv3%Lw@?;&@+y6vT;2A0 zyFQ<=vr`pg!r)4Z7ZX^Lt5b&leA%XG_YPRdmfs^zwLG!bKl`0jrqX(rkz3FuJosCZoWz}Q=E?#A1AWZd>rwv z5ZB0hYw{SJhvxebPsFR`o>^jTk~gfm5}M8Ux@%N(g+L#@VxYCM9&)^^o@H83M4Bz% zTB`c7527VdDi+oF6s46lS6jY)Lo+69@@gwEvqv z%~1H<=Z_CoY|WG3Oys0IFwy!zh!B_>eB3;ft@!zxQAw_G){3y4wxXqb4)?QNPD_Ey z!Ps?D@jY*CkWrZ(yH{Qb2ap;@uOxRAP1L{OtkHnXtY{j!`|A;AD74m!zEC$puas9u z9cjj79c08bX|B{rUMb9y|BU5=y!))@$eAi4Z$OX_-5*=RL>c?URe@d2J?A+G(lj?? zSJ_D)+I4Ap%(=6)eUx|nepUn*&8WZQ@{Zr32LJAhEu$*VQkyq%FKS5vPk`Nwd|ImL z1ww-PBsK5S2cois=1lpy*!~MI8cfMIN|@S6+t^ZD(-J`^!O-P}&o5+MSntPzJsDr+ zHgnvv3Vs|e-O&>2#jOtL_sHT>r@*G+xt364TF1R*wNY6^VNV9{S3$eIpgyI@Z+JMn zIv1A7h?c#Mya<;MbSqmzd)ps0trwBl!R|=T*ZyXx?)lh|pxo^E!XddsAwL6+SIOdy zv!-hoXY2!2XqpC!5tl{mF+)5O-TvcF9*Q(|w##GOA_7>I zG%NKOJ+W6%MNpDmUtr!}85NpUsvDpz%{>LIc@E{ejsh7OHKn2FRSbEqpBKiAkHp)H zrU&=@^oQ!w^91iEF1z&iGI;iU^Sc=V@{z2L$C%P;N5P{YDghSnHm+@;8vK=4Q}|&x zEmtpxAUp*n_&K+%B{!FSu!Vk5(QLzVD=@)UDcW8Eu^8-`Vy(Tw6iXSjty$LIr6ZZx zH8D6#3>$gL($QPf(M47OhwdEXb`+Fl2uUHJsJG%QTnD>5lHC(2OrpdrT*kX;?OkuL zt4AByO1b4hun3}V`UvnoUck>U?ddK==cE!W9IFp4#&&d#E`+pqJ(N@# z>bN3N0d&!8olXA&C&iOzD5IF56k!|XVI0dpOrf3 zhS@ofhs$M?^69)yi9bKgRvPNim*9tv!53d$$nBaiF1~4HRD82Thd3(!=lhWz#mq{ax4nhFvcRGwmanMB5Zw5^S_Ity(g;R{S(Ht^AyA2e4cpA;$EzSRaZ58YK~E z8qs!$Jucw~W!QXt;SDMU@vwuc*J%tiy?S-*ZMWy+JAAgSS!j9@(gpHuT)HP54}*P# zyzk}HN|E8XnX$hOD3=mXX*gCe4Db^gbQ4z4&Gi$S6ZD6x=F#}4!SZ?xcW1{2+i%p? zzJKOd{W$!^K)glUEe5S5Z32FggQ*f-Nr@iwTW$gL^P$_?I=b}p?3a_Nq9S+=WnqyP z!9LZ9Yk6};x97*KN0}<^A|rS?hd+eLwiy(0a^mopHYjdJN6;m=Y!Yp2hc@xxxV`IE zB|WK>ZR1~flMgXIMxL0EZ;z}gWNL~}CCDEriG}4~x|xODW}tIYC)XBPT3pRQV^6}a z=DR{mV?Q4`q!$&jGbyfxXWe#-!+D-2GU6>4gm z4*x54{p)V!vTa3rL_MPbi?_1VGms{=mU6!Ayg2+(hsTyz1|z(yV&Cu*xS6k4V~^=c zOhrv{B=}WpkRNeU!Km>70naAFUbD4 z!5-DIFJlE6s4w$R(Qj&sT!9*jQm3gq_D%3BiCC7fi@cCnwo&{zSG9-b0T4Q;cb;4| zyL}}8Z1XoP#ls74=*%n@Syq*s6h226%6;2Ro%T37xoxm{6Yu%Mrq^`kX${6Ns@X)} zVHvqM@tVUtgr9xh8W;VxJ1y#Y^l|+3OW}L)prD+n<-`)Bd6efsd6f#g%Fwa&lR*8{ zMyG=dQT(+%i~fk4`<5~+eA_E;tFqqbBp0ry)lCbXP>(mHaU<;D-=jxB3KMa{#F@^% zc{%xTztgz?h(>9;IUvBQCgupR5&~{%B5v;rGT;QVq1+G-UKj|%$Hf8VHo^spAQ5(G z5EmwDg$q_kpzNKHrU(=e&r(I&n`$7?24EoK1p;d#T+u*rDOa?N1{#QIfgoprE?ls* zJy0FOdsZI^ae*a(XP`wC2ooAp#|22=nZtDPd#DU(4d4!R#vTd;RPbFYLzo4|n_V32?58^hlBFx{D8ehvc{tfHy} zf{2KGXYy=R-%G0V;+_rbk0G25^G7ZOiVJ~a`T?s$IB_8u;bM~9xRA5n!Rmatd>Gm< z)iK4tR~I)yAuyr?tIKIAh-t8DTG}E|XTp?3piGgL4rqHM2y!;CvoW7#0n)ZaqR~If^{t6XbY49h>HtTi4zyb$qD-L#_)zo|HB{dKhS9 z3mGp-KI$J@?Cbo#bYbkMHM*%hzc0k$j0{aOMADkSToxnK2> z#E&Z<5PnW>5s{ylI}n-=R5f&{YDXiIG{|h}v&s7>-U!Zp5Mzfr`MlaFV;y!1(R?>9 zbDsXr?c1`l5fO|&caYc(=gwcaK}G)Nk)+4m&%az88+= zKQXm;Ha9;Vix)KSnVA0US@+pSdZm0_k(6V3H4;9DbqM??YL~l!V~=cE-x{ z_8IWxYAvRx{p_KGjJ%tCLLm#7qfZ`%L|w1=*gJsK z3=&@v$&%MIeA%z?cI}}IIoYi$(_3%X6xB(Shb*&@N@`*H3D4ysI-Vn?YL#O&wok7I zWlX7B%fHF0OfvM%vyhqSu`MFmgE+;>XRGIGvV?vm*dr_r7m%b^Q;UvpkJ48vNFQ++ zP$i5`sg$adQh6D0SFLrt=T=BS2;a4$E|vKsENd)-OUh-=FoWRZH9v#h;A_hGTOZ!P zm0DU&{N#bX54#x-eSQU0F&wRSF|@q?DpaV2l>5>as2tKi34Ju9S-5&mg5+F#mtU8I z#w%(H+t+W>m;*W+4)orN3Z+9SCcti2);2O1;}R`Cna+J(R+yeGvv(^`=_ZZj zH8lqq=Qi;{`9dE|3>hozki;fxFZ)WlbIHh^n2)Mp# zH`$T*N2) z$6$+ki&_%qN;l2oAi%oLp+i8VLzg)I;hZmJs6g_P;;x-r%hdcgjo{X}!$F-6fj6@B zJuE|TCar==bNa7%F~W=dx?=YYu%^ty6X#f?Vd*^PDzM9{lVmSfLcXnjJAP-mUf(K# zpT1%JA(Tv2)njk4w!NaWqnv7^P_(qWIPyfTU`*_a?+6Z=BV8f`k;qs`dfIy}WA-8) zZJiIcLD6fb*I}yV7Nt7ll($rElS`&>e6QL)oyKuC>Z#>|4G0Q?AV<6Oza?G?+zDxT zfKP?h*j$I#=+6zl`uej=+=mP*-%Sxa`OEpqr2Ll{U)IX~R!8f2hwt7w7i$9>CSoGI zJLLZDaQ2ZGY*N^Zq*pv!umv|!#qTfK4VB&O$B`wk-?(+ti=4{#>TmR>rpKGwFLU0q_N_a@%Bw?4+J^(GImf0SI8uMFB zbf4-C^}Jfk^j0WmYkDU-Ci#V|?RWlmS&u-Y3vrUDx}8C^K{;(dhP8A#Qdd%wf8IKOA5Kkc2A6OsB2(j-{d zMVw6hWmSKbZ|bBwd#+2x{G2>29&u%ZR`2A_Vi9+yLBt8wQ28JM?zo7z>)y882Dx2A zR;;)#si*5w1%+jSJ^oT#b9Rs^K0jFtCqorq2$85P>efRGl3CVs6}J*=rtpMKDRr(< zeCGHPKqGaI-k@OHAtCzf=%<*tT>Drfx%d=i9quQbCXxL^G3oTZx~gQ!~tG>uOGido>1}a<*^#%A2Os z6m=GTTMd^uxq1!1yWM4-zv!V3g~Wa&od;eOO^6k_*;2}&>mkim>U+ik4t{BrZWDV` zk@h1x?xF6961_^Q*w{)oNk@il%+9V>w~h)wbdTP?F+VBfQ&u1M{OW%6&FV?1r;RBC zW<3K|QCX6XMn|`I`S`fH6_wH5={d_=@7udpUOKv6)qCH3cn>FMGE=4~m^Ua<3c6N# zV9!Gqo5?XyQ|R!Cm1-Y}%u1t>xZ4m3$2uQS?T0OV=WbPsP!cRNS%%BvrRj3VaRDJd z;ax08Wj4>?mr+A0guV=X)2sos3Y94H5m84Dj=1`2dNU`zM@o1z(T`@fJDO9C>_S2e z*Fp@X)J`v?>n6)$e1boF#*n|bi+}M0{xE9(*<<)=*#LGMHw+5cYS4c%ZGfC#O`EgF zKTI3`f3t0Pc>kkmbJpk&)5h^n*2Q7zh0J&T#v!F#wwa@^B$nymNe zabTpHTq}QFS}_xsaHgc#J3Wntw)#HR2Hv9EbV7AZRk|__T;QAS@ZWxG5&z8(6e0br zLR8?3=cSV?275;4AFodOh9rU^7uk`d>!0Js1|pJ@bm(>5IT6mzysh@HrjP4jp7~Z( zJ2l0&gR^^|780Swo(eA9uqEENmt7o(V9v2FPP{!4#*;O#?3E5aZ0u25R~~FLsl@dQ zd+D3HIH3=oGe@~I?kh*0vY#4B57nKtBu%o`a`n7tsaswBR$x%c-_!NR%97wPdAgs& zIEs3Wa-zFIr*bprq;a}4TPd+&U(k{Kh~-u11k#XgamS4>R&oBL$-Q&usB9nl{R8lR zxea{gU;Udk{m-7@PvAj8FaX2cT#z5Q`@@JG5eSG=i9{ip~?o6WYQ^FMEXrq^zGx4z@oE5i=q8~qg-2d!xQ4|2p zNcvrw%hOkTzha5r2!nb~?|EzNRuPPc>`hve#X9Mn82@rHA|pWHCssG_b&zDigj`lHH`Z(XcXB9HgF z%PjZ4mSJqgLb-0&(vAa1eA~Ns_2x$8{fRVrq>*+aS!)Khj8yg9o@` zKOIesQwAI-f-TPcF^n(ffH`eEt8pm!yANmU_v!0!KYOVG}PalYd$X8=|Oq8#F%`=i3uPiHN8M&;T&!JBZ z3djZB7P_D|<#UdvqV9I}McT!5ADQ|`;w(~|C(9p-KV=#@xeTx7uJ`EXYabX2DVl@( z!g_i(M60-5db*NP8;1|QQl~%RVuNXDu3>vbKggubjLA!Tf6-o}yy${mQp7FB3pN{q zlR4MD3$ZZ#~w(jt;5xq-<@-G>m1a>!((uU~D zchNp0q-nC6C2kClAk4%`*ktg)X5Tu$MFV-dxpbZQu4K@?jG5=EblYU~0k30wKBe=C zO|ZSE<5%ioC{!(BPNQ-Su3>Zo@Au5?s@t)Z^A*XgZ$9WhntfIGl9;_xE^|6ET=<|c zHvSO|;_htEaa$vBpRM(AW!|Eh)Lhw2-1YI|o9_v3-!3ww(~i*Tz$Nr%_g>8BNa#wwL-xJ8|&n>My8=_4Adx6nL^<)(Fp3^xTS_lo9O9d6T)U&A^t< z(<}{+BSUSBb4wd{lP;Z)xrnubq_|^t=W$k(#T)&bQ8#R7)w7 ztt&ARgrE1#64dc&*-&|@(}_4pjJkzeh|o}1E_8&Kt5(;1YjE^WU6LMiv6xyY{B(?n zCr2L$7*QBe4`W521V8kOP1W*!`bpC_p**99=r`Y}na7zBTfs29DeB*bju9VeJEq>pifvt;{nuaJz4m%0u+cZdE?XTunR=e3&6J>Wf;o<$o_3xokDEloF|CB)Wmm*keAy=!nMm0a z$JdRuy4;z@*U~!M!&tl23RMjEAd#fy zuR-tPR+;2(V3E^6hMf!iEK;KDRxo?^?>GXVoySyQ4A?P)H6FSIjnM!K-@IvglQ0tjR z-T+nYX$pOVX7WMT0%{g=de}Wv>oIS4Iy_6wx){YLo9!MZRiTsFq!y3uydN-aN2TZA z?HPVbFFr-zjN0DSN5;fz1nx<>GA+az1cF7Gy2JcJ}TMfR@uwDFO(DC(9<+-d_3BZ0sF#NG7A%KZ9L-_Uz&v9WBo zzSYmHow_^IrIy+d(@QB`Y;z;bxJ#)2;qB9J;o15jIf_oIt;BW@x})EGPBb3pCc3K+ zo54E$(m5d;K-FJJ{`r)C*UJId_vvX5#MFGhrui8*w%?|0U_SGEx6OP}P~X_{IYbbT}P7os5nO}^97Ptdd561zII=n(a9O_xwyAkaSec@Ba)ia$wu>UP{p*~KGaw3lS9@`oz;S z)k$moR@wz=FDP3W+$u-lM2?dV-wlYVa^kp5k**(QgTuV_KC-0ls@R3w55H_Ozf1Hp z$hT82*6_CIzd=TZ*pV>e6{%bWKNxtlIN0{J>~>38fm`iO|V_VgVI$=cY%I*V`MzHIMg*o-b85t8<)7Tn9_oK51Q&TE4=O)_|WK zqA!Gd*qrI~XzBuq$0e*xLJLi&>(kI~O})qpPOt_4vjPNXCDZcG><=;^gq&h{B9)8&1^mMUHebzFUNqr)O zlIA8Cjks2qE7ExwTpsiABU*0n9C1fRK_8rKVPWOwad@h?6MsGH)ges__M;$H*6t9^ z^<{(Q`n^)72HJ-4eA(FE1(T5QQK7`bx0#Kj2gThkd}7CV=iM%D{oN!zitxfsijG`jALZT)>02{&XYU03dcJ?z#6bOh12-8ZaD@xO13b+cm+B(<* z!Ca85t&JT@z*U&>tcn1T#*o2`ptB-qYhgxRB~=jG-rmOA5)FcK@N+=eAzW-AGb9kS zaIr^PgCHC{j6jn}xS4=D5Xb(#LEuT4(E^Qj5CDT+TwFL@xH#;Q=3odvKR=ig3Wh@2 zffDQ}H#@Y6E4v+v4(RWU5lh{l)$C9lXFPG3+S`IHb-@r0PVkS8egse~?d?FAj!o{{ zJE4Ucot!M;0$h;$yxbyAKrUe3|WP-N9AOgh(lCv}A0BIwTD9i-$alkk@ zIUxMJJb+7O$fOSN3NtZe<^ZWUAdn_#ApQi>a6DFKk8rJa*2^Y1*Lb^N^_Auwi^ zf06HhTjC}TN=pA(=C-z&MS&?NAZc&vWD7*sV%9T-40qlgfYiM9khOp&wID`tcKJz-;s zS&afVCU)k+jIQi(gqewx4VqB|jJ93@j_=AUi&`2R-Z z<;8^0|J)t~IAHk;jguDwNbb+&02lNE%M?{DovATZ9qjROkd`71A+ynKJB z@p1jVE;o$(7hcdv6X0q968Mh}Ah3p|I|9G~2&`^z58Oz@9E*a$a&~6+ptE~6z*(9k z$UsPvj|UN(Dap&vBLS1(2A-t2cz{oFeo0<&k^g%MBg|zt6xsxdJ_8?whYJS7 LrKgutk;eT$6DOQX=HIU$ z|M|cFRet>Ezn&lE`BD3odytr;OmKcg*@eb^fgj^E!Uv!9Tk6>w$08|JMg$ukt?`f&BGf@BaJO zf3@%LU;ovP&tL!bUe90u)~>H!I^~bKbDz1u*E4@im~S)a+cUqzO}h&bO)b^~@dE|NPf~{i|?!{_ubP)2|=@%fGx!^qprv{)H>?$3MUS|NK}VEvGX- zyPWdlUw-}dkN^Fj{^h^C&%Uqn;eRfl*=nzEG5_*^{`HUls=w|Z6Mt-u)}PTYrD9 zwy&qYufIQ6+qb8_t-rso_}a_wv!T4J4fE_BB#H6zqgG6! zxAFB;Q5DRGe=Zo$f99j*{q(Af!~D(s}9B&<(k#{x$c~VaM zpvG^>{WFF1&zShu`_ZnF$EP(c-1qgSXXfWYF@1kVGqA_dr}WPH%);8d?+AHk=<>JU zwg5SwcNV*y)yUTHJZ{7L@EmOU`^iG2ylVrs8U1sFyu*T*W^tol;B?exj(2qud7HV3 zw9jC5-nV!g7yty0-Dk zqBh)41Co~Ql`yQ$yAsAgZQ45wLSBhbxi$(I0g!k8@2LR}aMJL}9(`LkIWTW|ZykX2 zS1v5|)(|q@UT+$_R*jrF)W_gfycK0vydt-=E8gB3dSrjf@|4`u$Z4*z26$#7 zzn$~2E7tpZV>|Py^**d_U;fs5+c{mqXBkm5e*#d!rMk+-4L9Pfx6Hfy~N zeTI-?09sD#ffZbDE$Y!&RY|Gep?B@A^=W5#AUHJZZTj$f=*@^m;+^(O4SlD>@?brz z&VF9aR@AJ+rtepvpX2VSM$RmngPIuoZF)Ic5uL5r?b9VRRp++5)FDQXt=b@lTWhZb z(LlTtxUt52z5`M8jMmaSM^ zdmxVM^CFu={0`0L5WgbT-QGNNPy4)eQeWs>=WVED)jNLM$a$uwrRsd%6~C&+Si;~{ z-o2^H`u$d2l}TkCEM` z)*~lnf8K|mDnV2lk++>(`meazdZvF$M)XW0dpFI3rf1%EVxxd%Glb0a`z`rx>GV8U z2DCyUlvTm~nWwnh2a)56@gizyc^g`W-l{<;r6C|$%&X)U`{I={>A(CRk@f%lM4Gw2-Edcg7Y=40U{2qJQs8Wf;&%yvPvp zzRliwd%3EZSC&wTVMGDcmoyf4`!KMV=LNM+@Gs7M1)~R9$hTc6)uB*}blZflUSQ_VUsr=#uJ5(21O=^XbXd zUN*o1eLwXCkv@N`Bj8mrwR~GO{Z)b1=kFwE!R>7)CEP3XRO1(sK7XIl8i9VBp?vJ* zHmuJ(7Ce!+!P_jrCBF+{L`ew2{3yRwd1r;b3Y|Upiq&c@wzh$Drh2Dxp1jXWp})OD z;n_i>PPdX^pHc=aEo&`e$_ba;3`n8B6L6`RuqZGsJ@X34y7dg@SqG(|5(6zWu%%dv z#9{}H64P29PtvI2bwuD;pAV~4AV<=^Yu$g5s3S_!L87Fvn!fb&Z`ix`pg*MJi-d9~ zvnsAKdk4(w34vq{!8BUfApsMs_fbvTOROM=2!vNf({%7E^-WKe--fGm&PR`&tj;Z= z16sALugDBLY1Pm>sxD|1rT<%*&XJl_lHUZwrB!Wt27p#=GaD_=msVMsAM96wyp4Q3 zC(1M;Wez!|x2DPV+to#HEw9dZd^Js`b`tHK&JxHkiF#PU23c+7?hm9NF0JZm6=)T; z`TLeu%+mIW6mt(F(&p8asgqWrI##Dj4&#=Z|Ow=mR9+h2Y}Ze3p%q?r@OR9A+E zj0r%~iUDB)oviO9dsOa_=B`+z(+JjleV2|F^h=nixa&I)rN2U$>N}mAiZNk=^+Dqc z!gPp4B!)0mY$3ez{=nXq7ZUYSV}Bnc3Tu%_H9~Fvaw4rWa47J}TDRx_%c0(tWJJ$& z(e3(<#0mltT}$)4eJK>#_PfP(_q@GLZC+oxaM%ir8pK;I)hz{y0&l2K_Y?$)g1UM~ zOoX?;B#O(i9MAvpjx05Ic}KPuA|_GgoztX`BP6Q4<2Ut;NmO|UML?70F5A1XK@L@b zRMCb(4z*B>_l@HjnklbxmW&zXPyk*ju?Uz#m3P!B-9|W6nch&1aH#UGr>Pp7L*Y}T zVuKv2=u=eqKn`XYO6EKmBvB|CduY7{JIwq0(ZV0^5a|JH$^p7WqsMTkkIHWlnp@TJ2Vrzapsptwt) zS~VktsldFzPlYhOt6FpYr9Gn71#^8Hq2_+qd62iE;FIMQaB3(ClWMG~M81UTz;2;O z%$ExG6kL0MK)(o(LcQzSgZF-OEVR6)mqDSR%U{tXTfrcO!ZYs@E(WN}%gdaa9(nt% zEImSbF-W0?3f8P>OZP|!z$2e&x;LDzhUpP1Al@Pcvi76CVxWHXG?|5pYSmOHcO!cw_e)P?W~WUIbzw*`wxkr z_aD1=wOz~TeV8=+nb=zrDO#FOEEEF|gJ+{U+%Jysr{`5nTH?@9?4PwgOIH`EeqJ`R zISs&|7N1$#LjobGe&&|K9b`~LJumI`KHTTf*V)kb3smF}Iwi_D_Wk8SKf|Azf~kynnLEeXs;J71Bh1^U*R zV?M#C&QLo!cYtt%gI@Oc&8Se0kxA}d@J$u7q}w5-t3LJ4`lqWIwC4b!ZilcRLf*D> zgkMB&fl+ODs!E10jQ#VL%tbTlC!@-;kzj&RQI&(n=`F0?DMd%xFiEPq^~g4|$5AV$ zkYQc^_7i92B&njp>=G*TlB!3>nRz+Y+defbHYn&qPJ{`qO@;mrZs9W|RYf1?mtHmg zNHtHIsU|6vNdu+wB&EV5#dfNBDOItdZ(d4O9_iS5DHV*1dg~R3>cAl_F<(w4eg4e6 zwW80>6ebze_@;L!85BNMQt**F2f_}0>5_;x*hM#T)DvC1+zA53o+#c3OcJP~c2Y`D z5~!j+ralKEqFrqCnXQ{>m*a7GX_Wg=87#vFD!k5Rxj+P*#Wrn&r9A zj-btctNWIaDFsjd8RS$?imK`?DtOErEk&{_b39H7kg5!VR#`|DzRlh1B&kv>N$4j? z)!srV0w+n8`P-vsK&q-%2UQ#p(d@T2WB~IeRa%rVS;pUAl{D)sF{+(s|tKctM$=_ae^;33kH1(2B%}$K~+B2Fwb8y9RWBIkrD%- zOWXCMm1Tl1b$7+1ScX5bckzKkJ*lETzcWvZr_&0zfL3AIpsZs5%i3TUS=6CWwbnqQ z$Ruoc1VEb|l$;a>I8-~|=Q21H+5dTDH=BFNLk>owwFVMJO$|$jo|&QlMefr1s$*Kz zpB>%3X?38Y)@Z!|J><}*OD`Q6)T!|K3^E|&Z4P&Z zKx937ycb#&CYCBy$h5?G9*x!lXJW_Go@YcIe{5k|57)B>RG&JspmWBd=?hY75;>9v z3zVr@ANiSL`%y&q0%eM_p}S~-G96ctp8{hd*FU!D06CJLa&7$l6Z-W6LoRZN1KPV5 zIFy9bLx#IRp~%QFYR8B;Cy1b4vac3PwyOF=EEKWYJlmP-L7%PS{najCj>nfLFSR`2>y||wQoHCw$2PpTO=KvmJ>mY|+W|4(T-s7EFeupA3+!?%r&ZbTYIO(0 ziO0cxdyxe6rAl&-7kWR9sLN~7dR?$XEnAdmykDSDEnQ4t*|6K}9S33)p6SPei-WYV z+DW`%hN2Cxcu%&#nAGW}C_v~Pr;Uj~k#iia@=MhQySFDbZMvPZrFE}OcvCnsaF7VG zQx?@>!(oLQR`{AXa2|_$504cH(>B*tDND|AHcH>#Ci!o}X-{A95|R{DTR(tkAr^;} zESQC9qYH&!aGy!V+O)Aike22w#of<8p=Wberwo8K`MNmxd|bqZ-brb8m%# zh+)3Zkh-pc-S*J8)PrDA;`vLeXfX!Fwp}`=fJmReb6O*T=p~Zknn4GPqVA@AB2vRK zGf$_3+d%VZd|9ATA^KgHWSi+^ha2+6^AE|?3q=E2l6OE&el3I33y+t6@-=-7Y`k46wGZwL%c9@w4c zck}%MWzwgPhj=@@4G8yXKx{&<9-8g=wl66S&a_Og)$QByZTxyMqHb^L3NV`CrdNG^ zneLY@n!dIJ+_(hT_H9orpIJt1NIynMnubKr@(TO|dzYYz6nzeyJt0!>gpvJho$9e@ zW}@pj<_#Z{)F6}cJm6Mwkx6AkJdJn@;8@5-oBGn6QC110!L@i$F`p;hK*TA$+E$uv`QVWwx51A_|~U}#{%BB zWkebrbfOcPVc1*Uvmd)`xwjrh6sTOi{P*J+H_WlFMjSD0?xNU;@<@k2O%iJthq!@q zlxakpoyXLD7l*iU^Un&BNX4MR>Xa@e&Xs+P&{zk#!cD<04sqjNT5nAm>+V)-7YDfk zq0ZSMPK9CQL_(b20*gvMHr5?^cs7Vr_g0Ilf7kLw^*B|wcns;+(j!&2I`oB+Z_G*c zyUYn)dW`H-zG;dLqSXBHM{liI=9U&05c6qA>ugY^@M$jOpMS%Cy~wd5e{751kOb9p zmuz%{EM4Oqzt$YpM#~_-2IErplDh6EXu`pnu$Q~{Fxk#%65n(R21#dDV^%Z;O@}ega?u!@Qa%Z%&?b&;*tTY=< zH#~Gkp+=vn%sCaa*cSO?$ZCZXZFUpPwb|hm$$i_SWQW_!D~<-`vsJ-5vBrm70aqrAo!d zhkdEi`;4Y3sgfu``IvFPCm zbe=B-t!H3Nk%2rS?Ko_$Jozc>_|q-Dj$_uYi)q8w(=ANZrLe!07#5BZtLF^yrA3d9 zu)>g-VHLzxf2E7Uu(QxeA(Bl@Y2jOf{Ho$w^kTyCy_ zTmo$*VQi4hdaH#%%M^4F7*wq})LS)SY(*;R)Zyg`(~BN)6dU@JzgKoLM^yA&+Ejho z;$UO8Y;$t$P87Ng5C;@VYRukcAXexz&lLH-SsOj0AhyzF^*Qj+U5^(#4+f@YGYhu_ z=aQ(macmMflw}9)OQ$7>ElTXPl_}xP>LG`!8U#v{0}e&*TpV$A5Qf(515?RgB+9`9 zK+K)fh@L1m@N1UStGV;~h;{ysyvvTPs;gWzle9{GMUsAcJg~(v2?tTh)%=ah;Pgbb z6^C;j#14-L%^-3%?9}eksw(|;5W0T#7oQmkVS8*D2O__B@j<6E62k^T#d5%_c9Tvq zVqS%>w`# zNH($-cFz~Hid6byR$VTMGkuC`)kekx*c$P*1EoKX^^#J ziOdME6J=gxIs#%}cS(fVpV+(p!mBViT1wzm$3#Jjcssz2`|oZ<{_mnFj* z8`00%_K1i5Tv`Q9%V9Vt&LZzM-tr#reVXXmiy)Xyvy%Sh7pb7xn(r5}+@Z980d8kl zo5#g;d&H|Y2rn`|Pqc7=ovtuK>QrvH#fu=8?Z+2WeG$4PB~FbX@?RhC`V{`<9UaXO zFH%0mysytM?C;IWVpL`MIV9?5GC&)?!kG|CyC@dzb`ZUM# zC!XU)-gepJT?5F0TSe?%ghXGO)y04YX_!4-8lxi1bpa7M_6>MGlLo27QnF+Du{=~V zNsp>rR6&v+HQfUriW6Vgi?mOImx_^Y8Iqr$x>oG+%=LQvz@uykNVhgNv~XZw2q%AJu#l!$6eJS#rfuPei8nSeZ178O0mEmbp=6j zevsRHjgIav9vOx)+{Hdi^&;~VL#d_`4kS64sa<5HEBq4UP_#F4s~oCdMmBwaVpx9j z@nY*@K}2@;{wf=Z1f(Fn)?U)nOv;v#rqx%v_5cdcwnE&hG)a#T^(i=y8sTP51@F_O zu!0;%cDXL=Gi_Nd{?OJqgsC&6yLwUY04FhI`t(YiS^MZih%eWdJxfS<%+UN!^E4@G z(c(cARYuh#;gNLrtX+sMlbCkF(>*@!BU39eQB#az9*#zN)C3Y9ef)8CKzJ;=T99mY zyAYBa&m7I#UB2dt8nNpq!JO+N$8k%pv)K(okX)bLrDmU!6%Be5f*2t3H`STavfC42 zGu}~K3%^5?Pr0W_NZ7MDQ$5DBYL*B&kG1UaiasQc($%W(q3QdJlMvbQyXfPGAJxnk z(4}?3AOs96-IX;+Xj!=q1`X*m!Bkop$M$CswNq2=0 zq1)B)@S(@)5u`G`?loB4yt|Y07X0b57MuXviYOmHcXf)^luL#j;Xu_^z8kX@ooW;1 zP|3C0xadd;8gRM|M%zedw^xUgCA5ImIWBm7mQBUgA5WP6NH13<*&;Vnf4%JJIp3Cj z30*2qzCr(Sd_YIt1-caGtd_STRUQ+)Jlys_dA5fxJ>Idui0M*^f-Ry;=!z;&!ynKu z0oxvwltZ5k>mxc_+SCdyPa2AI-wA{7LE_{yU;_2b4Av!3c4G4^WsSl$f^a)=mJ(pu z110T_ql#nvHV{aQ5FfGX*Si_s_QnFp&ZJZYUs7d9mU_KUDe{<_USwI37i$$D+ui~9 zF;1>~qv6@r&t0G*bU0R8%oAPmcx=|X@?(^b1DCde>WNY;KEkNtKOk~EC6B+#fZ9Tp-9hFi@8$u0Js8h}q5b@H~&qU}uUi3w( zw0HuqU!>js_M*d4F8gQPmnKdafgr;RGjyedI+c`DhF&z9pO>A#v^ajOSlvsaaF>lLSKQL@%^R!d`!y4uS=NJb5i}C5dM#Krf%d5I8o&Zy7K5^v75H7q+X4Jg3PupY|AYF> zQ!PxY#OzVRq)N>c`9`HYtxx?Vnm`rJcQw zDSDNO4opmj0P`l0h7;u2!4qV9W!m-kB8&!N=TrgvlW^Pa3ZGA$7V<6p0lllPmPZU5 zAv=1@nFlf7RKL(9n1s5JX7h$4l3t`|)oBjYGNi6Cb54-$7-Cg8B&kMc)sUoW55S9< zByG>gs-x$W5+0~>q?%)Ke=Gi&JUa~RMT%8l6jBXIit+VDOp=Nn08E+D+jj