From 4257e35caf6d2715a033ccf8d19570871e130aee Mon Sep 17 00:00:00 2001 From: Fanny Risbourg <frisbourg@laas.fr> Date: Fri, 11 Mar 2022 13:00:08 +0000 Subject: [PATCH] Clean repository --- CMakeLists.txt | 29 +- .../Equations_MPC_22_02_2020.pdf | Bin .../Evaluation_number_of_iterations.pdf | Bin .../Log_simulations.pdf | Bin .../cost_function.pdf | Bin .../dynamic_analysis.pdf | Bin {scripts => config}/config_solo12.yaml | 0 {src => config}/walk_parameters.yaml | 2 +- include/qrw/Estimator.hpp | 12 +- include/qrw/FakeRobot.hpp | 2 - include/qrw/Filter.hpp | 4 - include/qrw/FootTrajectoryGenerator.hpp | 1 - include/qrw/FootstepPlanner.hpp | 6 +- include/qrw/Gait.hpp | 1 - include/qrw/InvKin.hpp | 1 - include/qrw/Joystick.hpp | 19 +- include/qrw/MpcWrapper.hpp | 5 - .../FootTrajectoryGeneratorBezier.hpp | 8 +- .../qrw/{ => Solo3D}/FootstepPlannerQP.hpp | 7 +- include/qrw/{ => Solo3D}/Heightmap.hpp | 7 - include/qrw/{ => Solo3D}/StatePlanner3D.hpp | 5 +- include/qrw/{ => Solo3D}/Surface.hpp | 0 include/qrw/StatePlanner.hpp | 2 - include/qrw/WbcWrapper.hpp | 2 +- .../Solo3D/FootTrajectoryGeneratorBezier.cpp | 2 +- python/Solo3D/FootstepPlannerQP.cpp | 2 +- python/Solo3D/StatePlanner3D.cpp | 2 +- python/Solo3D/Surface.cpp | 2 +- scripts/Controller.py | 10 +- .../MPC_crocoddyl.py | 0 .../MPC_crocoddyl_2.py | 0 .../MPC_crocoddyl_planner.py | 0 .../Equations_MPC_22_02_2020.aux | 38 - .../Equations_MPC_22_02_2020.out | 10 - .../Equations_MPC_22_02_2020.synctex.gz | Bin 185264 -> 0 bytes .../Equations_MPC_22_02_2020.tex | 645 ------------ scripts/LICENSE | 25 - scripts/Logger.py | 944 ------------------ scripts/MPC_Wrapper.py | 16 +- scripts/__init__.py | 0 scripts/bauzil_stairs.stl | Bin 32684 -> 0 bytes scripts/config_solo12_bis.yaml | 58 -- scripts/main_mcapi_solo8.py | 280 ------ scripts/main_minimal_controler.py | 212 ---- scripts/main_solo12_control.py | 78 +- scripts/main_solo12_demo_estimator.py | 225 ----- scripts/main_solo12_replay.py | 142 +-- scripts/plot_IMU_mocap_result.py | 788 --------------- scripts/plot_IMU_mocap_result_bis.py | 802 --------------- scripts/plot_comparison_fb.py | 171 ---- scripts/solo3D/SurfacePlanner.py | 2 +- scripts/solo3D/SurfacePlannerWrapper.py | 1 - scripts/{ => solo3D}/heightmap_generator.py | 4 +- scripts/solo3D/{tools => }/heightmap_tools.py | 2 - .../solo3D/{tools => }/pyb_environment_3D.py | 0 scripts/solo3D/{tools => }/utils.py | 0 scripts/test_convergence_mpc.py | 563 ----------- scripts/test_mpc.py | 199 ---- scripts/test_new_InvKin.py | 214 ---- scripts/test_tasks_InvKin.py | 277 ----- scripts/{ => tools}/ForceMonitor.py | 4 - scripts/{ => tools}/LoggerControl.py | 0 scripts/{ => tools}/LoggerSensors.py | 0 scripts/{ => tools}/PyBulletSimulator.py | 0 scripts/{ => tools}/gamepadClient.py | 0 scripts/{ => tools}/place_com_with_invkin.py | 3 +- scripts/tools/qualisysClient.py | 161 +++ scripts/{ => tools}/utils_mpc.py | 37 +- src/Controller.cpp | 4 + src/FootstepPlanner.cpp | 5 + src/Joystick.cpp | 10 + src/MpcWrapper.cpp | 3 + .../FootTrajectoryGeneratorBezier.cpp | 6 +- src/{ => Solo3D}/FootstepPlannerQP.cpp | 7 +- src/{ => Solo3D}/Heightmap.cpp | 2 +- src/{ => Solo3D}/StatePlanner3D.cpp | 7 +- src/{ => Solo3D}/Surface.cpp | 2 +- src/st_to_cc.cpp | 3 +- .../python/crocoddyl}/README.md | 0 .../crocoddyl}/analyse_control_cycle.py | 0 .../crocoddyl/analyse_control_cycle_2.py | 0 .../python/crocoddyl}/analyse_simu.py | 0 .../python/crocoddyl/analyse_simu_2.py | 0 .../python/crocoddyl}/compare_mpcs.py | 0 .../test_4 => tests/python/crocoddyl}/main.py | 0 .../python/crocoddyl/main_2.py | 0 .../python/crocoddyl}/run_scenarios.py | 0 .../python/crocoddyl/run_scenarios_2.py | 0 .../python/crocoddyl}/unittest_augmented.py | 0 .../python/crocoddyl}/unittest_linear.py | 0 .../python/crocoddyl}/unittest_nonlinear.py | 0 .../python/crocoddyl}/unittest_step.py | 0 92 files changed, 317 insertions(+), 5764 deletions(-) rename {scripts/Documentation => Documentation}/Equations_MPC_22_02_2020.pdf (100%) rename {scripts/crocoddyl_doc => Documentation}/Evaluation_number_of_iterations.pdf (100%) rename {scripts/crocoddyl_doc => Documentation}/Log_simulations.pdf (100%) rename {scripts/crocoddyl_doc => Documentation}/cost_function.pdf (100%) rename {scripts/crocoddyl_doc => Documentation}/dynamic_analysis.pdf (100%) rename {scripts => config}/config_solo12.yaml (100%) rename {src => config}/walk_parameters.yaml (98%) rename include/qrw/{ => Solo3D}/FootTrajectoryGeneratorBezier.hpp (97%) rename include/qrw/{ => Solo3D}/FootstepPlannerQP.hpp (98%) rename include/qrw/{ => Solo3D}/Heightmap.hpp (97%) rename include/qrw/{ => Solo3D}/StatePlanner3D.hpp (97%) rename include/qrw/{ => Solo3D}/Surface.hpp (100%) rename scripts/{crocoddyl_class => Crocoddyl}/MPC_crocoddyl.py (100%) rename scripts/{crocoddyl_class => Crocoddyl}/MPC_crocoddyl_2.py (100%) rename scripts/{crocoddyl_class => Crocoddyl}/MPC_crocoddyl_planner.py (100%) delete mode 100644 scripts/Documentation/Equations_MPC_22_02_2020.aux delete mode 100644 scripts/Documentation/Equations_MPC_22_02_2020.out delete mode 100644 scripts/Documentation/Equations_MPC_22_02_2020.synctex.gz delete mode 100644 scripts/Documentation/Equations_MPC_22_02_2020.tex delete mode 100644 scripts/LICENSE delete mode 100644 scripts/Logger.py delete mode 100644 scripts/__init__.py delete mode 100644 scripts/bauzil_stairs.stl delete mode 100644 scripts/config_solo12_bis.yaml delete mode 100644 scripts/main_mcapi_solo8.py delete mode 100644 scripts/main_minimal_controler.py delete mode 100644 scripts/main_solo12_demo_estimator.py delete mode 100644 scripts/plot_IMU_mocap_result.py delete mode 100644 scripts/plot_IMU_mocap_result_bis.py delete mode 100644 scripts/plot_comparison_fb.py rename scripts/{ => solo3D}/heightmap_generator.py (97%) rename scripts/solo3D/{tools => }/heightmap_tools.py (99%) rename scripts/solo3D/{tools => }/pyb_environment_3D.py (100%) rename scripts/solo3D/{tools => }/utils.py (100%) delete mode 100644 scripts/test_convergence_mpc.py delete mode 100644 scripts/test_mpc.py delete mode 100644 scripts/test_new_InvKin.py delete mode 100644 scripts/test_tasks_InvKin.py rename scripts/{ => tools}/ForceMonitor.py (99%) rename scripts/{ => tools}/LoggerControl.py (100%) rename scripts/{ => tools}/LoggerSensors.py (100%) rename scripts/{ => tools}/PyBulletSimulator.py (100%) rename scripts/{ => tools}/gamepadClient.py (100%) rename scripts/{ => tools}/place_com_with_invkin.py (99%) create mode 100644 scripts/tools/qualisysClient.py rename scripts/{ => tools}/utils_mpc.py (69%) rename src/{ => Solo3D}/FootTrajectoryGeneratorBezier.cpp (99%) rename src/{ => Solo3D}/FootstepPlannerQP.cpp (98%) rename src/{ => Solo3D}/Heightmap.cpp (98%) rename src/{ => Solo3D}/StatePlanner3D.cpp (96%) rename src/{ => Solo3D}/Surface.cpp (96%) rename {scripts/crocoddyl_eval => tests/python/crocoddyl}/README.md (100%) rename {scripts/crocoddyl_eval/test_1 => tests/python/crocoddyl}/analyse_control_cycle.py (100%) rename scripts/crocoddyl_eval/test_3/analyse_control_cycle.py => tests/python/crocoddyl/analyse_control_cycle_2.py (100%) rename {scripts/crocoddyl_eval/test_4 => tests/python/crocoddyl}/analyse_simu.py (100%) rename scripts/crocoddyl_eval/test_5/analyse_simu.py => tests/python/crocoddyl/analyse_simu_2.py (100%) rename {scripts/crocoddyl_eval/test_6 => tests/python/crocoddyl}/compare_mpcs.py (100%) rename {scripts/crocoddyl_eval/test_4 => tests/python/crocoddyl}/main.py (100%) rename scripts/crocoddyl_eval/test_5/main.py => tests/python/crocoddyl/main_2.py (100%) rename {scripts/crocoddyl_eval/test_4 => tests/python/crocoddyl}/run_scenarios.py (100%) rename scripts/crocoddyl_eval/test_5/run_scenarios.py => tests/python/crocoddyl/run_scenarios_2.py (100%) rename {scripts/crocoddyl_eval/test_2 => tests/python/crocoddyl}/unittest_augmented.py (100%) rename {scripts/crocoddyl_eval/test_2 => tests/python/crocoddyl}/unittest_linear.py (100%) rename {scripts/crocoddyl_eval/test_2 => tests/python/crocoddyl}/unittest_nonlinear.py (100%) rename {scripts/crocoddyl_eval/test_2 => tests/python/crocoddyl}/unittest_step.py (100%) diff --git a/CMakeLists.txt b/CMakeLists.txt index c546d4b4..1bd332c2 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -47,15 +47,16 @@ SEARCH_FOR_BOOST() # Main Library set(${PROJECT_NAME}_HEADERS include/bindings/python.hpp - include/qrw/Heightmap.hpp + include/qrw/Solo3D/Heightmap.hpp + include/qrw/Solo3D/FootTrajectoryGeneratorBezier.hpp + include/qrw/Solo3D/FootstepPlannerQP.hpp + include/qrw/Solo3D/StatePlanner3D.hpp + include/qrw/Solo3D/Surface.hpp include/qrw/MPC.hpp include/qrw/Gait.hpp include/qrw/FootTrajectoryGenerator.hpp - include/qrw/FootTrajectoryGeneratorBezier.hpp include/qrw/FootstepPlanner.hpp - include/qrw/FootstepPlannerQP.hpp include/qrw/StatePlanner.hpp - include/qrw/StatePlanner3D.hpp include/qrw/Types.h include/qrw/InvKin.hpp include/qrw/QPWBC.hpp @@ -69,22 +70,20 @@ set(${PROJECT_NAME}_HEADERS include/qrw/MpcWrapper.hpp include/qrw/FakeRobot.hpp include/other/st_to_cc.hpp - include/qrw/FootTrajectoryGeneratorBezier.hpp - include/qrw/FootstepPlannerQP.hpp - include/qrw/Surface.hpp ) set(${PROJECT_NAME}_SOURCES src/st_to_cc.cpp - src/Heightmap.cpp + src/Solo3D/Heightmap.cpp + src/Solo3D/FootTrajectoryGeneratorBezier.cpp + src/Solo3D/FootstepPlannerQP.cpp + src/Solo3D/StatePlanner3D.cpp + src/Solo3D/Surface.cpp src/MPC.cpp src/Gait.cpp src/FootTrajectoryGenerator.cpp - src/FootTrajectoryGeneratorBezier.cpp src/FootstepPlanner.cpp - src/FootstepPlannerQP.cpp src/StatePlanner.cpp - src/StatePlanner3D.cpp src/InvKin.cpp src/QPWBC.cpp src/WbcWrapper.cpp @@ -95,9 +94,6 @@ set(${PROJECT_NAME}_SOURCES src/Filter.cpp src/Controller.cpp src/MpcWrapper.cpp - src/FootTrajectoryGeneratorBezier.cpp - src/FootstepPlannerQP.cpp - src/Surface.cpp ) add_library(${PROJECT_NAME} SHARED ${${PROJECT_NAME}_SOURCES} ${${PROJECT_NAME}_HEADERS}) @@ -154,9 +150,8 @@ endif() target_compile_options(${PROJECT_NAME} PUBLIC -DNDEBUG -O3) -target_compile_definitions(${PROJECT_NAME} PUBLIC CONFIG_SOLO12_YAML="${PROJECT_SOURCE_DIR}/scripts/config_solo12.yaml") -target_compile_definitions(${PROJECT_NAME} PUBLIC WALK_PARAMETERS_YAML="${PROJECT_SOURCE_DIR}/src/walk_parameters.yaml") - +target_compile_definitions(${PROJECT_NAME} PUBLIC CONFIG_SOLO12_YAML="${PROJECT_SOURCE_DIR}/config/config_solo12.yaml") +target_compile_definitions(${PROJECT_NAME} PUBLIC WALK_PARAMETERS_YAML="${PROJECT_SOURCE_DIR}/config/walk_parameters.yaml") # MQTT Interface add_subdirectory (paho.mqtt.c) diff --git a/scripts/Documentation/Equations_MPC_22_02_2020.pdf b/Documentation/Equations_MPC_22_02_2020.pdf similarity index 100% rename from scripts/Documentation/Equations_MPC_22_02_2020.pdf rename to Documentation/Equations_MPC_22_02_2020.pdf diff --git a/scripts/crocoddyl_doc/Evaluation_number_of_iterations.pdf b/Documentation/Evaluation_number_of_iterations.pdf similarity index 100% rename from scripts/crocoddyl_doc/Evaluation_number_of_iterations.pdf rename to Documentation/Evaluation_number_of_iterations.pdf diff --git a/scripts/crocoddyl_doc/Log_simulations.pdf b/Documentation/Log_simulations.pdf similarity index 100% rename from scripts/crocoddyl_doc/Log_simulations.pdf rename to Documentation/Log_simulations.pdf diff --git a/scripts/crocoddyl_doc/cost_function.pdf b/Documentation/cost_function.pdf similarity index 100% rename from scripts/crocoddyl_doc/cost_function.pdf rename to Documentation/cost_function.pdf diff --git a/scripts/crocoddyl_doc/dynamic_analysis.pdf b/Documentation/dynamic_analysis.pdf similarity index 100% rename from scripts/crocoddyl_doc/dynamic_analysis.pdf rename to Documentation/dynamic_analysis.pdf diff --git a/scripts/config_solo12.yaml b/config/config_solo12.yaml similarity index 100% rename from scripts/config_solo12.yaml rename to config/config_solo12.yaml diff --git a/src/walk_parameters.yaml b/config/walk_parameters.yaml similarity index 98% rename from src/walk_parameters.yaml rename to config/walk_parameters.yaml index 1d09a607..b8a25b29 100644 --- a/src/walk_parameters.yaml +++ b/config/walk_parameters.yaml @@ -24,7 +24,7 @@ robot: q_init: [0.0, 0.7, -1.4, 0.0, 0.7, -1.4, 0.0, -0.7, 1.4, 0.0, -0.7, 1.4] # Initial articular positions dt_wbc: 0.001 # Time step of the whole body control dt_mpc: 0.02 # Time step of the model predictive control - type_MPC: 0 # Which MPC solver you want to use: 0 for OSQP MPC, 1, 2, 3 for Crocoddyl MPCs + type_MPC: 3 # Which MPC solver you want to use: 0 for OSQP MPC, 1, 2, 3 for Crocoddyl MPCs # Kp_main: [0.0, 0.0, 0.0] # Proportional gains for the PD+ Kp_main: [3.0, 3.0, 3.0] # Proportional gains for the PD+ # Kd_main: [0., 0., 0.] # Derivative gains for the PD+ diff --git a/include/qrw/Estimator.hpp b/include/qrw/Estimator.hpp index d8c014f2..2e35fbaa 100644 --- a/include/qrw/Estimator.hpp +++ b/include/qrw/Estimator.hpp @@ -28,19 +28,19 @@ class Estimator { //////////////////////////////////////////////////////////////////////////////////////////////// /// - /// \brief Initialize with given data - /// - /// \param[in] params Object that stores parameters + /// \brief Destructor. /// //////////////////////////////////////////////////////////////////////////////////////////////// - void initialize(Params& params); + ~Estimator() {} // Empty destructor //////////////////////////////////////////////////////////////////////////////////////////////// /// - /// \brief Destructor. + /// \brief Initialize with given data + /// + /// \param[in] params Object that stores parameters /// //////////////////////////////////////////////////////////////////////////////////////////////// - ~Estimator() {} // Empty destructor + void initialize(Params& params); //////////////////////////////////////////////////////////////////////////////////////////////// /// diff --git a/include/qrw/FakeRobot.hpp b/include/qrw/FakeRobot.hpp index 96b9864d..0e32127d 100644 --- a/include/qrw/FakeRobot.hpp +++ b/include/qrw/FakeRobot.hpp @@ -9,8 +9,6 @@ #ifndef FAKEROBOT_H_INCLUDED #define FAKEROBOT_H_INCLUDED -#include <Eigen/Core> -#include <Eigen/Dense> #include "qrw/Types.h" class FakeJoints { diff --git a/include/qrw/Filter.hpp b/include/qrw/Filter.hpp index b1ad99e3..65af7687 100644 --- a/include/qrw/Filter.hpp +++ b/include/qrw/Filter.hpp @@ -10,12 +10,8 @@ #ifndef FILTER_H_INCLUDED #define FILTER_H_INCLUDED -#include <cmath> #include <deque> -#include <fstream> -#include <iostream> -#include "pinocchio/math/rpy.hpp" #include "qrw/Params.hpp" class Filter { diff --git a/include/qrw/FootTrajectoryGenerator.hpp b/include/qrw/FootTrajectoryGenerator.hpp index 543731ad..a5f1866a 100644 --- a/include/qrw/FootTrajectoryGenerator.hpp +++ b/include/qrw/FootTrajectoryGenerator.hpp @@ -12,7 +12,6 @@ #include "qrw/Gait.hpp" #include "qrw/Params.hpp" -#include "qrw/Types.h" class FootTrajectoryGenerator { public: diff --git a/include/qrw/FootstepPlanner.hpp b/include/qrw/FootstepPlanner.hpp index 9a17ee53..09d9288f 100644 --- a/include/qrw/FootstepPlanner.hpp +++ b/include/qrw/FootstepPlanner.hpp @@ -11,15 +11,11 @@ #ifndef FOOTSTEPPLANNER_H_INCLUDED #define FOOTSTEPPLANNER_H_INCLUDED -#include "pinocchio/math/rpy.hpp" #include "pinocchio/multibody/model.hpp" #include "pinocchio/multibody/data.hpp" -#include "pinocchio/parsers/urdf.hpp" -#include "pinocchio/algorithm/compute-all-terms.hpp" -#include "pinocchio/algorithm/frames.hpp" + #include "qrw/Gait.hpp" #include "qrw/Params.hpp" -#include "qrw/Types.h" #include <vector> // Order of feet/legs: FL, FR, HL, HR diff --git a/include/qrw/Gait.hpp b/include/qrw/Gait.hpp index b306a379..9b4f0b7a 100644 --- a/include/qrw/Gait.hpp +++ b/include/qrw/Gait.hpp @@ -13,7 +13,6 @@ #define GAIT_H_INCLUDED #include "qrw/Params.hpp" -#include "qrw/Types.h" // Order of feet/legs: FL, FR, HL, HR diff --git a/include/qrw/InvKin.hpp b/include/qrw/InvKin.hpp index 181098e6..b2259718 100644 --- a/include/qrw/InvKin.hpp +++ b/include/qrw/InvKin.hpp @@ -14,7 +14,6 @@ #include "pinocchio/multibody/data.hpp" #include "qrw/Params.hpp" -#include "qrw/Types.h" class InvKin { public: diff --git a/include/qrw/Joystick.hpp b/include/qrw/Joystick.hpp index 15e78c8e..08a8fcba 100644 --- a/include/qrw/Joystick.hpp +++ b/include/qrw/Joystick.hpp @@ -9,15 +9,10 @@ #ifndef JOYSTICK_H_INCLUDED #define JOYSTICK_H_INCLUDED -#include <fcntl.h> -#include <linux/joystick.h> -#include <stdio.h> -#include <unistd.h> - #include <chrono> +#include <linux/joystick.h> #include "qrw/Params.hpp" -#include "qrw/Types.h" struct gamepad_struct { double v_x = 0.0; // Up/down status of left pad @@ -57,11 +52,7 @@ class Joystick { /// \brief Destructor. /// //////////////////////////////////////////////////////////////////////////////////////////////// - ~Joystick() { - if (js != -1) { - close(js); - } - } + ~Joystick(); //////////////////////////////////////////////////////////////////////////////////////////////// /// @@ -146,7 +137,7 @@ class Joystick { double dt_wbc = 0.0; // Time step of the WBC int k_mpc = 0; // Number of WBC time step for one MPC time step - VectorNi k_switch; // Key frames for the polynomial velocity interpolation + VectorNi k_switch; // Key frames for the polynomial velocity interpolation Matrix6N v_switch; // Target velocity for the key frames // How much the gamepad velocity and position is filtered to avoid sharp changes @@ -155,8 +146,8 @@ class Joystick { double gp_alpha_vel_heavy_filter = 0.002; // Low pass filter coefficient for v_ref_heavy_filter_ // Maximum velocity values - double vXScale = 0.3; // Lateral - double vYScale = 0.5; // Forward + double vXScale = 0.3; // Lateral + double vYScale = 0.5; // Forward double vYawScale = 1.0; // Rotation // Maximum position values diff --git a/include/qrw/MpcWrapper.hpp b/include/qrw/MpcWrapper.hpp index 5c85a5ba..bdf630e2 100644 --- a/include/qrw/MpcWrapper.hpp +++ b/include/qrw/MpcWrapper.hpp @@ -10,11 +10,6 @@ #define MPCWRAPPER_H_INCLUDED #include "pinocchio/math/rpy.hpp" -#include <Eigen/Core> -#include <Eigen/Dense> -#include <chrono> -#include <thread> -#include <mutex> #include "qrw/Types.h" #include "qrw/MPC.hpp" diff --git a/include/qrw/FootTrajectoryGeneratorBezier.hpp b/include/qrw/Solo3D/FootTrajectoryGeneratorBezier.hpp similarity index 97% rename from include/qrw/FootTrajectoryGeneratorBezier.hpp rename to include/qrw/Solo3D/FootTrajectoryGeneratorBezier.hpp index 7cf1f09c..80b89b3d 100644 --- a/include/qrw/FootTrajectoryGeneratorBezier.hpp +++ b/include/qrw/Solo3D/FootTrajectoryGeneratorBezier.hpp @@ -10,23 +10,17 @@ #ifndef TRAJGEN_BEZIER_H_INCLUDED #define TRAJGEN_BEZIER_H_INCLUDED -#include <Eigen/Dense> #include <vector> #include "eiquadprog/eiquadprog-fast.hpp" #include "ndcurves/bezier_curve.h" #include "ndcurves/fwd.h" #include "ndcurves/optimization/details.h" -#include "pinocchio/algorithm/compute-all-terms.hpp" -#include "pinocchio/algorithm/frames.hpp" -#include "pinocchio/math/rpy.hpp" #include "pinocchio/multibody/data.hpp" #include "pinocchio/multibody/model.hpp" -#include "pinocchio/parsers/urdf.hpp" #include "qrw/Gait.hpp" #include "qrw/Params.hpp" -#include "qrw/Surface.hpp" -#include "qrw/Types.h" +#include "qrw/Solo3D/Surface.hpp" using namespace ndcurves; using namespace eiquadprog::solvers; diff --git a/include/qrw/FootstepPlannerQP.hpp b/include/qrw/Solo3D/FootstepPlannerQP.hpp similarity index 98% rename from include/qrw/FootstepPlannerQP.hpp rename to include/qrw/Solo3D/FootstepPlannerQP.hpp index 2c4ffd19..9a482b2f 100644 --- a/include/qrw/FootstepPlannerQP.hpp +++ b/include/qrw/Solo3D/FootstepPlannerQP.hpp @@ -14,16 +14,11 @@ #include <vector> #include "eiquadprog/eiquadprog-fast.hpp" -#include "pinocchio/algorithm/compute-all-terms.hpp" -#include "pinocchio/algorithm/frames.hpp" -#include "pinocchio/math/rpy.hpp" #include "pinocchio/multibody/data.hpp" #include "pinocchio/multibody/model.hpp" -#include "pinocchio/parsers/urdf.hpp" #include "qrw/Gait.hpp" #include "qrw/Params.hpp" -#include "qrw/Surface.hpp" -#include "qrw/Types.h" +#include "qrw/Solo3D/Surface.hpp" // Order of feet/legs: FL, FR, HL, HR diff --git a/include/qrw/Heightmap.hpp b/include/qrw/Solo3D/Heightmap.hpp similarity index 97% rename from include/qrw/Heightmap.hpp rename to include/qrw/Solo3D/Heightmap.hpp index 124eb39d..8ae42851 100644 --- a/include/qrw/Heightmap.hpp +++ b/include/qrw/Solo3D/Heightmap.hpp @@ -9,15 +9,8 @@ #ifndef HEIGHTMAP_H_INCLUDED #define HEIGHTMAP_H_INCLUDED -#include <stdio.h> - -#include <Eigen/Dense> -#include <fstream> -#include <iostream> - #include "eiquadprog/eiquadprog-fast.hpp" #include "qrw/Params.hpp" -#include "qrw/Types.h" using namespace std; diff --git a/include/qrw/StatePlanner3D.hpp b/include/qrw/Solo3D/StatePlanner3D.hpp similarity index 97% rename from include/qrw/StatePlanner3D.hpp rename to include/qrw/Solo3D/StatePlanner3D.hpp index 261eea60..66945ea3 100644 --- a/include/qrw/StatePlanner3D.hpp +++ b/include/qrw/Solo3D/StatePlanner3D.hpp @@ -10,11 +10,8 @@ #ifndef STATEPLANNER3D_H_INCLUDED #define STATEPLANNER3D_H_INCLUDED -#include "pinocchio/math/rpy.hpp" -#include "pinocchio/spatial/se3.hpp" -#include "qrw/Heightmap.hpp" +#include "qrw/Solo3D/Heightmap.hpp" #include "qrw/Params.hpp" -#include "qrw/Types.h" class StatePlanner3D { public: diff --git a/include/qrw/Surface.hpp b/include/qrw/Solo3D/Surface.hpp similarity index 100% rename from include/qrw/Surface.hpp rename to include/qrw/Solo3D/Surface.hpp diff --git a/include/qrw/StatePlanner.hpp b/include/qrw/StatePlanner.hpp index 7d8eedaa..9055eac0 100644 --- a/include/qrw/StatePlanner.hpp +++ b/include/qrw/StatePlanner.hpp @@ -10,9 +10,7 @@ #ifndef STATEPLANNER_H_INCLUDED #define STATEPLANNER_H_INCLUDED -#include "pinocchio/math/rpy.hpp" #include "qrw/Params.hpp" -#include "qrw/Types.h" class StatePlanner { public: diff --git a/include/qrw/WbcWrapper.hpp b/include/qrw/WbcWrapper.hpp index d74fe0b4..99c4eb51 100644 --- a/include/qrw/WbcWrapper.hpp +++ b/include/qrw/WbcWrapper.hpp @@ -12,8 +12,8 @@ #define WBC_WRAPPER_H_INCLUDED #include "qrw/InvKin.hpp" -#include "qrw/Params.hpp" #include "qrw/QPWBC.hpp" +#include "qrw/Params.hpp" class WbcWrapper { public: diff --git a/python/Solo3D/FootTrajectoryGeneratorBezier.cpp b/python/Solo3D/FootTrajectoryGeneratorBezier.cpp index 5acec150..16a09922 100644 --- a/python/Solo3D/FootTrajectoryGeneratorBezier.cpp +++ b/python/Solo3D/FootTrajectoryGeneratorBezier.cpp @@ -1,4 +1,4 @@ -#include "qrw/FootTrajectoryGeneratorBezier.hpp" +#include "qrw/Solo3D/FootTrajectoryGeneratorBezier.hpp" #include "bindings/python.hpp" diff --git a/python/Solo3D/FootstepPlannerQP.cpp b/python/Solo3D/FootstepPlannerQP.cpp index 0eabe80e..3fb91cc0 100644 --- a/python/Solo3D/FootstepPlannerQP.cpp +++ b/python/Solo3D/FootstepPlannerQP.cpp @@ -1,4 +1,4 @@ -#include "qrw/FootstepPlannerQP.hpp" +#include "qrw/Solo3D/FootstepPlannerQP.hpp" #include <boost/python/suite/indexing/vector_indexing_suite.hpp> #include "bindings/python.hpp" diff --git a/python/Solo3D/StatePlanner3D.cpp b/python/Solo3D/StatePlanner3D.cpp index 96dca84f..1ef2cc79 100644 --- a/python/Solo3D/StatePlanner3D.cpp +++ b/python/Solo3D/StatePlanner3D.cpp @@ -1,4 +1,4 @@ -#include "qrw/StatePlanner3D.hpp" +#include "qrw/Solo3D/StatePlanner3D.hpp" #include "bindings/python.hpp" diff --git a/python/Solo3D/Surface.cpp b/python/Solo3D/Surface.cpp index 6bc9a253..c15373ef 100644 --- a/python/Solo3D/Surface.cpp +++ b/python/Solo3D/Surface.cpp @@ -1,4 +1,4 @@ -#include "qrw/Surface.hpp" +#include "qrw/Solo3D/Surface.hpp" #include "bindings/python.hpp" diff --git a/scripts/Controller.py b/scripts/Controller.py index 8ea72b26..079fb719 100644 --- a/scripts/Controller.py +++ b/scripts/Controller.py @@ -1,13 +1,13 @@ import numpy as np -import utils_mpc import time -import MPC_Wrapper import pybullet as pyb import pinocchio as pin import quadruped_reactive_walking as qrw -from solo3D.tools.utils import quaternionToRPY +import MPC_Wrapper +from tools.utils_mpc import init_robot +from solo3D.utils import quaternionToRPY class Result: @@ -98,7 +98,7 @@ class Controller: params.perfectEstimator = False # Cannot use perfect estimator if we are running on real robot # Initialisation of the solo model/data and of the Gepetto viewer - self.solo = utils_mpc.init_robot(q_init, params) + self.solo = init_robot(q_init, params) # Create Joystick object self.joystick = qrw.Joystick() @@ -146,7 +146,7 @@ class Controller: if params.solo3D: from solo3D.SurfacePlannerWrapper import Surface_planner_wrapper if self.SIMULATION: - from solo3D.tools.pyb_environment_3D import PybEnvironment3D + from solo3D.pyb_environment_3D import PybEnvironment3D self.enable_multiprocessing_mip = params.enable_multiprocessing_mip self.offset_perfect_estimator = 0. diff --git a/scripts/crocoddyl_class/MPC_crocoddyl.py b/scripts/Crocoddyl/MPC_crocoddyl.py similarity index 100% rename from scripts/crocoddyl_class/MPC_crocoddyl.py rename to scripts/Crocoddyl/MPC_crocoddyl.py diff --git a/scripts/crocoddyl_class/MPC_crocoddyl_2.py b/scripts/Crocoddyl/MPC_crocoddyl_2.py similarity index 100% rename from scripts/crocoddyl_class/MPC_crocoddyl_2.py rename to scripts/Crocoddyl/MPC_crocoddyl_2.py diff --git a/scripts/crocoddyl_class/MPC_crocoddyl_planner.py b/scripts/Crocoddyl/MPC_crocoddyl_planner.py similarity index 100% rename from scripts/crocoddyl_class/MPC_crocoddyl_planner.py rename to scripts/Crocoddyl/MPC_crocoddyl_planner.py diff --git a/scripts/Documentation/Equations_MPC_22_02_2020.aux b/scripts/Documentation/Equations_MPC_22_02_2020.aux deleted file mode 100644 index 2771ee2b..00000000 --- a/scripts/Documentation/Equations_MPC_22_02_2020.aux +++ /dev/null @@ -1,38 +0,0 @@ -\relax -\providecommand\hyper@newdestlabel[2]{} -\providecommand\HyperFirstAtBeginDocument{\AtBeginDocument} -\HyperFirstAtBeginDocument{\ifx\hyper@anchor\@undefined -\global\let\oldcontentsline\contentsline -\gdef\contentsline#1#2#3#4{\oldcontentsline{#1}{#2}{#3}} -\global\let\oldnewlabel\newlabel -\gdef\newlabel#1#2{\newlabelxx{#1}#2} -\gdef\newlabelxx#1#2#3#4#5#6{\oldnewlabel{#1}{{#2}{#3}}} -\AtEndDocument{\ifx\hyper@anchor\@undefined -\let\contentsline\oldcontentsline -\let\newlabel\oldnewlabel -\fi} -\fi} -\global\let\hyper@last\relax -\gdef\HyperFirstAtBeginDocument#1{#1} -\providecommand\HyField@AuxAddToFields[1]{} -\providecommand\HyField@AuxAddToCoFields[2]{} -\babel@aux{english}{} -\@writefile{toc}{\contentsline {section}{\numberline {1}State Estimator}{1}{section.1}} -\@writefile{toc}{\contentsline {section}{\numberline {2}MpcInterface}{1}{section.2}} -\newlabel{eq:oMl_T}{{7}{2}{MpcInterface}{equation.2.7}{}} -\newlabel{eq:oMl_R}{{8}{2}{MpcInterface}{equation.2.8}{}} -\@writefile{toc}{\contentsline {section}{\numberline {3}Footstep Planner}{3}{section.3}} -\newlabel{eq:gait0}{{18}{3}{Footstep Planner}{equation.3.18}{}} -\newlabel{eq:gait123}{{19}{3}{Footstep Planner}{equation.3.19}{}} -\@writefile{toc}{\contentsline {section}{\numberline {4}Foot trajectory generator}{5}{section.4}} -\@writefile{toc}{\contentsline {section}{\numberline {5}State vector}{7}{section.5}} -\@writefile{toc}{\contentsline {section}{\numberline {6}Dynamics equations and constraints}{9}{section.6}} -\newlabel{eq:c_linear}{{49}{9}{Dynamics equations and constraints}{equation.6.49}{}} -\newlabel{eq:c_angular}{{50}{9}{Dynamics equations and constraints}{equation.6.50}{}} -\newlabel{eq:assumption1}{{51}{9}{Dynamics equations and constraints}{equation.6.51}{}} -\newlabel{eq:c_angular_bis}{{54}{9}{Dynamics equations and constraints}{equation.6.54}{}} -\newlabel{eq:approx_angular_velocity}{{55}{9}{Dynamics equations and constraints}{equation.6.55}{}} -\@writefile{toc}{\contentsline {section}{\numberline {7}MPC matrices for dynamics and constraints}{11}{section.7}} -\@writefile{toc}{\contentsline {section}{\numberline {8}MPC cost function}{13}{section.8}} -\@writefile{toc}{\contentsline {section}{\numberline {9}Output of the MPC}{14}{section.9}} -\@writefile{toc}{\contentsline {section}{\numberline {10}Inverse dynamics}{14}{section.10}} diff --git a/scripts/Documentation/Equations_MPC_22_02_2020.out b/scripts/Documentation/Equations_MPC_22_02_2020.out deleted file mode 100644 index e4dbcef9..00000000 --- a/scripts/Documentation/Equations_MPC_22_02_2020.out +++ /dev/null @@ -1,10 +0,0 @@ -\BOOKMARK [1][-]{section.1}{State Estimator}{}% 1 -\BOOKMARK [1][-]{section.2}{MpcInterface}{}% 2 -\BOOKMARK [1][-]{section.3}{Footstep Planner}{}% 3 -\BOOKMARK [1][-]{section.4}{Foot trajectory generator}{}% 4 -\BOOKMARK [1][-]{section.5}{State vector}{}% 5 -\BOOKMARK [1][-]{section.6}{Dynamics equations and constraints}{}% 6 -\BOOKMARK [1][-]{section.7}{MPC matrices for dynamics and constraints}{}% 7 -\BOOKMARK [1][-]{section.8}{MPC cost function}{}% 8 -\BOOKMARK [1][-]{section.9}{Output of the MPC}{}% 9 -\BOOKMARK [1][-]{section.10}{Inverse dynamics}{}% 10 diff --git a/scripts/Documentation/Equations_MPC_22_02_2020.synctex.gz b/scripts/Documentation/Equations_MPC_22_02_2020.synctex.gz deleted file mode 100644 index 95ed3693c96f0ea8217ccaa115a9555e3c7d42e0..0000000000000000000000000000000000000000 GIT binary patch literal 0 HcmV?d00001 literal 185264 zcmYhiWmp`+5;hu02=4Cg7Tn$4-2yD`Zi~CSy9aj*?(QyGWRV1S76@>2&bi-r@BEpW zp04+)sjjMiyQYUU7Vgu3kIy~5dWjYt%`}hoCX2WmsCq%}BR&)B?WU08#fV?rTWDdi z>hz2pM&?!)zgQlmKD@@qdwFZ&TpM~Db~5JFEZM()4ITXc1vl~o+%SLjzC0ZG?)9-g zJl%1^T6p!K@^N<3uxoPl@YbMWA}sXx<>6vHlC=L_#RTO4aew{%u-))6eRszC@jATD zx?5n<-y<jje0^A6_v-Hn@Oy9B@A0P=?tcfbe?0dCS^EQCPd={u-(CZ`j|<bEtxDrw z#?OWm>oD9t&Yqn9J@)f`y}f3{4g|hu-rg<0n!E$wA7e}c-yk?2Z{UlLNR!>Z9^w91 z$aSI@X}<%~xdT$4&_@SsUG)33^p#_2;Mc|B6R!`*<IDQk;O^M|>)Gplq6jI-X=R`L zR40Dw1Nh-jnb?sWxPSjg`bA~;@%|a%Wjt~om396qYM2z2bpC^QrE+zasqbz5WZg?8 z6r-&#eVi4wkW@rC(C@|L^*J#yklS*7<FHmKRB&DQs9^LgQD^YTcl+=AE&2!Ps&B8J z@Y}<~{?XCC|EmSSE#7}E1NaQyKbk*@L_OqrhdjO|nppm=XWPK;uLA<Sdf$Zmdfr~{ z|6Xo4kdnN=WOfK>{W2SwzX}xGySg|T7&A1Vu+q~X1_gZF+#gLxCQox!%ya@FnXD$U zg~ZQ>S9%5?fp2%`#5piIXT5gMSKX|IyCNc<0=`f0O|Cyd8QpvVZ+AkPf)j4NYCK0h zf;~XmDq-OsKVR>T<@<;Fr?ctd^~{s`hW@^f_Z#qfM<Oa^E}`K!kB75uk-jz)Y3`4& z3ZQ^Z{C%!=K`Rb<^M;P2vEzrMXBU7=FS!m*e^Rfz&Ci>SGl#CGmzE8V7E-@np?*Ju z2+cP>?sH!aOU3hvBVUbr!wDGWvMx}JNk8xz5>F!-vuOO|JHWLUx#Ke6=?I*enLK{+ z)$rwY#_IR^88hA%<Y@Z!#SLxj*Y|!@ti!&(zpDZGn}$xqS0VvEufFeB6MMeX{;v-g z-6!jjFK+*UR^N4&m;|pM|9jmR@O(FY!rFkf*|94v%`?_Le`QigA|30oZg8G>XJ{0d zpy(J)$(y^L5zuKDr``OVdDSpa+8+<B=h-41-RmGVCvfSW&QBl>?41qp2Y#HrX0jI2 z7eC*DxBE$q1N{BpuXm-h>v>GBOWrHaYrmC<$Ox|+e1nK~&o{_2|7pnlHFDU%2Hr9a z!F`7u{mN7+oCtrMyIa@2=MoGoRy^?FL=0587d$a+WmhzP_tkle&U@<@?D_j}@yBOn zkC{f~BHrtt>*Epn^j;`X`aB(3xO?osh<!5NeSdj;xvpX>6_GLSpbAHHtgYJ5SW*3* zuoHRctx&;xBwKuOHatCC7;;xf8O{~xOuxSdMZxtP8#OvqXKp^^PUtz}2LMj5e6#v{ zG5xyU;AB!5rtCy4kn*se$=YBtVTHKXK~)^<GNL<XpshV{i^+xG56s~d0`ccaTV8<z zfV6lZ{tW2|JeZLEItd#9<l$nvBNBJ;c8!g*8Tj#b*X^b~*9GFwJ2s4kf&+CVRP#9< zx?(+(lN7ADoPEk&zqx(9D>M;?Kkh(jN}m!@%M=bQjV{n}J`**tH9_jU_xie1l*PI$ zg6LK7J_kAL5fKW+e9L~HlRd93q)z~r&D<V6KSU#)=t(2|xr$qGvmNCF@r#zP|9uJn zl34=cm!^%|hsd%uu<q{44LT85y1noAo3h2+^?3m0LAxOT=NGbc*RzeZIJ?u^7#O&@ z_bZj)hC|K1-jCbcKNl-^#|E%JYWMqrfdNlq*S#Lj@_i=nkU$cUoWM*+!faQ*>dMXK z{&vU7d}2w6!FXBi-o^BE<_81y$E!rD><5;1%E$Wz@SPK%>-j2iB9as<Ixv8dBK7YR zEZ|w<6mo?+!ER<<4TSu?WF36JLX~9~{w*n6zdGx7lqu35C|D`9-Js$`D=c4=ODq5H z^~YI<Ozb?i)n%haj0-<Rn;+Np@C*CiZ&^=N&ij9ugzWl5_d56=vb(*-DhnL1H~fwM za`)yKEnjoC{(ii9HF4%t7eC`_Q&(?7i2i4eZgUr2tX#DNg<=sZ53FP|gL>5cXZsmA zdfj7Bhque`;SYTOya?{vKM{E!(gl`C?t@2O|Ktj{s6_JH93DMK0)S^bT#Ir}$nQHj zcP}t4H)Yfv%C_s;y6u0Gbh2jtzEnHCf-6f?#!x>WRVO}EevZKcy|;m#-(*TV3j44H zKmnJXhW*fd&c!0*DqJrSS5Kca$A5Jo`wySI22Yaidg^!WZ@POtY;t<Td-{(VPm z_grNC=k@pF39}C^;}aEso55~xD=zKnBElCF!ylc$teyHh$X$lV|F$db-)*a)+NVxy zk=~86WR6F!ub=4LsvM>Yi(EpEK3wWPZr|E2^wmE;G~H(Ld|*Ew!4H3tZ<ZrZPE7j! zKVI6H9u6AD&R&X_?*Cpt5I*mV?0%@PIe+EaZ4@f<+M4z|mT}x5{pOfsqn>_+;&5TK z+o)C)AYSjc1q$$A?=-wR+y3_c{%3nTu;-(tsWZSnj_LhV><8oxTkwaE$XjGbV&T8s z+|OtkA}IQH9~clo^Dgps68J>A+yC)+?b{IW(*N4<(WmI%@Fenv8Llq<cHi()xqCmK zR@Y@6Dz|UtB!0_%>X&M+N^@3dG{aJJ7^p2GbfMZ&_;hOZlG(I5eEImT(7&SV6zTO_ zxJ{+KtVr+kpQn$+BSf*tJQ?oEpIFQDEcE6QoX{Sxn{1IdM&dsF()c+#N9t-;wyR`1 zs=_b!bLlTot27c@r&(&FSxfU{7@o#tg&sG&p~;+?*7cEmu4<d3$d3{4MypSyX?`bi zfbFS{B_iw7<MOoM5YZxSprw+UpoOKLi+w4EUhvVz*d~_Z;l^4g5mh_#lyCHfp*#(q zT3(Ba9u{mv2wO>(eb%*<8^vU@pi_bxOV+v2aE0_~lHu`2nTSeY#{p{j2ET1tVjbU8 zbVTr~jrrK1RSn$F2jdFkL9DGA7H_9tmS3LnE+oX30c%@~>({RBeDwV;*+D|cn==fU z)~9&EIXU@y=DLL`eZ&`>QjA8y2a4Qfem6G8aZSw&^Q<Qb+s+iT{8tijo<+jT?JPTI zYx(q5jC@1Yke!G22YPC4y;LpaIr#pt!m1r9<V4)K5#iThQkdTo6=J1?XcVQqCx=R` zeI4@Is;&INjy)5b_+S`TW1z{|T+G*iDWXDL9$=k1iZmj$T0ld4g$kKRg293V7k<uV zTyqJHv9Rh$mJKKstF}jDLs6MsN^EdiAiQ*w!+;)}^$JTkrOHMRmi3AtHA&4J^Jg8+ zE%uxxJt6BAm)wNza+qUH^bUuVokXs3>}|Y;GT?(7!9ci$gJJ2zI>!<q&G=Gi4iMI1 zFLjSQwBgMrN0p4K*&>qSq^crw;~NUBoe0rjQ=EVv#j{z#NLCAF)I%8Lr{0$Kbdr#b z-D1ivLOndg%ckZz&~RpKKCS1)XYJQnN?nZN(Nhw{k2W)}8U)Fl5aUY?gBX<g&yc8B z4#wS@TJ)`g^O0u{Id59blt?l-@%eC-#H^R*5P){+I+#EO_8fR&Wa1oRKyUC1-4WeX zsYK7-mk&JbaN-zns?f{#wiC!<-8U_};0B2@KB-$afc0RsC;sV~B>B$)FSv4d9LOBK zOn}LrAA-#CM!oGphCM)?wPaebibuotAjDoLL6~oY8=T5PO{cbEHz|=Cj_|&wiYHB} zmmyOVLNX<SwSBH_tdwmghar^lLVN9i)G7RxZio_USXi>uTdfYwMo>-CCJ+V7S$#+C zHVWQ2dFPj(JfKIT7ZOLjK#7Oi2APde2~_(A;1!Nm7Q*B8ikXU6p?rx{2W|h#sl@Q9 z+v5p<Hq}r(zlb^<?ODytljx}=D-7{kZB%&M|Ci~Peg@0AvUG}LT~?i8rw~YEede=O z9MqsNlWqC=gFe}MtloBtMNj@SANr)?QQm};WDZch%w@1@A~nUuOjYG<X)afiEsV^q zN_RJAX1PfIb7zW=;_JdwUYr@7Z6^-k8qs1YCsm4l3<FoYxh`+$v?xxMmCwf&Xj5*I z^B_A#7e?C;=QZ=%Y@5X&my;O=v+!G|TJd9f%NlN^tPU;Z*qPvKi3nl#6DJ_G5t@LH zs-%OFon6K@R5hJE5Xk}FGdd!2*G705ZkjN=oIco+b9htjr&9XVq9{uuuxlyKs2bq# ziG$r3bo^#&y{vgYnS>g_y{cTobzXPCeeg8O*`W497BhKLq~dqOy`ogHH;s~_dY<n< zd^$&cdyp4(zz`!f6Cz9Ljx^`S5Px4h!Ya^gIfzAQkuS*+jevlKytD=&JTDXUp6M&` z&9xrusHw1Ba&G@dBQ5PO70r_QGx-_KP+d7m%~vs1$1qu~(++#cQ97cr5>nKafU(J< zmrkZ|kE`^zX3P3`xH^NZlrvjeTQ><`QR`5vGa|nDv=#fDPP*ihOTiOMZb(M1xz@V# zR4TWMwQ9&Z49l4Cs26a;Os#BOS9Z;3DkPQ!BSE6ljjgwWHABaSHNlhgS*xZgNNeAa z21+`^O`dwXusz!l3*RoPXZElpg+t%Ez%Z@klSjFaosxJv>qKoR5#xS0tT~_uc)Z!X zjJ}P^;@d9!q08wuT>l>aHL|0((>cDHzr2=i`Z_NP2&+vWnNwv^g$xw~8xlTyS(OA{ zO1g`i;jENgZk1{ro<Nd%f?{!2{%Th;A(dj0t^i=iT~e1;2t;JJbzIP|vvq?Kc2YHu zS4^40shHbHCSIN~)j3a@ZZr^+?)}jeB!CNA;2p4qrlm}EouU9|uSJZ+u*;c#j<C<L zPwwbi#bFPhmP?T`|8}6=rnV>FBAo${P3$pFR!btNoirTI;MaSm+R)1~h}jX`8VIRx zy$vB|8<wy9F7sK7uQ#PWQAT=fniiaPYcBOhIbKygDANj0p*51yzUKxPZ^(YF-2+3K zffV}}lT}(V<qM{3oU+AWm^7S4xiXfFtEus~Nvu|l+S#VIc4vy{QjN=`sIEQb45jyV zgvYdyq!Z^9k=fle3RDPbOkd7Yw<Y#$|70dB0Y_M!%1Z}A9Nx@&ugdk!XAMlbABK9O ziWuDuc9l4U+TW`L)VO8czA0hW{R?rrd1>3hm`QQDwxqOl4WdXV+dKguAsO@xTu1^t zfxPM$;VMGp6bP1)U8WQtjyD#v`W)>7>54zJNQ#8i;lvF+#u^Bo>$l_<oARxSSn?>` zJEvxoXEng5B5jI)F0v#cu2y9)_30)cEpV6?QR1BO+J?VKRpEC$^idR*+I6ucR!tXl zAr0ZJt+)u5A|4Qg0XY;bg*V=#4S#kV5ZP{_yDGHuQgww|@ehEAz7~JKPgegE8jI&% z4ubzHm{KxEQ?o}DkEgB`HK@15rbGu26_JUt#`JJ0DpO}(<m$7>@QZkF6?MAUlAyPy z!nesF!xg=t!fbmNltd(fsUB(H&+m_v3cop;Kyw3|(5aG4CRZ4<-fQx*0Z(s!PfZyF zA1hLX3-K6*AmnI9+#>Hv%UD+XJ^$(<x}|d;m`}T7L|V^RCgk^Fi&4QaGnRtl9K8jU zz;AlimLy@y9ySm->V(GwI`Pc3vUZP;r1%a|?j-RdNDMtG`O8Vaz;VtW>D7t$4~&f} z`uCpPHV<fvRK{6&Y8%-3*Ewhf=%<OyPQ$kBh}BU9;#63|_uRtJa`k|4=X6JgdqMJI zj=PS-rnI!Ifr51N<cnbo)4NRMUU#m*vFmo-!!n)TN!?DghnU;tlD{^_ed}(K#%nF( zW9a5IzK;NniM7rG8+El!#Y4q=ua#z_*jrKI5nrLjmY|*4>EsVxCPtM9qNMC?x!#_? zt#pAonO6@x#hL$_+C~HyIru)+Lg0m#?`2FASKKtQ9`sqa+L$V-KsF-(12CQEEI;ci zuxWpy1|C1${{K~Qn*mVHDc=)e(m+$+E4p|WB`HkMPm!Wdg}NF?Mi;;wIvOWPK#?FW zXb90#E&8alvWhTI6&@e?33>gt5VB(WBfzuhR-yf+F1&z4STf=L@Sk>qbcx2M%c(2> zRlfKnOwhN&s#J3XBxl^f^gn3<A=HIfU+$>hDk$~&ucU7d&W7{SJ~5H*DXzD-<Ds`{ zsq=EDdg7PIN7sY|e#(`;(qXnGwK{2qI7cdXx4i`d_ss=17$UTU;`3O|-^~*jIQX#S zd%^-UjuJDc>G_8l&L!ueU3pl?>wV?(XAS2em&e0p#>W4K(CMPQ$4*4$*NtloPa}NZ z5Ql=gE};eyXPj2Kq3=PQ%!QzqY>A?nce@8)vH-_TE5<(*nVE?6jIJ>{s|9_f)1#wG zssDIfu6)ySd<tLY*U|3}gVFG5w-G@~G$oXD3bWiw*K+%5owC3w;<`<kPn9r-H${RH zWpZ@n|8a+~Q0Y;hi3kTQ2tVa1_J6?E%v4z7G1$qKSa%iEk8y2(d|M6bsr}-yqZx_< zd8DQ?%;-+j%v03nn7HC_l(^iUPE6H1xZ?24N1i;-9jhE_ObIvFz+yMu%`KmUZ?8lC zZV|z>#?uoV*|s5HZk~E0e3ley78}MxUT9YyT+L?sw6=cxb54DFm(%CPlMn$P>+P7O zR$rR2X}g*lDwMu(im<WPNtF%XRZqEwGeeO#-Dn!q`Y3$frdp?Ubv`zd&+dya><3SN z^SKaCOVhd9;vAy(Cp!BM{4Z}(8j@bd>|c4wVCQ>$&>7qGJgVb=+n^A`Tn@xS(^@o- zs&}Ggi3>ISmEV&jE=(%9gsEsv`F$?_9qK<_rlD!i!<W>*yW;StXDGtVajH`8j2nM< z-P+P`LDLnL2^P368Q>I7Q;|o=^KaZ(>p<(YPam+Fq`9$CdpBi#+6ZxYGAGwzYklNC zc%`5%jg!&XV~kjkK5lYYmt|M^pz5U>1~Ff8koxjVsq0}y)N@GnP!ne%sE`wk1}kR~ z&g!#;73(~yC(Vm{h$Z1m>2*CavJ(oHZ$%)g2>npkle9VqHe2Lggcv!iHl|U0Pc(w7 z;Z8l5q-I+C{=xHnpyjY>YLH1)ibER%!U15_Zhil1w=+R^jS>@55uT*`pb*enU6+>> z5<6u7<I088+Jf7k-xSc(6Hre?n~lcaF4jPkO$sAmo9NGs-0drHh$)Y%DA>l-PM$}n zI+qvqGml6cO|p`{71_=;mkr)BO_(>#B!3%3XszMuG^p&CU$+*LKL)aK$T)W$S@Ri8 zh=_PFe;%7t6|t$*IY;VCB&W1IuWbjFu}D3bmH=xaDkx$?F*Iy`oHxR=D!I%2f%s4< z`H2VRIxTNBo`t)Y^c<vO^k9yK8WpkG@@QW*(jRfc@_23nu9|B}^qf#i2!I%Fi!5=P zU?iJHb-qIh>xx_P%1XY@rfC#H!!UQY@!E7v=)73D8uG9=Ki*!-iDtLzS{TL2iBJPq z+#wQV?lu}+9RLn3ewr$Iyvz$vou+KDFH7VtFFrT4R2`0Gw2JNFWG~qrUn*O!mcxo3 zCtoyM6bBtW!R9g2U2JIf{xa|k56Tf!d?4kxC|1B&nImTEjthEEttiz+-)ndqqX9ZP z4I7R*l^9PlJ=W8pbE_<sY?+`^eP>7&rc+6b7epZS8gX0a-!g)sfpIj{)hW0poM%-^ zrHo*Ugf%3iX-C?AAZ3H%pztfCcGe{>E_434?{`(zoY97QWS7bxS5Svp=1j)1@CcVK zdF?0{HM#r`CzIM_b!wzyAzTCndSf}g1KL*gm1>(I4el7*hi9~~Llq8Hx@5}X@wp|= z-$e%oIjN1wF<@9c^fBIHR9+ioj_;7NHnjLOSli(yn1sT(@p|{*LZU8FMhKyL*!bmV z;{=DWDb$w_RsN=2i3_)!TDq2R7H7jqrY#u()xT5?MT=USaSnxz&7RzMo|GgB8&@t~ zX-f2gV<;qlLXJllr7@Fz&SNLJ_9Rp29xYrVbmR^yo9pZo>u%671hDb>o2dW?7^Jzs z;(w&4A>K1Vk`6T^aUm0qoOy)99TUo?I7qubMkvuPK*c_4kU3-n>&zeH2;Q<RelOKI zOhM%u-7(?T2?8kF5?Iv1x;Szh>SwJ~j4{;3cu3I$e`@>Dp@=lP{S6qK$}ayKRtCd` zQ*=)wNa|Q%uh79T4VC^CuH1U`Iq#7$_MnlidC`t)Rk-kJKoPBdKVAO(yvji&m9SNJ zc5seD9O2JNmRwcYa+slCw6g!@#F^`TC5*4r28#R*qQ&y^XjHREVg(v0A*lTkf8RtS z4p5XHxT%~9;Ij!TWAB{#qO=W^#ttp1@4<B)KEqJ8mcRrwRGvAhVOC%hshqp%nU+qe zUkn`gXd>cm;ypj3Y+GAHuT7-uKSwx8R7~*S-*)@(-4exU(We&i?wBrI^0$@_r(1Uz z!hdC<?uDx9CUm@lRS4jb>A#AU;|mi@%B2}PUlig-K>EEeIRBva4*vqfz1?0xoS6yp zXm6lFWYE9b&hWq4aX4#3Ob9-C)?HE3-nitC;%3D9EA*wf+T-Hsn}cz{6<u5LO3mhr z(NUg@sC}9f4^fc#W!O@r@o27e&kq10N`B}#&y1ieq?bW?fCP1lqtEQpyN=B3?zV5< z*3uHRCs6T!r&9lMuir-rm7P4_ku^L8XM^zXzFc`52dI#<vkU$~LiE$|Jr%zKmzJ)! zfJ|1Y@=Z-KZMF(>Kh0@9qm@nJ9v!ie;L^~L{TCa?-V!?4Oe^mT=Kp0FJi#cv_Rv^c zghnq>xuS458fD+0i~|xsbIT?8BP^#V<NApJNL}QO9^b1mgdbfBq{4m1!C5RQVy;rG z)ARVtW#Iqv4+jV*<F?PZhBeqmJnjF2UqMiMcW#;t(UNG0NmG?{XKfxFu_mb+npebG z=doyf4bRZ09C@@U+xNrv{&~UNC)vg=Jx0zJrtw)fzlNref5eK-n(L8K(T^b)%Piyn zGPA3yf4CZ(;3;gOKUL@A(vrh|3|36;vds6lTN)8~5PeFehG$?&aFPpWB*hX_H{w2{ z^1Jgx?X=KnAm8L=O42{aSPR2siO==W**uWaW<2{ZWmxV3t{Z*6H}g_Ekhz)J^YOE5 z0{=?<rA{w+^hM3KICK4S$S78REvkh<PsKOpZ$rDht)-TuJDoy)bLE$REDY4)KkJLo z@wo3vuJ&IN7MPp43!B;aqe-h;3u%rM-G+s2R3S1b+=UMvKhyx-(2>r8LVrzDCvJ|* zgPWI+B7J4bKxQiaIEw32?R$0;<txx~Dx@CwZv5wt6!-!locd33pWS5cGsW2L+WY^p zrQO+SD}kk;3^(DY#XkPZNwxUd-Rq`P@Y0uEwQ!%1#9wfhxbk^8N#mieQ$JgCsL=mI zm#zesEMsH<xU|fe|DiWdcdqB?(L!y%5-C((TD46GqzXz3(N+Oib+$PP6r_q{D7f`y z#(nW6n@@33$Tpk}`u%uPoon-qY#j~Ly`?*57<Myc{VJXDj0_Ub`xx*yl}U2Bg^|=L zJn<@_diItp%d@Tn3Y^rqm_lG=!L9d>_M+w;CNHkruC;c(xy$v!t)=1%JMCP-s$Kn< z-Z{PG_-lV8UZm`)Q=mFVcikLjqhm&m=siMAhXq6%n1k!2_(Klr&YL+P2j_{*^h=JU zG+QD%9JBg+a+14)wN);(e?n83ub<k)bdmy*WS99U)<dMv9&)R7sn*Zp{DvFopcLBk zPJk^%c8pSU#NC0>FyXc9Fy=XCO+(NAq~!V5KC+7JnT*<{u8RYNA_0cwvG_aSdd+I) z%i`@C_#m&@y2(k171Y)T#o9r_g98@kTJ+6XZ!`$+D4-Fnk^Zk-FA^fW5~FK(C$na& zA!DI6la(+U;2Er~oF4&*o~-1;SxmuzNQb+Qgn$KfP_E&DGWDE_5WjQdHu;Ryrf2v- zSN=n~a4|6d9A^`YYcaJn?$IVVs5Xs*_Ed}cuq>Oua2@Iqg0->{)uO35-wXsxAjDV< zW`OT*V@T<sW|Y@*G3w8gf!@z!<78i3nvKKeAnl{igszv=zpa4wWFEfssE;ZeWJl;n zgrv82((!*)+5|WDB>VAXZp)$r1bvNS$sHTtD6H8)NbxB|>GrJZd9?sP`m&o&rU)>t z5@u$~UyT7ChE0$nijt41$YCp6RCvB9A1~*^v`89$>wJR)f(NIkdDm~(ue-;fzC`GC z*JPUfPV1BdqJ|X&KhN#MFAY(<PPz7@R_DIk0LFlpee=-ru^-zllUPsTRGr{4??erv zy1x?iSMg2`R6J5QwmYY|aJil@;oopB69nJFi8HEpx%HY9-Z~vpEUgN^(q#N>1Rg7$ zbRSR2|1F^N-H0$jTO`7}8*rr*XNldkQkHBXXX)9O+|)oLz73IOJX|Qgt3B%U`eI7P zN^92RGGMpJy-f672YCr4SE-R~W<zZUm(o782{A`DMZam-c}>n8hTDqL-3-u_A|)UC zP}Z(HM^$fIsuz?(N^8sU56I*%E<o1a2#XkcS0VMWS|&~bigXVK|0uZ_K<(BnDo2n| z<JO!MllHG*hU!ozKfzDWty?`}#*D;6*z(?*(c|PSj&QDz^qSmmzAjBi2|n_O+~D=( z@SM*sZBn4b@~YQ9uY)#0!Kn$BTiAYU$16j5YBo>~+s?x5ySs`4lB(%~@AKq`M<{Ua zDm?zUHb`J$9Nb20R<!y!(4>&Ar^Hp@$xCZ9mvVzW+ZHCbc$sx%;XRM^Q%5$r=$&Cx za%F=R$nW(LdRh+haMY<>Kd|uNJvkXO?T~QQzhhScpEp`0MwCGmE}k2a854FaWu<Cj zVp$kJMUy1&-sExbBP;o65Smp%fTo(QlIYHCu_UQ0IwF$?k^0bh-u&swi51sp9PS2Y z%9Bijv9CI{RV=o{Jm2CC4*2jZ&>1z=?OH1Gn6YzOI}6~}e=*y(;1IT8UCm!&;|UlG z-{2_Ihcm*moYRJP46xV}>|^`Y;Po;8m@8WmFmznYrZp5InaZfgAEMFje?$6{T4H!N zG&Y(><!M47_p~8#RVBmN2$$*XmnKoRYX{d!<VVRssIInM0OzHn8r4g-G^NL`FkD4v zt)@Gvm%Q&7EPF>zTWTnDGBIgJEpg79jQ*;y0z=*u73nuZu&JHEgPWInKGDDLz7k`! zlyzHnJ*gfORiB?~fnedER$U^8f!oJCvDY-!MMTpx82t6T3UHppYI$B|*jQRLVXi<$ z+d`hH!f$x@kBT=B_r`G}GYB$IF$#-K^hTc&TXaFbELVGNG}JR@t4w}xL8PUGRY3pU z+_Vyn|Mc!kkFk2(49H|JS*Gren{AQXQ1E$SvQpNrTdS50O*SN?Y?*jfNBLKv_YB{n z(zH<G?VoQW8^*67gALry>L;@ch)%w_J(h({44?l-wUVT2wzX!ykxu^_T_9*YT<-`w z-hIPw$PC&^;4?7=`J_JSbYW1(mfq&kneTGU>bg<n(U%7w^I`*a=>lA2G8nSyRYIet zl0s9q_12`Jyq`0MCMQPs`IoWrkqJXFYZaAriPf>-;XOBqgZ%vwJ&PCM9}YH?YrlH7 z&HiU0QW`L78L$1$$x5oN?4=sdIPvEG=N@Qc5%x>7=Pu$1TCHznGycOlu5*AmUNjDS zZ6?YO$_;JHM?c8R%<FgX#-;}Fx1|{^QS+)o6J~+3bF)`UX_2~1ti2iHwemSiFOz3X z7UGKJxhD7aSlb5Q{t%rh@#dcK@8Z7+nNAo=!T@Z+#8NxUwBIYovYhgC45=1A>9}i& zGI@qk1*!N%-f+<dft16t3&M!(2*ODsOhhmgn1XY|tKyiM8fkY3o`;W(`gCQyvx5%m z!_(pBT>pw6`C3Q|vD#v9rZ)jmtq6HfE)&AI+NRL$_ze5kjg6<*e*zt6FnVyi#aLsB zxrDz~L~nT8)8O@E5kA%Ky*sdQ<AC!`VweX6ngs4e&*Mg18MviV1;F3Uz>VAmc6)2d z&Rmy!gw>M0e-H3R-hFmnsmIBb?SCGYm$1|LnT~mA?gcmlefIzpq{MRv^K~Xci~_*0 z@mKvk;yG4o9^DURqs~|EJq`w|NHRt%wiV`j82HfP{d0B};q?$=YKg-yU;ik_x{{<R z5v!s0;o-9u!dO6%vh#aeaWa|`@^6flM(eXnluy*wvlhxq>}v5G)GhjIBn@0fjN>PK zsHHwH$MrNSYDG8CF^~ywVp`Znpi9<cl$U&B`NWbxUazgEjM<fuZXNDrpV78=L!HQ~ zlZWJmQ7&c^H)EMO)iYJ*j3>eta~srgm}aju@T}j-sqH^vUKS;DvP#MA84A@}g&}~+ zOndf+%6K!GpFOQT<zy*;X3*wY_yoqD7aIUDBYBdU59cI7RF{L3b3-zQZf9%`Gv||7 zHZaR@Xa>1@9=a!oMM&k&`}vmO06GJ9QG}W^hYnsSnYZIuuVwpm01gZ6?8d@`Gn@o2 zDK|^%*vOXVZj<KR|B~<34QCN?)`IB6YC1I{YaySS_!u(kH|inBSat`kl6Hc!sk@9g zeB^<w>zuWM+$z9^V(d64AAY-9x?(20OHQcYko4x)r2+lEeK30y=V|3ZYRF8K38vt= z-VQy>K6`UP)&8(E8UTgI#T&Fi!}V`1pLUyLAGU(xS5o)8$Td)A%C~$uh}LP$*7o3} z>O@oD{hTjTP8}D%e65yXbZ{0QCe}!#M6IMpJ5{buT6=kIh|VpcMD43dTeBWl%+v(5 z*71_53fChFf~T%9bJMM6+s1?J<PWMADAIQA&+*VgPSYuPl*4u$W5?L|Ygk%1Z%)@6 zK94o%@=ypn?X}2+_HKuOiZ02V-VjX6Z3aX3bSc>7s1nE){GUc<o-~LJgOSg8bcmdo z<uywpG9!CzXqA3k{-rqnzZC9P=N%OxcoJ+^J|-~YN9gHMaLA8&`=tNZn`LZOtFcDN zlSU=(1Q*{k0WKJ0T$(f00j`-S6M=8=>#Lo)-mE30GjNtt-wcwGa>D+~2E;(OYJurv zwNsMlwUUatCC4Nvu0tFf{%zwuTC%7y5nOWHGlsOk6REcgR+n!!BKX01iGdOZCXbVh zM&DNcDV~VnRD3gADZ*`Eczv!q9Kl;In9&jE`y7#|0GwjL9Zu}TKvmdAA|+gzR;@Ym z>dDg=AKbA&Ga000-al=P@d7D)mK{6%CLh2u{@H17){bb(E<Uy{115XyN3hGCt(;#c zoHi$xV}>F}jIEzfowlO`49O_DuQ8>uH;YLj!-*}v1Ebs7>1yA}S@OI`yZ?M``Y-uz zrtQ9y9WOaPq(7YjIG53lbt8_XPjFE+oX)hOFpi^(i)G;pH8_F1xUesX3bu6z&0%fm zYTuNa3irY@89ob-v0H9Lg@W@C9lagkPGG<2bsY@+37**tkCe_p>-b6@K0K&mCCRt* zqv_uVoW|9teyzkB(rHD$2H})08{#i|Bf*5`_<DBsW1)R1abGcw*F0mlkXQ_r#eVGU z$)>X#r{&&G4VMvBC857LG=j=&^<?99j(XNoW_&S3IostfdWKjS#g0qjO_M@aaYVTm z)dpUs^kuM$^y^B<VhK>EU7EECL0tow>3K})C!fJ3+%?xxQ{PG2h;l7^T=Vir?=^8A zD%Dk|nG$3XnsK&f%B_o$Q%kzA#}YEv7cAYm@weM)oVFhpA{syEwV!Snz(CdOp(@hx zP5$IB&bl5+B^zoXKQeeoqkES1@i_mNl*X1jGVZ3nuBUFnG~89tQ2&^COWIygVDC&g z7{tr=LZ|i60R(@=ZeRPh=utEfugS2nkD)Kv-0?jVOUpX^<y*Pmnf6O*7YgflMrCQ1 z@r-Hp6TsIKI`t%g_xDez*>26tL_0#Ln<)yt|BC)jB=CrvHq`kZ{62Ar(w0qyyW!Z` z60O*^Nhme;%KDhfm3-Ztw1?_Hfu0rsa#daPj3JqGy_li0KTqC$B2i5Wo%$xZFaphg zG`Y*!*_pU<4^}FLs0ZSWM!v$&`ys$8ppDA?wdY6>zCLvs!k0nteeix-<B`cuPPY?_ z_*F-poW+yTg8`DlQs<l>+qk)n9=}7_hP&Il5hMruTrGl=uQ{2+BYL&=ZtyBsKc|M- z8CQ>&?i9QqNFKsbDmTnTJNwgK@|a4}?;{lVkS(38BVbo9rS<9xL=8+#)nbK*c}LXk zbaj)t-NPOg=GSJ(P%P=CfkF6$J#>}d29E6|A2#aDtl3R8NmIuDNDZ>+3sNwR4l%az z8cx<k<IlrYXmMpTq4Ge!u>&}8aC=?<W4sbx`{;FvXB#!+n!$WS%T=(h^AJ~8NZb(n z&f4UJ;aw-v&c=T7ZqwPnEe!ffbDi`K)Wr4JGz|<B6EL)SR0hdXc~3Fo{E4B=+V^DH zs3cSd4@HB2&r=&&B|dW;Xg$E-gT|CnN#r*0S}v30kP-P2n&VW8)|e)oW7ZG4vF$h< z(+g}!*p4;-aWU^{RBAl~*G&mxmhsk>T)4RaLPnM1{rpS-0#))b=}+sw5MY9f2A|#f z;ZN`pJgO$ET}6GFAUkKzoy;)@)rqyFm!9C1Y|FCzm51XVpy%&9Fo^Kru|~WXeuH0V zY!a%bEmyih{I4onRjM42uHI}Y{s7S$oih!05Q8PJ9*)oyR}-xOwH>@0*gUy;y&Smy zZ<Eh#$%n1;NTFG)U!+14eIUt5sp0V6_9x?)lKsb)gU;=FM_z%VaV7o-&;+U*8BX~W zn5BQ0YJ8cRkD;`!FLh{{SNgzFMBsFzUV&FdXD=?^FoJ-Ej?|w!cN0l1S_#Vq5?TcC zvjR%gt3?iK%r>PviorgM0cz9PERZ?h9+()xy_Z6ALoR~3PgM1D2^HsjoN>~H^YSk~ zLb@XDkoVE32`I}-tcE|F;f@KVxaJ)eaftoFsJmGwjQVc68%<@aMW?;}C5qU)rKvyK za8g}TN_5%|!nho_w-$0*D1ye5iRz(H%YAxP4Who;fXWGWy?fSTQ7BGyKrxn*6GLuu zcR7tY@wf$e=-N5=MRER0SS@F_5C%&2jh+SOvNiV{ah|uwgV<jAF`48q71nDt5aZZM zzr`9}?g&^?pSn7TS;K(=AIfH|ak(>WqO(msl+~o0U&lh*a3#UC-)fo)m*-;5QMD5R zAP<g}$Ex>K>l}9|vR4Ql)Hz&A7!Q}JLbqPwD=9bTN@1Tgg8yKn<gdJi*>oUBAbrtH z|BU!LxPMKD+0LeY`15CcW<TBeZsu1*M^%s`p~57TfdNURP^NH!0x=FQpUHu|{9P>; zY5e3A9&9|9gOxz+a!+T4-O3%Wh*s>CE}O7^WVxH#VU3HzdW2^mOUWnaa~juZE^Wq8 zPeXtby>`h!D*R#$D`GG)GX#w#jEq*rnBI+i3Lc*|jJHrL+AvBRs0U{sAjc^MPd@dA z$>2;r^-7sR2(uQXgcozAdqXn<cs0*nk?mhO5R0n2W3I1K%I4WTXv<*og}-7@9~y5W zUMu11a8wGGKnYzGS&QS(9F?++=;>sZdcn&Zu^dh30qtJLa13^6oNHKYz$1!|IiJUQ z*}5NYY*O-eAQAF_lWm!YEB?U6YVM3ojX|is<__ZW3C;{;sm4@~gQ|@2y|m~+MCZA3 z=2x0taaSi1UO9uVw;KYLJ}wFxa?Xs6J~!q{#%&~imDF|K4a%(;9b)^wZ;P$@bR;Q* zP#ZlDkY^!O9turc!y(x&?<$QD9upJgk8W4I>b&yXBWuCA!s9|NW8b0*+xS?MI|S11 zzU#h$RmdUgXNwx5w+<ox0#Hd_C`MdZ)&cMYr=UF6*kw(_FemATx|YVi9vIAl?X?sT ziRd`2rO3VG8?8H*3U7g!QZ>son>>2$$@#0is`=|Zo=`YzRdMXNGVMgijdwPs%B3i* z{xV2=wFJV++Gjor*PNC!N7_dOJ)4Ef-Rkg8_es7s&C#Awn8eLh9&Rv(loiLE4Z|SH z?k1OOPx+qddCS{K$Kiiir0!aErxMI#k$Asq#22;%>|xJ|+p)JLZvu@yv&LWg>#WTq zvt40jEDUZam3v;aclZ_4nNbX{>xQKVr8=|-79EHOG!r=Fg(J^?I!N@zk53al7j4^W z)ol~aDmSSS3W9dJ9bnIYwPRDhMce#x(4<z{Al%w;SOb$!O|^Rv)+;;Lb$aCvjnl9| z)*So>^{zDkgLy4L+F2TkJnY?P*4G&|ZP?4Y*_L`Il?sk|E@8(%iFGrW7W{#Ayt!2r z9}zMUhP|ZUV+t#Q&Qh-22C>l>96_R7@Fj4%3+mnJaSMR6kvQu`pR4z#C6D3Ip7(R9 ztHT-AIPTiq4?#l^br$&*vG#yYKQ&xsQjr)nUKe`sQsh2i>h~2h1e;Wf5c`ebtSf4o zUwGd~j3=5q2dJZ~V!<BGeN7aCLb3IIRAy0Hs-I!&`~U383N&2?1tc7gR{Go!GxiZV zP!*y<Pgzs$PeIX^#HV3DvLcY{-hf9B;&A1MskV}W1QuJy7r*`=%hha@#q&h8=}8hI zZ3x)^PyS}BFpir}LVYsI`tv&7fv_}=1J%p;<hLr%4bH6}y_6-$@ZTB!KMhFT33FRh zNBx3gtwW*wIvhqbOXI_|h6JOze{75Y)3}I8E1anW`IJi{Ko73ZWBdPLK=M%yaU5E2 zfTKVc^vo{bJilQfWV1eNS3@=vO`2tE%6}6=*XFq`mhtOa#B4oQl)9t{=ZB4cPb@e8 zwOMO$<*s^FvJ~Nwgnvx76rr~%W@24abRVus95>SC_u*q65{EQ9FN|0R)wp?`F;{;y zeyN-2vrz1-hsB`GhhVGsADQLCjqrrD{aM04#+%B<9{y#XvtfO+Y?_zGdc&;g2h-0m zK~`6Mr=Pt(sD~v)je%(XT=$I9%N9FtqDA-PW?rdyN=AL)#g(jy-_uFak|OsrPRj?O zziWz3F#TN)x4nC2l26<u)<G<m=>PBV;Q8<Os^<yfEM^uTa;l=o_Fen1s8fca)k1E} z*qUgjZz*1KK3z)AlSrEoJ#&+=x*dkrZ^5!bM&NUE|26%0i2h;VBbV=4>fVPFZq(xA zcrXaJANq}!u;!&}Zk&(8?DE^=__u-f7uUZGXa*?Vk0v{TZ`fsof4BRig|ZA_(=Pvx z{T%5i@Xu0x3l3tGIcAHvKjR~^Ef;Y;3>Z#co)&S1t-$Xj<p1KM<#){kN@5>P(C+iV zFBubmK@&C;!x4*m5Llhlwl0e`he&4zH+@q0rMh-&vz4EZX}-xQ)~~*u*nE3_`@&6y z`7(0jC0Q>XhN3)E#uELID*6{{Q@Nj^uOhe`N&%LJh+nR=<0p1ulg%UJYdOAW8E`IM zac<+}t`#~LT04aY(LE+zd`VyKZyAN-#y$kAhMx<eYoBl@TyE<GQWmfiPIoN?ns-s& zGtaC+QQiY%V6rm?llC%ir+V`}-cyJj0GlVhBlQn7R-$Eo;0uSpEGA320eA3Hl6mf2 zL#KJieMPX&Y${ff#KE;hHqDxxV!VU}+WzLz5g{IU1@Xo7JTyWOxgv9c&!A*mNP6O@ z9V>gYmblr-7-U0&G34AlUQkiL!63HVRliZJEKzS4^p(Y|vxs?K?}YjSmIA?5yjr{N zmS+wi#-B2`vMtU-<rpQdca8q{Cbk|-6T}apkMY2VhBx$@NkFk*e#_dqw|}}Bo;XMW zj}qiXS4qlrX+3RT$IHb_h9lx_JCMW_;cM|>i52tt3Ma^KDSs&3#qZ3Z#7~?BwNA%f z@OyK{A8BC~#(TGp)wO*tm|KwgQ73@83TlBa<>s)n>^qUOO0l5v?KA%H?h!+l=(s`P z$%VzTRU3jUQ)W_Rgy6l(z`HJ_l40Hn@zW%xbLNA50Ti*Ly{MJx0ha%4Wv{R>@e8y+ z2GgaMDx)E^GULE9^gx8Gj^`uiz_}}(Os-3^v;>hawLZ2WOj_Ngw1g3QdXDTgRH95! z*;IEB@wFxLPlHb{%e%|QV=WP#b|!1HP?gwwHc;Q?o%SfpHRyCeQ2BJkg!(nHAo~0~ z+W~VKb$vtFV{n;2qv)880HKvUZc#T(kx09c7Qf?#v#&M}Y@T*dB}@=~Z*XE-!Oeu! zHAndg-c)LY;U8U%wg5AV&c_KbBCOLcOb{Xsy^z`q(*0}N{_h%rJ%p23Q9K$R{#~AY zjn4;q&{mcLZ1Yiz;3RDcBCGFTpeHNIrF}F?xrzEzJgq;&WR$rP{zPe)<%qIG80alf znG@1BlCsU^WTv%?>d$Lw9+M-p*UN=NJK2a$y2HC6awP%x*5Vt(@mc*I7CrqQ+Q^b+ zYI2ZlCdu!2nZ#Up<P!b6in;t~tWjdmCbA`_d6m=Ny6~kq!^j@Oe(@u&y%l`btanT( z6UDX5JLIRw(UaxGwADSq<EXVwv75wxc^m&#n?b5@{W+o?U!a=d0B?&ik(JO$J=y7+ z#{Cn%HOe2}-3_#pXK4$OSsuw>NDH^|Rd#x%SFk(k6@<@GK=WM(irqa1r)O!HC}60D zs$}ts;sJ^?=jKd5e;&Ha=i9DSgo9_AYK|yFOqL0|nL?aTBmz9w!Fm<0dGhg=o26}{ zH#wQr185Ix@>+Y1z!=OUi%7fu^r8V`%FbL}I;T&D+6DApFKGpbQyiVSM437+NALs2 zKA$1Yw{(UR{H6{Hbcx4>MMfF?CErBoMA*K~VBqV}$s_DkmN%CT(C6Wm%MloQ6ZUXU zLOB;{rD7-0&b8XQgvO@R(0@{_AqEy{<sjb7TqxG?5}h{RrwQ?&)t|S16(R}oofy-k z`}E|CuF>}CI~QV%ZaoEyc^9{-5%x5(;>mcFV1_`}oK=+0sH=vbUbyeFZUX%=S%&!- zrLQgVw8s~c>F1zKpV?J~3BtZON`}%{g^9kN6e0ocXE-~DLMA>S_7X9LBl$0K&~(mz zd6IGw?G8sJ4mt67U-Im-{+P?<`FF!){PoSw@ki_(Ko@z!VyX+yJQR-{p%R?7shB)x zF_iNUMtplE22{vY(%fE<twdg=d-@w^8KwuvK%2q@w$S(Hs7Gt~=f*8QQuL*ZZly4H z!z1RhnosCUE`z*#p!D&jr9}*OP`fstaYtAW`FuuFji4EP*L3RMc0xvykmEg%r)Ym? zSWj`ovtd`5;Ua2gl3ln$kgj<Br>3x-vpg1ZKi4TaB~ryrvj+!wABj9>^7Wsi7|lr; zpGPp*VOx*(5VDxa??C%Oc9}_1zlg{(lDd}ozPE(|%kJC5n9@Q2x!?ZRzr7wS_Ob4h z1D`H~QP2p6tAnr4FxO!zH9(CAHi{Zh?~bC&OioJQ%S^6N-a!qhxbF*_Sz-G`QDA<z z@%WvK<W+cg85HVUCnqM%HA61CzLhEC-kHMk$vLtVA+;bkIG~Vihwm?x^Z8&ELSWy( zPrvIvlwZNT<Cni&iS@_JG_&jHqPjh-v%2PN^TtN`-D7!O2uoI5cEY(dJ|(Od>+Bay z7%?2Md)c^LXmw4C?fAw`xMhZRdPI0@U9uySM~-}Pf=GGMdzr@YO&IAq|MP(SZuc(* z-Fvn!n5(O23xs_$MhvBY_}zEk)w$t4?G48`sKkkSKyR)=8=n0{d;f`W(A&_0O#%HA z2eW7Yd6N_1t~JA@|Ft}X_&L$r<_VFy`CALJOUJ7e?MsIOgE}rK3`Lf}sgtylh44Vo zqw2h}D)vV%RJ~Dr{qL+gdtSqM;abl*nKG7FN6acj9UlcF2GKH>yb@-9w`hSN8h`dP z@ak`5mv#c9?AX=cU3#AXBC>t;w_^q})}+uglR=(MR@kC(x15rw89^O}-wxL4iamiv zHC7OqdLaD_ec4*dP`Pwg!H_GS1hQZ*Dg2)k{(;u=?-fVwmUDLkix|Ev>1_1q0)3TI zVkiphUzLk#L>69ZmnPciuSnmt|812!;m$u^_*^Z3!rah3m$?=kc?Gxe+PLokhC<tU zhV|EaA1?O}%4ANSbMLzJ=7agPcH{#s8WoIz8k*co?pTV2Ch<(vJTT>pNuP$?@3K%c z4>}q9mMVcakj_Mq_vs;yNsHY(>((ebdH=6$oR3znHZMg<Z_)Bbr$dR+YNWy}#*u6a znm|#@amXWqLzk1Pd^IykCbErQsgifC|AHb6Z;qc$M#?97G0u8JG%X*Q7De4@*<ypT zFkOs@Ls<h;IXvP^vG$a2>O<Id#@sCF>nZW}5*4kiGL(GBu1;(x8<K-(7v#LmaFbda zch5mxbYou<D?g};wK`S(8x4uL=6a>`PGyZ_V&v$-$Y?C5Hc(eYY*FWX+yqkB^|idw z)y<w`tnpFe3vuVh+Ud@KHNMH@_mR{P1tF`WADc@PbX1ySs6^RxSY>I}qG%~O$X$V; z2yIH6Fu|-;hsLqJ&X5&^qi42#F-SUHhM^C_5~A)4?Ox1jI-SGIUKo+HNUmPvVcH$Q z(njYEnwTft7OuZIv#Z8iK9P8#7l;`%R^%p@VKs#W-N_-$cQEKed2M4mMv;sA<)~RM zzIc@Whu)kS#0_Cb^`taSjxer`DV!nkE)6YPV{geRz4i-lgBf4)klw!Sb8}6EhN``> zF$XplRy&woPc9fX$fYi>D5}fQotci#hTIYIm-W+1m9E%9tuuN9vgyziub~k6X!yAL zl)Q@z7OBd#`#@xioX1@)jcf~`@kHl$1>EYtpPNG#I};b;8?2&;<P4%gD4tOAsZw)t zT-J=0P_gU92G5aoM3K)w%Hs)VWkKcg(oOIz<rsjK&)!WIQaF@m3ak@m?P&}A(ix0; z6emF*S}cMv8EfL?d88n0YAaH0*R&#NuMkA>TRU_XCn@V|XWv_Otk`Kyn;-I@s`4v1 z;K?>`YOB+rz=*U*+U#kW1P7AdPE%FC(g|Dw6fzq#Fe7fQS=Iv^*!bnizIt$fqCO%~ zS%XX9gilJY=d%n)tSkSukAWJ#_>+ujUGLyoMmg#!$a(ZnN>T}lASM&MgHN+d0~f9v zZCGMVDuIJERa^a{g~Viwed*2UUF|kpVw_iA*H7dG$yX+&vAsVEf;-!MG}Ybl0XsCN zMrlMh?MW4!qR>;T3vwvT3IW;di$@E#C`xFqqJ>qkCRTJ$E{{vw)}rHYV91v4V(xm$ zH^Hwwje}fVO2~s0j@<dRFSs%sU$&+;%7ezga+t4AI2+V4T)A9MUe}W!8bt?pTijH) zCP^4f)oG<%4Ami2#Km+`9V!s9m?ej?>>)3<V!;raR!L&`3hJVDG5EzVrV)auOx@EK zw>-e946K9-;@&<8m>FCt+aBJKM7wy)cUhO8D+GEBqu)GjP$t5rQkz21Yyv&Ix%cv` zE-`?Tip=oLisCgE@nRaww5Qxq<Wu^;II||5dpYr`z;h_vTfCMs#xu@fV#AOjgTrQ0 zdF`U*W>PxFg)YUPd8+1BtIQ5{0-uy8pfu)#avdjrCkTG#Go-@9?uDU2;KBYm7lENM z<z?`_BuZ%_Brag|<uV3I0C)rWL_2*%;iR2=X&$5*7byfoOp@#gI@a>v&`!UeOC~ED zsRkf0iYst<mmD^sd(H<NEXIF<*egXfJ9uL)k+JG(VN-;}eIuXYyc%s>L12NSOU0vA zJYxUUR?C)3xx_J~czn1X)(J*<MgL;T7a!hzp%dnfwlE79ZQ;}6BW3M|(itR&#?QpJ zRs5M5=SrON{?MQ~`B!jKqTorhfO9NvxL30P5@=Roj1}Icjy0Z1F3Vbekl}X;De`4w zqN#Y4X>k|SJ;7u!uVi2d+A{aURdYP2q?^1Rfy)z99wqFI5lVp!fl2rnRV{@ZpBVW6 z;q5J>>I$}WQQY0#-66=v-Q6{~OM*KI?z(Xe?oMz>aCdii2p&Ai-6T1u&*<~I@9WWT zygyLvy=twhZ_fEmsj7uq&(hRn8F4;xTm^%-7c!wW)~B!?65-vIg_&@{F9YkAha_v5 zTVgQwjj33ilM<E22ndOEt{iGKl}Q<O<1v8{WCptA^mMf{<w$%|qH+}4gw&EfwrUzc z2yLEFJSu20Z>!H>#v_|;ap0x9)`7|2*bWZ^!rXrc-^MTIwUCKs-}mRiyn;(xpvD9s zckWd8&X|FN@&ftzODW;AsK}0k;QMc#qM<4^;=f1OI=!Rs%Hke->dy7Y=zmvFc^NGZ zC+Z$dALpY-NiTqsPIkFxi~Sncmo)~V&dF7&yNeLb$pv95vyE6n2@IbUXxKp#m18Fo zju*XY1co^mw^$b!%3K2~3I(uC><;$;Mdq;t-}V9hl*1ao3S*<g9y%(6*1+nQO(c8) z?N!~-T0FR1U!<~imC(w=qSwWDo<k>llf?u0pwl%rAH|MVQWq=DdTV^4a*3qHx^pJO zB6E_v8@>{+o52?~>|QQ=tX80%HvORNNagCC_gJOp!x5;n>}d2^df^cNnmjqHH^P1A zZajjBoI{@;Be=F3dT0aN=a4B1KAj6^J2Owbb=4R17O75$TLsTou_DbObrc_OGD2<N zNSH%8zylF%AAXL0FX`UBNlKa{I<=Y!nxg$J3y&86{>^8xi*^Hqv<`PIzd5cDYTvY5 z$XvBTV?|wBbgXnKPdvID9573A;tt)RTXC-r)=lxNtPNvwO*-4a{(^5}rO|`aJrXg* zwdoThEcC3Brb2oXFg@44Bbe<(VET!dHe4BPHDSg0#C)mI&u-rfbv=)!l1kIKDzXX( zGc!6oYUeejFC=K;y1rn-T<$B0Yz3Uo)AW9ZqQ=sab93$LX5#`F=>aQ-+4@N!&f-YI zj>8bHbsPw3;~FsEm!DyxVk&`c#acmnM$&PkfY-hIXcN9WkVoI+ygP;E!wybNSsx=V zjX8yM)dR&TPO4BDl#QGsX4~X+1T@_n$eSTw9UvFtGdGGO48wsFK<K`M<S4Hwh(|V( zB9EEoL}<;P<ahyyRc;TWzsBbMm%F*$0xu8E46$LPY9ntSrn_)Z2cL>Er6&qu`g9+< zCBK2K8JVqNZx4p@q6#zovU%ucJoLBgMGg4C`_l4dWpsP+i;u*EY6beXG<5i-xXK(` zK7_;rdviR>2Gbtf%MlJm4=RgB6h{jIzww*w-pd00SU6$48}M4L<MK;!&WbS7N?pMh z<IdS$xCMBKS_EMfzPvC})3lw;kO4+LF=ApzHU+0qaE3ILSrW5blP6EO6LsW7Ik4E> z*yP@KPSRe2ZXz$xMv`Vk#m2F9<dqbtv0tJEV$tmOoPzJ`Ej`(<<B!^h3IYY8<ISHN zhRll6gQkLFke1g+rwS-VU}kxcc72d?b~+so>lbwMQGHxEyexc!G?Bfzfxe_jLR~FN z7Rb;e)xe^9=rQ>EX!URGZ#ayGt=Vi0Y&V9QoNb+C_SM;TrN2o|5NJDFM}Bu$z!a0e ziMh5Dd+)&QE_Ng?;~DHNiI)^*aR~ihyo*NGw`Lct@=85}0z5)tI2KDYbWejte&2=5 z);<#f4ijL~<f&j-6)YVdOc@h6H8m#+kA2ai6t2CrZY&uy<%!*~8CC8}`&n-~ivl^? zx3oWH&>{w>M!|~pbLism@r5j*0DLL-d*4|ClC`2TV+y&xSdOna)Q|N(;ut%<aq~8k z;m`Cz+Inbu^|q0KPBH=JEjKp#p6;M;T`h|16E$DK^10K(?Zqp3oxQ38I8ND0ojkI@ z;K+B(Y;mjQ6kT?_+78FLMt03E%B`3TXIM7Hc=M=*iHK>>ymu~(X+>KW)nQ4GhIfcG z@o~kJ%{%c|_fox`GhSrUj)v2tLr_ds){k8T9Yvna0TZyiR0ip_D;1Bs(HjCkLpKD3 zpqKX%z04AaGQ@5kHV6c2dWO}!ZYJ34&#&CLsdviE=R@cv6$6V9L=eCUfzToaE>e*v zw~oj15d#N6JAxY)vGpvpxCboU&lF=LIJkY1P6W?CXz~F>sI|65$i%hNU9$UTlT8dT zLlV5qTk})Y+Y?i;wFO=MOvuEn@6~}P1g6Mo>>qhE%}#7>#U$gh<&>IeXx5HFfd;nz zMsx!v7nOO0txfO}H*rHU7s0KCEZSit&mK>poUAJ~x8xLEBam`@pM`ItE=ufa*7Mj9 z4T#9r-^c=IW4;3TT!(I{fE%&ubPw#q<_AFK717IVXD>>|tot~Mp`^89OQ<e&30FEM z|445~5|Y2oCU&PA7g(*HO2=Oie}`S8Pp)W}^kHz|7ZII0Z?MRO-YCzDNH^OZt)s6q z3wok9<Lha&{fnv5YuHFfoBGTlWlZq?fG>+agQJkp^Y6ZY=h-z030DMQ*I8!yt1zV% zA<%K>dD6jQ#|L6Y&|Y3G^DO6~GJ;10^Y+R|VmM@Qf^T(2d<SB0)KkhQVqrm=3(Qi} z85gZ6_I-~$I7p)=ql)`c2gL4Y-kS-V5Uv7KMg()IA@*HnaU^0^MPetA!W^M8;3CgN zcRCHv1{)F?Szw3HjixAySa_q<z8A4Tk9IYzsF7TTaF)7*H75|%@0iB`zEoigW~7C^ zPq&vaJT9x5Ot{J3DVIlw|6MQEy)X`|q$uJuQdg0~7Nkv?CXDilLScVD=ZYRZbG5gM zo;xNEBAsT|Q3_<*XJTKnD%E|8$+FL!H596tGdn|+35sA#>}4=-Ixzhevz7(<pcBM& zwSDz44>b-gI-p1kuVxiUG_-;Mq!TxqnPVBTjt;8JgAXlTrHR?cH<$|?!zFL^)Y<j& z@42u87vS2(CNXRyYwMECLggTeCW?XE!_H8WG4_muD3k(WgUc4kno9x1hT_V}3ZD+) zhn3Zh#n*G8#k2HK0F|vfN43C&BC5RzhaQIUe2W#cVPQgg1pG)u7FjS}EdeopaAVv( z8C8pL^ybd8A|&``JhNQqp6GU4E?h%xv1qL@3rHoI0+v#|lpnf=4*e;L8!#Nt(H<sL zUB#wW7+bY*?+Z&g0FmS0jEM|jY8(Y~G*Yk3?Wop)Xslvn!kEE;q{^H68f161FwQde z1ge25JB8^)N#zxp0^-e&TEr6Bv2UGp(I|$eJo8LdDIsjbUP3BXS45`6feyLT{)|g0 z4o4)Rn9d?`pJ5NhnaQ_i9$x?ji4~K8LxbteU%A#uxQ<QNgH=S$9sNv~m@J2ix?Ae* zYD#EMzB8JAIS#RL#EVOU6IV{`P>OW*rgDSySTexG0c2QqWu5eJd|g?8x1{I?ct(Td z?4ID{L1r!*IfM&Y)dji8tzjlbAQo2JE{%|Ef|ItIdmzN~lX^M<!`5dA0cNn?v9FMc zl$x9zC2u~8_DOf{@JxoUjv0yUTNj@>25F3u1(f>pgHPdQeDJo>a7y4T+hrJvY*D<l ziXWVZRg*UN<%6=><b*Z#@;GWmJp`YI)t*P!de^a8ZIEFy*S*N&ta2&-7%891?TqI; z+S~`LxPHk<3Ql+WbK`K>T`hN(DAejbjBAWCOZF#`G(U}Y1gF(0r*M!LYI!Q<mXtop zc6GS-VjM)e@<vg%8(uM93P6tC-*45;Y1R!6pRy6J3<4)39SK2H9Fj}KQmQ~D{#DEs zEl|dg=m_f;3gOudwkA%)L^3qlj_8_fosnTb*3!6w|EUDqdoxY7OGif>k9<z@N=pqC z?3gE8f4Bk$0)MIOR3dolf$7wETrQld<9cq$Z`*97fA^+o>XykH;^9mEOmq%OhPQu- zHnp|@SK8QP-c0^ZUJN=I5fP0W@c_A&%chaNH%SovL9di{oWqleL|Z)EGH<g3KHr1x z^AKQ@icb{mE}PAt)gzFcHY~}DhFR%5A9WZ>0+qp@0KRu9M-tZAyCc8STxaQ1V{XxV zZPM|}i0ld@uws1{t#H%P5d0=&&c5}ODEa~K(S9sHc77ttdS+bdhF(yFbH*l4dR81X z{OIXSWk1?4Ij$h|9$BBI1$+3Mq}hN8%`;xa1}0|L*Dbzwdz37XBLfz``9>ESHY{A< z(eV{{PkI2r)-ev{=Q!W#cDF>6Q~r^0W<l&tg%V=^U`Fcu@LmaYq78<*w<A*G=uyL% zB85n^ao=pg<g9@%#BA_%eAXB$j*?DYjo^~v9-Q&6FX<e<l^s<Ok-N4fz7isJ7gXpf zj&6<qpqNLbo1WvGDIzHFwF<1ld1*;I>ffUd40x}wuCy{2Tf{lGq@YKoPtqPt<^TBr zn4|@^G`8BET2yqL0<_~#*4hQn;7q`|*zkG-X)GNrD|S4PG%l-}HVn43m&J^LD`7AN zT&Fu^+l1X6;YkqU==0tD0cH7;9%NMy-*pxI)j83$rzZRq{%eHKdho}st2p$>*I%F- zuHu8b3$f*mKh|5LjLTL_6dGU4$olqF%n#CAm>*<@fojz`mps0_hZ<7S6%gR3T9ADE zD8p&w{T6VingNh~O$?6yuSj}n`sbP1Ob#rUcai*2;JXS4>@!RuMgtw}S{m}x6*P|u zh!)8yck+HJL-0h|jv$&uz<VxO1O5me*D%Bm%R#PpmF^?b3Ohc@QL<ST6^c99WHe4n z)Ai2?XcZ7Qh8J5^i>TVr<~7Zl;51m{=dDE7hqh<_rAhU+_@)#{bYV`6J9vDa2By@0 zAXGA3oixF;^8j2nI61oAniloCEfoFH3)6ItvQqW=m{9&T2%Mnso9%%Cc!ew~CtqIA zKucfcq?9^|XnKTy);%K|LxxVxi7JoH&y|Ut_7i#wAgA-FfljT_=aw|p*U2IWNF#|w z_eyeP6C6XUiNq)leG?3p0Aq5HI%qUECYsbWCgXk&IvxinAlLPl-`zuZa-YtmH&s>4 z!WE5rYI8|=ZK`2}1z8j#j5R2jvX6j@X#2Gmii831M$qcljqgIMIlTOwVvkFu;aK=F zDd+2!XDm%6GwFApK6aVfFZM6?Vt2~0cQ4GH5HzA<u!@0D8@4Dd+%jlKsX@V~6`e#> zXPPX5P<hn^R2u$p7y!x4Ge!|8_#4CbTPvqwqJd}Maj4kxyqUV@0AQt(15A)JBvkg{ z4P>HhHU2Aw6@gIGl_XS`mW^Zq-<3X{>4Fj#1{uInFbS26jedMrQUCLz4QD;MOlg7$ zENI2x$-WDV6>M<2dn7&bD3_wTAc*_D0WLAo7$Ru3fDe#{YZ<OB39BB3U;HzxWA;wX zwTsIIjhO8@VZAdNg%85K)(^5%eSdV}8rq*jp<aUY4(rY(1KXP$BWs1;LmoAG>n>3$ z^q#<JAveKcf0-87x_sx1V}gsn-Lz!5JqcF`kR4jD$Pul=BQ_SWH%dib?RrPUV&@8D zHD6EVisBP;4V+>unI%)DEL_QIFql&cAFo(ZkSH1+32njQ;?JT1ZFs@K=$NuqN6AV> zq=6GNfF`Je_fe(9=ctB_Uk|8&gJfYfKyPzan}Toe!v2Up*@h5X$VFgpGn_Eshu|cJ zH{!I+MGpPY@?AR;NH5f-q}<K^?9ZIU=%&|EV%xcAJ^Bf=qPay+y=pvXpfRctXLy?C z&<VX@>xd4n=$(;s<vVc<4v|$lfH#(Xh1%UtCPh<6WXdo&=dB(rOGDoIh5aR%pY2oB zeqRo@xoqmUHb#!}ku6Rb+EM&TE^8^vHu->cq|0-)%a*b?6;Gw`EyP1IVg#N0S}WM( zS}3)@TG6?UFr9W)l8ERbWBRdhi3DRVjEhD-$L&w_QJavR4i@`}%DmC<DvrfA>G9GN zL{HW`U$drEST`pdiOc7v4NgpDvlyteH-<MOq!X%Or2tnt>FX>3P8sur={14ZP!wim zQT5U2MviGau%+EPLMWoaC_J0kaCoM4wUQ~qEKbfuw{WJ{%M-_;z*kXc$R%Z#V#W!o z8dHJ=$E<P{UCvR3JfDV5D@Ft&u2*eGe|7>=_P?+o1ru+THN;@Wc3_4u@+yMOKRa#% zj89UKvPyZK<-2u18Cw&2Gsk&0E)N?1)cFxx;M#S56=g<#f!07r3r?@twMPRMVGv0S z@B=Ka=`ZRTv(>fTgmAryUU~X?7t`wpV=F*gCU|GGO~c>}dC-Am?o>vc(^?Q*qNbq) z;m=bsGJc#j8zvV&=Cx4{m2OaW@&fS0xiAW8se&Zl0hw#{&JTJ%0WcE3WoD>xw)e(Y zpHr%6aDCWf=By7HMWGW6IAc|{`k3hfK}my@42mOiL1x%3Y+_)S)$oSJXkY~8=0Dau znxNdlPblEF)*)0-s`xund#ldeBa6(N8@%;YZzT&M2JkudX}qK8VT8d5pe+|T6Jx+f zhG&Bh!&~jYIw5#I`)jvS=C~{y=Fnc8(v>B>lq{JOT+S<gh+F)X<gnCheH^%x@&@CU zPm0hT-&+&kGYpVn0{GDcwv|9{YF@<Jwu@EBrCkkKjdd+~jsG(vL6h^w1oWy7TPQvc zt~dkq#-0;N`kG=eE;kg5m@Xc>gUe#Qtf69?d`Klmkt&8AWC#lhP0ayk41n7MTQ2m` zJMflfteBnNC4-B7ixlHRdrwXD$qr5-9mJva@6Mi@kdM;Wbu!%P1XRWqBU|a}2u6~c zao8kvb0xI4@t~z?V-xP=IC`%^32tY)IeExW&XV@(LH;~kDjg;Az@d3Euto-}y8J58 zGo?nd67Ow`VZcEv;w<`**M1NR<~LZVyTzsbxoDTgp)wy};>r-Y;6$n-opb#?C~<=V z?fH3U#uSh-;~gm<j1z&aE2It&c2e3;1(6?);%r0YyKJDXV@unxmB_(BEA9u148}VF zEunxdJyfcb1OHhBm6$4C3@LK(xG?_{VToR9nTM>=Vsc-U8htPj8ZO-PZjK1xo&r!B zapZ(7B0Zx9^SkS#mu=9X2$b_)EgQN7&3}+m#D%1O8#DyijWih;$3~;&%f;yGTSn|3 zQ=nsS`dRAdZwUa#4$HUjIlb*Z<dl<mo7j$e;1XHA<rvk47)l*Ti@2}`rxq>tSW1+s z7ru@J!uO7Gy*^puX6(j-$z`Gtzb}oIEENq5o@}+}?rC&fR=Dks_Ptvm+fqc9(L^2) z(hdR(2UxvBUeA=_f{VWt(bg5er!{EuPaTgj(tU*+O>N-qgcvde*-lmn7iS6OJRA5A zAvZ@ej79Lpy%N|ZrYb70%2BVBPbk+037_1h%sxC7v$`O`Ii&Aiq0Ql*>142i?MdU( ze?!vzPzG!IV`UA^!|0?0@09hs`fdNnIy=R)+Q-k%JmMX-pdX|-vwTYgsjBtA)IO@d zxt8}kPW&b>XmpuCEcBtwi0qPjO~pMaL;m^UtVOAPdlY(Yq?Bdr=UbuCkX6dQHb<Y| z#T=(?_j%*Eh`|`dW}ef^I#0dPCjAx%V+W0~8~IuUigWH>+%(X_pQC;e7Gg8e6wW)| zTxJ8UF7xfCAR5GG1687_MWubA0(#Ip7Iv>R9;XHzzE3=cL$CU=MnLQ5)wCJwgPV3Y zLA;g+QHgzxQFS(WxF^oQJrvv1Ka(_1n6oy{gL^U>Rtb~FUt9OMAUl;}Cq&NcE=0z~ zchi<pGK@Vek-PSRD@YS}99z>fhom)e${*1M%lMTPeIDMy7=kC`w+;J_DbhE^*}(n= ze7>bz61*{{1)Z$ThO?_p9;~?iPAfdsEFiKa7J5bG3kwb)4G9#2Fgdc}zlI>t#Z3#{ zB&nWO9`ra{8NA`pX~e_lh6519c|&O4O#X|uox`c_-*j20pQ{A}z1LI;_&=xYvJ-YB ztd0oV@3(j{uH-q(mHU>Ox7;Tl(2Ay%=7h5*xNz7qgl3VAMyLs#(Pt$l>o@dD$W@8O z(p*3JQuh5c?tt>a5T+v}5EYIEmq~VUiFXvy_t561&dXZ*o-f)a$bQD%;bo<6&IU zv2c?p56w<knaSCAk_tuv8*ZhlkG%_hB_gtt=O%5f=2O|H;H}^zpyiu43h~rUC#yr` zha}&VL=UN!Nbp8c%~Q`oH2hha7{BVst|O-sJ<Bn6AfAn-idU~gFmPNeYl;R}3ZIu8 zxxbY5&Q`3)y`!iTXtM7=N&{^|@p12_UMi#D4fi)Vu`|xG{lv*Yv{dq)9tBaEZ;ZH~ ztKq5!S8=6E+kH4E5+I)@vb&cp4#j6?mL1$l&PQ*o%gu5G%f6Nj3-6q_Xc-C`c!|)$ zz2LzIRvSOi?})Y1U0&VQ1W21d=q23rMD1t!hm!TD!EG}d+f{%?Q+|NDAnwWJ%k9k_ zDP~#A5IJzE_6=0kj9J~X&hOR|uDSG1V(<{l^nX6HCGyKzOL_2gk<*X;`B{uquNg8i zmEu8Q3NpVj;6+QkGSQNkG9;$?i>6aCeMx~0R1x@P9)}s$VQ-36=zgF;pKC0;LO2oq z2X#=EM|DAeJ%kw<tY`t*587mOJJX$MSo}e#8<iohDg?7LJ_d;Gm<QH{xLSNKThRzP z^2~M<b%J0j*D?S~@@V~;stJ1&-y0$xKpNZ4oIt6FO0{?3j?1-RN#Gj{47)jS9*6&A z^@d%YZY&}1<Ns%x*KOsR0Y#H-?D!@we=5)eg4cAd_I-#GLgYALHQZs^S~^XtfG7XG zgH1Q1_WK)hWJi>@A6c<mzpT&9c1V43_5H<&$C0R5w`lSKV0L2vMp37!!1RqP1$?9q zH04vUI1+XN(A^9ASl9mLSs9#G`oq)3LCME_!)I-M=aj5-bd!wwg;}aT4@zJ6aL)%p zQK``OA4K-nP-^Fj<fAYzY_O)G$YpRIQAEnAd!^9}49W;bGSPkOAKd5a-ljU{RCnPM z>RPCyXL`9Gh^+56loiju2ZVhCE`(yM8YE_Z42{x~w<j2fxk!Z$k^j^@Pa5IT#H?t8 zQ4BsG$#W(WGLWYAQoIAZ7M25P6}0~BNg4uLVR6w4=~_<Q9sM@Hg}%AXlowI;(%afW z=sh370a%*V8${>U-Z8NAD11l`9VkMcnP_Y<B)n_=;1lPA>9ntAW=eO+Z}eVz%KR!{ zZ%g7q>L5rTZC}Qaj8+Ls8%<FM&Bg#XGBXPgdmNXl@tTpNuv(QHF)T>NsKQ+pCq$g7 zEn(i7v@&W1(On3-1EJkiT4Tc1ky0E&Zr4o`=W0PeMU5)U4p9wv=t9%*gkpD=!Qw11 zI#78nL5Q~Z4boh;SV*X|WQO8(4igWDE$6sM{y2=bm435rLtZF-W=JUVz8iXhkLUqK z3<5RNGyvi5(sD15Y0EeOrzsrP02>-ko}=>0TUWm;anweausVNm{YRy+B2u`Z<RBTE zTF{lVJ62NRUOgG(dqL#hN!!%M_vYybI3pdcShui>Oj@-KaPy|k+%zHce5s4S0Q}d2 z?wlJVv1=?Af?oZxeNi8*HJEGO#WtAjGfxu{8DGQHz>)yEf_dO%nF-zREqHedb<D&l z1vxD&<#jXdG+p2Cb5{HBjEzv>xSix=+L;ec4qrpzTa+P$-5-i=O{pME!*fVGlU3=( zCp>PInaieJl~Gp)->P`d1V&pb*_-LkOW{NejzZx}X6`}p<M+#Re)K4j#6%+D-!XTz z#HwKp?z1~i;{f2Z_{R+tg~S(k082yUka%t4maRmkt_T!26EXt=dK(uI-D`DHZ{!}r zQQ>uOOCmh07iyknjenAA&ck$c$8aZJ=Vp^uR`EiZjqb-*dPl9oLo8;WLK><fSckmT z;ZRP!9${GlJ20>G<*sd*^)$IKHl`fwt4bqukFp<<rXf&Ij_BV>uQHW%HuM~hK^N`k z+{2YfTAY1Q1Rc`N%d&jrMK=`f(qd84)av;$B_|c?XQ*><XdZg~ZmoqkemZ#751Q8! zs2;zK#?X|=Z0pjEQDkdAj!ze?1I(ti=UBvUFIDqWN==k3;n;A}jW<b-z7`b?y&tsp ztsZieXW_nL=Ln)Lu8jrI_O@T(FP=GZFp+P+`%0`!+KKY1qT>i}cT|(YQj>6;qx+O@ z2-u^@YAcyCd;uiBi4{EuXLfOKsSSqdAHloQ4&*s7-v<-Z!8aqU%!*E)gsIcg;<eo> z!ZlC$q~fhCK;T`)XO5bAystl>kcB6S0qLV=Zoh3az!<oI$U$(&xvDS4T}TcS=ff*1 z?L}<LqO^1}>)Fr`bUC=TBYM)D3kaknkscLdmSorIEY86qVvm?sAm`N+h_}2^lM2&z zOx8fi2^@qLmRF^N?zJcevXS9opPX^2g$9*0niE>HB{^gVn)SU&vaCub!nW7Mu<V$? z>y^VI+Ah9SKokqw-P5(M3fuOSn0baL-{9&E`dmSPOhHUJ?{Jyn#|zOy#`OMxx{ON> zNav~U%x3(ia?q}=g4=lQn2JAMj4zVDryf$V)y~+o)02wDu+}grlfiL2f~-(B#yQ7L zSd|BunWR@B5Q}x5DrGwwYQgwCyt5`OnO8x;+!JAJPIyJbOA@2I5S|*;n1iM!piA;# zIB#tY?1kkOm8thkysek=<wLcZ8F&g^Djzs0g(inpcnfeAaqfj>$*QF{k3;^^5iH3f zu+62iI$9B@l~mT#xOk0fCG@sfi}gns#O;mOD!x>5>qoynSRvnn&d>8bUJ)D3dT5+m zegY$YjJHgAgX&_QU%gAAT)x_wTXa){j!3K1$Ja7)5V3U4Gh{Js^K*>ZD}{z|ky7D9 z=Ok5!P-hPuo&v&W;ooS25*$%$q!a)xms-JS-~cdwCC*$Q<KT?0Pai{%fX!B`pg^^T zbuQe(=2{&%rM{9hQ;#@IM@Io)k9q}qo!+3t`bIwtkw+1fpp97%UzA>RLeI!`N)=fl zSYYU#nnp)Yac?0hyF+@*`QXl%H61f(yqF(JHV~Jw#hla?`2oNvX&ntoxd@AugW$Q( z<_(4zYWXLwX>&)Kmk$%|6n&z>Y+d~1N&@}a!!4!yuml3O3LVtskMP%Grysg-i7Ueq zdK9MlQczQZ>9;wf$O`F|z06NQn`)MpI_Ou!$0xq{P8y-55Y9-QR)ej%oOIZCG{P+I zFcWSHa?tMiKc_b|EivMyPCO0bXFK<XUqoR45Fn2Ks<~u4yUZzkMn6tE$|%$?Mk1cJ z{pmh+=sH?aC%g}zl*o{_J>>!4#|_v;8%H!c+n42E4;!)?NClRlpQTZC1+>l0Y6j;{ zM(Dbfb%EVb_H>huB)rSKHJm0l5q&Xugfcr-y{KjL=aPoV!>O2kOm{rfDaak1dAV!o zUZv=+rU&*u3RA*;&<I3xyHX+)g)|;#?)|RSWd<GZj64>hPGt`>B&w#ef>FCP59Wc` zCFo9Kf+?JO$D?HYX2TuvIY^$wL&afJAg*rEObMD_z0v^bF<S6e+-$Fo=##TWu=?Wz z3!|5PxH`$wG{G9Sz(n{P63^C9m|gZbWT%nd-J3^j=htudFxI%9me8yODDLJA3SPgX zG*SDk?S2`$9(%-VU=!^S=%_s}6*a62-%>(XYM{eU80h(2iLPQSej{rSb-lKW<ToBB zKyoLh+!UxhZB-J7XsRh*<p>X`0u$yI8K7+YAO=bT!~Ff@av`_I30#}Om^kMiR6>JS zt1Z@vKnYn>=xlJ!L<M@Z7z7C__#6aN)o7^v)H;M?>o!(~+D@{in+qtNEJa?#S*%c? zgW9@66Nxa=bxlHk-GIH7yG`(kl6HXxw0k?3J4--n33+xF;nEWhZf|M*^EL$NaYUS1 zY9b1QiEX@~>~Su1m*dC!5r5U|kkDq|0Xkcu7!)UiK-)m^Ona$6@`)PVv~DR|9jSlJ z7<}}u_{ThMVzb1+K*O8o(dx?NdQHyF&Al#T^WUL>=BeM??qQCF0eWib7gbJ!z;hh` zQRIsa)w$O_<+<D)Ued35Feud}wCH_J>;cxEH-Eb}ZjbXj|4DT>=|HJ2NYbLcnI2ew z=lp&nK^?AZmpqqGarqLy6l&ZS$r_n^?*Z|rYv`AQhPx8=+jL>(aAvC|hTogu<B+F1 zC|{Ffagpya*nc*;v*789*8Clev7P6A>>r@#c_RM-^E!XzUvPLXhUi}rR`DyaZvk6p z27^U@|395a2|b|@cyjS+cb%kz*vvUlI6D`#`}eZs&25?R{BHfA);0!6>L2X=4~Tg~ zzywGj%HLP|^Vq#ge0b<~ix{-c_qSGfT!1zx{uzsP3lwN9se~Jy1*Ms<^%4gVfd3H4 zNGRfK->J)kzg=xX0PbNy{1FGYfj>wbL7_Ysbbl%jgd6`r$Sng@K2Wh~!za>LTe`4k zeVm1V%9w=y$S3~kN&SuIpx%Es(6Rsj2m15?&S)Vy(Q9yBf_cmJ=~V}WzL&V)#_Inr zxIEN>w}I5~b>7xroFF@NgFq9Pm$H-w{o{exnoBL0?`5nH0z9a!!nrv_$RY~Twf#`k zjfBO&YU(2`^;=C32qpiaruVTOzcsvZd!3)-x0-Tp(h>Ys({_)&ziN81k)ZlpO?efk zFX4|oh8>%=yO90uno5X_8`cp+ts8oB*y{u>bjZGR2o~L-t*XP2q&Alz2|U~-iL!!P zt|X>DBVD`KcS!-Tn>iepEggauTiu{5WXJcv(PxJ(y?*w3iS<&>b#a5;V(RU>@#w13 zJCV)u_s!Xt4sZQF>OprLtMxaXP9+^n9LwwX`NbdkMYW)QGYmmsZa*p|N}b#)`(h|d z#=I{V%Fi^aL?jjJ!am|suQANQg@2LbTu%hl<g2!&RL1Qf+)7qry#EEfV`+EZ=WDY5 z_)8LeS_kGD!dv)-F~U9!{N8=EtNZbuKh*RDJs;0yzsx~{mpEunAFE6@f#uC|o7yKX z-$dI2^Szt?9{)|b7=R^(#Gv_^f3F_<^e{&HHJY6wGdqEqUn!8?RFfk#c_D0#0+D(+ zjaaJcJo^(@$`EdiAqNhUoU4+VITET7FsoQwqB!ky@y;Pe?FLmrBYA5n_dI(h|9UC3 zSr=;bPVW4W4l&E{v11;eT|OW27(>z{lpz}p-<nTnnGRP@Iu^7UqC4K5YPO<<)}wu= zj+)LRpet4JO+cVH`%w9c{z1#w*@Bdm#t@#1F2$!(j^`vg^f~5~?3o7~d<xxG@6Mow z09m!n8H;q|wSaA%&PV{$hffs@J3l*yo-t39go5!%+YgHH^c}cbo0+$n#){;caGu$0 z?D3maiqKY<5G){ZC(^6Taq+SAYn{lY8WWgHNnQE72d6mFS;sf<OV+l6d?x1`-l)y- zy+baNlF{2N{5FB-8>s`&V0Igkus}sg`N=f1JbL+>NQlkUNfgT0c&wW*69x1_^~xIt z$|h8EU_x{njm&i=J6|s@RTu$&*_C?C1az0?#8<NnN2_S=I4mb>rdcjYg9sR{Ts<>$ zs&*<|Tc23VzLE6kXu2UDk-$2(auY+_K38!GW*`$sT9xtb04x!)t-4?;GAS;+)M1+S z@^SRiWB0IXh`~;6`RYh7r&$3_0h*3a1ivGePP7wrfIDq%bxCNpuMElO_~U3R_9AnB zNtwW*a>Lr>5f4Qvv!JKGwFB8p-Cg?QyC)p<Koip^u<mfKDC&yE@bk<@N%cE6?C4Pj zGdSjx409xFE1jp>H`k&DfM{fMRG!L>Ii!7o8}PmfI7!ww-f7$bu4}d!AiAFRr9t8$ z!CRjSJ@Xiqn--@02{_DFn})zTnge__{5&?5AMw$(P|TlZ>HJ)C^3uw)P+&U=N2>XV zeT~L-K<Cdc4orf}qC-BSFox9+wiHR6wGy>y%6w<Ad~u+r3_@-(_)L&z(ccHQ%TI|4 zM|LuD<x4%jW*np%9^ctV42VP<in%4BzM>MF(zM33iAN2pzK%(M$;QXS6LNpqkW}gp zjsBo@>Q%#e%R}@v!o>c5r`!jcb2X~M*NJr2$7z}=pUy{$Wc|@FFSo^J;#-#iR&Up7 zAi8v?$qQ?hlx31N?T?8eLWkX+o^Va)PHKA$T8>-w<Y;glvY;4iE}DZUwlE>nZ-<ur z41P=jH5mK3V)Ow5)6&V{gLyy#cKK+_RQaTWP;W9hg_(@N6+BlF?tb=4LY%r0yeW7Q zAiG{D1*0vg8X_%`IVnf+qz`Wv8YcO&h3v0jrBqz034ThWaEx>t@>cP~v=C~mMwgs` ziH-!j2y{$^aH&%waZ{^ed7S6~e5Ct%LX?9<<2C;RI(Q}lSyj_Etl@DT`JijJZ3IHt zr~x&(`^|O$+!7ZSETQ0TJJ+*cK~03yg!yCRwFGeg%}-rpou};Xl^#wsN#~Y~bOjyf zuHx@VHk1Gg<Wui0>*39lh@ewyY4{|Zv|m$ez=x?d<*f_?aHb3W%`Nt-_ZRx299Caa zyQVNeIWucKWPc-v<3?W(tSjA@G<Tm7#h&&YM_+vpbD6o1QNGdlhyC#@Zx-0_o-X3K zRk*KTet7*jkG3lxRr-`j-!J<#f*4(tRdaJeO4?L?i;lnoRr+&#E5)-@3&sf<PlaVD z$}{#S9gU==Ve}y3d1G+YxrUep8Mcd2Pt>`J7)q#a+dKJ|BPD9AG|}TP$hhly!7~(M zo6Xz#{K@eT=1+e<iu|^Fh#NJj?u|bAUOgnQ4KLi3MTUi~^6QWLxEdX^>|6F!gHvf* zCfTZ#>u!rJ5x-l!(ox_S+u08v>AwDI{V<8Pur2cS*Uy(1em-cw9_B7o;wLqKWl|N{ ziLtf=je8UU&MjqF1Xgw>BL2$`NG2uGP-9_N0}&$x$5|(9&3J;6Hjk}5@XlRk5m8>J zv#uKyM_=v4SYq6%RERZKqBgszMDo*(fH0WbSn=z{=5LQv{)fa<J)VzdgV47{U_8Y4 zdDncmDzDGU^~g$y-EiL&hs^O1@!#`XRT35wJ>#3mC!bau!9E;-rT5O&lAkU*ig==u zl;uI$ui*Z6A9nrx>GYlj+vDlS{o&zeiNx8T8KBBnBzUCLoxDE!<ya&&BG3#r$D=Dg zynYt~G{MYR)W2WezP14FTVAk85p?`4xvbDF#}Dxl`RBx*)*=_6*8hu+s`UIH{Ph;U zC0QeV!uM*(msfp-TQriSG)~Qxi?Mp;^Cs!Y#mDN+c8#^;`^`_EK7PWegA{f>k_Q)J zW^NynQ2mQ@n*!Evm_sF!{vzo6_sd)lP^-HRa+2RzMq=3s+>gFXaWG5)%k82|9Mb!> z^?&aeF1LIIIoEccLI|ed8_@TIOp>}$Z{!tLAvx7%gJ^?Bo3Fx2o4*XcdX%-yUVIf6 z{v||h3j5&*BuigCy>|(JQ0e-F;`+aa?7zbrExCRdw$yE1IYP^?&}^5Mo}p}BO-N=M z^1Eu})4t(Dx#IJWyqBMcPo47p*&lxWcznF4N9Vs35Bq|(H9K=1^%s?&uDPTCTgd)f ztV@%Kg+;1PZ|stISfFI`l+`rUDvEsL^I=a4u#m+WV*e?2)-t-I-(n}la02@)_9`}u z{7N5K5`xPT$W(=--_mQ75cq3aS1gzo>-?8f{u`hc^&pDCg+B{A>R+Ac7?sfdV=$oB z@T*Sb%J+%?wWkXX)rC$-ROBOKP|Nw%Adm8|r>-Dx<LEBGxqQ^UK>4z(;w;|TN;>sx zypcz?r^vkZ;m4Ue$0(W-wLJc(PPr5g_h#V!$zFreFq1eSg~`JAj!Ac9>8*Uq<Kvk= z=(>sD*U5vfy9e$+{0#j#%w+Ax=2bNW18aF8({n5fcDv+GgPdBAB|Iy@uUI}d%FUSD ztNY%7GbaKgI4VVv`l>4TaypPnrgT~^HjBwci5O73F9*1Fggt+0qv-{`k=E+OFC(&I znc8I~tRT1D4=@t{?3m)zfNF(rN*c>?ez#30e%`A)FfNp35$*>#{ALOIbPx2$+F7q| z=u%ig^!snUs#E7j$t#)l8fG`X1`;3LF&>UilCOIlFHYSk7Dpd*<30_=A$S=sKJFws zLH(A4FKxW?t015mv~)S!#fQ*esjyAXlFw?@nIf_c`nNnX>P=R>Us2c3?a^==j75C4 zVvjZaEMaDpF0JN2cZ%Sx`9ql2n(5vrEx{noEZ$8q91feO`OSs;Uy|r)V~IUCzy-86 zn`VELZf5N6(bf0b6{^?AIE4f5o1Q_V>VWKkKXBmx@c`9Wohn)D*L!*@Qk{Aunv*jW zcm28Y@cT)&6U6V)zvV-Cy(7e1?swJXw7<EfzFuaq^BwprxBALRztV?(?x@rs`Z$bL zK5m(3{>zWCe`zize;4BqKOX-fPY^#I|K-Q!|KP{ifAZtsj%XRbZMKso@EhSzBUtCo zEY#~;i4RF7ZjJm}!ZDbjISCUV&8RwpG!o~i-pK`nSJVjM(k5YElJDFN@wW>R|K|io z{-WwDH(2!!{<jNibN$P3_E^NJznu$cM!$LUpL63k9{M{s5H-5~lN$fgaq87v&%C)$ zp}VVSmm&;UrBh3!uM-8Rw>yM&1-N5DL<*t|`G3GP;Ng)#335@SIQYY1u4|__e~9+a z-Jsj-|1h-g`9o5y{yK)I^(!s@2U2`2d4D{~zabSL^G_G_?-1wx^&}Ka=YBm(d)~aH zd&dzkbjq963Amdvl>Z6Et97S6IFKhOk+j4;ZdqjZe|58e#f9klS6mNkSM<cqZPfqT z7X`0g)zv`k)rnt`gA)EfOhZl#{hMjX2`&DT3F(aL+#fOlwO&Psf+wc#{sPum%}QGP zWt-Uj)sV=PmG`8*PKsT9Z*~9>sK^hq0rGruzg02Se$7B8_P6^me<vrc+6+cQFvY)7 zRIs-caLDX9Jn)CLKJg0`?i&6zomAJqWC%j|kDxo`rT@Wq^3s3!ZuD<Y9^#9cfAZbT zU%nH&`NMaP9+>)HeEoU__d~sJ3>`PLU|57(N|<o_KCP=;;`azz(C;?*jHnHq=hPci z`noHpTfp5X6-7^;)63(x`;2f1|NC`Bdz+5R>CnXMeOdPl<^u<-S*1|5?GYBg(hrtx zC=zR!&h?`*)5LwUqBwx5QTY3PMY^4xb=Nv<KuQxVy|IC8%A&E{PxWE^j)yed_+J`P zh1D-+lki<r^rF}PS4>Bff=?DlZjUebOYxQv-q#g#)XAj91Cu}Dbl+EH6eOTVf$CG= ztA7YchI9@SB<uI!Qe@+99^||rRk)PZj))e>P#j&V{i{j1L*Y0ITE8up4!vh*>2K6w z7p3Y`st@++VrtOaXFt6LPl(2eO){N-6nm2Ren3ko56w*;WYr(}(7ecUeqWM=vGGr) z)6X)x`UleyHu$ajp(2Brt7xJ5+wCsqTw4xKxBCUnzi3y+!j1Po2hZ|bPu~Zy5N^Kx zhj!T{#QLm5{0Z59Q&O`?>c1G;|HL>z^z<*rasQY0{}>18p_~?js4A!4hES`WnXfEz z7$hK=K)P>Z_${_SY8UQb$qK|0zJI~BN!b6diS8ZWZ~gym972T!Td&43Wl?a};t%p0 zE`uemYbPoHiJhdTo#6k(fd5WSzlpBu)S{E@RRiKd8W3MXdtD&FeEMVfr2pT&1q;>x z-CMje>i>iTU+L#RIPgD<2KQgQ#XHk~^%k8{hMfSV|1{Zw@sK^J-#n-FU-R5+*#2MY zz$Edf8K(;UKkW1$`Xf0={W}REopAzfntIjfzdVO?^oQr-%tv7>-?v0$4}Eub_41|? z9#+S2KYlpq{~Iy<B`au_<(AfXA`s<2)DD3TIT!r34-h%MhF~}?=DT@+^9~OX>Hl#h z?SF_4)YtRqucTiw{v+uvU@Q=nu{3v4gUI;LAVD{q`$O@dd+@#*ox%Sz(_KykXQVUe z{(nPto$V3hI~^{?Y1FzD*;7a21a;LaOjrTNJzuFW=3%YUD|B1j#ygTKo|op!+3Hig z&oB=f<}t{AQM9J+)hMKYG_)QlmUk8EoLY>%5soqwI^z8J^~fu5AFc1gy0#H1t0h@o zo=eD56m<tH5<alo^ee1c%${{@eG!pAo=yf60^&Sp+-5eVG0#96l{DS_;U1NAaBQkr z3Q?93llgGBYTO2izcm7P9#f=OTcRMAX03HyAQdckLR1NPcWGvP=U%A}5xsWzHr)^9 zn*cY$bsM299s!`aFwqCP12!t_@~W|ZW&kikVV#NB`EI#-^zz;gHJX`2%Wb3%=DAH* z2>td);z8(Tvf9|kHDOgC>oe`oXlRb~ja%F&TjQ5>yyUsUA`Iz^iHXn&XLPtGqE`By z0UTI;WO{z#<?77}aniRK{h9~42Q4}J;K=#rZTaW>y86gX8aU9V$)0vM`VkLyoKsK6 zif)n|PkV?ejr3?;@B}6Ha)I$<cPgd`3NdGmb%A@8T-kVa-6jmjiuBAyUP+4dW1WU$ z;3A_g$+HnAeKTbzzG6JG^u&1NC*@W>HbpTyf=kJwP3Y#eNFAxvVs#+|>T|^pI_xfY zT{>(OEES5|3Hm(&34}Ajou~~`MEGpV6=#s<qD4`Sbm)}V2u_upMW&0-zSaolB!vMh zSf~?eot5a)-W)a-g=M5?#zdx;R%-zX9=^#U@q93}6G<YllH@<4WAQuJ$w+6q#00MG zzkNj|H?0+-5p2V)9S^JRf(S6ASfWF&G!fY3`O?bj_@zMJki*o>m?TOoZ+|7SH4;UH z4(jx60`*S3+&4H?IV8Zvs(wQ@I*r=!8jl<)#m{sFU^M4^$0on9U0*<?QIL7%#&fYK zJ=a2pnE^tMJ`rqbl#e>@a=eRdm=IrShmNMI#jOGp32L;CK`q{VcXvdHTOz7r4BjQ3 zl-ojD-CAct&@M+&W(5Oftjv+JZY2^NqqV+jHP@V)?T}Bzu|*=ur7FcFwfzRXuUnT` zBa%Td{0@WJFJtiKl)jvr;#y|5jD|EZUVK=$k4vKDreqV*i4N`)JuEs}ZzdMai_x5> z%|v~cIdLiXWDGN4nlh4$yNk=IAC^C(fYl|R1lYfEr@`8=XdxkBqoQ~pYCBczitr`d z2{sl3U2KJG{Gu|^Eg~(KrOWYjuhV&Gc?@l0_r5x&+uv1)wSP921QV<R!pvO4X=(tk z(FhB+A-@Us)8P)8QC<;tx7HH1HW#;R(vEDcD2;f6lj?5oNmX|k6F&Ld+#l!b-0Ck{ zhIHoB?+Mwye;eK~G?gLeGyyF#_w-dG3iUG{OsZgN;?)V3ipdU$MRk^%AqVx`tmt!y z!93X>Fufqb^wwFcq#>Sm7zeNQKemqbYEe48EXAf}CtNVeYii>c(%mNd8t=`k82CHn z5P3KN6l_*t<UrIs+3G{Xp5=f=W{wSofWlcE6-iVQyLC3HcdXfchZvRvfbF$QWm zJZjyg^0tvNuV7qLQ4cNnmYD2=DF*MlCVZ`wiPYyKZGH6F+@|?LWBx095{3S#d6ThE zwCvhL!MXeKP_iGeU6-JcOvLuZK>vatHWtfP7}(qGU9Rhn!a#_0P2m$Z9vLHw>~t8; z-lNh0Eby%Er{H}^r$}+!>N31MpAyB>Ig-W#yY<znc!bh;F)(-WDoJoo9(MzX8_ih4 z3MAG0;xP^$mxk5lFOTy$0U-%=g8PIW*(TZ&F(nI<BHNi52s6~2(cZ$RTb1qkqaeY5 zalOm~AB`Q%Yn;1khIkoU5(Z!uzze0En%GmCpYGa^Dc|5?vESNmq-^DK0NhfhpV*f# zPSP!~WO6Nxze0hncl8yosO}l8%&0*`cNdEo1%Gq@{s~^)g2y>Zl)iDfy8Zim=v*n) zTD|HfqY?SVlW4?YrkO1^6%{jaqzz)2lg#AtKnyBn^aAKyh{)!Ge&p@!@eym$n$Wx^ zmMkGXl?rh;=dVrjPkn^_et5Jh53Qpj%VSg8zj^|?PQl)2-su>nT)bT+XE)revReH* zH)79*^t`j8*rf*(>L1x7`LN(4o&I@ZRvZ#0?7a~i?d7u@%=nFcmaYP#<&2#ODpcni z3lfhI9wqLN9W!G<&_7ijyOFyQGx~n`NkMa_n)CSrS5PWsAv%|JO5uS^Vyaij4&uY} zy4tAC$i7zme!u2jJyn!RH#kkEExuwfzBW|YZh&z)lri^?N_aip2XTA)Ja-hPM2$Kd zYS@9v12SHKLk^=2Z0<)LQWQy1D${wA$Q{U|q`*CqDAQpnM}W>;zXh+BO0eQP+vACD zG=%ReuzU43Mmf;1(G==HB8fwccqUl%Fmf&D??6g|jm?pWz_hV}U`XlW5K<H(6<Vhc zBu@ctd6PpQJXd(XnGFqWGYk7wSM06$L$ov{`M*)ZE$zTnkbQcl0A&$p+hcCOynS3L zTADs`3ENqy72axF-#^~+A)>vT0OwlnB70^ut4J!H(T5vEQgkT!b(24+g)nCiE6!>S z?wBJ|5)@yXqaB>~KK$()`L31T03o;<)L+2>{*GAE5DyZ=A7;u*#*SM8{!{5)tk61^ zCLw}f<+QvL)0W<C-7U;OQ>kTl!nJ3LIT%S1@$~E4!Fw(_&bh)~`e5Bnbobdz#I}j` z7_U;aqhdojlaHKB+tYqnNFr*58i)lFH9~z>n%G3iC0qi=GmVVkBYjyR3hJ#7h9NNh z)rAtPV-<uk@wT^MFW+zg-BRt=PXCt{*ugYneAXaM719(Vd8(rdN@$SPSb!lboWmsh zLSp-R#LLk;?M2lVhL`mK+caXQl&R?1hZ%B|2OYb)Fovq~*D|oSCI<>f<ZM;>#(*t^ zL(uTU@4_CfIl|b!UxyTLj+HL9gG<&CMvC(kVjAeA4#Y*TzYCoBD68)(n@p}Y^z8Cy z`Mj!ftHDJ2Z$WK%FrYZuzusPocmC$Nz&^8?E40xe`Wf?p?d$<BbSN(5MWh)u2+Uja zRsxAWs@$89@>ZPi+6E5_6c~Qeh7?9Ig(g`^dB6@N4V=sr+cLxREYVE2awUZUzb!{_ zK~=lqeUI=Yat*P|i3DqnOW948_00Q0o5an#GxuV+K=cD`oKy${DEB50XQ`tAK!NHx zZJhZ2Ng}4f?pv7{GJk4yQB{b*Y;lN5{VgDA{Vv9e#l-l`l11$A`XF2II5i(s7}#qp z$c_Rk0kT+p;n@`*8Tws#7w<6W5p#qCm9Jg5osJ&BpAJ>F+6kKB>fc*ixMnzw&zjj< z2p6-nci@#k6!QuGM7*xJ-o9;Ntm*B*@0uw;?#Fvbc(ZtW99qC9EA$@VuLic=L3kvu zIe0-{Y|x`7TiCd~EH}nhNu^K!!eqL+EO%~?L!*pPtK%VrCp0{JxRqUpBz3?si713u z#S{A!qeYp5qCl{$cA75I%-1*oM!D{c;XbhSSS3`-bzL2n8XU-ekoqQB%WP+GpdLvH z))<4}12Z<Y81`5?H|X8nw&a*&CUfOAZ12h!u&g+qttHio#td{wB$JNxzFf9=yyGky ze!+?{5B`x|Cp=f&6&ebDLRC-$xY^kV(>03*M{oc}*G-*o&^j*2Z2HKk4C{0%zSG6f zkJ-2?Xi8KpI@IXHSg`FALyG<46qxXnv14k%mI!DHie|1P9kI!TW(mcy$vztH@rsQW zhPMp)5VunCeP!*(qLZ#`u2S2Nm8_jNU|=2ITs|=6;iYO*M*V`aRoLwMWfigS{glS^ znX0Kw+E!aQ7$1q&aJUlfMgB?>+Qaa=%mCQzOlmee3qSs$iV~0=`iTqBIB<5{r)_cQ za#y?u2^O<4?}(Qi=z@~ABE=^#<>$vby?mFXz`ZfuAfVlNRqa(|wT#t<r7Ad|0pY@u zX|R`MR>;;|f<Z3hx5Hb{wV$`u&<8=UpGr?ml*abdA6`zeNsQNd1<zl9K!>j$QI{Pu z;+SW(W(8yyw|s+ArDay_ij&MArA$KkBjGbaUB90}n2SsY+L0BVd?nG(&-W&r{bost z!e_F4!c#va?GT^{p(adP1p5S0WZhayj92kJw&<?N^w@?yFi<1kBW1Nlb!f+KS8y|b z^{9e9pm}>EeRXT|#-#%P!*~(V^23sXePb<qXxaB%2UiW8=#&wL#bz~1E$YvF%W6!S zL((M-lxLPiY^tu=9u2M@snn*@CR}`teL8APv;z{Xpp$bGR-DN!X@PZHYz{Nu4GMz1 zP>zY9%%15k<TdfHlt~MS-oZ|5A19Zx_h<z;G2uod(l^!AL4*%v6r-PMO7eN=xXHEz z8)B(bn_W*~LG9X`aiN(VPw}pZ(41yh+=`+)1EyKe%5qUkns1MU+4ZCzQ6*0)=cuDw zQvC{VXxd8e&|xGLK@0cvTz43tsdJh3Efw7kyF{u%j;1Sn^Lf<>OjGRa9Dnur0bee1 zz>}>i@O68|##Hq_zJHph{_=|%W9$U%gIUw{8Ws&8UZEN|?QAobJ*{M-7GtwAF##8# za-?3uo<H}ZwTnhWBBdsHn<pq(>rLv2=Q2lS7TojBPc;+Bmd=j7oRo#|6>J3K4T3#T zjXuGY`H@V%a_LiovmGnCPtnRw<Af@pTS6f);aysQ5Q&_+vHf*Jx_zX}xAAfKtzg1s zDIK%;$~l7Maz`>~!$LTzwqVb8)WtKR31M%@p<;>B6ZR4MkfPlv#gim4`6?CmEc3l0 zPeXii$1w^dq)xo7wfGGx^|N}MCZSxPP@DksKHh`O9>;elNgVvUC`A3JR6bo-E+wB0 zl>ZL^+dw40V><b`$%#;AXj}GT_=4E_A)TN}SZ@A}4T=eNfY;ax{XVS~Y}N7&!Cu>< z(a>eqd%;KNa#OQg7_mtGG~(zhlz4TzGg8f@SG3Yl?EKQ69}dO=WV%QtSt8aq-`uEu z$h-syhdyMqB*dgP1%|I_rtQv%BN)OYXpE2ynCTb=BeMkAcBm_i5Q$VFB_lQ#?^jhu zbi_CPeP^V1a4>2g9lt_A9g>V8qW4CwjE90RCR=oNou@AWMB`#Dm{Qkl2P_@Fdl|Qt zP&V+twnko**Q<}0l?GjG*&d@kJT3VOQ?v(~o>_-(wcAQs*2Pb#sUb}f2sN4eS2ET> zk5P3AyV`uI<sOBC0OQo|>t-raG$35|q7Qtz=S`8*3roDVM`KD;s9`~wsgiNrR4I%@ z((Q~pa1?<VRv?t=DFR=wcmBdWhcq;>jQ{yG$)|mmbD>Syi}7@u8g0Yz6DrTNjjhsv zr%v(4w#c%~>s&ARaN0zgMOu9jS*5+rl#CTx5%+*nBmO&jsz*B`1|c?)wAJ`f@V<v6 zBaX5{pR)G>{+HyxH1gaw2){r4-AP~?`*o}!m!a=utpT09`JhKL$ge%0FlCFLS$PXw z2K6ka1KH47Ke4G5LKf9Qi7!)h@Oy820MIGtmzcN4W1(cbw1!`u=s7#|)4&KDbyB8E z|FEgpqJ@UvH!gfy$vEU~8^V>*wU1%H1dSNxA5+xP>Cv{cw=aUn077m@=)SBVOENSf zbs^&zj7=fh8Ts1ArJye4%1mf=Y03bg^*MjoQ?=b6se1~e8*C18??dy0f>YGZPYGHI z<<HLOjAv#<tq=GmCproW#!xfYn_43$-W^8G@d<F!M-3+rjW{VcAmXiSmj+6W#q+ah z5W~%Y1tHo)iTt)wgIXeldr7It3G{rFQ>`2o?-;pbnV_w6JX!c=T{4c7MQO@7Kz7C* zIG!wppO*cdat&&n(0P!*+zF{A#}c?f`tMymM(L4l-smw6G1GY8=qu!U6Z{)}O;j1J zpl|N*jG7?;W{zZFhP@;#j{uD?Ne)a*cBx7Z=MrBYOAfwpqSLeB@KCROKGczTz3dMh zl&QrZIPi~Xj2uDy3me+VA><<i(=3*qgE}%D-FFUH$5;l3Swiu2DUo&1poSzWl7lfN zEG=!pK~a#M1OgVnbygO|o7Q%xzH>xgjU1*HmU6~WEk#|6TmY*R@CuI&^5%-o2hC#- z^%AfXamHSC9|-yuYXJxXU-$e4bvZK(4sYusZ|La0+O9=&dl#cKFlY+{p>6bkF8T;* zNPVx<kAf!P3ZMP*t0LC8?JruE*W!&Ff|ZiKlMf*AvvzV5xLmbc$d%UfS$F5bkfN*w z=o}dvjj;$sYj=Q$nT@Xg#fMNdd6^{9{#){28u_M!HIia^8qbMh6c-R_4S12G|IlN- z9pvpRlILutFlQ;p0I3iL`7CDu%<7!IV!y@a$KcxS-9<T-u(#GHJ`qW?Ib73232QH_ zp{-dnDQU^uIo%Mbyk8&qV61$v0x9**n5Gi;MkB`gM_)IAmw>##U6#k--+*<mE-;R# z49hf~9roKE3$?lCT!d@gbRGz1TeAevc)org!07nK!4Nkg_a*IG*u`}N{^<bk9c>kx z0Fsq2E`rzu0{FZMzDxc~BNv;XJ)Px~_3v$hLH@l>z~}YZ(3adb!2;ZD0zP$y)##3! zU}^o$CV;*haEJwM6FBM*{3f|?0!K+`!@hgoHo-!pZ-Vx=I2nGS6RThc7`VYZ{BS-o z20c`p#NetQy!~1<7~i5Sb?Uh_97CT_`y4I$TLD_^ADDB;7A^FF58aJ*gFaCT=hZ9o zME-Bf`L9NP@_259V+^heRp6lkzZ77VSZ{D>5$Vnni-e4CM0@EXT&IOWirV~Mb^omZ zKZ7;xlVN{7JX(<$grTgBe0yQsXc)zXpCEcIKPJ0Uk4G1BSj(ueQ}|I~mhsOV!X13x z0ih*Ae=F_-v@e=SHMN@Z&BfQr|7|(@;v3|5i*Ho;djPRL=$I8I`n^6Bcv*rQ-@XJp z3^@?0^2)8P62?c!gYaz$V#<@Bb^omZkUhECe6QuTymWun!06e2ZRuehCOT%$s@8RQ zuIyTetF;<ldA0d{bt!0Fj4%U3JWRs17~dwLh;_FV`T_b!tZ^yq$KwBv@D9z{sI0<! zIRJ<6^>T8kuG-%xzbYTD+Pk7N%%1`LxMBjdisp0l*kb%<yWBJMgZcZEzh9K}-o^Rv zC#h}scl|Pj6pR8ACPinR?G>!AX7kVgWV%NG=l}Zu{Es#N`9Cefv~&3<C=(9&wS_sE z_OT~()0Fs9r&ikQ@3}AEz*r*|;|2acgA7HGUMuR~wBy&OcJzYuA!nS~1Z7LmUVl&0 zwO^lTetm;x?PPBoL%gGJ>vCWS=;{tj2WvOh`0+tN7SzjofIQv<T;OZn;AdVDKyZ#4 zGCx{%rc944X9v^ubK%9bw|iNIUlz@KS$QzAc4NxU#E6Uuy-~R6YE=D%CmWgxG4jrq z1{+LA=)zI3QLI{LwA!GCQ<_UQ3?47v6t+++RA<RXSIHEu*2q{w&OYqJYoYN+zTw`B z!)z4l%;#3nP=ZdAcQ)8;5E;=ct#G`v=GU;DjSmVTnzh>KG*5@Zt?`aG;Du-1R-DHX zOmj;q4tgSt46&vhUt+^H)f%6SrJsplgG?yCszb%^A5kt3#~a9~E)R^orAxYCD}2RV zwRxtqEzZBZ4;B4YQcP(t4z>^e6|B+<`h{ouaqn!r?h3{!t)R7qO(9krPfRplESqsX zue4$uI2+sc`@EZ<;tbjczgv8~nlB?@*+tze$h@VDX%@l@njz+R;xW=%XX-y=*V7ki z`?=;<c<=3JYfOu!D}Q$s+J0}6H4J+f-Dnf0$XyY>30p=-jgpNax}x<;SFC5;A?&c7 z4W>(lx~{PWeqMD+G@c(c4?}~UfTmk3s$pCde#};?;d5gMXTg>j%H3)6V@rni7prIm z<H%bp$Eby=%Gww)25@3<xsA>7SsCMGDQwsW_}T2Opj}bRGVw!rC3+2JtvH<J48$nd zA`>S?qp{(<r`w8P!@v2pT4kfRp^2jL{IqA~YG#~SY<|%xik}ub^IQ$2I6bT+o8|W@ zqq5o1(q4#GFn}`M)%N0WJVD-RogLz2XWM>1iJ5G1_U8D}ySM!0@qty@sfS{eUb@&Q z#G}`vH;LYLk|{OMMf=VahO{v_1+3qhs%O%GqSRy!P8>VSTofSc(Me<DLB(i9I~z7y z<+s0c6QLi~$Y8}g8#IJqtu`DudH7b-2sSh@Fl?d1mZ3))FGd6tM3Zgy4T~pT;l*Au zBo_uM+}XHA{hXD(Haa+AsSUOvL+C(n>Ruc_p9Y2`JQwG@O{Lf<*nHrWRb_-3%M@0a z7%J#EunxR7R8(kqR*A-^%3%1i@tMxU{;lybEecS2xg-lVF41VURuqO}Jg_m|7^I-m z=jJ;Qi{BgX86*%o_g)+WQ9@<aRvR=Hy1dBZJhO1+B!2I*Vy|ZV{Uk#mXA^An8&xIp zktZhSqMpVTh_SqTAt23Rs0G*=5esrK^`8r)M~a`brP`PGD%#r}oVMpGGF@+j-<b+U zczthIoGKK*Qya;Y7_QzaHC5W_A?>Z^yKuhp-wU(!nWAUXxio$i<VP97#$aX)(xI`z zpyrO<*+R1igVN#lRT-N_utgmEA!%Kv=O$wm3bw>>b5)xYIuo}gw6kH}GaXhHHq2P8 zCQ7!1agR~yo1<OAHy|4ueV`0OkDhCD2C6?jo_99Ozy(HYq+^WYYGiE;%g>Ok8XIhD z`hab#hjwXY*uMRDDy$3{xK|T0GY)9;>==AC%H`p5WjOrVI&YXdX$n1vWqw82*_bPV zzC%iFSm34_x3e)vNxKv{j|F8Sr)=*tBj1~4r%yADE)Q9oks;%Dw(a+$>_fS*T<&CF z<y%tQsfQSgbebQ9ObsctM<Ju^Y_MjAyz-n2yE8!%gMw7vneq@l9!E<wJ5x=(*eXg* zjGUQxDY9|V@0VXemAWW|aXuEo#wXM~dX(C5a2h_f-`N<V+<B|j)?QPYx{ocNRAeTI z+=~kq3)yR<%Tq4!NyyH|fFR7)rL+RtmgR@*osE}+490Y>4eAs9yu?to3l^HM=h~>X zwws%+&o4i$B3j|NG3aBjv;syi8X@M{K@o3{>XcRlW;|Qirn<$jGGgSh0T_#48+n%* z<S~l*Z@EEI*5=<;gH@H1U~A7&O3-R!_)SI!*&6S8mCm<4`|tczz@Q;pHJ&kBsfM3h zH$}+Cw*7t*ElfWO3;oVCyIwwB)KjfW)F)>l)YFG`koevJt8!yXu**DDfH$V0p~B>8 zo`jug=uh;ZjQh_Jus9#Y&y_iA7V2T&!IU;dX)aW;$VfIj7j_(K-`TELH4<LzK9jJt z$M0X`cLs{if5EaUu$hn1q?@F|I0TNwi>`YNws^z2U7hy^S$<KS{cyQmo{N6)_;gUN z6t<Q)CK=HWADQ)U&izCAeYv@hj0U?`&%_JZ?4$Z7ahJ=o$fx>p81Zv~jU<X=ibS6I z=VfGJK3PV@-r0(&3`C`^0WJZsN;Y22d8^e1nPQpqW@oGPE>2ac4dczVBbG0WDs0;z zR-)tcHe0e*9A8mH*?7ip^G0pFW4Lmx1i{9S1jehig+huT8c#>$XvF+GJ}#&sYOTop z3@3LVlQP0KRa=1(rmDHKHC>D;G|#p1hTier^wxOZ&Ur@T*o*TP%AyHMD~6!m*|y(L z0vO^0ljCodyOx9~4Dum@dCyhdQcNm*e%A%00|B(W!PbB0B~i+vxKe0cMy)u=)r9ep zeDs{4Baq6-Z}%yA$p|sm{Dw6~KKEp%k-Y~t&{xkoSt1x5Kia*QIJGFIw|KcIZ;Z+D z-0*5sxMZkD3C0YyKe?nbGC^rxTC`|pnGeoHiHtJCJWE=MkPwU(>1BzI9}7~DfX`6f zLy}bmIva+dRz(Gj8OkJMWsq&XjR^`G<f&v#F*Ro<jWOf=aEG-*<&AAo8DY>sJw7m^ z>y>WD%98L5eHV@FBXcn%roT{Xq>oF)_LPhmHm0ps8L?aJ<#qYa*gy7Zj9sJ%#vM2c z8?N!>?t~3$Oo0L2FY=e85tXybY>xByE={;KqWqmNoNOrKcZ?{Gb?8QW1&q$lOJK=i zdH(~`M{rnPP?|#>{CLB(JA%VO5HTf$;J|D~tRcz4kPJN11P2ys;Bzv;0nM11HzWsE z6F)*qj^ue&b*Q5hY9C&5R17(T!w3$pcKR3Z95BxKDNeSExo?t5P67-;$wz3SD8>X} z92mjTwu}!4pfXI}q4JO^Vh#Y`{+1I*WV2k7t%@}M)3Ok+^)G<ci*bd=-g$qfv$%DQ z5*T9-2ga-J1Ho(eVa)kqw?xn3#pccseN-523$`v@oX-pudR>g}@Jy%CW29Pys7^l$ zngB#D4waw$4%E_GHTTT<O6Nt*vz_bXqMiU#47xgj=9u_`xXJxeb?2e^$HcG$=p0Zm zm>E=ZWPbj!?;KE}dGJ<dL44zQ0WtIS!~}lzqBdahj(dmk&q94pdab?)nJgvxLD)Sq zSvR^7{h?6>h8v$O58!t%Y~z?uJsQk><-9Bq<ASM&W^d(47QWiCRd#;|w(d{(ru!8- za#Ox!_Y04y9Ax*a=dFO1-QPK`?)OIV<wZ!du9IQ>B22GO4@;v4#Jfhy%59{Wj|NtA z5o61nT*IWmlB1%c<Ryo7?K`pLXfc<f5t~o|yf(_0l6KhrlfK2@;1fW_YxhN6c$XLl z^_(Ne5DAe|rnl&C1>pPT=>7T0#T&h$|F#|U2e0=7`M)jazZ&_`>%A^x&?{7dhX(vo zfc2zUVFpL4-k<&5Nm%(pKMcZkTDTM1dbsNTTLI2bE*LP~I7U8M8~N_)-a^3h>x`eZ z{8&11uIK&9MQv|xL0Q)_{u$lCZf$Qm2H3eg%o>{PVm5erVe(<ncVHXz0pAU}Z>#Az z=)Oe*Jq-E|98(Uy3a>3H^`}9{&dk9a2mQ95QAR5CW0bpR0DTyaSBE5Ic21roa~Q_+ zga*GN%*grCfWQoM;cXp!faGq6Itn%K+fw62{%^~XQsW}Oml{`vzX!l)Qf`*O+}L@M z9q;fWJ2t*uc62x~6>3$NF^($+9vXzJ>|kW)wzsaj|5ktxZ)NK1l|55qE-gI>5Nu+f zW>w3~DwQ4H%Dj?M1cqc@3OY%V3zSmi0;Ck#hJOb%DRMXbLyE}ZpPP6a{vFVhayII~ zTQBo*_^AuGm-%w|zgO8T2-_qb_7xxQdAqDfU7j$j#@m3r%M<3waB?3_dGfZ8r05tu z`~dxP5L26?HGpp^P7GtrhZu|E^kW)r<NeY!+O+3R|Azdkd^~sB)yru{c3^4M460%i zOk-cN_T8=-0#1^TmncMg?#+(AG+8%tZ;szD`odTd*~;Gw&Y5CGIn^W>_F2%=JaWvw zyE9mmC|Z^lJv3kxRV$w*NDe+{VX{C`hh=~Yn#6liHbWw=z~Ep&ecA{+hfkCfasVy< z+od2!(6;mxUJey~zbm743yuU;FPcL?82zc;fA1WaCL3Iq9L#0O=v0D(W*!r2?*KoM zv>1g0`2AXjbCvdmMVBcGiC1L@ioS;9T$DLt?!5i*n97+T$(J=8#%rpMzFLUigJA%l zr4m}@sk8A-d+`ff|2@#scH;M(`Ay4+-%DmH^eU>Sg>6E3uRh1lX6f|RZsRvTN_^|w z*6thzBX6kEf)7TB8=j;pBi+FnpiwaL#+fc$DkI&PyzC-$r&6NT`xqIl*&G-lsuDdx zv>JIwMQ4kBux(=0YTn%L0N(^a^vkLW{T^*ptEzO0c5+@FzX<TF{$3&!CqDghT8X?K zz<SM+(egEU*cr!gIi_DNRxU~CExtu@7bSWeI;E<ebH4CAmlFWhjlo{k3E-C<#`%^_ z!G?BxttCoiitJ>oS|awajYe)$s63R%JL4P``dTwtv1kewb7s<I0aV((MNTP`lZSS} zw6(#TlwuS!GaB#Py7O{M=?w1~)ktGx40>DTdgZh+=DP#}52tJoKo_TPZHN-+pMBmW zZDF!{r%KvCFLDM>OVl4P@*ztziSts7fh4IzW->9anY9d=8Tif7h~gNvC6}rdSNX|5 z$yU@*URQW4n>ACU1}GsM(~XbOducgq_0escZn2{M+#{xa*4j&Sk-sFhM9*{-3qED7 z<2U4}G6uf8rvbG$CC1m2F;QZqE08s6i77IB#G!MU36pA+CFa80)u5JG=pno;s=>%; z?$K0rf|&7%5rRZhYR$$wxqujP^7ZL!2k4gGj_<7v4rdEJ^|Z!2x|zf(7nkF=<7Uw+ zjIap<p8$%c&<CL$#*slFa@NO@LFh06PL_xhDYg%nJ3v`!ja*iYTA3ITQmd*Mez=i4 z5$70waz>l7_RKcNLsLp-WX=Onp~y02^A30z4mgPAX2Jo*2af7ydIeGra=k$;^Tkb3 z89CWaDcGAruT3m}2@F}fSG5C2Axjn7+FKz@PkMgLxybwP*i)%}&E0-4ytiOu_usMb zm{4f^-Zf8d?B(~Lj8tOAlvciQ%TBP>!f1PC=|$q7DP6G?_~3Tu!+#p)h*ufuc)?dR z@9l3wG?_~4a0h7kG7*=kij&rqh_|Yy!bvx__Vs5kk+&kz?PE@WPJ;db#Dt@`9$L+B zyX}r;Zyb!V!erRmI5Z!jQ?GE^6;Iz2g|UQ4A1>LH%6zd_P6=O{)a3WMoH`X>7Fw4? ziF~L=+ff48(P*TVRkhbVF>8%?n9E}8p(=(AVrmIdBBNX~HJ4Um%CuMHIMNL+M==45 zCdsUl>o^V}m}*>i<X$88Web8Y7%TYlvX?eSzTl+qqUbzxYrEzbvjZ@1_(DNc)!d1y zRaY0}8N=SmwZMx;1_@aiX$DG>Cm1*2B=VSzuA+t;kq0F?aR57cuLD|lr3jnFII7Ik z=BD_TY)~p4-zX_;1>%Uew}Wk%>i7j`-CkU&!G~<L;`lzrGx+7sXPJrH2d^@6DtRR* z7_Dc5u%I($<^Vl0;^2x-XJk@7zDM7?ZlO*<3pNtq>B?k%qAE`x@}Q4OU{(wlC1Zf9 z#K7ztBQpW;hD9*awxsLr8)H~B*~||Gayf7%GGnS*V@(WUSViZZ!R*Du%wo-^RP>pp z(!>x!vP2pZv{prl4h+;gwGy#lsg_7aMr4m4ngR_uVmrvD#P)3F03?Rb406i3r$Vgi zlrtm?jF%!yEPN)O4pmiVS1yNMRVFL)davlLnNL+Q<SCRs0YF3KgDbh~y<vtUE0;cl zx6pm>0ARq4m)oyB+n~>;(rOB6m>*U$wpY~As*FtJ;nRV!<w3R|7$FN8;z#rWQ=I9i zErCm{i>h|uDDRmhCDl85ADIt;g8L#Lzw=2jY=iyxl<AA^=I_r-&>KFXEE_#95YSMZ zX@b5~D$#<T`ZjYc?DU|e1Dv4ejX}<o+#3Vm)+at`5**BbkVV&;#m^9HCm><h)F|ul z%>2z&v~%#IB%gx|j>w4H=Fkruyarm)0jT`ob?6`?p)tCw;Arv3s+AnY(E;#KM}?6{ z`&MwEZe~&x9CXC;IR**vAmz2lUKGrIUJ1$OGT#<I?n(d%ma01d%_mR}J6&KBAIeG~ z@|(?xgZAaAs9<PqWZ9448Txn`l567$V0GkM;jw8~zty+<!BGMu^#`b+ugVV;ecu;a zT*dJV9!@pOpbq>ZMA!Z1%U0+_UAV-u&S2Yfi{=sY#_;E22=ws{lVOxJfxu@OEhLzM zHGjpIH?suK&tPT{cHh*}avfrP{4BilL^PDoCkD_t7+*Y_BAc@VKN&Fsx@!$McIpzk z`d?80(x~4;XTL~-Wp08=0vnX4no@nI#=gM_*iJpdT#j+bIoLD_m#LpMz8<FEmvIsH zXw@4iy7ptO4CZ-(Wj~h<qsF~H@t>C2pr=ZYbNOdx$~b#{=!d*urkc^h#BgjB1{XCd z{(FbUL}imh8TB#?M=7ITjU1;S)_te`rBTayg~~<Ee3DQ%OKvOhYp3q>dQo4e@SKxO z-Q1hgyv`c0dA-Vbcis6tsIzVQR;PA7lKEAS<@2FA_rLcByz{L~W0D+}#y@=*CuVFf z*w%IK$x*@vtitgPHmIx~<N3b`BOh^;LAcfpr0Ifh5+t=-a!;R!0gRq+9IKNz;aV#t zfe=YdTjN5KA_=ExYRbso{T<l4KjEA1({+e(KM&n6El6vX-G>5SO$@U8JICte&8WGK zF?{W8)X~YCgiH+QWusc;T?XEjL-?}iiX6h%YdW_~)|Uc&l<ME4{-sfi-S6nt64Nq+ zpQQSvzLDw-8H0r%4!eJ;@v~H)WgMjX0)CR}uD#~6t1|FWs!#gwNOdTFIq{ZLO7#hS zORB5nN2xBU<-Bq;yG1yBl<JfEMyk^xvwaRb%<HW28&ciTkY)O`vsC9ThH*`BzDxDl z09C3lB%h>uX?~xn7OD6NfY%7swKteB6QlbpxBC}KPf-zr9^?E)U6=sd4eBZExYr8f zYK<2CtpNO>mQ6mlXr*^F<)Rt%-Cr4&d9bqHi~Qe~^Iwhp;P?C@9Aj`*`1=ApwQdT~ zQ6ZD!hL=y>0e{W<iE%lK-r&evYIi=0Na)c$n$Z{GGCK^8o16ZB)%~{usE*H94YZc+ z+S1kY_C*sThS$uheoS_yGU51q6@;TIr?sGeW`{~({MZS0E`E4w_r`lq2hf&brJ&&b z+F$%)U+Xg7e6v<xxwu~AeLQ7T%Lp78e{LD?ubaw(V~&Zx=G+Uy_qm_FsW9g(!(thJ z_@M)H%4=IfpiVUim$`2tVv`$HOdh&G^0K)Dms|1+%mydbVVQ?o88>EI=6+NcJ+_jI z>$H7<#BTNc48>Qa-`n*U`M)hk?D|fAyX$*}D)7*Nv91H%Cl}zC0_<{Nz`!6obveL% zan1OA5w3C|6z;KE_umR|dOY<aOg0qW+ssBv5l}2|6J{-o2vF)-A5UFnFgQtC%b2@A z(0nL|v86*|Oo#pr0E5VQO#1F;_S3c@uTfTaf8iJFw2t!EO=WWT?}Xd#AH6AsQS9~I z&p;T}4#IW!Lox*$M-`K&!n$^40&ly&Z}NS)tH9XXbG|-6{~QY3G?^)9zN4A&@ik+@ zEt<)qOpo^ki!!Y~NBBPZRrz?1u-jDga<BulRo2cA1I_m^hfl8D)=2W{%FVRP)D&qN zUugfG=^pvQeEk0V`kjU*6~9qAKcvLY#+(U;R{h3SOLBY;v#>$b<j!W<&6Kj>vo>bS zN0%BSgqe>EJ{WmeSQ@<wBjXsBa;TA^%!ApRS_WfFn#m=zGeWA?Hv3AAZ3K)QQp->~ z?URVYm`$R)r<fz#!gl0CA1Z`7)3z!lI>u>oMvj`Jp~ZLP8Y9e|m`sw4{1#|=>#HyZ zrWuc3^a1iQ@yVGik!q65>To*x@wugs6DahJJ#;P^rge1M%(~KsMUFF%WWO?w5=$!0 zYfx(=R#H1;1!IL^SjTZ=#IcqQ9dh=jc;@h3YwRU5v<(v|swH~Q8?q=%9KvQVaR<i7 z$yEj=oMkDgGU(5XoKxH?zsP$XiJy`<RihY;^d+8~uz`v|A+)jOi1TUroovAjnPyFU zV(JASz2;!*IITV`;J|D#k`ZIz+ZEbmOf{_1q#8aL5{!Y~4hyh1mC399i7_&Vw25j{ z6J2hi92=W4F?@3}7<q`eDZglQ*l_4$W#p*fwHlpip@8M6QUo)6l*&kV#p0LQA3(<O za~N*E#SJFvO=$tQPEC2Gj_}%W^HHUxJ|-B0WqRtW*2pAi&2eF8jGT9;Hx)vsxz-6r zM(WB7us1c+N3lJ$-WYjSxNS+TH8RN7%M{reOK^<#s4-Rw$aEOh%CN;ronUX1$<4ms z7@66Z4{5YM(nam1CGU(3*Z(eG-fJAPX=mJlqtMC>6BciU7E^1`59A^rLaQ=Kgj<S< zsa*Ckg;VmL0U>v`TyPrXy0N*=MrFkEdUs>1*sDz2pwz}pFLiCrlyyvjVOPe4sqj<f zLUoze*3QVlnhc4f)yP18eBmS*A?pld5o?Ue^BKUQ#)QR1|7c}s&{F*6mYJ9eP;8mi zMTwQU%Jrr&P)JHnGBSRLk8bb0o05ky+LkpmC5tiE9GXJkp<F*SCGc@qjgm1$%cu$} zV}xeG=K!K9SPr>K_`O6rQZdk*);T&byVI!DLia(n58m)b&dHg@$%Y+i)wKl4fr&Cn zGFohhc3XaKDkMi}Fa8AM%lCG69`+yKx=6_(7&qW3ISQqAxRV?`ZfGa(b-?0?hHg8f zn3le2h=4#(dNbL&QN;)+MHWYGmFdlu;%a4h-z?Y|4A1f{*gN0cZuFr|bS2x`VR>EX zc)IQ-lE22JwS-}ap{^8JB8)fFZhiL>W6ZE@yjmjjar4=nU~Hb2yoOa6b7<dDBx6nt z(zcJvV06qE5f6-xxf|Tllx;X2MYJ(qbe{fFOfx6}##3jkP62q68C+Jj!Sl5aPiUp_ zf%ZIAu$?i`jo0supNt8mx^k!ystc3PtBl1m|A1V5eBR`kElgqL5t8`6e`iDwp~;55 z#ziF1IXcTF!B5%@Myl56D`k+}U(=yeVH_euFmAw6mefei`Bn=FJgdqeA6iJVFH5}_ z(>~EpS;9**j`GG<_|%n3{+W%MP4Kd|3QgT{w%^$1KIXPF*$F=0-B>=PQR=gfHv?w2 zXNn9y7YkLE2t_cqYZRqK2wz)_>^bv|Vpi0yL!>}Rc`KU&Il~vEvcv>_MsMFsd?@%7 zLb)=F(*zzGFr-thwh7Af1UO33_EBbIq?2M{{A8uq&Oi||;lRk~(oD9kF+#DiFwjNk z=o@L6>Qt2I80Fo`;TqD-Lt?CJVMsT=TZ&0#WGboVHn%e}zz6g7Xrq=HOg+j)=6K`G zC_P$@jL5^+vx2eknxK4OWcs7SBBKz%!j?1dDYzNYK`F7tV{9kk&dBd`%+NL%p?=$V z(1doz9XLrZNMr16cPqUZ@f@ddCm+&_VFA##Squf%ynW{96xb#^Th4)T#x}Nj`%EWW ze%jjDYBS`FR$DC@BO`00`2>qOXndCcGj-|RRFoWpx5^T6Y(f=sYKcsi5tiW{jL-lb z-*GEFXJQlHgv+KxX1=XamKYO-Z&jN@>z65}1tarFF;}U^$OuHVTLfdp9%V8Lr4Mu^ zW9S>f=$J!|S-g}QUCTh4<pe_FFtCd{f%IUiOj5Ov8ozMy7EP8I>851%&d)w1CR1~V zra;b69H~u7m2uMK1X9$LY~=)ETIsu}P9PMiP#EQ7XY{<Uqnn?`$otd0;L|AMO;9OX z=Y4y!YGofhKP^L;$PzuIF`toXP3fXYFz&!nMp<Uyu(#G457%M_d9R$8T8zmse($o& z7shIt#X~EvY1~bv%4JnVak(8CMHI(<#waecwNPWHiHrj!^274ZRw5I{MvaYGPWU`Q z@bQ%+j`a_WSTyui7K~H~nm|w(naY-zwtL4dT}k+9LX^l&K?_wY5jv%Bt_nLNFMY6Z zRK~>5V)nqu6fex)t1;%by`5ytFa&D#DkFp*y{JUz`R<$Pl0=E^;Rkb&DkZumfL)a( zGV~ukr$vd5Stz|aL5!MF8B#|u`pPu(MP-bPWnm6AV!~lE>oqd{45QRY#>i|*MrW*< z&st>X=|;~m`=UfTIX5x6mH1Hb<<g7psY{7p0tk$bG~A~7&M3$E37zS1JY$b{!s{W> zOL;3b*SVgcia>l!5uI@21-aZHQTTn@zVj^??pNTt!S~RBA-WmnT%Tgbhzv9X1S3Dr zdao{1=%yLsD~oZR5_&Ij2ackfpJ{?wME4bDll!SG#<6cP>O1)~ju{KkEX4%AM;xL! zV_{Nn+t|3wdBdQvm3Gw3QpfMi*6fWauJSg#SgkmSXjq6j3BHz{5xR@Y2)*9%p`Bpl zb!uHo+!>iWf#FRBBfqvc6<A?pLLeGaf|1`SX_{$_EhopRsWCG!lg`N9N<SXKm>D9j z>WqcH_2JORdgVOS82LPtv99*%Wnzicw8*VQx^%~sqgJBh=SY4r6(wQ|aQ0=1f$#02 zT!9Y-pCZ~a#?n&amjHOP7IZ1bmlO2h=!8>>IewmjraW84;B0j|PNWu-O%6HaKcAhZ zjdA)%WS>kEk2_<II3B7|Yb?-GT##FiZ&n%VP-ny{XG9n=P7}Ds$<kP+nBv<avu5pR zGT-uA#mv!~hXITqvWa12Y~@&u+}3|<_#r6zi;%Gd!y;HVXUf;n!o)Mn2>qDsclFFN zN-`md!I}VrW7KkfQPc?eoxYvpFTxqb_<}1l&53D*r4cY0ssv=(Ge&xmj980U$*Oel ze90fY+<7Afl*Twtt(|cPj>j3arwDEQ_PY_Iccww!D~~njb_Q?1V;XI<T=w6wnEAPG z{65Y%NHXf8qdAseV8%I?_*S||HZ;o7;5oC=Cag)aLBhR4N4@i<d5kfinh%l@YHBsn zPDZ|1S{&j$pQ3Sf?2NQV=`f_U6lN{G#tw{_!`IUtg%JY^rMpVTlD%yQ<GGJe078pu zvNJN7L}?oCxkg7@n(y-Wxux$p##@e>W3txZs#+q=34Ul6jL^`T4_IZyW-q5vbIc(1 zVbpN?#mb9w(TBnhzsXAgCRV72HhKo`WejI!oSADp(1%hmTF}L~FT&-{g5eCT>|7Hu zd}pLGCJv{ZpeYdc5_jM%DWJb$N8L#Z27jf2dy!8`K?B!{-(S(7!u-7}%GfW)q@`Mz z9cg@1W2}yHs3y1Xf`{LEGqP4c1y77^p{&&m;mW+s{Fb=0)%KPrXsxTzzM^-c71l5v z5|z#!faLJa0^TZO0`qF#hX1W5>ln4J$QIgm5Vie%>=`QLQG2M-XP9bUuMrv|U34U4 zwESYb*EkuWm)Ot_g^iIPh<vbWQ!9g=r79U~Y9TbV8nMF@!v_jR*lL;S>9rc6KYKbv zNJhTn^;xgc$CkBQGWyJ$%cwFkRb>fsa9nJOD%8PweUUG6I_Pl7C(vq*nb!zaE>g#f zXLFb*W_o{J3Y<&iSDcib5hc=TI0k<xvE`$yYUg~rhX_S7zCs}xwJE-|G}*E#Q`BuG z?!Zw7ws@cV!-j7B7X~((<U<HCTKiH=do#k{d4J8LdZRDYQfU!w^pHG!0Vn7y3@S$S z7r#S)3PJvEu~cij<`h7tzf~4B(*+Nf<Dn=h1u@zrIk3(G^C$=opDA4rbp+#^<Er3@ z43p0r=bZx*yn1IO2VG|(x9iS<e*2dVwQ<m!n&CzT2ZN9?<nPYmT9lh8Tg9xr^jDM| zEmRQo(hmH7t(&<9`#NKYDMl4|m3g4(YjoxU;p@2=Z29>3#!2$!@r@g9@g04&5WmB? za$HHB%eOoG&c^&9m3sQdmYFfe$Biv_HhL369e0Ay+Jc=ysd%o>GHY(L;&#TCCpzmj zh5)&mjbsdbK$nVIWA?PA>}2dfvAoKZL&k`$wM3^jg;6b=eZQB8t%i**0cWs)7=voB z${D^9h<mRmBgJ}ga=7U0QnFKri%#Z@s3)5eO~T<^Wr^6U7?P|uB~$iPFBusbm;OOo zQ%drT$S4_0jSRu6)kt^mV1pbrX#Bx3JBLyus$-x-*?Fdi&vo4;9T>ZGuWAS8A+v1Y z>?#95$qft}vA<F9uL#l64Dy$Vz!t4gs5w6U_r5nFA(?-Br|;RCcY69-`et-*43>G0 zE5~c+2vo?5Y*Kq`;)-mOjmCP001+IK*T~$zJ4bps21*XTRSWr0M`=l!qvYU6l(!KX z`^#aAJ6VULv#4{j4&JwxSY<yL!8bDotKi`Gg?8t=b1>al`|!MTz^qAp!6-OV<hyA( zAFd_IE{6`bux#}JR7_NJ)(`-!!j$D8(k^b1k9H0m;XIaQ2Weu4au`I&a##U}1;^)N zj8i&+hX#zIAPeXPHGnSx&}_=?_>%cZIA1cq!@fmJIKE_VGJ**uc+-9nUeAbMawYPm z!>D5NKqT=Y=KvO-m>Ee(_LwIj8z2U+smf07Z|pm$5I)OM6~N%2Kft=he!oP~6l+~{ zK{aPI(WioUp*K^}GjbsoMV&&ArU5^TVs&TtikJm@i|uFI7vYPc7bF1Q;pfamAOG8e z%wLIq!KQ~$`1`wrC^5Qk(EV30@I83LD`w7Zk5kKMMWPbpYg+%GM((|wUwSLY&RF46 z`N_{5qdGJ~KBA>@ei8OnUfOF%EPOwkI(YIcTbt~|0HFCnyKjlz%%!osr#2@!Q|?%6 z2l)i(ic9;Z13v~70@Gw>S@#6!h0;<!)Wr95Yi!C!nE2wu55l$Z3V`-(FZ{=tw*xds zN`PMqKwY}>iNU@f{xyTzu76$9FOA`~qIw@A{mglQ@2erU9106CIBHDo-gs}?0NU3$ z1DS@RA#BWF3{0A@5c;G{9;XyNOD@VQp4c12aKxDEpM?=@nJ@~r5oGh+3()I*rjAA% zz<B?Y?tuI^lUP;^!?-9Wae-B6-5{Q&3?MRfXWO4GOBqx>W0v*BK=IX0!Wo<4)av8s z*4Aj88ML`B!V%q~RYAuQnm_x<?!Zrehoeg#9RhG7QU^;$lGB?R>dw#LnoHmn41+=T zou3`Ux#5c$)M(PL9Xd;+$$2A<GM}vR<Ghqcun3vUc=q{k1vti-X@r%p+v?iL_s^oG z*^f1wvTpOQn|j`2%(OE24Ti3qvy3@)I9FlAMLBgl@RM46bEDmguMDVB-kNwp&KS>d zdZO?JU=($1fuq88B7B?3wF1VX&1Z#+gqEL#+#sA23CLBZAL&(09(ok>y0-%hPby45 zD};|@UdFWcxN}%K+Vdt%a9|}e518QKb#(U2wEa?mZA=Dyv$z?CFYuw4T-?l{2)(X~ z#Vr6mkXoaL{>kX7A67WmrscbGxx&@TWFWOyLB2hCKP_`c9E4siRRjV2q&p5*;@(b= zGa^NETIP^ayjGWmPvB;m3&Qs)T`Ksz%mZ(*UQ1(N=7I7*7P-v%w4r^xkjp$&YCb_O z+6bFEpL#ri??`Z1K3JNZ;3>gp<@^8`4(B*c-eBrsE2UCX4sT28p+nDGXj&*+HwEz1 zC<@ex@?FjUeG&FxOoQ<MyP`3Tq69?`*CgzVGr3~1+!MYmmV3JY>IHtVSWe{2;-7Hg zH-NmxufH7`8OX{mfvolgB<K6b^+#P0!er%ZQ7rlRZIiV#2vcd6bT(Ok53>lGFwUYu zA8~4hS=<h*hU*<+H(c-N{;L=G(Qw_#K?Uu*Xol-X{%_0qrML3UaP6?Eo=yQD4A+tv zz^fCkhAXdiOP)>L4OiKR0q{$8ir+L`JGn4i2OtesQTGI(?}O{saP5Q#!*vuc4c7&d zhO2DU27KFay=73_^{-3X4cBc&?S`vZ4c%}Zz;3vTrVYR_QDQ0ghHIxh7_Lm!?V(=X z8?Kn`#7xfLGF&^cFkG=Ipm@LJ+egE-6CMrM(ds+HwG$o<S240X@J+)No%MV||2@OC zQy&ahMH)@c8)?)H*Ml_bcH`*tZn%!R?+n+ak*eXkZ1df4-Rn^e*QE?;xQeOU0ZpT~ zEiF#;Yw-iB(PC%G!Y2?o;pdpAN5c1sTq=l+h5o^CH7$~CCtQtC2;GqEsA4f(`6w<- zU^QHs1xOx6&VshCJ)VZEVe-}k2fvefD>=|+X0VvRF9i^W>jmE|ZrX*640c%Dd@$k} zqHSN?0=O|;LBvl;A67UcFHto(tZ=n5#c*Yw(^8MioR8#8@$#4!fObDK3|G0#hg~TO zpTOs3E(y<u>+Le{hU;OOcf(aI^KQ5vmU%Z^#iH%@sp#<lz9Yeh;krn0X}F4w(G6G8 zs&0Zxb?F4{hO2~zow9dR0QZKgs^;&8>mXDO*Qr5$%W%E3Sndfo!}ZQ$IT3!xa6QYj z2^*$Ei}{1$Dn{nB;kqv%Ip3P$DuvZBT>UFpz+$*EW;i5&Vl4S64cCi78m^<HZn*w$ z3%dK(suFJBT2;FJTkAsjoo}t8$DhBoet+aXe`{S@dHU8GT!j_zN;CBFTWcpgd}|#| z6(+0b!vH)C51YShvR>rUWbMGgWZmnYfKPlGb#Jm>geQ}=7k)5VCv-4bMWZ%gu^Zp_ z!v_W)OI9$b?fTax36u4GMG2F2Uk$@#?SL>@_onRtUk_J$<Y}YwZH8YO!+Y+fW)m`W zOZID-%u#2BsQTI&uwkGF_{nf3+-QP&wn5Op@6ZWHgW96HLlgCX*x;RTS$C)$NEubk z&TW8d#<A%P6TUQ3*ho;ZT3Gr~%VL2m^$0UAMQ@njVJTypaS3XNO-nbv6hJlOa%|5p z*W#xEiP<$t7CwQ>K)qQt;{@URL@pIT;5e)4w+t%>ozx7%Wg-i2GH5JZRZJc%<J!jU z0v4VMwV|5Xv0=E{l%2P-#}g<FYZg@zSpzDjN^%jdR&jeE7iQtTITh+KuZ;HQ@IkSU z!3hoqW$?x>9r&dH`v>0vf8IIGH<y9u<<0@bAaYUc907c`5ovw#b?S%h)9k=n!(scV zm7Q%w+uo*{;~sK+(OH7rLjw32=p78BaaAv)MjrSY$mDodM)3<D3Jn<-mcDI}S8Y?+ zeavcp*t=M(na^BhrzY@u?@Ge=rL<J=aql{Y<Aj27*t@(Xs6NQO>*(2xt{wKS;~N^j zbQhZiE7&qbrs(kmKJQ(a$}L&qVeiu0*+2%#ofwL356MMyB4d^K!`@|fg}1dhI7-W> zB0I1FHw!CKq?foZthbxrad>C!w^-&`+_%olBmVag8PH5?ne-vyq;l)kmt!c+K`@u` z02m|7DQ>|h!uOT7Q~)C)C~m=R0~Qk~doRLe)zGnoj~aUw%QnR5aS3+d$LRSO$oHOy z|MX;x??ggfdX4+IiGT`eR_kS{sNY2NG7{#_Ee<8q{@nCI0q{cNsDqs-Z!RP{p?)DT z^uO<2NZi<?_k{a}#Em_ABK+2c#L+OEuw$rKQ$Jlu>?3n?A+Z?-a=z6IiAk_uNJIwo z4FBRn;$o17@F?kgAtAn`cY5VZdWUbnq-%uxmvoIzd`X{#-};h1`u)8x>0<o8SC06S zK3jSGlFrB_HGI03xW1%cgr_g*y{Y0_LiAw(0Y`WI_O--CF0UmzaJZJ(>z)7wXZgmp z#6@_zmgt2at|caPxRwx&+JNt0ODqh0R&swW@tvxVC5dZ^_Z20sCHB=Yt|dAkt|j)S z?Ldnw*&bHiT}#|Ch--<?@ZnlwmdWIG>Hb<Gl;-p~8Q!lYrX^lo)5|aVd0(*s`+dcL zBdpl?;l84U_;G`9y{}+&aVk%}?!Og4zpsEg+8hUFBjsg)VF*q;YgzP0r5<r#0mF>B zZPqdtj{(|!cIn2K0(`c$cJj|Ev1N=dU&s6`w$=`*widHb7v^DFx;1YNGJ|x=PECM0 zmArmWA_%w7-LnE8alWhfB-Jy<u^EKR0&3}}Xu(`nOr8j%$K?quJf$VPnjM>-=?wI5 zMUNK%Z4OqqwV0ox-D+KgtJ`}@OkOn$A2$y${g}^9G>6{dO^@0+7~P=eLkBQQm<S^~ zumLx=7858IUSiCJwR}wXe4prL<$P5g7P&KRTO7|dEW`Rs0d`w_z@G&Sb89oX(m}v5 zfw+lvS;T)Uz~^fnn)I=xzdlHrmUfR>BBYd2D?4B7_)zIaa1=ER)sy+WUQF>0s6Oi< zQbT)_WW!c>A*5BveF@<6mY0O@Q@T{}amzQWGQO6^w&h)fff0B|wrzR(u-TU^-?u#P z8kiVbE?U?Ep#&#;Jb{}nkHwf=li6a+GaDbDNT1G~ajG-3Z!PnXR_-e*RosQ1IU%fB zZV3W9Plt$$V7Yed0Ha-{5BC*2;dWm!U>qdAe7LWOu`)eCCtU9<pt}X0HdhssC-ZrI zoxpO9&<AntITWAw`-(v%^r-E=0=gyRqb};PxUcAC@UHH7U9stj0{F&tg=XA|>xxdO zUsnvh@O#%4H+Jeh;eK6lW2c@7zja-4G#DogGb;0|?uYA&ePnK~D>j2c&bNA9F$vfP zH={sdk7o#ys0HZY`gKN<&j>p}Bexz^+zV~>^LL+X(-!;h59Rk>PN934pTB?YzcX-y zIs0{;=;qA4mrl#^?A1j&3_w%NF1l+x8{#~JZ1nOw2gI(cDa_vo2SaBw)6m{iX1DYy zi4kJ}v~~<^^qG+?tQ8|Ee(&@-x<U=I|Ni?m?Q=zpdB^_u{e{PgqOX}S7Xi*|=%{wC znSQhK+Ahx*IV}=85DofXjsS$?$p33OCz0_j!s}}5mhQiLfttwpR)^=+*8gtc=GB(c z%CR3-80Sh%#U0hxMhM%Kp<+5=U*ClI0FGO~H+AqtNI32l(T4%}Trg-KuC_>CniGf_ z<P%8Tw{8MI2E=4=44f?Lo`7d)O@Gvx8X*QII5!B_!Wm4?&s}hx-3l~EN`PMq&@%1N ziSvCoe3u+LbqY>z)4wd|mqtD>wU|)G7>FG@Z*S{>-)0Tpw+>)%K)f=r-~fIp!27D5 z@Xe})MhXRw_vm8PG96pwK|AXHTLF%@I<LZ+6}PO7e6wR*i)0I<w&Zm=eBIRZcKy-H zfM&qp_DdQ6jBeQYip?kn-7>o>zjbbtz5t&$fMeujEP!<bjCIbL_U-(hje6cf*TEup zr2u}~^U|M3lO~>jUxY)!>V$8~>5)QLPLJfuNpnxQE2lRn&57{CNpm7!HqV3$OhHrp zrks8p8L6DMIqAyjwg$yyy(y;(!KP?L6C%^Mepk`x^x}k@1sxTQ-{UX~3~fKj=a;l2 ztg0J#gk9aZqx-L3;74_1C)dBEoyh-fIluH)zNs4nh5?QObajJC2fP`CtGdBUJm}M- zsk^!%`!E2U0p%47@EhtzCl~6*0HnGh>Yf0kbZiN&KdT#^@Stvt!lk;gKvLb1joN^3 zsv8Tr<%vGjgxA%e+NOV5&aQ53YiU<E_H{7SjREZH#sGG8<GgAY`17hA>V{mk<Fp@j z@9M^=TfO7GbPfjhTw8k3IV$rutZQP|Irhrr9q&u=fb<M+i)&Fl_)W$*IsCj}v}^TW z0{FZY97ELeqHWm<tKt!$l-RXVzc<BW_KqGJ2lZobngDLq4^>?6>c=2d)sI={x73fj zljojrQ$Oxbo)h7B)Q|IKT67C;pO#WbQ$NJWd{#g9l_(}lRX^Sqcxy$T3J5k=Wblr8 zJC@qjzWEoFzh9J${9l>ybC5E)elb^e;zq$s<}fKb>ujrFeP#OLpZ`g8Rr$~V4gdKc zYyR_pUT;Vvl&S0!<JB%L%uHeUy2h#u18#QO>+fauRuKEL+8$*4_Zei+lT=#c{!Kf6 zeQHN9NFQ>@exI_FwAbI0bnVwCnqS|bSvxs2S7w2%Z_5FPY^?6EbbQMg^C`x;OM-g2 zfKAX-IhLk_uXU4tCI%z-X4U}x$q%NK>F_+6uAdnoCY7-NT=D;S)3{Yp`It3Wr3$)j zTDtabg;`Vh!6}O0nXi+1y|!Ac^PX8B_i7$zcoxUNwy@Is?_c}xSa;5!V}&%j61a^! zT|bE$Qn4_TXsEZ=@Ug5i9=;|hg|dHqy%4hKUuTQ9c>E&RB88}N8e6uICt1vyWjqYV zeNfn{W!?y}np$RQyDnI&<8`vp+op&{x|USPYK??C#Z1Wuw#?*ADjOg8CofhI^oLkN z45B!m6U(yRi-WenU;=^-8?m{{YiuPoC3bHGUFi7OYcDPYYzSAh;&77TjFX*$*;S}? z?!{&1PA}SObD7_W=VBbcS7t3vvYLu>)<-e%*d2unMyUp7QDP{*y*LJbPBw^ELrdc; zNv+k`n8DIDXfMuV#$ynI2`T_~?Xt?p@BPqRtIy*15w?C2$;mM-@FJ2A%16GWuI<!Q z>he8`orRd<!XkB<@7)ik>u2UYa@p=bSIaG2_9`g7Of5<k*oe%cwKMUC5z`yqxcuC| zmMM=y6>N|OEo#8IGRvesbhp{rXuiedH8x%=LgCyy%mb@AVC=;)rv{xul;U8>7*}L* ziD~YNEG~Iwzf9U#WDGC{QLtr*Dh4l6T7gAkAelrf3WFC_F}t*K!(n<EAk^#g+k7pU z<Y6lgvd<oigE9B1I3^!vND#rs!-^LAag6vPh)ER$8#TXVwTWl)${6H&!LX7~Wn(lZ z`eE;EiBB1`)7bbZ5Q0dsmBNH|QR`b}CPX>^zQuY`=O2fEPR!H0v(XQm*>p8Fx&xWC z&nG=bDkE3zzjq0?SF`<ol5E-HEY7!*%_OE2>eS=sKu=b)|4drz1$AO_?INgo#Gv=% z=jSB=u^)}!s1uWHGDOx+4egQE&Q4v?C4SQ1sB3oZG~TG06{IqT$VSejAW-kDq=#XO z=@-9yh)s^=UJl*zO$maYNpkRS@jC_*#n0yNCsv<4rr|*eS4EPbPkSBHUic)<){izu z5!8!~QHG6ifv?6fI|9tT9F`hFPY(sOK*aNoX=5ra>3e=>ik*qhg?ygenXaFisV^}X z<W?9ne;K;tpPRt<-law>*yuaLuiEEESSYiWag_H~M5cy;j<y%aY^jjIS}SN3rwI?X z#OHI+2Nbs4Qn44o#?4Za*BXy0_NUsICGkUTSVfVU%>`S9W;%y(tBsF>GcRj5HXMcq z+P_vCbZ$y+yN@vBFl15|Ba9OnT6)k%m>-dxk@E~q7kY4=i!Ja~dm3yNV}hUdR$v8U zSvj%ZsX|452<XLmre}474Uz`RLl(tBMkET!y*Nhs3)U)~8asPu+kT&-e(rf@b-}^@ zDZd}6V}cTb6YZkz6=%pyM&9T@Kd+69y<>D`P1iOWr#rT7+ji1X2OZnCopfy5?sRr+ z+qOGa$98gd_jBLR`;K$IamM#&?LBI(RdrR>WUZRB#$Zi9T}0yy6&sy*L}!d5-N$c^ zv?Rh8Kg&;<+oGND@*~JltqM=Kp%wJuo!z!ml!Cv>PmKrE7rH(lMeo8cW(y2X?`)ji zel8EO>u`Mznww|bkJ8Cv*;IyohEv83%VShe;v;I@Os}p}VzJ$4vIa37{Ok!QwsSWo zKgEQuKKz})3(`wxoM$mS9}E4KnWZPN$V~bniOk3FJ2~S4BrSa*x1sK3rs$PJshK{4 zsW#eej7M4O-Th0$;E?UH7T6Am*$r*mHfYy<LauE>iUCjls~?Y0NBrIm#GPqY9=^@Q zjWgkR{5FLtx$M9J4{nlmNFb8+nUlQA3QZqZHypn8(nZRq!O!vnzSnbmd-V#TUvKqA z&fk%Fq)I%?nOU6GCR8|r87QWWjKgPGAM{jZWXHc*L>SBFH&zGWkc#n>+KiU$^%~1- zqzu274yrWtkCsbj^?yfp1>>-q$65&-=gQ|Lbv28UZOvnDHFX@rS-bFND`f7CnR-nk z!Fr0J)N-M|viV%7`DJjNC0Y%;Mw@1n1$J;WC|4t!@>NxHwK^LaUv?h+n}n@`?l_FZ zGeMHc$Z1rkm~QQt!R~PB-<o*6qAa%ETt#X<JCEeNk6)p%hiky#ow(etb)gHNS^7@s zD5iU?q_QA{r)=hdnfy@expQl&5JE`hhAOytm+k48=WZuMRO0H^RwQVNZgsr6I%`yP zMI@^hOg(6A5f(HE^n|OXSkgZ)h97ajv(I6Kf@ro5(FA}b(lOZJ*?a<q<SXD366Hk4 zi^9DGtccgHKBkc}cA6;L8^0v&F|p8mH>q^2pjQ8ywoHT#Yor|t%+yDn?8c&7$y1^; z0>}Gv9=KO`YdV4bS~KA=R+SVg1iJH-6kUieh1+Ra=am(!Z1NjzXl7ZK!}|}J47C$_ zk4pXVZ^V7ShE~2+&q%~YCI2Giwq#Ej*@q;&?p2t8;obdFV<Ju`%(0-=$rT8nzwn6_ zgLYGT(AL|W9pQ5$>v^|E{gr5fno9}8Dv>=P6PT9{27S$V>COw2gWj)7D*};#l&QYh zKRKODYor}oVTFznlRow;8j*jTd9R&0gxVU6P(gggx5S2HAqS)r!@|)99LpcGK%<eE z%vbi;8WV1;6MkbO@Vnz{52MX8HtNO9?|kau@-=7;l5Z`0qAI||G*QaR%lieKkSw@b z3&Sqc^XgRh1!B(<hs#Az4yJkJ?jg^qQQp<ZeYF^A4s6LiSQ&`v+ORR5Bo65<9f)Tq z{tvZ?aTb*p-Mk>hsHH*NAjz1hj`+JlA@9l+t0%p(ZpYInF#H=PE(d(BatsnIy+on* zH9VwtV@7e=T1EY;JHP}d&`GnGj*1^YunjbxaG;*1qofg{gt;SYn1h*z2I^tWdQ{Wa z-zr>d7kWZS6Ky{ND;T|w$_JmxMt5n)(qyJr1Hh55W3MgEtVfWnXEnbMAi}5DdYScu z2I{oB87v+dm5}D2itcUH@UxN6HZUB^eF?~a=`c2K4L1j@CXGvZHcAb`P4qDo)-HXb zPE7CBU}9N??~<TlX9@Zi`MZU6Hkq5-rx_pBJgtwXF9l|tyI^rR$n>Dv80(B*s9J_- z=8!1YAI1LLXu6T(sbPY)4+HB{O|)f|w9MCiGExi$j<NS;FBO~U1Gbpt7_Mh7PoBpl z60=Gl(n#HG?oI8tT0lH=JoCF}wCM6FFkeZMNLu74;yWE`=lG^f@-FSC+s!ueeG)k| z;aFGJi-5c-u2_0IN)FEhvV6f2c|H9Tmi^avFO$=Js*{SILll#a_M5Bm!WvffgN!h% z$dc%RYHD%Eda77rsThzOrY9Qi$K>*$VoXGMEOC|jbA&f@Zh!4$@y~f`IZRHsP^jYD z>Lu1GcyP}U7Jge)#VoS}lRacPT=si$Txv%)<R{%9;^T>cKnn6hZAT^=kvUA)nB_|R z{R|WJ$hbo7dOjwrIV9JZEauDmZpFN<X65~PCz*s3n6;=*Wk;P3+apA$^EJu}vL!Y% zQnkAItCt3i!@-NpwI;Z4#{(Wj&3hv1dteBPM{zP~UFUGPSgd5%Kr@48&Cu>KRkFzq zI^wBw8^RA<zeuhLL=T3^yK;fV@78zR0qHFcT#4w;hsH_BJ|xH={g`U*y1W=VL`_%% zV?HLr(pWf_RrIFkO%1YvI3f{r2;L`wq7OaR+QarBkjM|6)bB%s_<N?zlIE}<`p!nx z`%k*-L`1|(-Sm6lVHj?wx<kCr*}5<M!Atz7A758ePe)yMH77Uq__pABg)s6uud1}? zm!bH|;{!zAyef)6u?t5aKbVlr3G~RZqlw3(iBE2RFcHVTT-?r?ER(qzqDxN6DZc&O z^o!cmyXoz63t{<rv47#`^VGpYtkyiPCQR_KnXZ9NDcUjBq;z*+n_2OC^PJ5b!9d8j zm^VJp4gc9!mr7^aRqP!X?YBkML+SKu<@K?!=H}TK);to7(qWyNa33z;4{|?7CP5f7 zGwOi)9{`&M$;B)qM*x5Ar#38%JFOu0u0oxjIk(tTgFEN4q#+Ej6S3gCjj+Lw^a|0T za}|1tLN|a!4VDQ?@!Z|abFd`Zp2No*YwRta&<!AD!NX*z&k-Ira&a^(8saN~qPZPk zZGNstKQDAGoNAn`$dXdo7dvUsYy&d10Sf56+e0flb*gEzv`kzQhv-SxUtBY#BU@n# zSnpbCg{K2lLnq@`?6(IzMSV9X6AY;Y7q7iZw;NZ@UOw(DaQ@4*;*8M`a3~}406AT< z>p3uGzCvL{@JrzCg56Loy{f^%RP1do*!R6+@hB@L6aj2W(oTm-(Dz;*S*RhT4A_%t z$fchcOgSEA((@<>Amh=9X8<yC!%JfI!Yr1MCU*G|EW$LaP|YY5mefhON(0=^^#M3$ z9PqjMQ8A1VSe1(LqRD1AxvN2Tm|G?gy=ID@=c6Yi4T`NHFh02MODss!+I^R=TtAXw zqxuqw`~ZurxhLEeVaxtt;LO395e0v+21^Bxq!lb;u>F0>U#@7i+-UeCSPI^&guQCW z2wVvlv4TNNDG#`sAW}346DpwloZ?Rid&vYs5wDI`e?QM4W{90z%BmZ62%gtN@#9#8 z4BivVe@bkp&SEin#)q~$7SbIHBvT45kd}BeOl(RzY}L0KH2zoJsolTT4y%1B{%^G$ z@$OGpI?c$`Hxs|go<Hu;yW6YsH^Pd9{({BMG!~;N>m>gdElwcr!?z46*~Xkq0Vx5H zG@8|Y+<3Gj1CUOnaB&N5F0Sj`&;FJD*VG{$#aqghvtf2TGobGP)S4tYLSMRKRA&32 zO50*oNb^GCtm|vwA|XfHrGcSEa+Rx^KE}>yIYcq44o};OSU~VpsN{J8YRwiWVZ%}K zadmxf*<B~D-pmtAZJlN1%%AZYXNMyUzWxz?d*tcRiI2O#0j7L8!j5wlZG~`YRtZ{6 zJ+>QcRp1ux1{YyPk~_OUM|cN3QUceY-Sc?&_r6;cljf;Ke-<_A>FjQ{3(3&$!Y&*G zfW3-RCmkX}|MJ&`hmB8>vZuQ@6ZT7gn(O6R#-G|E;O2mOlyn=8b|aPT!91brcUxT9 zVg#TnyR`g*Kv*^Jz@)d|ac@Ge@8$-{jb<v*4DIlS$!bG}x+Rb}Ekoh@4`GqAos-yO zjeL`to6H%eJ#btFyO2<qrDI02D`|u3;2VUof4G}8z5Z04oWh$i^7)omhjX{}ELh4t zGDZb{fBHO+xjCEq`_wCLotd|znb}>-b;OjZwcGvvZaFWnUDMs^sd)H)PR`>+kh;KO z_<iVSk9EI~z2eEW6F#jP-w$TrkB7ULTb{B1$Qz&MtOalMKYX2tHMS;0pJKqBgn5Fe znFu9lvJ82KWI&n3Ouw%y9KI>Xcz4pqf4pCev8OAr^Yp^_<W(t4>Y|o<eXleXuhUT6 z-ZAfGj96Zpc{I8v^Y&~jQwc0FWKKzawqeGIrOU0`L5BQ;Wt?<OhCZYLZ`4XXG^VI0 zQ4(zxH`e;dj9^9Aa)1noq1m`C1Tqs3L`s=%Uq^T}G_{q*K=CsnT9LPVnVz1VYs;<s zVd`12FHkUy-z!BHuju}6Y8Z(W8`}lAO9T=?ZLuy{GdAF@T~kcC%0nK5<wg}EZ*m=i z_!(sH7cT<p+UFBoQvB3wC!xlp{gmUbw~KXI4oZmj`(!GD#*0}4t$>h8OdC@*E61;u zB9qhSH3-Zm{^5JmmX!VFJffP2VTTyCPFRh^gv$YTn5%3njz`#~ZXDX0Tihiw0mU&5 zCwN-uy~Jcc>TatSHGv<2-TAgIj&g=!6rz@;-DPw;W5bYGLh>+KS*S6k<=u+>nt;S~ z?!=tH%<dk(Hd@R@4f&U*eFtEt5UVsK1Av`^J)sM2!_(S6X%+o~`|IX(v53sOCPu{D zEE^su<%$CmxHr{9#kak$GhApOLvAu$IP_}~z+*a0v!w$jL@jFM9lYOt&9X<?INKG{ z0CgbI!pX;j%9d0ZUsXEu^7Xa{l>rw6A`_Myi}*t=wib+!t&P)s#eYRX>Ec@u9&WkQ zo_kdEzQ4B?>pA_cd*unN!{(QE;>DHSPE&=%**|>3SLTyTGz4XU|HfVBhF!kpRA}Dc z6z%9QXqVJYXEL&p)GB0Ji75kH9|)FGujB?IFs5G1ujl!i6IHyKKja`a`j+R#b`S0Z z)YxWCZ$ed{oP3V<H8|Pbu-h2**iNXX`#`)6vR%eVhA?PvHS|7=hSeeU0EI}K8fJlA z)$+!208y;mL_02N%V|L0t>aq~Ul-a|U6hHeAK`_RpX6Xjk|9DLhhJ*VR;Q}y6lac- zXpK7!xxlWhTMkb0a72pHi{S}_(SuI%0W~C0vNG~DFcj}CkN)`K7ImgGc#RIR8E)C{ zf^0Ip?9x<3`FC(kluiVsV{A5XH~48`IyoXlyn*MXzM2#QUZ^@07k!e}sZJ=QY?I(0 zPxV(G6!rM%UIe5y1XCxYDyq*585XBHV-slW&I`|NQ+%3=n*Sl+(-$h{Mjt!phX$(0 zJ)G#rL3Zdz)+J!+06Xw?`-x5n6m2IEfi|sspZSYs;58|s0H`qmbr*#UO3s^-Bl{W; zif(RWom#Vi!oO4K0)&FM*2>x1riJ#u$OeeLZn8Bt0Z?cAo$SQA+YI<l?DLK-5UTW+ zHV<pF>4u~Z#N@vq&;NjIkqFRL6M(tg7N8+~P_z@J9rBr1f{n3CbJXSu&)*O>vcGeW z?eQL<_im4+`R(LV!Jb(I#6_rgQ8?Nen~~i?RdZfQ@y<)Ucs48c(ig;c-sRUCOY`Du z(P;SgZuI(oaq{5NMb?$t^>MfV;L%oeP)-E2oO1isfv5`f?p|WAUUuKxkdMAS3OJHc z3Q*iydTz9a<*Rp9$)Jnl{FO1X87}aoFUegWSY3kWU71B!F(Ww%ZPTWkjA1?AAmeM` z;sk$HC&Vfz!cV);k2N5O;QFYaq3v+6x!K}Vcy(fipk&QjC=$T<;kq$N=%L$?oY#;$ zOT4-K7%oe5>_z!*gE*P!CNyVtzEXt-zTIszKke&d8rpa@Py%CuiZb#8H?sxzovUvS zn41tMa~*k>bM-FtVK;VFH2(9vD#qxxe(G2q-l^T#E=G7topxQ!-^La-5L~$%_dn?w z@n#8PJ{sZ&KTh)Cz6QIb1nSgHI#$apYD`*<@Zd6O93H$<mj?RO#vK3oeH-9`t;Rcz zD4kcJ%h5!*$NdUKt=+V*FSta12B|mcIHCO4baA)jUfy3$3G``n;_(AwzzkdKc@I%H zi(S*Gq$vJlr+6r>^)L)I;%)!GSolm|4cCNsc|c-C*QQ1h0T^iL#kK4wI!J)v+Cu0Y zJLtQNa6bmTxVG?(_4uaN04w~j=z?y;TXPKBGy!~PTvQALQfiN$x*7K}`w1O%n{oDj zdkUZqG}q*GTmJ+8PpzAO{;Kg6hZtVXJ63Q0#oS5{{h~8yYu55#=EOU7wEj;^Jq*aH zfg5o(V;YtJvgKG0gR?pOe`c2Eg;a}h%oFb>qk{3G1}_$Jxzj-WALD8D-FTr1;#J*0 z6qG3(&4;k1i9u}DSBaYdm#HH!L+bCCh1K(w{tuZ@Gw+sktt_t5Qvr>(lDV&_UjlSH zxga06sOUlqFXd3?`xKi^y&s2uZ^NUBwgnDuxjrF(WfX|HijC?0DWLW~xDs_n)$Z-> zg0^@@mGy@o@Pbi4vXRElIA`AfdI`CB!7jY-rnHL}f`b<yoxZs-f=?Z<Z&i$4Uz>6> zs=ohWnbigt-p78H`LuG{A(kARMkv9CBG}b@GJJ*0JjQ_y7c%cq8x-vFmuK6rttI{5 z*%9l7JR-b*T!Pr*gY)yB>|Ivm%yuNS@w<_T87^;iCI<pjC%b3qY8yH(MD<(MXyeik z&$i`4*4YCIg_`mEj6Pb(oYZw$c@c{L@dFC!+)A-jt73GEjnqR0DtZzXfr`A4?g&%j zxT3WOAwp52faL<M&^_ggMQIvv=R%^2?a$jsros4no2!U2>6?@OtN~lrF|cWNo*1_g zaZf5JTn|hytQ87I?;r&80?!7+wI*){4NcmPje&?{HlU#?z&dviJ65xO!c&V6RP8Dm z_GwaA+DqZh-aU3<E_coAZJtVh=Zm62yBA0rE?$@=Fan(665ea%p)!v*9NfU-T<g^8 zb*eE$TFy}@@07AN@>gCFm$slgUj=^67lW1{yFZuxYr51+om$(6N>lv5ngCGuZ;e$j zo$8XropqD0pMeI&8H(zkTR?-NO$BIBc*oa_k-uuOxV8ipN9iyaO#D@_^r@H8r71G% zm1~Zlae?>T*uPT$QDxg@`zR?!S_}rFgAA$FLhB6MZBZNNI_%VcWmDoRg8@(ww04ZC zL+0X&lXlu9^^w1N6yh-$v?w;ps9PtUg`(r`gLtRZ{OJUXYg^EQ?=(Noi$Plu<Dbia zIx+Zv=tOGG|8FP$r^4W<jsH_8fb8jdVVU#SRq0h8Bc~f`)b0f;X`Nmahn66C?6&_k z6R*vV*7PEcS&1kts=Z4RK<39a3FxvxTORaw_FSXl!&__lf{9=%&`Yr|vEt9j(%8`b z?9fGRgni0t>3RH?=UIOb9*O6bV%u^Siooh!WDFFVe0#vgvVTRm{H2Pz$$Q(#8u7F& zhxw=GKZ6AT+IzrM>OhOYdE?IY)2`F?w41~Pe-BT*OZf}62k_&m8TQ!oK3({m7YoKH zn^bl|LQT92qEYjT1ds~9iZ9Yj^XqxQ;74hKd2TEQ_v#Fu^Md_XeCj|A*N9UnUkok( zGNFS-I@r7IsbK^;XK{VGy(>aH+P75mM|=ReYle2m)#N<~#ppnMaO2H-Gc<Rb##(34 zk8(;PzxeHeh$OtxG{b(^(k`z)0ie!_ekI)9J>eJ9dH^Y}!z4f8@9y=Z?7#iZST86$ zy!-y*fM}oJb9+*y3fTPcd3(R!EWfDO)YJ9k_x+>r1YIXgUgxS9UsV24dAOVoHjp5M zsGjWn_)Csdix+c@6<-Sf>d`N({3}28p8ipzUoy}^02X!LHI7V#AdFwjDPp03D$fjz z{sM5W1?EfF-3PKPmH`S>f^wUcII-~V9=44CI+Mp|D*xkjvLfCFOU*@=4H|)!#9oV# z{bd`m3}3m8f23=5INOboUKrbkqa`25*1mHa(wDz>ZG1_g`~y9xAjXyfh%8A3-*kr5 z*aYR!4d|ugjs=OuA4Z{=b$l)BME}<lO^1FKDLS53+GPfv({UmGM@h?Jrv5L)9(jyn z83Z`&1h|*iUE2Tpv~y;KFaP+|9Py?EN3iiFLz2-$Q0=eWm?VFBl6dwO^nW#ljo}U~ zvH5YO?!VtME%w*Sl`YyooA#0UkGGvDMN6lEYJq+7r&A^odjD<7d+FatGNoAQE=7tg zUdykR{ZlRcfPg#bY$2Q1M#r2Hzq)l>9^|UA&f!;^d8_yMti3v#yCFfl%{##Y2*Tg) zXYi*N4p+-BEeBnpwFNp`!JoGg++FSq`dy*hFE>BeM89CJ5>oti;CS;0O+U)fPagdA zx)|&9yzSmPqrABP(#J<V?2Ex**F*Uq2heZbkJD9Oa2?c2q^hK8<wF4N<iTcLW|ry? zote#Av+CZ``u+3V7pG=$G8=^Q4<8_TjMb;^{dK=(^ZG(k|EGIv_<3RV6~4>_xYe>= z;{VM2Do6W~7U(|&w0aIAUSx9@d6njGvr7B#NH=bqY@%Emff7J<Q_Q+TQ<2z|>qQMg z(aq^1|3ey$@QnY?7ezdRn?KpC!ChDEA-I0}eS#DYa3v-;+<E!3zz*^s3(leq94)?a zfe}cAjTTk^&c)jQ4cOEFQu}|wF8iDOZ?NK<F#jL0V0a}RWC?#+h6JCZ{ohK`#CX<0 z6Qn}_AOTPLzeS?44s+RqKmFCs|40+`0HP^(t6P7FL%#+3m#Kk&PCN;vJ$ks`_7m(d zM7uU}o28e&yYz$$X4_N^q+o&vS*iq^Ld5fp8PjyvSE?W*`l16^9&hN!4)<K0D@n@E zk{wFTXzySGbewl~a+*;$HUzsg7F3(}$zewV!Ge}S>x>GmiK}sGX!n9U6wj$iu@f$* zh@8667(EdtO8Df`qGiS~IBMG!i75Sbqy&j5^`En~;c0kuuTDQ;L7bM`96_C@^5{3v z8@V~YF|~calr7dBR41DBsUK3;aT0)zR(GgHBb4i(9PV@#KIJ=EP{5or-0>F8Kg4=v ztzG<$JZk=>(=y~UXo$=giXjNN&?!V<MtBityGrlwE+hDIi6HZv<thq8`DK0Ki|RNT z+KP0oD8*X3ivr|wBcvk!c^soDxjMAFoY6RANb}B=1BOH^E*fT}y7C<E{xK{sxhT{I zq(blxuZ8d5Lj~pOl$Eyni;WjWqtjevCh=%u*nWIVh5Y6(xFIf9s#rgSHuE7M7@AcT zllgS_gwo6W@~w9UuIS_hg0xx0a3OETQ)bx<%m!9#ifIZktqCS-YInCN+^fy58Tt#w zd|$R6qU6Hh%u!M!n3}PjTrL~dyM`L~R$zW~Sk8zj=P*AuLpyHj7jyGWTJuo&D3g3N z)-mMG$|<v<hxWA7!+1kx#+N$c5>ywZ@K5_Cw{%|XqV%Nt+!p<_G_GZ=Ue@G`84ON) z3&QpZKfPGnBHq?-d4LCKUFbH1iGq&${#;Z5qYNNm2;<*LOE|fm*R{JmY-}agZCD~s z&1YdA^kBalvc$)&c?2wxT^7+tz;X~jvIUxSp#`(t`%z)S>?e5MaRdup_djI9)Eul^ za<~c96$e(Zc?B(ken}vHP#_-C8cxl>|8C-Xpio%er=%7Zzu#Ywz=4Y_23~3&Vmx}9 z&^8hmUs<@r$p8IUHZ?MUAk{b}48<OEg}<ANPmCj*)q5{^j(L&1_SpX5^TV_E$S<%b z-Psv9w$aYP#p$$CQ`VUjFgSrPI_%KspU2WG4v5YTM~q-QcRked_mqS=k@ATGhuS5I zoZ9i}rTfD~yJA(mazV#ePCdg~#b0Ma-?_A+;MrE8Axa2xp@W31+wlq@E#V+LAQzp# zg)QTzS3Saug|!Y-w!$FOh+K#YvLW$DW*z*bn3@GiHn{mIuAcFhUGYn6PZWFUu2;F- zU%;r6F9=z$jVt=o3+*5UradCMWo0?}Z*F_e`!ziK4AJXVCv(27SeI4*3<F8abGVJ| zqALnFk>&XWErl>Nj%cr0-~k!rc(-^YU#26tLq*v>iG6M!jgpn)@=nBN`r#nGaQDPg z!VfS#&w6@cD>2$G-ksr_JfbJc7YV6}1FPt9bn5|fBp+BTMnH&MA6O9B84~;Wh%mm? zmN5U3O`5~Qd!CE&@~%9o$k!-QckD3ld|jWJFeW3dsu_tOag6d3IBWgik`xwvt{}~l zb0Jgr%rco=(JI>1_XD%DgTZvtt>X5|W%Jlk`Oelu2Gd~};2+X*Rp5>00UVZ<;Hmit zXKExO8wBYtbYfW-T!1<Pn6$;GvC->o+8ARe6XHOu!2&f5SFvss{IK2p6@x<8#qgH# zeBq<O+;IZpb8x*(>i)@AXiF2s;LrEw<>GPz--#VRWvH32gnVPKdd0dt{xKK!vhs^J zO~n$A|Ca&Xnuf{_IloWw+wC(Fm{oK|{rq!{(>rFirfp^$-=+@l<6S<;bkEJONFE`4 z3}Q{OQOrqSg$H=hMk-sESXK+OTcTcGU9XT#hMqcff2`AzP|%}mrALRS3}6g{e2eBn zW+3a0_(G3yvASF|TIScB&CbK2jGOhA3c=aU1NDXQmMr4BB>_qGJ^4j>p!YRS1vF<& zBWHahB<JK-PC~D!9UnyDLhg|K`1sFaq#;xnU4EP}<My616y!tn`AJKXf|(SVg)nug zpV$X@HJ0N##mLGg-=bK(#?e>R=Bz+nIHK67Fi0>?sISNkgAY^_$R-JB5c8(9B!W6~ z98*q~56=}ZsX5tpGS|7fse9g!7AJ$rC}ryJwo`C(V%(oAR53+t{jXSkh&@&LXHvbG zRz8W0Yhk+8Be5q!hV~VQn3DFcn={ZjQg!okBV0z}g<u7fm2q{v1>^O=CpV|>=|d%@ ztk<X_Li%I>`c5s;H+;r+KYb&5+bLAhyW^5Nh`GhyV4x8CREZ7$+;=^^tRPDF<2YD4 zy9=+#t>dv?5!9GPu)!4hH)py2m;NsL$Cp{_%hX~6P^YOpc79j9n`ta-d6REY=Dzm7 zuVH)Cv3YVb7Mck;i&a5H6{qIHun*7d%do?UoFMYq4NdMVX^K^~M3XPY^@AVfx8UFD zV2DcdjfQ+lnXFs6z&z=|)SkoT<AJ+$smh;D-<1SU%JzFi9w-U5f1B|)bSk0T-SLly zuB_}wf0Re_eW%bPjLBRpR{gFv+VWlGQx9B#Y1sgQ^I}9uo5<_h_b$eHD8H4@T+3G1 zOW8ttCbopGB8Mt7Wmv$BkBqPbS&8|L7qIML46R-CN$2D0RQ1Rq6uuf%%fwq5_F1hL zB#{wz4k~u+A(#8e(Y}}(I1EYGknimZ$d*`er<u*s2(o+GoR|?U^;Gjo-GU%{JL{pM zNM1XF$UlGbRz8u6QA8!TcJkF<`)_Q1b#dNIM~4b9&oIEoT4{tHUm4h+0dLY5_nD_3 zl)q@hsCmT^SwySRqE!n6vsYQd-uB;pjcnD;^Q8Fo-X);-%zhgzzo;?66yh|*HqDa% zAd|-)HHK-I@A4cHab9urJ+9tMbnTbYu-=lgg8S{!;5_*bwzR*_z%Wzz@M$-xvpCT^ z)@899O}|@*Q((<`L%LR<D11P1{8DJ>uP+k|!GZTm7ySYE&H@uXZ%QD;!Sk}%gHf3_ z?&*t67c5cXEGNs>UTKJRb!~9CHe$bLst~_oAJn*5ajS;S^llIio0qqY!C)+{JHcFp z`DtA~1g~x}!b0wLB!;90fB(*=^qvko(A>Y+q5A{=u~s3@d_K5~5xBT;4p%V^Tg=Of z5n%(Dduo$UL$|I;))5<)Hfz7Eg8?%tV%4Kd1?i{v1OB~M0lt0bw@ZHWJh6{DRT^bn znU<w3uOsNszSZSWcpV3BrHro5^-y?a&ISi;vM+PkpfmEb?cr5hBp;P9$T-$xIld=t zk4l$)@@QeR@>yG$HS{_w3#Xx4ddRq~Mn1n9u=)=czK#<A)Nue2xQOU}jBprvH&KJg z!jmQUTR{hY(m{{1X(leatMnfjWmX+nAG6$p6lnzzF&e6`s@s<S;S3R*%hX_)vMs4r zhHr7DmD*IgY%wQxEeg1oCi&AYw&$D}Fq$xPoWC%n-Aw7w)}$uYe_)xjEyJQ`;(lJ9 z7r8p9=Eh|n082g*daVJ0CA}FHmyr%}5lQF9Aaj(G92O6r@VV^o)XbC2#bkg15#5#h z(73nsP1#U2!W#IUS@sC|YaKx?P|TY8WxIk6sV%S;gCX!xMYO{vUj9RCNyJu9V(S}k z@Oo#|)`A=-GPS@u=q7`Qb^cEAbF0g%P`|J69>4O)<S8?nR6xO<2_4gY=<h3(a7twI zElY6yuTS$0@c!)mDVhu~2sSxj=XXyqC;lBPKlZ9j-L+a@L8iwd%!C4j%HatWQIX9B z-7b^dVb0{XY|O)=ZmR1+qBxmF&tGjLdE>B6PY5cLT-$BR-qR)-pLo&mvd&TfRyBO! zeT$zi3M!co2{a61FM;2xF`caguJmr&lqcD(!{r^i!Vu}%8NcCq*oqxQum>7w?LeN{ zfxk9#;68iU@T~avBw5-JHLo=furChQY0tO^2@bs}_^(^&tUjkh&q!R(o{WhK-Z%%c zG%6_!ylgjIE+SmE&)sPxCSrCtFKT)T^`x=@kT#RI;ooH~!|vB1Q!A{<)%tKFr3@3h zWXdfm@%*Q>0xrsB^3}G-bT1Xsu4G!RLuAZC7J50r@JmzAx({VYy}D`$i5|2G9`GF@ zmGSd)7GtLEx1rU6{4l`FM*$4zn-9CV9nhuvQN=zJN#!;GjF&@CL&dyUM;~hq&Y6u_ zw1^66ZjbEbK@hN*RXNB&oRAndQoOC^)Q8V(B7G9%(o;S&!&o=SG-<8<Z6nFLIz;YM z6dgJ#+i7=pG})wm*Nd2~8=)|cPrn_hh_=I9Xnh%}I377l@D`@O6g7*x+2Wq4*zJM7 zcWEg}=s(5F6L<X<w^2fZ_|s_XthSIb8#{t;HH<V5_+Jtr%2khEQ)p1RjpyQd4Bpb< zEfPeNG8*t`1eyXm@C?;sOtFjyj6In`$Kxb@{$)r3x#<>;qPR}ZaA{@=6PNDuXot?4 zAN@-LP(C0V-^PGBA&Yw%oIWU;e%{Hd3^o;IWi=t&${LuyEP(~*VNlY~NxG2E7q3&a zlc&ZcN>rmTi)+YJDM@Um#ix3i57Gt9F_pWjZYMv+<<CR<;))3yDlO7{X=S2cDM-fS zb7+Iux{zaOi&N8<^qP+=BN56zCcYqQ;4jTJ?7VEt6>6!b!@N~qng*!canHwQ2t#5> zC%>cXpT>?Tjx8U4IOBIkb<og6Q3R``z^dZtj^8XW2Jav+@Dbqk>-={2^3e4<#uhmx zX}<H4;NGQl_n=UVldZGkWlqhW)z#Hm6}}{*<MWkL?n2mS(=rHVasC0ARwu-l7>SRO zRi{;-$(=$OI~6Ogub4uP^r$t@d_FM*XY>%wb1{c4BIyW)v}qidE?P0|;g`-q&yT(> zhMOOG-;Pr~>f=SvSYlK1Cmv-8D;%p%1nd=BDW_ngwxm5Rl~BM3iP1#)e|9r{B;5TN z3`9%4`++rpNbQ8JVqE0a27+R|%(Y~qTsELuZrT(#$5qA#A}W2y5&K>5*@i&DMCOJQ zq}W7o@iq4_XZ^+Nd^;;W{QQpX{kmuU-Nfbt7!&^~Cw6L~?)}xhGUsEwo{VYfvrg9y zH5mYK_aZp88EHf)X~i_@Wrte9(@7}<1J6rxnZ3fRnQNZy=`?MgJ!K$T?P;VlHaZXK zc<Vi^*vnm^7RWY)dSuneRoksiAv6)Y&kn$Tgvf;ZSuC+<LN~Xs&Yz;0AENCEkX6Fi z2uO4AO$}bgdQ$i<QFJB}nzum8=0o^%E-agvuvjAu>9g#9UZ`{_>YSE(|7RjzHYB+$ zA>8y-Gu2pP2Xb~?mhrsV2}@!L2`qOxydT!nRqbE0x(lNm@L`y5di<yk@UX45?fT1- zSZ9n4Phryp&siix`kHJfub$LzYhz}%$tuK2D)S`-tj$#(nhEaI`Q`JAkjVARX+zt4 zk0D?(u77VH9^NQUy?TeIEEVS5y`a&DmzMHoQ~~Vjr`;u8{V6pAW2R$mA#m#1e!s$0 zu-eb0n=9}W5$UM8dkcbp(Ut9wuL^0?ki{Lv0#IN&M<UbkG<cQ|^tXipK69VHIkncS zOLF+PYsu!f;9-);T3;@jL`9p1R<#abu<8Mi?}a$L!A_ItpB2)I#UMGWoGfxgiMN#L zEwds~65Opw7U@@)33rX<x^t9HB{0xro(T{CR2ZL<A|WdqgHjis=3|m<7oFx&;@&nS zYg5JEAfI1N_w`GwxG9YR$Mgfn7>4auTHGC&C|uuj>;YJ)07u&ayDAkpc;<R!Lv#<j zT*DEpe5RpNw8~6Pis#|rr_3LwPA9h56hMtZvo1tJx6HXcNSR-GaQBp;WKp!d()D$F z5T?cWW`S>V7CZPe@!*hfk`h=&wA#2v-hKrEB$mj$BLsmf)OgY~;QbLPn87#t(+SB{ zcKU)5j0c&fYS?YUWl#Kq5jDD>SM(=QXzAdrT?qgv*t@y=SeBGtzX?@Gvts5-n&?*G z#5cBu@4Nf9>}3*m{H&MeV!7#L>Llj`;H355b79kPl2F*?L+cJ%5OVCl&^e!b==#6Y zJFu)nRp$Y>W#wO+nAaap=V9K=B#P`+&>}E7QNf!!aHV@4^G9PR)LJ4R;*&*Os75kl ze3}H5v0UHwJI0~HuEr9iLc{^xUv&8R9;Zn^=Q*K^<7xG>qz(Z+3{0IKG_CS<hXT5h zfCf{g&|nU6aHrU!9~mcH-OwtV8N6s%Ki9S81BSdO)_*Q?4T^4w@r%Pj)X^~%%R~a2 za0)gILppjep<$SzRS_O2NQ@{ozNr#p#C7fcp!hKAc8iQkJ|5ZwF2fmgJQ1TtF&l!5 z8dF3s>+hR12$|ebZMTWjz>=RZHx5Q=rZT%;<UkE(V?OGaCn%bz!FeN!+ENPziZ8YP zj$n*e@7*Ag%o}4S>o9hHB*WlrLPC}ODiJ}|-=8|6!ulKwx>?J5&8?~I3_(=aSbrYz z6U7b!m}*Nb%FGxh{=F10B3SB>KX4JvFi41MWh{9uEDo!}i~n0EbTNw=y+@Jm!A<ed z@kpbmc7g(lbhnBa#X<7LJBn<-x0sBWNc4e9_pA4PyjI|2j3le~TJ5QhCS{DHSYAy@ z>lliSM%y@SGQwp_9vwI`;8(ko_kBrQ;i5QhuLPcalU#H|0Q#04xV`R5M*#Lujor7= z7{Wz$Y<Nz=EHzh%WbH?NE0-%*6HaZL31$L)`14e-B>BwuuUO5?hZlDiLnGU1BFP<I zmr`ZZAtzG50Kex15Pyspy`G%F>-Q2yw0wRvLKQ*S_soB=&T1k#>GR1?&255?>&Qeq zTx-b36ZK(84IYXyvQGMs^RWx%ry*hLhwDq&5#<eb<kXlNj|QBgMd04)RFk5S#UE-P zi!9g2N{qscq^sufU^<M2I1vp|)>+3am1Ca@TExCa)kKAliqd&vqt0<CoiQO1$H~~} zUg$xpW3{79q*k)*CiK;4i+p2xvM6pLN47G|L~(fW#ol4}?n9}$IT8>LKSFLJX;g-y z7emTNSaA@?n|aMY=7us=ftSX!?V>sjIVkugKVAN4f0eWbQ1^NC%{PB62pt^`!iX6e z%P$#hhgPgW1&0y(Cf8u_8s)TXUc*5#`Lk90c`JQTqG8#`$Ujv)`Djp7wc{GuQt1YI zEh3+3k!UG#X>o*~FXap@jq*WDO&r|5$Pc9B{-SaaFA~<-TLWqaDN@DHS6h3*$KmdK z<>ukQ!s}b^(#7=MW00wvZkXT<jO&j=E)?_RpOq(I74mFw0xjRrS3g-2QEqtc#t&g} z28W98w2j%594x<z6jcRXY@iuZF?9{ENyNqrs+A(AcQHK~l9a?>=_x~P-VOqOKv@jV zwd1u(;7wisAj0NP0oh+PiRK!uFt#HxWRs;XbMF--w9(cyCUIIuG>wD@r>@sQH#8fM z%j(PEqx+;DB3?D;zRl#_^gtj=HO`%1hH+FY(^G`wYr&_;PJ(E1P}YcKFkj@Vp+9VD zZQvCky6pv~hu+c?G0AGK1)fGHsQW{SAMS^#a<E8>h8Y`43WxYahal7|b);?B!+0rN zW&TGcf!AH^0uMN+^xPVj>bD^Vj^c^9anks(Jfu@rC_=FX5~nR=RWK$Da1l_FVyn(@ z<gR|>>xq<QptW*dkd;mqNIm-D<2z~ib>(a-RRLjKQZL3dZNp9OCz<Ld3{3QwiP1O{ zO3h4j7b<u8e3e(`%2#0g1uZ}q9fy>yZ~6Dque56S<|YW7rNUdXt48mj^t2Et01~!T zR$KV6eWLEIP#K{bR3Z*(FxZ$j=@(KFN<79!00AyUak)5YW4~3t@x2u0D|d46GB#4e zM6%iH$UEBIMOc6ba@z93QM}!id5J~;u+Y0<r9eN?F7GW~x)*I!q%e5RbfrVa&t0Wx z2c1O)T2$Cgq_yE&YX)ei`hE8mc{GV#{`?tIV=>w(r_12xBFUYJq=SLsUVJu|ihOHg zVkDrR;iuvJ`9Z^<XAWVTv~;LdY*cyZ$OfKi_p3ozI_PTHx^TiLX3p5XTimHaU*>u^ zXJP>PtoFX85ObmYfTwPwz97Ts_mTs$4<Wv2(j)LtoF_%_diDS;M7fyY?b}BWql_U_ zHqUVcD7q>LGQ$`&>IE?f(!k_42?#${z6m_b{p01kQRdRMVKs}p<&bS(Ve9(lQ}&_n ztUCF+@SpIq$R@O7w(^`kOUtD7B8{?|nI$y~+53Mye!l`!uw-j-NE1n0-9wNa)j*V3 zCxM$NCgC<B?VWdiWATtkI&=cv$D^rY(pm^p*wXqed>YO_G$~@1+R@*d-XWG~8P7a1 z=_1Y^qM1s(DISR|=0rb+v9w3JJLNS0;v_?|QUIYX{*Bgq{8B}%N7ixZP)3YgA;-&w zJ+SgO%VApVMxr!W#k^SXvWQVnxGo#cEt=rY&AE9;pZi`3sySPl1JgIysn~DDJr-hk z%D#_=@crugR64`op<Zs1IFPWZb#@@*-9Ghsvmnt14&PApq)@HY^(WZYM1#P$4G?%? zJyf9}k3u9v!NybQ6LKDa#k(j!e~Ms1dRos$|At1=2bVTEB_a!ONWN9*$p?5FA|`vd z88zPy8w)qA@v{&sGGg|R{#Y_6Wts0<KN!};o6I5Iz{)B9LAJx1X~*Od?_%*tBSgxw z@3^y26wursB$nh~{<>x4{<?|z)MIQJ9<g?EV}`{gm;T<qk=ykZ6}p0{Qu`gDjaAf4 z`K)>>%bAz%mF;)T7YNxy@=$W9Q)5e5oWLp+b;>UWmoD?wLu62!I?UqHy;Pt$V5wq; zmmB7`p1(TT;Ar(iV3nC`8iOriC@|bftl%`&b`8}HqhuxTSk@=m)>0?I0Z(iNyJE^% z%APRz;m8^i-zhF2UT=)!Cae?l^|_sY#!YcB>dBg}yIeS6sZiByH=9mihb;PGl^$n3 zaXUS*WW#gNMHaT1r9Sr^(mm%oFA9A>+tdT*;da2ezwncVlaltlQ;}icLF@iP>1W3r z^9gAM+?B+RZsB42^oVyJ|B;K2Qm3I`Qo$M00<HwZc>N6Q^#%d}x$NAxm5%4uSk~!I zuZWPD6kawlRgZIV{XM7jbm7p*{xRExNz3}>fpGWX$>+y%lgr2Z(#gX(*TIjq_^v6} zALP$6T~Ykoo?-Wqh*Ni{XF}q!NqW~Wqr;I!LxsM%XZ3tJn&lT7rzB7dzPscn!2%W6 zN@}sWojMp)37diJc`46DNJ1Q@9xgb6!Snh$7I2>^e_(mq#*NY$+aHt8RqSMCG(f%D zfW%}Ty4lm{Cwr9yTp7@Cp{+h&s>C_@t3!^O@x#B)Sn-3DFOBY*ydAM$d4!)gG)s-$ zo!*%RjJj)-c$(yxP{^zF(|XTumQ&<_0c(S}0&d#8k~SG>_a-H%`{rMK%XV2_&ThV= zf}!ZPf0SHSdUJZ$989QJNAa5|v4AKs^U6{TIl_8nlAj0Hsv09Z5(j)#ATilumZp0X zN+`}XuqzIOl2vAKLu&1q7XHiEz~F8}nT&dT8t2=yqr2;RZ|~vhPGKH#6}E|}iU<kk z&rG5%I0z*pkP9SK?l~a3V?@h{?RBke1LG>&BwS1dW<lY-Qgpk=Y#+=_*gQ+jv3@y+ z%K|$Gqs-V2UJK}*K1@^HZ<W|%A{K^F;|LVt&o@4Ta8&Yk5-$u#PX44%bjIB)Uq<zh z!x!z3STlqRTySjA2Hn^Yaj|FlY1$2VZ@A}p4K>5sg=s6T`nwIW>C^cK@g!<SgPTFP z96f>oAR|i>dX>K;%0@IYdVWVt?O4E4i5(clZiAB$UNw&?9AV+Y(rVG|jsWD$LM&cz zN$M1b@aTAq`~vXZ-(ke)GImX}7D&Bl+cA{FZqx5*yw<~JYWPZ&6A?#(1&sZ{AgcA| z5=HysV-v?Kl}f)|wGQC%TjgnkB#SnK&_FLS%$a<mO`>svn>RZaQw@W+?r!?DI4aZ? zN;Rz&s#5LAdtY$G9FyR!G38lgMTJSBAs|*ha4h<bK19>QCJ!_|;Sx&SP(DT&EM;jc z$)5{0A+`kK_2G%T^VoT9a>|Ubg-w-!J0l?Ivz0X<Q9QO$j28cUMB7u$BL9sxM)0Ch zY!rZbTE8^LIuh3|QecRs@27A?=WwKE`2bgaGeBz(pO8^VB@%gTXem`Sl5I$RQHoe3 z)JgO^c38{h)vgIu@b5Mm9FSk*qIAQRSWC&V%)^!L=;txq)-xFS@SYtxa2+!5#-)ns zE!H!GW9=nsA&i*r8UU@JSNM?w0Fuyvf!QdA#%DXMPbfm@7S=>7=*GQ2Of6joc2f+V zVI0;~pKM7~Ro`fY5g|3*i!Q`LadLa^VfSC8^mA^ps<n=1st3Cx@xt2kkVy3inBISh z6g8bk$DkswT9}?z1&8sc8BRO@La`=IN!v)VAJ2`y8?_Op&;km}AS>Ae^iF9mPjn^q z+^Ws=CjOJnCnADbxi^Ghyo!>ymwBj{u({Q~E5Ha=%J4315mBa*>S%v6&K)o53UvUR ze~!?U4kOf-<id9h05X#gnG>107)HI>BpfVrbZIiC*wJqK%&^yIymD{5cnQMn2OQ+u zn6Gc+1Wy70b~)oka`}<;Zy{jXSjc5%A<94Njw&tVx!Vlm=?9~i^QuZKwTuN67Znuf zSx6$kcBw{w+ngn)b!h$u<2hrfe+gF=U>q6Hw0RqfTZb@xo;$177)B2reGauXHx8Q( z#>yB1IPTAr6!fMW#7gVP{e1Q<GMJeDZr0Es-?YJK2ctkXNr^2$gNAx&aU!2>sA<ph z1md6z=N)Rr&`$ulS~H4nZLIej3Ns7k*GdXOiPxDBezFj-Cv0goL$jmM=p9wJ0sp$4 z37uAxVxZz_LpqC}DqJYM=^pa;fSoY|tA2V?LbdR`rqh`CRzjn0xubAgC=z(UE**kn zp3L4AQsk9Cv56`w-2RRar(XDuFZ1gesraI+59X_PKW*rMJFir*WppG<%xIQn+*e&m zdC~<E!VH9c`T9qr?xtxdy#vR%b7D|7M*}qGv$^IfFM)mT4yP;ZQ~vh7swz%@Z2K|+ z*>1uY^)1>RrTH{J4SQX2Cq_Qyk9IDz7|!eXLE$>VjaPf>Pjt{49t&+0FGD$%GaCKI zC%l<4fOdrv?Zt0e{+k7w#+S{p8J6+#cr>7ymNz=nT$rNnnsQM4Xs@LED0)7v&+(48 zf(L;{h@%?W8`P=lV5}-~Es&4&qvWc3V;af~yQiTphKe!4=*q4KlVj^oXSLO^ms)*& zy0n0X@({JWnfff-wfyc@ECzHVMf5CY-#(~jdP`6b_0YSy0t^bgF2<h=D?W<lPR<xs zKk2*e6f0(tqA`iT?_$Y8TPYH!Vn13c$@d5<#niSpPJJ(e)Rkz%-3LsbCxNRisJEA_ zgS}$x9|@cK5Qw)78kgRhw=3HQU_W9aA^`W1tkqAoQ_N8!5!yPtG4wVYuax*1x<dM3 z_1+%dg?M1G$irc@5Wvv6>v>PKimRuEW2aPL)HvtolpcZIN^=*1at%JsDuJ`q(Ikyw zxf5#^@I!?dJdS-KzzW@9q<nJKy^hbG3zMCTOZ)}77FXq6TZmL>^!YK3ZbP`I>3U?? zjS%g|w%b_OoNX({{ZRLL7|WronR7NufAA|ky@$#tr=B9l^1va->Rp^Qu-9M9m;8y0 zM>WOqO<Qsl^hn9!%k!19AQf7X4e|cvwj0NHPgxDYt#`EKJ+I!!i~3tN(Wa~ldzQS~ z)!eo6y&{>TOq+!*0AD)+-cI!R4Iwf15NF(t+d&c(@%)<lV7m@YciH=$P<A@xH+PO? zw4GQ`L1&GRTU~kJ?x$txO0!ie{*Y<Zs^b`D|H8gbr9Mw%3`5nh@C&Z*EmToFHhslZ z$SoP9dqZgrL4>+nT)H;&-J+nL#wyb%%J)|W_ak$A-acFx3D8u@z8sxN1a!Q5shT%I z;_zz&R$>^5C(P<$0obT(!E1qsMg*A~8cJ}6l8ETFiC<tQ@>#HvCy1hl-K{VMh*<iH z+u+cLD3^x_XxL0KUgpA(;NHsk){)ae1%_Zr+#??BF$|5re0M%ZHWRz+IcH`uu;M8m zPS_1_%bpO6T6QLFlq2coF?rHQWoDkw_Z&FVD(Y-VW80#z!p<HvtJyR@qh&pM_2%~R z&;adlc<Zcub~qRPqCFvb@TA*`*}AD@UeH3UtlY0b;ddAaiK60q<ILyG_#AGPEB$yc z1#z&t0<Jx40IsR;YOl=GoaIr|A;4Dzjw)4Ocg3!KKz2Do0-G37`@L4em`7S5KmJA= ztWBwF5(jyL+?1rjQ`S7y)-^Z{`|_l9g|rcx*3VqbJhr2ua7cF4rd7B@KgKwExo3k? zc{qPo4z5F`f*hFtAB}B^$yXmuKm|noAg44QPt@O2Y=1q2-5G!CZ~zCH(!xoHVcNAu zWOyEf(P+F++z*tg%)vfGK8e@+muXB*{F~)$SX@G!+W;PE6daz84m^2`)Ng>>Q=OrE z)S^PQOCDU&59Iv4Bu6@bEa^S6vbC~&+4K_4B!9tNbm5}rz#b4^z5)Ei<U{POdo8`r zJ=)w-XWdc2*A}021#f9d+mS)6m8W2o37k8Nsq3zfw|3@tzo)MEwYHDvuCF&;^MV@r zK^i(S$cw!YYHTO@9h@<W-Y?IG$YX9`PKUgsn3uV{aaXRz(LHZp2d^GV9mYef6F7&) znT7p;Prct}EtT56zen3mepx*<Hb{sjU;v=vj_(61p<=x2cP+QDKi-}_34~6}O4=%1 z2n4HS<z=Eo#s~shtEL)>)ARM2_xtf6tZY*FbR<zmDRJWKWSE<{QJ1Ai`x^jL^+P|Z z)vKngZpZX)D?)=eSxFiCPnV{0&Ggc!7lw@PLtg;SOW1QS5&>+~MEMwyJZEXQ0bl^1 zNj&KYuuae9NBqq%Fo0Y^Wss~Td*^lPZV*=U?F8tOgkbn1=b`bQZWswYp206;?w%9w z6|AQ{ByB+{itk=1`^DCs60>ER4X*+B-n-wiEmuEOIm?l;#+h&+@GnutCYRus9fm`i z;N9tjF4j*LDUzmR>yH#_UP`l%@cX2+XZjy2d>ciyv3TjrddNb!L#tkggF?fRP1HOu z2l&SXaq&j1x`)@WR=5cbxnQOlv*$v`TFoM;duF3Ed$yz@8K!kJQ=oFbT)au97*7do zx?fvSwgq>)JBdSf)=_V|l?;7|>%o<A<$yH?CjRnJ3Xqd_M(XoHi5eH&%ji<v(V}dF z972<fKp~w^8M_QdVUCrQ|BeEyiCVW<u?UQXO}!W`9?g3H9-8ubLC3&TH9SQl@;xtU z>j`XMz%5!;-(}yhAfVpaoxc8#*P7JyAZ6m}K4dauMSC#j{>8WYrs9iSEw?&WR7=b2 zWIK<}$9WCF`x{;BVdS<V?r(w2ZWT)n&LOZe54&_5Q|?Y7hCwAE!3SBUf*BsYKn^Q3 z1^Xw7uleX1%_Cy8-n?k7IIm0*8Ja8IU4}7(TTi~BFWLps>KO)@dXhcP2zIo!vH+M9 zQZ4PV-z@azmHUaZP~#dM^nK!a;hT1qCB0Nr_gCB;3p>L{Eqq<Nf^*<W3sdM`jjh$b z?<d6|=n{DK4^@&C_8~fDxji<rlSDY!Uo2u84}pOZ<}IUDyjJ0@R9y!noR)jTn?4~i zXAA0lgzC(q0k8O!2D@u^PhN(}5$$WK7zYKdg;p%>1O&&32cBo+)5$9YB26S&gUWe; zP61u8GZZt%t>>p?D#!QNsS~pwx&X&!9)$69=6IMBu1BJH8t~zod9dR{m~5MxXDONT z(z}L757!>dPt`jYyS?YQDqqDhb3hpZ{N#RzneKz`5&sVW?m!X0PCQO-MpYlZU|rin zi>xE)qeA1oU6J$83oRwb*Dwk#LAJdu^4pvsMQdT@BZ&r$d1R|L(7+d|HnrZ2pJ(P` z)m-NVwKqq>S15UdCmO4PbS5LdqXnkaZq8}6&Y+iKp#{k1Ty$^ryYnHnh1U5*B`dTz zl5Khmjmc~IfJBgL_{FKr$mSRjfiu}yXO_htHS%P0jjrRERCA4iUC~*iV-SG%dQ#mp zHJmvqKH=$`tLE>KRa#h@OZ|>c7~CYfi43v{d#{U4Ey1ffKC;VY)AS*KXST5F?=F32 z;Afm7hyVO;-hk(EaqnnK$$^459BY-&fgWk8^T^yE8gGdtS|rPqV4{J6S(Z-DWBtx* zfw6xGp&7Y_X-4<?@&28)3t?r<-~U)-owxattn;Lhvk<@UGk>2U4djX5JVSoHpCR+> zgsCv9aT*q{`7`Y{%h}A&r0Ib#dMnHz`ubvy$L!%1!?e$<SFVPQ|GyWADaxR!PS8XA z+(x<>i?vuLftttbv&~tB##C4Xo3v&6P42TrKl)R{I=+|@vUrKaN4>11`-bEvktNg) zp=8a_#=?>xC=G3dm*bk!MmLveF??GJ>_IPSx_)MeV))GFbaf^C`ucYMjK9W>#r*kc z0KOQ#g;A$WlCOc}EEToLSLldZ$2_9}qFSg<%c3WV^mB#IrI1JlzjvBc{S&{__cJo3 zsAVv^kPMFo_>MT<IG!0RN3e%jp8fl0p7-NAbF8CadZt;#vLs1NPwO_iEID|h1wMhu zS)s8&C`<^sTYeefPn?gBnHTO8>(d3&86K~QZuN9!e$NbkWpA?G$o%~`*dJ<PA9*+g z|Fa-2BN6T!fa(1i0;dQGr3Bh(edp%18inv~<(T+HW6C%Nz1(+>FAx;IZ9ZB`W{tc% zSIsdZ@DK}PPf74rK06D@YI?5UzpyLl#MikOcI^z7^h)0Pjuv2+80;FD`?+mVxb;w0 zQ3*-1>qO&$f;}ncv44N@#fLb*JRX=jpA}<3lNygV561Xe5V|Ldq$?}^F^on{Bd{pb zc}B4=QrXSDgXeBkXom3PUUw{{Xm7;8Yk$6aQybChM2bIVcE^|QCjOW!1msZsw15B1 zPl06sS=>SKQ{bzco)ka9#$;qdv>1aKL3~xaHqgorIZL!(2G}AvpX0Z!;oJxg;g*=E zR}<XmL=hYYqKiFU30_>K&qWb@{r-jECGzcbxDcEQ1!IsU<q8!2H+lC?@XE)^zACiJ z?32A&`@XrB_<&@h{TRQm?_rHGeS_?V8P%Z1Y?=c9RWIymYz3HhYEsOpNH4n~#9@<U z@4Avo5$Zpas~JLkDf<#l{C+b6dS)ssZ3LY6;pI<Wr!!>i_4U$(BLq0?<kbiZ>8@e5 zgg$W=2qaK0@}5B;{am3-!=tAa%sPL5h@Y9RuKW9)L;iF47F?O1%_}GXSl6(-_py|v z3JU1;I(k$#!?K1oxT`M6ODdcXbNpKu{L;s609J44k^uYn&lF&7=ggSNO@ej*G_=MH zttrVh`DK7jLXay{{6q*)A<@sS2=TR(-NJb2qbRX{|3V2IypUK~P+~!uC_ZdX|1o}F z>aAn+w6z6B*1O2g-r3oYn9q<^b5QtMs@rM~J$cGRiB?L)1`fualHkLW*jQj)k#hac zBx~8$$|}!z=qs=9_P!dDI~<G2S2u2nN8bvRfS%Mma5{{%B5!Eh&q{~nxe0!Z-`Dpn zDFgNs-7q$?G1tf@7lVb?Ss=jcu$E}nVeKH5djBL3m=KoXjCvbbov6dwjU1BwXkj1L z{;6Qfb=|*zURS1urL$PCYw(38P%ze&7rOp(P6X&>Bhk8nMpqr*xQlgFzc2SK6EFtB z?%UIuu$;V6lxV5rtZ>oTB@(=rU7}gb&MUK%d2c!zugHD4EW6Q(*3n|BynMYaJHxw} zl0+{1`u)qYLnGj`y34Xt?y$JLv3`Z+?7fm^43kaC=9cFC$fYcoUH-mxF@Igx#w-tc z%isuor);#5wlFI+=whs|sn}sTtXcWvV26pu*ZST!3ytf;CrM)POBa*PiQjKJ8mI{6 zvVT+3GT%02w?2Q~Ch|tFI7a`h-=}-C@@<M&-=oXiLC*F2kMa9-^Tjl3J<IPah|5A} zvi-^|w<)W3dT5N}RKG)_G)fQ+zz+-zQ9XD+0<GNzqx1P{))>s~RI1k)iFJW*7>vMg zC&rHjSS}g|OX-~WV*!{;k24QAG@Grv<XAEj3(gN`-p=9YdDg03jsG$LA41wjh0Rh} zWo3PR(cxHvsDy(Nwi5Syo$ZENXPpN{5SHR<WBtAmq>OAQ;Uowp;v@>jN%xQ@iUfQn z3d=c^<USImFagK8`!-R2ue03{%b5BLQAS;#_MIq1XWCLhlm$*;Bd7Pb1}uz`AN3&P zKTnCXgx8vxFR=Px7Cu+t^2H>}E(HJ;I`F~v$F!zZe|`ir)IV$E<)B;8=LlI6q~;;x zRwpe%{!Fy)V&YZ0MC*|mk%B;5y^Zn!k)lxGF(_pm4zj-=1HM~i-bqe+0u}}a!V(Co zD<09l=&ojq!&Qw#S#^aY*_Ctf3&4b){n8cIFy#Y7k|U>7`i&g9@|xWqBkNBya6%#m zSaL)0F%Sbw68faq8;l>A{@)rZYlYBvsSzWC)=M#ajIECfOA0ZK_g@lm_n3ID`=k*w z{$y~1)nm<klj+ntG5?Ss2fb{O5ft==TP>2LE+*X~!*`g(K()y1c~Hl!$q{K}ev*ic zmBq?OYbbH#1943wG8Htd6dOB8!B>mSJrU0qe=NZ43T9t(Y6tDfMTnsg^~#Y|Aj<U0 z{TT4oA}{x0B<L|NG5OY2(}1lXo)VO&Xf!40zt7K0j6BEI=UaC2bwN|VH)geKyZI$k zOJIh8quWuldCAno+P_JmF`6}}F3|Fl1-xLaXLkz#EWY}b4Pwxa^#iPdu(*3=3N3{Q zw(Wsg-wj0k`)ePGp<qM4juX*h#y-JOX}8$NO`&eFv4V(ix<zboru#TsOu6=r2%`?> znr^Z4?Q_@585oP^F6$gzXB501L*SAm7pz&aI1+T53u4H_U1lOe#jLex)(X%356NPZ z@&4+0@Cw8lp;Q%b_Sm2~=Ug-*keHCrMC{COpY+NxZ%XJzvnB0HoQEb`M$hEnO%Emd z$O0;I4*8I9eAcAdGBOSrt?CvdbKZM%a*@f#hbAvu++s(xC;?Y_6mhJV@Kqi)m`Ztn zzT^=PquBQEuf8jz>?l}f^Ei*AD@$DYQu%CEHrFb{Or83jL7;)&3E2;mk}?g=F^}9p z$t_o0?hN%(h}_8`bcOh1z;}x!`=LNhz``hPR4CJ3_2h@XXpE7M%)$ZRvad7-O$x-i zl|b6mEowxjtFGRgJu*vL4OLGLqA@d%gK9A|(9t!s#mfBWHEBc!Cor<yLTsMN+Vzq{ zpfUDFuUud?jC@(SCFyvOl&TRKKFL@fgPa&YMQhMQVU1hJ7TscEeY{l7p|E&B^O~H@ z0>z~>5g~M0BUKNjxn3E(pjrg)jiNACiwuLy`9hTr;m*r{gDQNqURfJh4uzTM!;M#B zU`k1wSMaYHCUw?`EdI>Q(H3HQ1>vfpEJ-I@lz^)Uq(KA;d6X1m!r8)VW@*0k*ag7n z=d+I-7z6H)X7KB)))v9FjO51)?e%+M$QVZ^e@~35tEwB8(P?j^ee0(2)l1Z9lwnvU zfwt6N30}?RLdH<PlZ#T<-E?MIh<lcAk+`EgXL)WdfrsN4Qqxz3_{)MrHwaC7^hdEj zSX$H#=7-Yn!*6P5#koC-KQ_A2&%0B9R5k}6&@s5%_}^Ro#ZF;Ji<%}Y@{D81pijtX zH+zl9^e@97Wza{#E&A{U=n#G%=o9JMaOp-Ls~<%lnwj3GJAGnry~M1inW)uPXVM2d z5zOu`h&_!^MhlTvKqyC#KNet{2TUDPt&KM7Sq&vqB9`t$JBRW@{4wDB>|{QS7B2wk zN%7$6wHh1Hu<gf9$K{%crz;dECdiy0&RCvNBhr<6TZ>kpV}DqS&a0=}TJ%`hhsmo7 zZt-eovDe-{@@g-Qd7N&%YW1UdwU^FZ-&bDc%h{)~A&7qfJ`+DM>@Hu4&&!{hF2oNE z{-`$b!?<m`5Fcj-(<qq4*KmXQe4fpcm7j>u<obmXbei~PKa%)p0?k^)=X=(ABmM?_ zAwG-qhCA`;Ve&WP$IPPUHu14zM#ejZ$hRQfmO|7JV!cQq4OlI<#CLC&6ymGyH2jJZ zk!kZ-<H(Rg3cg#Uf44ggs66sR(Q6?Aj4|V5i+A<ufA;m?*4Hq8A#`W9o98Eeyfa&$ zpao3U?0$Zo92Dp>zvgSs+W!MN;I}2fu+rg;dVRcG*#KT4@sTp){{O?fes{88WdV{g z{^y6|UPq6mCn|w!ER%_sr-YRQeAyp%zN<XE&d^_n_VxsCyi%CN@*S^?9rm~SL=pIp zW3Mz`*L$tF1!#_mZ#*rQZ!9Zw(G&yqz-X(Aum)jW9|K#Qs{q@yfm#~%iOk!DQ6yo@ zA{H$^S`_eY^DuxoHZ=wfSdJu^%{58&{P3Z}_Vh_x53Gk?hBNHG(P7E@JTAKxVtX0? z24bQ;9<_n7Z6evC1YC`!oLdd<o4<%Pr<nF<e!i?5ZVYPA^Y>}pWF`iQNAoQBzAV4W zCm%7Y<{G`;uB+x+&yBffjOJ)8#6S<Dz=L*AhlCu*_PFqLYxMC*#PP7Q6|=`csZ_d} z0h4^-r%Q`0XPvU$VoJ<reQA+5;GQx{wg?NS^|v*AZ?V_TgdqwMhCUQYo{M)x+Qlv% z@Qql*sO4^ulZSL4TUsJgDvwKDqsPdo#8fq6a*gl!O~l09pgn3thN&?%s)bm5e@5m= z#FG4Yg<>IMb3>iFP?c52#?`-pNU_#W&e+n)GyF)k2q6@Cxn+@iJofEDZ==XcWy7l^ zTMPv{ax|&J_qQVvr$UU0kBiI&+_FX@O2AbJL5blieiK5kqA~OH<&xp6Y#QV9_rG33 zhz?g?-;3`XtJX32LwpYb%n)hyJ%d7O?CSfT=m*H^`*EE%Y-WML90%Nz8iTboTR4WK z?jRS5JWH6QS1i=!ix+u|+vII-1P6VL^62{WBg&)y$yEB8M1Db^BkUk@eM->P2^Fe3 z(aN)oxk97G<w%J;T7v;yk5(sI>rA*?1X`PDd^`yj*=VodJu_Pm(@nI;Qn*a8dN#-x zvI`N`MjN|bBC-a1Pu-dT^KU=HTjWq+>UZXFQY|*#=O=Hq2>U9v)`~(5qd}J}qR@dJ zO4L0DK8fks?vW9*EKDrtz$6XyjOiAkUZ)m<*&-_>G9k5UkuzuVJ=G$(pe1LIv9>sB z4lBgQ0FN#?Y*U57QmnnC5m`#ySF=Yxg^E3^IlyeqteSBF@CNk4mb7&t7BwAlAh5iU zNk?j}zTLW7(m=K-0ZR_Q2@0m{3Z|g=_xX9|)&AHs&(F6gz+uI+cs9ez@40MIP;&Ge zJb#D$fLh^HbFiZ;3pg0fbv~o!4V6G+^&TIcg~nGqe%w|FJcftT+hHOG9{o;_lkrex zXm%DNR?5euChqyL-nUDO%+Hpi-6FF-v7V?#Y}GN}wS|Z^sHI+d#Aj{Tw+3Pbhj`cZ z92$>Co?NoUmYA|7nJsb~jbI{)*hA)jEktUsEP$&J1GYqp_Bw>X2*87?3z7K+(>NXO zh~t_uWi@$v3DUTllr82_fzjLwkZP%W7c?T%oHAhELTrU;$f_C&Cy-daL$=6*-+4Gi z?=41BrDQ$1Lt=;)CEzMbSh7C&`YCQ6pR@krxaE0$zRrKw+|b_V@ALeR30i|Yn$N6j zyEivq>Sv9|xR1;f%x{QkX*ZrlEm#Ur4g^+gA4PFAAg9JRa~jY~9pNr=4A9r>I5>>K zCl>p?Oqv1EF@2adlkzg9mO_M`&EP0=){KA}o>Pg~ShJ`mt4F4mhhosx<gud}SKU;L zBx7W@K4U0+OrOVAk}X2I@Ty9;2<5~LHZ;b_0`)9JqYzn8BDY{7LU9YsWTz0JP=H+3 zoC6wxQmfYiyOtSvywxKU;pGtkD-faDVDmbYWky6M^YSZ1D8jJWOmat9t3E_c9ELfK zXJl57Yx7G)3Ajmxz__~XzDb4YZJM7i8)O)IPW?WsZOGqw$63$s|9br%{U~83zi+8@ z&Ru?wLlwtdQ{S^t5VJ`t1O^pV>Jkbgg30MERTz;)*yGX1j|Eub!ZE9J(HNt85sm_l zk$cCGH{hQqz1P~U^#NZog?|~tyL~a&Hte+xOihu^%C95Ayw{&^D-+PnEGE#1CUpG{ z+m^50*YE$lelIOCUEA*5<?ssn1sEq=80#aN17mciu$0YJC@f4-ZZt=g2E$WmP;4D5 z0==V!iRM{TBbKIy!8Zg9Vb=gYZKkhC0TS2&LR$?1Yulg#m_z5Yp2~N+s>RYFcGIOR zR%v9SR1IKa&7SlaYJp<&wi@)KmW2pol4(#iVxzTl5J(Ij2f%p3q7WHA>sVgIpgg2C z(*o-`gi+Sb>p6tTy5G5)LxI)Ua?*2v5y13{_8f2!vtEcs#J0j2T}(ts7)Zm*<oUn` ztEUiu4ESmhn=@1OUVw)JL~7EXYUc6t?szBW*5@10=s?aJ@W&i9jyeY7Cu_y{e4ByD zYHSDKcg9AwmzhJ=*m%DA=N?~UTOeLr)PrC@7GTb1WcKuOHf!w|He7FP27!>`2R3`9 z8!l??aHvBQY~cdHvCGg91z4h6jzI$UiG4_Q#_;v@v7R?ShmzJP0bifbRolNaJy7PN zQ9sCY(YD}stc}*!hwJy&Blh_I{g1gQ85#p)k5-qjX%*l2pyn7kYwGkR!!u)#ib8Ar zBT2M2(K@RFL$zCIQ>Hl@+}vcMJwLLQ7iWzFHbrT?)=`MO0eeGaP5H19$9>QNUx<bE zE1+V_Df}4lL!iSXbVaS+0a(lTVb3u(7(2A8MZ|t<nRP;sRa~Nf6qJ*L-m_)BcbIj0 zY#Z=fW9yNby^<PRfOXf>$$5WlP^=@QYW4kN0oHj`c(Rzx7kIX`1HKTU81mA_V!yyQ zaPHRQ$nNx^M+mv-PHtJ}(J07Ub&Huba8ovi!h4*QFNlRtyhBk#`7z+D#R4H2N>yuo z0AL^Hb}u?NJ}k^}(btEY!I-Xz$)Jx>v5wGjyfRCC*V`%ZO*&+oK-{`T3ruC*^r$!B z%cvV4T0e!G9Cd@1!6@X_ISlJ`C<UGNUDeWK6e}Aij)ll2$ytwj1HOoAo&>Zn)m8$Z zC1#_)Y^CUi$*s4N2CT!FE}5dYO5|I9UiljGaUW|EQ39^#9cIw+!ABQ(ST%O%=gS`H z%+#KaW>_L)k*@J6HV<!s1|vT3dfY;*`N_f)Z5=+~AV%@Z_B@|1`%<h1`Gz%?tjF(J zz6zZ6j#!UV%k}1YhDbyxCZhtN)gu$!4Sh@^W+=_cI}@>t8~&;hYw(3RrY*$E&`L72 zq*`Zo&~TZ2k3-kCTBN(0_KZRdOxVtR-4<e?b#~5SN$1*QDSC2&Pk~Y@);fedG8JTv z$Rf$kWpgMck7A7%L>$Dq+lZJSmO{@V^17Q<LS&1KYQT<*R*Q7cb>_QJEv}6!Ta<wN z4rX9S__~8}FebWHUY{?Q0TZ>yw11y!B@1nYqj}~V>Px?1;1aL=C0Z>n?c$C`0UJhe z<2xFyS{UEn!s7;KNR39sEOCN=K!maiepT~^76i#uvTl*F{Fxer(PCm=>J&91<TNu1 znuvv=nDK(hpL_U#*qM{j>p9finFva^So<^Qo7EyD4C9<NBFuuus5=9Z&%(hNdJd!5 z0<*DLi1h0{ca1>w%%D|ek7<hxM;WY#${MXcD8$_(?C0*w1u^mVJ==&pn^^B#A?93| zGv7okEK`}9Mr56nlVv0#BTZt^3mljuqdLv@e1+TlvH$qIE4Zb!@(P|W6E&iz`X7=t zl*oEiE$EH?%0*@F>_b)wL<zVGvCLWv{;Lpsm7kuUAO6kC=*9K>lt%HT>#pXTZ*K9{ zxPEF`p|N;CS7>|pIH)Il<RJ0*Kr3geL-+njzcjp=V*J$S{MbFR#mKZKE|@JcdtN@^ zTZ*wtgsbKpGSgW_O-j$lsl#@a0LZ8`9D1^=!pG1}c9jnC1)(3hZn4uf)~jxj&szB0 z%xIA*S!yeKC?h3HDb1R7V6vCtO_GR#aoq<8$sQR~6fPVV7&+~177J-a9eFi*)*@rt zaNQ#7#g%5am|Lp3Xs+d|L8CL-Hqg9tH^fRCs&unQ*jSlK<kcLQFDPC%P+(qsrg}G8 zjH6ybOsYj@2MH%RH-KtNy8uEQ8F$qfVi>ATw#WgSj#0sS&#l-`Yw$~;Nkj>_O1i>_ zn(nKld(}CcpKo;ynl&ZN{C%oxnOR2s(R@tc*`;^UJ<O9ypmqAEL$=UZ&Skt?lz0$< zP<Od?4aCTII;Cnvx}_LF|Bl$U_`w9n87mR_6s?A2_Q>2CjDA&!Fw!$a?JPuaKkHd( z#L72{R8|c{`h}S|Q?3zowG0zMFB0puLt`^nDR3wHc0ptaEOwNMm_{~VJ$YW=Bo?2v z5Hr;A;g^?)tZ5yijacZnt(VCUX&*J`Vv+rbb5elD>`f=eatg7gnU5B)1g5rg2Yibk z)==%v8a%Wo-^yiov5-Bz>8iyz3Zyub-{Z(m<MbT1FfkC9%#er@a1|z%&oKKpVZ!>A z%s4SWf8KIKXr$bSTX+6G)hX!BtR^GBhaEkF;^g<8*>j_Azo*JXf9iWyj;TydClS0K z32TzZ;EM?+lu#I$Umgdu#Gw2icUTgG58H+kDKS_vx}Jc4p5)t0G0Dxx#~6)!wt4wt zF4eAj37+&6Zl8kEOVpnq;R2&9dKrNkFX(fGtb@+vXzl2P>8&;zqna;hP@7r9$3mm+ z(P#(@w8kg4zQ3d8KGC4!GWpj=d;RWN?IQ4u677u=i9UI29G;dxvok0}C?$!R(oIC@ zLq1#(BQvLZ8<9`XT<90Xo<}Mb3z4=ZBcIgdGm|{Vq+6u_)Q4oY2=kc9`!0yRIMx+; zNAwGEROsWSv_$Nz-CnZQBOiA&5?LVzZceb8i5MHm7BrvnRa0Q4Eeo;WEE&EyiC9?d zwAn+gybr3Ep<*B@6nm&F*uyIKa-9NSijQj|*&-`A4UOjBVszj{*7B2xIG7u#ZSq<i zdG?*=j2M|fxSO1@g^om&fPHjqdBhkzRwDiwnwFO1e||pu$c=gO&Sqlin~co2g`YRt zlnsntak{x4cq`>ZbLEf#jDn5|j|JnI%Fh}H-y49yMGeIBvYHtTREwD}HF0iOLt%<k zY#@zTS{*Nvt)al$8zt%#Vq?OQkgXn}PCDv2Y7X?x^Ik`_$Pnk$j#-PL@Eu)jQ4b{q zCgrX6P?+ng<)#rMli&7e_L!I@q+JkG8oANT9&t+64DqKX&o>A-<8_Nn&V=*a97<)R zV%5CFdfhCEV-5w@Bx}Pe#7IYZXeJY~x>;p8JB5gipF%QuZN#eMZ;eQUpeZKZJu;bU zIeBdf8$KcL7r>Mmsw)Y&3zNpjf!~Bltvs*e`h4jjoo_MDW@4&+Z#h>+RvU%KIxdX; zJP~u52EvdIOme6@WCTX2&hC*BQ2v1L^PfHiR|H}`#0oQKH;oAEwYwo5?mg0j)?Lzw zI67Eu#ze$^<O*%Xb^g=mUbAkIZoE90=h`A`iqPAo5Sb7rFhih)=$TRTLhgVAl{Z)> zB0j*1R5gc?UJ=TwMaI-IZ=$jC%tsX&9;#X#VN}^`K%oFj7XU1kQM*8m0j3j+L|D8K z8srw;016QY0qAHhDGZ>e$|n&ciNxC%3z1eRG<uCVtxyYbZ*qYs0oUEntkf{oKU$$_ zJ!hVuFI~a0Jf_>fPostf(#!sxu@jJp3ynGh*Gn{4S-_jCBASCn7@-~?qlHaB14RI4 z9b~7QgUvhAyvX0X<2%i$x?y<|+Pv@Gge}XMy(UK0p2ueOSY6d1h)(4>S_6k2UHmwG zWQ(9f=Q~&pfbPpwfT}CL^=w(vXb(OICPyo}#hiIK7TqG#M-I_$3?2qWOa3zWnx0nx zs>RB?(j>{T#|Xug1rjx4AEGo_L!p|*2k{CqFzqH-&FYc$<gucfoB^cbL1XslnIQDC z<Xmo-y+qtS^5Sy{2#JXEz2@x99uxD|wM&ngwZ4MMWV|t@uA&hu)4Sw)B9>EnV*juP ztwwB-w`?X=VK%|O&0TRuWZYvbn%qpcpM#=W+=wkvG17>EuaROkhZ08#Ej<UyTaZm| z_T3|t?8a(HY7R@R$`&QyDsNezw)C&^Hb3po`T3S~H8a)i`hB`}Tx@(5x|=V&j@gon zJDlVbc&rYQS!wDWaqC2$WyBBo7B?{JBK10>$LL~Z_IHICnfRJQ*+69VkD=a4#0&|C zS#HGGxqw^hIA%Nb8nH$g_r9AwGWk^CHjs#XGa75Q5ChXKz~WSh&jM;r5@%}{bXTSW zz7hGnoFdie5&M9ST#bl*%4$g_BEuqm)>MTwrjA<7p+W+*UNu!&G$b(A(&`aw$c>;8 zD-&FFN!8sW%fZJRV&gN<E{D2%?9h&RU8@ioF%q3Q)X1t%>Cz+ftha0r6*2@?e9_x+ z>ug4kOH@ci3AoA-s>{#<KE87}WXS7tB}3-#ONL~eOzmi%G4g4P0_R3P9*M^)S~&2t zi3q6=JtC@sj2z?f)*@u#$Y}N6;<E(b4Zej39}$&fZVv@0tS^-9itJArgmtCq^7?w~ zO1x&E1~>tKZ1KcbTG^%olQFYEn3`;Hj1cQ4Vi}KU`UMe26T`ABM81b`zG-4?!0!;F zG8;4XLrDz29M81;G%;A4atLu_XpKSS{xT=%wlJ~mIWcCL&z2YBj|Et&BTsVfD8Wms z#W6dL7#tr$ddY-o3vs68u6lokk&@GEwx%y&WZbk`WOyE5(<sEq+Z>-vM99lBj(<6n zlK9M}=@xNt@=31QBF@al*Qg4Sj`SGJm1WY0=z^9myzs^BCF0?{Pr0R{=Kytq4i-&L zzOrMsU27<j1!0EoRU$GGh_|;YUkvbKQX?+0ZXhn{EfFQ)D%N4BFmcrv)v!{K(aw8) zz8!I+z~#|Q#QCwVlvpRGP)G|jUi%CpzM(BkeN=*?nkUdYi#RlI^~T#fNYSM5=$(Tq zpRE2oFR5C*A-0B1AP2g8WKsgw0$hkoe%4fm2UoVpTO<ZFTP?D1Jg+ttB8Jgimy>sg zbi*o_u7^TpqNK}E8b{LYq4Z%kCe<Pomy+{^T#Szj=K_c^2BvLtIqMd|4TVXp6d+~R zm)C<2d_Kbpa;qzBFn?b3wUUSaEfMKo$fcWO1aG=wyeq^`r=-aXO#Ygf{zxJ+c!Xlx z>JcJ?=`SvbSX1WDv3lGaTp~)qb?4{E-2K0OpZEHF-RJf3O6+Kc_h#!(zk&R$ry$Wf zv&oSI?r5E_@DK1pdu50+&=^OHqqA+ir9TcsBB};4_yp}dm@P6BO{Jb85wXsZFNZ8d zh(l`K8j-1B`A$b7{uuDxA{6X#EKa~f0bF-58?Hq+hwSjQQtSHgRGI+bLnk?^UlzQA zM`EA#LEYBx7y#Dxyk#2o@eQqja7^)!jsC5l)dminad9ZAu>oJG(QvlKkWXqbQS=gv ziJ4Y4XZ*6@7DZZO!EyhQB24TsoR69!U;Ei@Ff83`ifq6aiZE5&xGld^gl+>y$5|}j znf51K7!(o{dnkMzK%kSG&w@3B20GUG(8pK~4L7Uhj<2yM;}XDLli*-Qj6+?m$!~VH z8|sO#4<%igCYX+_-=GUrzhS>!7begM9*#7FHVXccHhiM!PRVwm4PW@RQ?75?{9b3f zA*fENYT9^)J@xdRHX|D}O~iNFEQ83iQrjUXek{PUl%@&wM$N+y=9q#uXhcSam!es8 zTS}fgQ6r{YSu)T>ERG4}^jU)crR1tUOSbo&6)T)ZtUO+0HxZfoH$;8h)7vsaYc0g? z9F&t|jtjsz%&c2v5Cjtk?iNP{&_gY%d~m5JA9>%*(oe=vm^!32uayDj^cwj$6(F)8 zjngc#Z7-v%rD#b+3Ak!tg(=$dH`@!J#!fHN>+|JOi#agA=lcDx*Y8lxm?BDk&sf<s zZY2Z)_E&lu><Xjv39;80WG-gVQW$YO2fFkTF^A#klNhWUF+6+{0}7<`@zMt?_OT$L z!oXp}Izbu(OPH8JNMX>|-cOQj(Om*xV=urz&&AjaI~R{N30NfK+2-Yox$tE#JdefR z`^V7UtUo_Od-I<l!bsgUq0bTGcM^fu*%OO5gEO5&=2LmrsZeO7M540th88B8XG9%q z!Ad+<!1a7?xe+N0(?Sd^FHdqvL?#$!MHgeBSo#tgH|0c}0NAt4@ugd&OKpftqs0oo zZAs6acgJ=3@eD-fP-Dhpg$U&aXIxiQ`!V3F#m-QLv&EkU=p*Bq>Iy=j^TCcW#=vOl zdQ5%+SZ{+VhBTnD7OzuX(M*plOK5c!8D4e3H)0<Z5G*F*WeSr^YDC_K4F}CcOw4zb z7h)ePr>PS9SUHm_<03X4RNDZqDMf+=(1YZ=UTfYf^;q;;PeewJ4)?M|1edqcP43zP zLn2DRK12>#g3SfXw|_L_@p<n#QDDD5Us9w~t!n%CSKoyRAb7Z}<`WCaPc(XRnWJ5y z@sTn2^c{`mk$c(T$@S{@S95fd7g|TFxq=<#mn>tPf7gR&mjC3th1OZSicUR&hM_mU zfPF_hL?Bq8P(K!U47e$=NkqRzAXQ76K@yQ~Iy)5-f%s#<cZ<yW6TAlSm`x{19tyyq z<LK`>claUKmM7oq!<nNdk7|Zx+>^+8B!;=ZG2`2^v+!ADd3A-Dc@0&wiI{l}buQJ9 z1z0UI35P4@TJS!Mm9Z6KVYKxz#y_E8V?Ui|Ko9*gdF<`Rk|0)(oo_+C-YX2N>`X3f zATnCJj0jM%$ds|;jh<|g=3-=-X{*JNL@R2l4J~h6@f(PA6psi`iHHVUN}7WgVq<WD z=3oXK&^p#FvW8$OCOI*X*j%|xzR+-Q_T-r|dqlBHL<W8awF{3^tG7CiWQoYbtaVe) zz{1H4A61B~#7RxrM2sv!R;osfI6;S#?Jh7Be4jBm&#OOV*JA-1&4~YuEG(Gk-P|6B zQ5mJD=7%%U;CW8H4Yz2(^#JRzD<S?rT0v#iRG6Qy6DMRhu0>WeOv{?~LB)sTUZGX@ ze4%cjHI}NNb}-S_iBs}$k%;D6W*W;bnp;PFr+1VaR-iGkn#t^qQNUh<?!w(8@aR^o z-BlA2`#H6PxcjJLhG;p^a7ceXfbmI9oB@rH5Soylb<n#rDLMS%<CaMx@@-;FCe6Sc zEa|3+#^OX}FuBoV<Es?k^c<KmZiq+OVyk2|Ih5TZbZ?%Yszt`5F;Asxk(UwA%b<IU z%syU*#v@x~0jd*mwFqkAz>5~Sn7t;CFlLFE_;iPNw8l^vG!fzjalB0EHX^;g<M5V< z)Eh?dh=It53pwbOWsc)GgwcJDtQ}bUg{^6=U?h?_t4ADPfp4iaB2EPtY~t*IOtDT| zw8<7F;3o5U!w8#4%e*s~3Nnx7IFHYli65DyCLYbOn)VtrOBpgLz(SkaH*<DWr<!Ak z1RY66bB(z<oL6Yro{g{Y7aHra$3u8AjciW}k8z<)C#CxPG2n*+&LD}h0S^Vpm|<nb z2ZlnXTX4}3f`!FZ*5_NT9#38R1;7^v<-k~n9}i2GN72*d6L<QV-=}%{H=q+A@Qv7+ z2fSMA;TexeiK-B>h<r9<A~yP0>xHl_Gwov2EjET*^<cF~O|-Mhr$h|Q`3sq9BErIk zlBauQs^v<9-Jn`vC2ojTH3!x+tT#4=LYbHs!W>Fvj8M8DGW)PkHX=(2g>ace<3sCc zQ?1hrA2iFbgma6*WSK}0E(?82#Bplll(l+{zCT~JDnw9|WkO6u3P_wsirh=gsTL*R zD*rs=8uB-tuRvetW3Ku6()lRwn?IV#IN`ROi>v@t6dH9fCLc1;z&;s5OQA846#P-& z@%+}ASXuy6-iTYy#OHpLE%F5jBNdI2c-}FLO&}5Z>VPlpEyTo&p`0}$q#DBuOvIL+ z5!VW_aRr*$V;D&vp=?P+YCs-)*+gVwYr5VQB1|J_ufZZWpX#=fZiu|y$tGJc-4SDK zH6myl$3{00dAl7ie8~HGS8PVa|5Ei{Q<aJTatbz8`LK{-)C!UI9TY?p5vo;X<_?9} z`HZYJi>i_N1naquOLRomG1V*;nVzzDlcjj62K^^$#CfS^Aub6b5hdU%TE=U>^vxd% z<D=0fH$PvZCDShPM>DJkxJ650agnIdDz*s@^LMmuRx!#0TUViVm-y7h>aFv|`Z1@4 z)(Y)*3yszv3*9L^3M3p&)fy&F5k_njjmV6+Om%Jbn4y!L6WQ*#ULXR4*<*o>54WL? zD1BE{k3R-{UYcpd=dIa8f*G~q;>hjfn3))+MLhkWJltVWtq*5N$^hYD3I~(?FYg(- zwsCnQn2v>eC_rTR*()y^9SY!Iceq;^Fwj|UetvmqoLI!b&__ixmS5!iO>31{Yl2a{ z3vmf?oO`8o4ZyT~K4y9dX|O}`*19tNA<KMU5IZwoR%?tfW1&-BHYQF4CYLjJ=19WI z@-k`;yvR)_Z!TFGM|L&cRig*ecWZKyY5Ex;BoUc;J=T06G7|7G8u{l?MI|Es!^95O z<hJCKh!SuWiG1i-<5v%xV_oz8`4W|pFGY^u|C*wbPvf)ro@!Pe9t`<?rIUp_Pkiqk ztL%|i1Ojt=r9`DgV&EWii7J2u#LT2|RW}ux!Gp$@#7GQf;1R6=kZCP=-Bf}Z<<35q z5Ns?A7c@q3IPpT$7?lNu!evx^(7;C-s;Sme;2o62z!LEiM$eon1X<5kV|Z4AE_#BD zj~b~M6$TSv@|HkhM80(^dOboaymHV>JFa<Z)Jw~N^ge7Si80a)M@>ZNQt0I*;>4(~ zjg&(QgBe}<Tts2O`0~S+7Z}Xd#B#|BBhnGe;-LzI#Rc=p)Y2!ub|qt!x!3<PJ{VDL zV@ubyr6KI-az69;6~-{lgYLJ!{O9@Qh%Dgyvh}H_R^p~Br;Y&6M)hWXF;Ul8HR>}M zkN^Ger+xVU%76Vg^v(ZU8J!4`@@FE;v~rFRrp*xXmHw^9F^X?r|J-N#8!-0_!TbXL za|dGY#?r>%{wL%3`_njPLpI5o=eyukQ{TS+xj#MU_34|xf8(2Tl5=ce*dE>zK+?)) z>Gv1wwEZn>(VefxOR7wfVt&Y+HPnua8~Ku6*$&lrPqu1*vY>2EZvFiFy5PqEF*<+# zV}8#|B<u<KeaBX2B{0!?&y96@<j**PTjNs9-~W03zFB$BIxw8vt#0H8uXDEU<eIfa z7KuJA4;A@}uV;<U*Vm(e@JeA~I?Q@D62t$e?Miku$#L_&-(r9~WC3MB`;xCx=yN5I zw>mXo_}$G<5n6&2BmSJR-Q%vVpQILwq9_JMj&G0|>3B`crOt@x{*0ofS0X!zpa4mF zJJI>GMLc3A+l~K@NH$`y{GE`?f`4`nCyT+!!iM~|2e+W)9T^5=b}`8f8KtB`8OSUo zxuMXGHgtvP{rs53uk<vU@zubQ(VH2K&`lg6*tFy6=IyrMM;jh|4>fnZQvnWUWV+L* zD0t{;fN2h%Ejy}N;@i6*3mM5rR5BD!2opTW@L3sYKlk#27k&=$aa;gU`J@&heKwPs zm#x)Cku&V;B*+RG7v2_)tfESi^@5C!sb(_l2aiG%NJqm5Pq&6rk(rA%hg8hDcx~_~ z$Bc(Of~+Nek3#4>8FI0c)CsakqJ}DX%HUxpkyRqdkaG};%#_}c%@Vb2I2oDXNG_?7 z6}+C$Nw5mZ7Lh`SH;32E$!T-;NRA3OEhF<N434@eoh%mG$z_mX2O-@UCvzF~jFQ4C zk01mSBpJ#R<fP4cXm3Gw{e9e@7QIfUD!wP(U7rXW(YT4U<cZymjf~O|w$;+^KcC~l zJ7<z-j$IvU5EqV(eMV}qa&(LH5G9;AzHMd0jKD|wu|gI+$3HUGh~Ze=DPeRAd=vmD zvzPx4GZ`7q`R{a9%)xDbuSjks=S8<~>RHYU8PxEiiQ{LK*0NdRlL3b`=N!Ml3h;9L zaLCb#D)8~>1vLX0KAhahZ^`kIJsVCNfltk#gtEX#F}JX3KY-Cu@W;We?99YJC6@ob z_`X)?JWLNO@$hWrB`tNQryC*^*U_(p_q`I1FAsEc#HUucRT8oWCu9fxndmNyXpP`d zOhLs*aaOwAGW1UkeVN$;CYdDNm)im$oNcYl*YHqxm+bcwkH+6-hU^<S;!xK8?BFn0 zf&>gJg8oI4yV@(QgV@T}F5|o!ECE4}$ZVHpR|^+k>TEVdKfBr4Xa-LyX~PY6Y;6|c z;cJmu*#Vp7cZbG|0L0mRC!^CUz|A!Pog(1{Sq&QsJmaSQHUOUrfURo>Kdoy@$lv5P z>k3DnA$bz($^qkf<-zJ@42TPL?siEL%9xYgE$L%Fy$u?F-L7T_Jgp|m_h4Bzt9iW7 zZMXdEqP2Ik7Bz(B+He3{n+|?j8>F5<&Q-ZK$X^;)arre!u7L5BaJ%P<@u&fEyFi7^ z=<57#fnMuuHWU+1GO<c{8fbHRTqTr>%NKU6tAv~k$N(r-iL6STS#p&)fUQyoKdn-2 zRS)xKl`5We1us{L13pqFQ)jb-D&Fywbh|(mnNaDbvss|Wer6k$E?QQu4a!NO9>CMu zAds6lvtJtrBaGS=YlDYTh%#Ynuf6k)Fq8!A766%b*`^OtF~}lDdkO(xgLO#Y9_q7H zwM_f*B317XU4>TP{qQ915if$YfE^}l+C>fJ)Jg4-**%9sc27poYDb)+ghBzRyf(TR zjIv0i7u^J`e7B^2kqb)jovyML%PRPex5#m^76#uZpfdv{H+|>(87KBWup^!XKQf<w z!0mp+e67Ee`DcHh8uoPsCir0mP<RY^LpCdbFgc&1Tmcu2#a(^?zD8qL3g{?nFAGGI zccE?;2<{{t%VL4Zen4QQT%ZZ)48s?+A~%Ld1rz_gHmyK*+O3V&mDm^p@wzM%{ID!Y za^vlGSv;9qsDUJw#TSoch;mst1;iuN@d6$w(D0}e!PVgabl!y{XowC`TIyxM0oAIU zy{N;p4Fp`a>RHp?M=6_ZSh&SE(a)ZnF&~BCERSoKV`7YIe)NDdkBpOa_rNwMi9R3L z60|#NJM>sAI(?8rkc{T>`-z{TZ53(x@2GQ{F?IGk%qOy1<?pzoulQ%bB_GABIDSP= zKKL`)@0QFAydV+{p?nT$2ss05;l2u0Qdopml86WjTE&D%yn+I;jHrbsC<4B0TDJip zLASTEsept#UNQ>BrCL;@porC@z{CWc@*x20R$jq$gEGk^enVcqc#Rfd(4lh7(fJ0W zi)TeP*@$8>KZywjC2pG81u5&dUeuZ}RmU&wgScbppBnlyyA_NID5SIYwjdBugA(@I ziP#lYX*WhZr5{}!in~g{2UZz@KZl{Wn(VCyRHVF&^lA|Thb~?fr%LZ?;iJ+SlFrk$ zcQx5tLkUlv*M`ostG4PbbOERn*r~v2q>~<iPLWzvR@hLW4k2z>9q_3D*t!hx)4F7X ze5h`>E~)w^5n^39fKIvQp&RUeAB~fWckXsc$Uu(<*Ic<IT0iHKENyrc2i>hkSuUv; zrkCX|%6ZEHjJE^)$lLRly5a4(AadSvzz51_6iw#GHT8zU<C-cNtaY}R`EgC%aT(q_ zMC%DI7g9xWm7>mN4q#j!;3qB@%s1v8mkSbc1~0kH0Uu<Iy0Verg3ytYZW&y$+i=a4 z4A%M)5={4-idg9_Zz~e5`678+6CToVwNVhcL#On*ROf&efQ5mr+}w7Em(^K2K$1em zKm{W5p+-Lt=ju3wz@zAT?_!RgtQCWsTL&yO1<~P2umVYJQ2|o20<O`z9AIM#6VO?q z-lKNdSAHzL-1CD}y~l^|4L@u;vg!(cAl?rl-vjV98oN@AdsJ@{xwT5&u#4>ViqlQ7 z3xSHrQ7G6o0i9jDtIZDa%BiJ;drl#Iyxkrpr(BIK*Q?+ZVy*CLUvP?3jH}J)E#P@q zkn<jZu7|ca8z7>}6WweUJv0=-ysHc=O~2Z_j(&DMuQtqln0Dh-D}7XDevE8MZme^6 zSDRub`n=i@G~yKjhIT^7?{vb@hMvEFoxdY1d<{$IsHriUqx*G&rsQOa&V}L)BeR{X zAnS*fWMoj65UbW(jj26~=7X<Dwuk-0nj_^vw{6@X_QOCjjf{s1f)EyswO$*DMW$}M z>(L`U$4!p`iCv)pIU&l1AicNNV?q*IIsybC-2)1;+G~Ub8ED;RsKwL0E~!IpzD?w5 z;M{fyfu}x2i*Q*wL<=ZGaTW<Ujg>8WQVTw0*`mkeM3@)K7!f3~6I(=?#v8dsy1(Pf z$%g`;k=sqK1QKb-Tbx6|_QAt^L0It^C~!WHp?HIzgA|EYCNve!&e5Ysv8nc*g3SSG zxM(y*wg~NqAOmeE9vS9sku44l#arZn5k;{oE;xmW-*;gYgx;gjJNi&T4(|=p(o6=U zhYCV@d7SBt44xVXVZ4x~p@JfwgLpw!$VjDQSL+RC5{kEQGP=7MB%o7zLn*9?8eoHN z07y1$NTNa8l3GXJVqSC?-rf{R=#e@S9vg))pq8XHawq`>XiAhVMvI7lt4<F2@{#LI z5GE*?sxBSfJW;SS%b}nOrp0m2TPz93*QEG>1LiEF)Kri`y)wy81QX)#+8mmpf%Juf z(2>E}?o<0Ypm=;LPEH=hbLh&eP9Co|X!C7`iqCPVgQX3X)(LqH1=sMFq8VwTMaXQd z`W#3cd@38l<dJ;7s6(NnE;en+3CZ3y2%FJ*EI2`Ym2;?g7nS77qnxa1pZNAIdSo%e z(_l{MA@F!;rp&?9v4uqJk`Sj4ieGCz;;f)+rX=)mfD}$RdnBV2eBBV9`Qo%5hqmQ} z9I#cxcsY}eyL%r==&5-%?LhB+WMp-K(|R<6N6uqX1cDD^l65_cfYnq*a|Jm~Le!eG zhU5c5xtz|LRzo+agk-c7gsciei`08b_V}j2XNyRrZ)T5^f&+S2h~>jGF>Q?ABe#B( zgm4o%Yjwg}Tv;bKbT>*AMI!-;?i@%rDY`=XQ)HOax<U@#<}cwbR_qtEX%VjrLeX2q z%Xd7C5quPYK~ZS~E;2VMIAExG0-3Ci0kOXo<pKmDzB2@)ij`}hgv+K!hhm{g?-7qU zFOwT;K9M5#dXLDDXNufWD8Lx3*|ZqxLW&|BT8r&+x+Ba;*%4QH#dpfZD5gW)1u3r% z>9>=U^7^L0r<z9&aC{_UE9(&J?Tp`aMTb<(RhyhAR+;GKW`rGqIB=EF(y#4|V`KC< z`H`kd0N~v8Hp#Ar{#LpgYMK*rz+Qh>Plx!E{_bTvI{Gl95&nzo-e?9d6NcqPHwGk{ z5@Z=+#&Bt0$ObQH&me>ABzseS@Ax_4MV-XYg{<``y2p1<WCT)1UCD+I(F-!<EkfF7 zg^W%YUy#y{)1d+_@>{EfmaaKDXGusJ*qBf?K3PXnXqSmhKt%~>IR#v5j@SxiD6Nnp z3?5EM$0{8MK_w)4LNu@>q{}8=n5%Q3OFEMCN<v(<5b(=;d{f}l&PP^)BE<nYH&GL1 z(-qyLs?!$;C6&u&f$-8DHoi7F+&x=jb3R5Q%BOzdfb3ghbJ3NpD57VzF=E~DURk!- zl5HBfYh1{XXSu1#;Kyh9Wml6rt7&$H5Cl{r5rmok=7TCE^#2*Tu_a+4U4tU?Dq(vd zV8tBpQmcfGhCyzlm=j+aKNU3U*p(e&MTK8gH<6yM);T$O56d!Cb@GckW`rED)zdA% zNO^L1AQM!(=$z<7;kF`FYct5Q6Q>W9y2XMrG8l$%cwfoF)OdyL1|0E>4$Kco=EnPb zQ{Yn-h7^z}dH~)uz@Wfa6?j#}7)p)p^Y$16@+H*SB7;xm=>jROEXRNaZJ%6uS1sBt zsq95TIHW9=gve*xw5Gx*4xgrZ%Uf3D7|FWE2Oil~prayIudZb*u4UvDgsD}ZPU_^~ z+C+M6NmycT0b>dwDone&AuOn#S9HRHvR-K;Jr(73o#eAK-CWzZ=<t3Y3C{!}YJA3p z&s~TX<?7m3UQXzd*TH3t-3~X{_R*Zp0Yw{;EJC&zQ6oJ#bq**ofnY^Jh|9Niax*UK zJOq>EP-qkQ_Wpvmh$4+H7j<$7L`xf4!Yw-$U6#B>-VwhcB$hZN9M%XO-FtGB8wH=! zQVZ(kEs}{>km_Gq*{PK|AqVW#HI7I4e4o721!czKKp$>ql(<Q2GYLCsnAHf{LapRZ z)_*T}x?IKYa3dp6H}8f{d6Xk(-Ap?;paO0YWHr;iCDBzzhnK{-4~t<~+Y-LZ25k#q zrQ=;02m+NI40b_?)O^<HL&2*r+BlLh#8wttC5#z&EF%d?8zOC<I#lW}p=^~PEXccr zoUENNw20%WyHZNX&?E?(NfkMB=4NZ&ev<^dVM<=OI+Yrd)Rv&lq22ex0-uD)Gg-L6 zghd-7MpOzQlq6ZZn-(K#E0nAbB^eZe*bpXC*YH<pLrF+!ZKcSdqDzENUL!<;${MBg zqGXlHNv^De*U>M#n9re-YDTtTK}f0q!E4%3;Cg_6R1ngy6}Kj>N96CMdyZTOQic&Z z`(=wrN=VyG9ZFYvf{+8Y+K_e)o^L*AL)6hgqV0~}Vm_eOG7@fu`Fqz-)#1apz_+G7 zvNM7JIfNrJibx71M{`wDz@!Ln(+61w1{IwI1)ibfn~<OgC{edgZ|Itoqs?-D_&kqN zin6JU+!}7vc`-HHb>^L-kOg;Sgys}A<Dr?Ps19|Eyr7^vZFES~C;%2oVb{*Tj&+?f z(&YdNkYQaMooz6>49%)l4k?+*id)jhoI%SZ9_2`PR9f*AB-`-=zqca*Nc)N}n*V7t z<|m$<<E_Zi!mn2msm17C!26>&NH#43WlluI4gPqX?=`^l?cZgaj1z6x1;sSVrkMfo zNPca$^<qlPnT@<kW+1kprMCgBwyw?pI3vThz;^}E%Do^X8e99<@lA~->!bQ^L!TP{ z5oI+d=&{_(8V#P+Q1PsJ06GP#Pvul31=5M(bISmHDu5+|?*c}#l8nTHo5<XT7?Ery z4a8-g@B+J?qhe5GA|YRhm<F}&FQXj*kD8BOPJ;v3GzR!-8Ugt&VCu?gpkij-@fL5{ zQD{z#Hqs@NOzsVUteLuU<Wm8#X$<hwG$Pra$Ud`~2ALogpYp^sB3+y4j<gvqB4@0V z0J57r67h&>Z~&Xe06$FwHXjnvZl;mwI$HB)ZzQ|~jhkuET{+^7y#Qpm@zQ2*Z~&Xe z06$FwSx21T?hQQcN^Y|^;HqtQuox}f(a5@#0EFn_DV3N82e4@j@Y6JK`$ZD5%`^%g zS(_-QQSj1w-2wxEnu1}O_&W#m;p}2?%bAT9E}YG9YQ$Ft$yGeTjwm+Cndc1Zglu*N z3O<LlPT*4kT)8^I4_tM~Rz)bAX%GdS8rI4|p;jXvn{ehWfPU&Cvx&cECvJ!+snm{^ zaq9M7k#8tRseBzw$C{+_6#&MH0e)fyc!9Y74J*hjZ#8)YEAVkE+9+8u0i6}7Y8*Q& zmXaRj$Ty7i$2)#_l-dkZiz5#-p2A3eZ~)`S06+1A7O#+vu;YhESsAmDR~V9E)f?{u zFbpyzzLTPX%;>Rg1;Gm1h!~_~1>Rnku-PRXz*sTBPpk-qtVFxrB_U^0Uz=SLNuErR z=Q4ax?PZPx;3-{=avB`KrZK=z(|{~}WmFtZ)Ar&Hi@UpPaCdk2pn>4-Ebi{^76|Sx ziw6P(cMa|Ymyi2-zaKNFPS2d~nVzocva70C3O{U$3#j!~=ii2nx^HCHtlqg#mM19m zc`;`y*}1rrDa;%|lFCA2xR1etiMPn#3;Q?5Bd_U?*r66%lo&#P#Kzj?El1TxWv?>$ zecp`hed%e@jEkD>*&Nw9ZLNecW5^o3=kgf)Ame!T*QH&;1llY3*tGDiul(L;{})XF z)wDH(A?&bO-fzuzK|^5scQR<IUv+a|oVu-XJfAU5Hl2MXeto&R<i0&3m;rWt7ahW^ z4T^e9{tlXYc%IR0hkf>2u(8X*&npIyHqQ|49q?HW(POhiHdP<8i#(Ep2~b2O*@OKz zRvVwmmBG{yrw2cTWje1VuQvHa`Jw-YyfFue&7}`gYY@-#tf2=)c4!)iNM1@mlJko` zlJgE<(Yk@IBn%_SUV#w7K^EC60g;%_hY{N@QxI!B7czSd+1U<KtB1O)Z9MdI`XU*) zgO={GzqsGir_rbHcJ{Zs4**kqH{i7$qNHx(&o%?pnXPsnyGGXIk-*9Abb%fR_wdCP zV{7ETsrbnu&!G-MKepUSqQWPK{B}V<p5*_v{rbPLR*Klb#3AM{soI|ZQ_2K$<qS4G zA}~HnjUYR>Bmohvxn-`PXUfu=!S``5I7uC)R&ZXLNo}lYgcOJt9fCle49yW%4>xvy zzVOs!1<d-#z$;-e-Z)~iPz3*eF!nHB=$L}GqNsJ){fK|eRIYeahHn5?jQEZ7C>otz zCC@;DI1Z)Jk;f|?U3)IiE65x3CY%($sL5t10paL%S<q~Y!dS1t&FMGddbZNar*bE= zTWKLxmXi_o;n-*fvW?MQSF{5tD-|0pCMJ;Y=<|OW@2(lZSACUw@xPwb-#Wl&Pd>GG z-<(?BhBobJHd4&9`TM=Kw!PV1@@<a$+3$Sr-n3PO@<w4TWTjWa?|80NNG+W(%hT;@ zrAvYE@YhgToIOW_?sHjO9)6P-+*JMeql=AeQAd5cqnTbYYZTm#j0<0j`9Ubj+hLM` z{p)-A>*m_{dEUwEo9oBR#5Fd-)rnm}Ijq;%FNoiFQA<zIk?hXIA96`*H0a8g?=J!$ zJ(7)fZ<_@QUSPZs*C%j}kd>f$wYF1DVJUVE-3Y|{OBxiW&+njJrNXpzC&2JR&TWcw zAsMo;=0MPs?;+@9WQx>+QzDz&uF^tdhnd(~LJEH>8Jh6%QiogdNQh8XY<SNg)fB36 zq9h#A8fq$nC9)S@m<co;nfHMcNjExg5y18pbmg~h(V#@N?FpB9LVN-1m+SSzNGS=+ zZC21smlwvi@{mD?#Ifs$YLyEc@tV^vTU-kw)dmwwRyE?`F&NT0&Z~izPQ9gL7|R(^ zGiRvU6{2wJT;Gt?5mD;+T)J6~bg(!>A89A)i(P3yxnp^qy5V&{@C!S2*icusdl5g3 z*;>rcWJr3-RZBU*jOPXy_KfcaSK1XHJ(H3@ac3Y2l0RWfF7pM~DL4FKhnn>;y$+EL zCZQD5icP;(R0k2hd+E;EOvx$#oKyUk%4@Efugu`JToUZ64rCuuojLe2?bp`5Wk!qn zb$_)e7CyvG(u<9Rn07;$$03#l%L|V01U(T6@0t>6DOcjvSExe5g3;pJ@?gFnhKSLT zxoh<Dh~0Oh0i0q<M^-V0ox#BYc9uxcFz4}!+%Z9R-yR`p=wz9jvk8KWErT2;Bvr9W zbCWQsnh=A@mO@%Nk{ibVInmYTFNK|8{lv(<O{O3}NX$?yeFIr6A=ORWlLIEl-5{*d zrf_geu1-a>d~4ehlkgXbUi>21c&KfSis_zIpfmRZ;a#W8gj&92)k?ivkIVwygOOFf zPeKI@d{pewYJPQr>O-5L(M&>hhvb)%mYUS3mKs4>{arhn$qV?MA}GI1?|Srz+RCpD z*K4lpOug5lU|ZKd;-yLvirN|EPx34yVc}aR@m2;Xq;_ICq2#~14qALkgnR$DIq-6R zv}J#o5I%j$+6RL+jjGk31B-Wd$Fe%&ryOKmI_&VQ3Sj{aZUzLb2k|C!N5PQyu-<f* z1hx@Rp9Z~yPiKn|x4TI|CWxXcgKPE9-%9J_uXYs#7a>)mU(alBv`!WIzw5B;5<DA3 z23rIn@-F$>T)^Hvl#7*Xl+W~(QgT2R|M@|g4v{)@(lRED2dFv&()JyF802n3oQ!Wb z#m!`55C3_UPSe)JM|OrH!<+zzk%~;8!cJ3QDk`-0(~1KKu#^|&_vi*3nl5=HJ6D@C z?=YQRqAtAYWz5J$&<rOv@>1}shnyqTr_6YXM5WPKp0n?XA6b94gfK7mQbpc^2*fi@ zFb;zN%@HbkLTIq>^Lw=K+A;`tm#w!l5;|`4gCW)O=^!2ywq^Y7>1LO+_+RP4jxt}! z5L~pv5EC9(4^AWn^NQi<^ww6l_vQhmKjoWvhO-)>oP~ckZI}JqwVtRxzxwCHuL1ke zv6%|!HGWk@2lN<!AM(hr1>avN4&1KoN3Z14vwDn3$<?>SVB{HwnopL{xr3>{nWhnp zOQXzKO6MyG%xvYrW;x^pzeLyGfQzDko1S)XEeouVYcN-3+4lv#tMqx~Zd%vQj{5Jr zjOCWx>^&#k6|fXZrsc1+@<$2xz_@GcT+HmvedcYrK{vH4!OWS;`W4aN%rO>1J@&(X z_}iC80(r^R5iyT<W%XDLL}kcroe?D|NQw=xc61$TKRP1P83(igyv^_Z#(p^RIUH=v zmIh26`#<bvbm%Z9MybrZVqFpT#m$-3HscSHF)&FY(-Sz?)aaKl%{X%NIU=gfx;fW9 zP*j2#tc}(3$znG(?g!iSKeeY<XS1_xQ(6J2!&Ty|Kv*x7<cZJBF$;$b8AJt;$Vop! z@mE}GENI^elJq4gnPA-Wsa(Hh%#k$lyUJR*Mr+lt<%nu9i8UXo;StzKV%H{hGP`*v z8V)Ue<^@&7kCqvf@<RZI3eQJ}W)keoi039kjl?W#@p<!`epgNVBLc_Yi?R3QBXgNY zo9Y>kTlVq(@|yR!8ZRDRfZhnxl)Ga+pB??__6aIz0<+>U(q30fY|CIg-W9O>(q1uV zeWpmG%mu{b3Z87JT3BQ^V2E}_p*|^Tq}O!law{eEw+()Q+&+F@t^LwX-;SuX?v|e@ z)vqZRl$m9BFd_Cf;!*4rO~l9%;y{-OD1=5RoODwFQD-x-m&nHziWZB9s9<0uV(9fM zbA@#tz+~Y<hski?#zm4rF(XFEBR=ET)lo~4A!_DgU?JRVZK`hHqHt)yBVy#?@z^;Q zyxdG|)R{+2ZLE4y89zPL5ebC$W?8>BjIMdl9k-=RCmzL=p$k(aXYQSe6zx64K0A24 zf4)6&LprY@e!%1t;K}R}UV=-y)kNM_ERu+nn&OJ@+ke|&K<l5}k8uS*^%8E_6=5T` z?5jo()eyn3ZJ3}h>=e~OrS)EaNG))2@W~Q`)K$q87nl^-=_ux=2FG@=@UfBR!Xdr$ zzFo>A@_&qPCL#s-u(ob=;)M-WoF*UqvU$2zmYmL2-U?l&M<DZ^ou{zAPz~5PAO^_o zMia604$u9w<uvr$C>>4)lyX)EaH5s2I6&0q22Ycd_UyBmg%Z`$21BlBCb~)h7}#gw zI!vzKkmO9DVKzz<+xuh@{a{rHFDSZ4Rv83j_;d_DH8NBs_B7e8m&H}@*)=jZW=={| zKM!E;!BEAQtE`a%XeVoyuxtZ|urnv!Jm?;Bh(f4@izWQ&g^%Vkqp^8~$U}t)nQjrE z5dE?Fw({5ez>)4iWk{6@81<jA>HIq56ZH`KRZ#peHa+@t;lWg8t5VRgFy~pJl5xSo zsA8+lmJ(`72(4pJN`NTO@M<&!ANH?@`ocH(dQf*~P7EtSn;YE#YK!7c<mh;<h|&=Z zRkaN3tVdRu{?jE~FgTtb>ogw9Y+__VFLlimia$5wNkz~5XVVHWnp%_ZFM{YcigBiw zp_r^-qC!L0UqT9ocnW!Vl?<g--!zbHdSeiZ2L+4yrW@>^BLZ)?W@l(Ycd%>0tI%Sh zKOLL4JaQZi+Ty_vEi)N$6T?*AZOY_4Tm6>BNoDlMs$r!t!U9bPy-v#L8n?3xjPEE( zh(-~gHR=2$+lz0eB9;B9#EN%NUTafbCI%(~RQ~Uey7g?%D#$CK3E@bvZBZc+PcO)D zXl??a7V~L^utGsEVpDaa-PMHgDz^t34~|9+;=$HE4?7(htL6NbQ8isNb45a&V<5MC zzJmW5N*kl$h3l^;K#FyRI$%#u2fPV}>Vpb!28h=;HLN|)!BH4Z=og@q7bvft!T<Qg zL?eScRu-mN(9aCO)HM4Xgj70C&V&P-BW8Bhl?&*H+LYIE9sTkmU71{!n9v!%aCaDU zD6)&ZB<arAsi3U{Q1JdH()K8^tlb!L^~ACc&wbSUh6i}$;wXWz%d-;llL9m}tSsY- zI#4GUd|qu|Teiz}HNV}7jbo;J9>Kx#H+PM0Xy6-OUJfpHv=d|Zm_SG*%#l`Vt2&I! zbEc<z_ckwxT#NHRKePHICPt?5wKC>zM}*Pa2w#rOni^F4J<K_;Q$I(6DZJc7UA8+z zc=r9Xy+EX=IfnEXM$Y_2xGNji6_6Cm(EYX}jgfpmhwa~R3<uMFZ-c*30conh*T2EL z9+vvKS1KkRHxfjYT*@vM8l0V*Ac71!CwZ0^q4cc(a;Q6Kcj<nU8Z^6A*$Mb>HEr13 zSYcCcNGGm7jq7_LWYz42kw^S|;RbFGMW5=@{)WCXf&k*)kL;mh?rC&=yz(47zzT`} zsq6ns2{`fd$h@({0ggUw#Cv&XwG7XgSlQ2F^9*rP_-6gvw^}COY{&OFnzYI{g>IT_ zm@u~5aIw0z7i8TU$)ZR;?dkoc4%|e)VWT{|9w+^quZ>YY{yps|MxZNziUSSV@PYOY zi1AEZN50c~p&98PBQyAd;>9I%n94bMdAYQuh7YynaNnx<Hs-Z{^sE209C`OqV#-Or zp2Xl&d2%}I>!a^0z@*eJx`NNqJ(|)oyhpDa8)HBe!BNJ6(-S*hWf-fmIra#Vjv!jM zIOJnzPPMBP9t&$2%O<Qg%u<e2{LE1iEEZWY&WrWHSph@-zPm?8i!8fq$h&ift_nSb zG#E-Pni(gp3q^r=u#fH=UC~%PtS#^O6}JG2gsucNgiO)_uAqb)%X$n@tybGb>7SRE zg!J*B5#FnzAQq^&gaPe<6R96G0H);`h3`VGDwotL4ZaG~XpQWQl9es0kI`gMHy@*> zrNoo!U!WdEQuQT217Z2KdjB!AWsq=ez$<oBk2DmEtEguJ*#7Kfhx22tXBnp+^^BP7 zWxw#fgEa~Ld6vXN<_01EBl^nAe37UkxE@E+v`PpyZyJHGFoL4yM0k6??VW{>XNK~I zE>&<Q!b(~{7US<_Uze3I$*9X~E_xsijPTS(A=a1CQC}@h=f96FS}6~Zq>9pS5MrPQ zO%fF;7??S&MO|vZ(t50y=Oz|@9)2A$42)4F2T3O)VyAOiYF=q1yvCTcI@m*;R!$6; zbdEt=oyyQS*^najHG1p|1sw<EbaHNl1iNVE7v-R4F<5>BRo=V$uL8`NX06m~#Oj#_ zwAPy>b$k6lEO?(NLgONR#|c8?4lJ8Jiw=@8hXhl0xgaQ9tz2jrNOINUXbmFv<QxQ_ zQf0;J$N*vk8@tJle@7w=$N5``;#)1ZPl6jyvcfK%QG8c43U^;iAqcLgN-`mc```pI zKQo2Y-9FrZ<zddVF7-RH@cIs`5uH+|pV;s&k26YlWUK?pjY%nCPY+E?-=mkhAYlPf zA<?iH&Hr0Ia7;3tb1`3u@KOgd-z*v@g#3EqS@ntu{R_2Z40_Bix4Gh@Tfsl}zc>p( zYVr+X`R&k2RaL>tb9ZH3afR&S`(;F8tQE>Ewlbk8Z6C>C-H>fMv2TpRFS<Wvz^MAE z<mjPZNGjpktCU2O-c8D-e2~3?RYF#p_fG2dM$)zmHS(<zNul5NiEIMc!z-tgT5F{K zsmaN5CX`|Qlu77}T971H*WkIr;WH(<k6FFq<xcs*{mwUY&EK1+P5Zn)j=s2WH&UEi zM=X$4<HGC6t0!$UsE@Z|s!rb7vQPwIXh^=ulXrAO%$7~>EiB1VbdbvUB2M^2#)DQY zvRlQ=q!f9cBD2}yG1&2d&cEjVNbL{bnj9}z#KYJyr2&<~@{UByB8AZcqRVfD!O+Gj z?kZQ&hRx<v_C176rG#a&F?42la=GbBLy4eY*(LkgP3Od26JH{lgIHwbWEHEcZunS2 z!?^rvlM}JLV@hYj2~aRn6_Ug?`4Bs+g_4!9bkGYJBCL#?_OmBjI#^n8dYn7RR)lCJ zvC0OP+$>S^TQL;r<RY!7&b>5zB$EZqK$%1HOx;qb%Rh)L02JH1%KXM#xm#n(X_#Lr z_PqFK(F`K(Q2iY1E#Ln$57^^|+KA%4T=qR)_747Tcqw$<CeKZ<qwrHK3Os-PrG%{y zPVEd@qOE;s4wzcmMXA`qJ`typ@P1&f*wNBlnu5A?`bP}(12&et@ws#=m9qtk^c8dA zu}rFx#8x|*J*I+BEU5hZJI1bDC2R2+wUu5suWd34j{uGZ$N_5(VQ&u_?T?p?mpDhj z$uGwcY~}l?$BL$=e7>8exkz?Ou7;NLhJ_(p<j5GC1UkSQub-#IyKS0eZVi@?AGwd{ ze7<%hkM@cvqByL=(<q-F7uvM;60$ugv`}a%d718tLNW>Xo$F)@%9%-KkSB!GRgssF zTTRg){=Gr&88nkKh#z#3Be0gXF<Ji}U#X>ID*rVqck_gu@l3N|eozDQYqT>wuk~mt zh$)?rX2>NcTToVbfsC&a9%L-ZjmL^$>pc5y`c%?La}E7&`;jE$kjzp}3%En6dKxL1 zN_oWjdKBSEDMP>^g#!j9X=G9jOJ#6}Uysh*g9W_oS660LK7KxB!=xBaLPRjhcDH5n zHi0kGX$izp@I_N9@d;#|D$dH2;LA2hD$20m|Ba`>6iqS#xyRY)W0oiR+MBUd6)>+- zZ;fV=xjHGkq*4!u>KEa>vz#FJu5R5_1V7q^l?0*~X-^ljgQvQ+vsA(jkG-@M#WU$D z7oR7I4}g0+3-BY_6aS+1Y%$Bu;kI9{z}0GK^W9<4se7DrtN)dsjhQ6aYIjvsYGl_e zexd*lb|cU%6EDv#RwtQcXhh@#5%l&?<f$%D?{+CLgXXK(NOD5`n`J0I{`~pxbU*kg zIh0YM55xNbM6iO!8Y7I~dC=o?x;){!=g74;PyA-$^o_V#?CFnwp^x0k)9wo=VUvD6 z+Lcl1aJZZO+FjFcI@(MBCj21bSEy^pbG%-TT<GX&>nlFuK^s=WK@r;SLtGakedmD} zak=4EA5VF2MChH`&i`0vo~zNj#0)f#AdxGzF4}0AW|T4SB~Rg^331L=yhbl!?LMB) zP#^?K6Qv!!qE%Y46U}pbsMS+v%$nL}N!4)$8Wr&(8iyzg`d4B{Q>rwB;$F2~hxs3# ze$#pk1YEnS^`eqz8T2X04MGu{BurBeRvF?hNaDB)`suuNz;A3b6I0;x@g(fcwixQ* zr#p^bPF-!;l#T`W8yxG$<0XJ?pagbz4((#Zc$|q?ck=3_@@L*Fr|89q49<x3t!BSJ zeyou^`Np{oJ6@|X$CqW>9rX=`51Ell?+uIhY|mN_X1-~)?94`*7Up}M<~|4+Ddv{I zJVX8Azp|2CKoFuhc@}(5Ume(d=o_L`{;PFu*stjqT1KA1I<z!$x8Wg-{i=poB8E;G zW1x9ic8fHeIi^Y6hvv5*sN||y@Un&b#V08Lw3|~h2+mQ!{@yZArVksomx%WG2Bevs ztFZU5zmv9kfG>O{iy&TB;H8j2;*r2uEJKH$60@xc`X@h1N{aA8{EH4Bl|V|_c=$u} zO77LUH?LK4XpHWQP6p2L>!1X=Jv6OwW7S;Px7`QmrHHLl4Y59!H_)8rMw)$EBvc*2 ze(a^!q<A8VgIe*aU7+&mvp}8;ozX^~>m<DG7|wCW=p%~`S|OPYf;{*iOL>6ziAD1^ zaDQ6{>GJi#^*K9Sf&m?D@$2~E#WjRRFdV7z-{~bO3^ihOu1R#!!b#@sY2q2i90>mJ z{g$imx^dg|2vlA2)xzkLrQvd{(cg!Ftv|!cYdc26cA`p3Qz1<a^906Z$HNYMS2*kv z#twctB5MU$@Teu&XMJ_2$qDcq13k(TI0mBGx$nNCtfeq=M9=~DzcHx-sP`J?C$5j# z?DRbOgc0o)wc<q{`b@leiXIG_sq2Pz7+NbO!t^yS%+<kxG8EnxROnTW(|;A}HDq~S zuv7;94IiJ)G5Y2-9AO6{9svWbDc@K8#*_nqRx&in?zqxS;ybHd->^*fewqY+6y}6g z17TOyWU+j{X$74l{a6n4;&`dyGk?E^=VH1g7vAv_a>i{%9$T?iDnA&~n^@x#)QtJ3 zA)^c<mIJ(3M^{)23{(ZiFETcZ8=(o7Z61TC)y2LEIm3`&)rt!jJ|G5P?2ur`mIXU8 z`?@rlu_6w(Z~@!vWMOt7g&UbpTK;T*YIEEt{W7SCgwO#sUT>_|<9Kb4KSr;Q5w(U4 zAEFW-I5v@9WBcpK;_IGXkkljF*(H&b=wBO1N-Ky}k@H}j*%`)a9i=jnD7>HDf9;(1 zP(vIap(hv?=TRj1CAqQk?MN_<URoT@OsQilD0moB`6qGaKiRu7=C389I%S_mwK@Fs zR}p98+tgx$!*bZ)*KBB35}J>1i!776$T{<UnH+Qdv-sv2d4Oy1gV7T$VTN`n$>X4* z-jSF!{K!`SLb(UGQx}?(`3Q|b>V9%Y#-7-U<915~yzw_WbHUf`LBiwX`>4T|yB+$x zHL-!+FyU3?D2cnE7ZkS_&n5`vp28C<`m$_b{xl@sAYC@2#lUd!tQD;D&3~$>KMS{# z;v!VJR;Ndlw)YD1pGSVTXc@(j#OTNxAP47g47;W)=;At@@QCC*VRgNS@F;piiF_Ev zP3+y6vYIebIc|20^<7|YIJ^E$)q6Y1p~QrNxUlHQ#4-g0YGYfT*Dn;eb2)b?auvN% zjdf9f5&@n>)A@f785^Q1kE@xzYp9-3O8BcCpZ1G&l=;9zhr)LOPbeeb9f!i+X%&aU zj_Gw2@aW2h(0@FRag5_QZ>9jpvEm285lCj@C+0LY=>R2oB-cpW%t0fC9Pt)^og|q< zXfpHtu>kRX8rQ<W47^gz2!m5`g2aEFg!5xTi|@Lwx9}L2oN^fDj-BmZASDJh%qIK# zt71~jvbdh&r~wY0k6*cb$(G5>mKLcRGWB46-d>7uv1TzPQjI5j+HVco5*XfsaotPi z?xwAmyD$GTjwTXH?34rlNzJ^sxoJl&u3SDWO$QlW&HV`%2-%_u^=S|4aw?VZDVS(! zlFIYyyK(bTwX4P%z;$~iIYM*P?9+4(Le07x)6mz5iMiZAe(_fsWF5Y)Efy*y`TAGv zp8_`8?YL*RRCA0Y$*;|Kj+@xIwY>)|oNqBW6h!NU0W_V7b0|))!mo;M#BqEsew|@Y z(HXbM1<En{8;u*~=FnAC$^C6!r5Yh%R;LaamZrT2+|opcCAYZduStX6JT6LMytAyt zl+dnbxse{DnE2(rkC*E$PU58V84|_prKVUXF<1`b`dTdKuMfT-SrrC&wsI%@u~coX zZ4TlQJ&S+7(G>S~qEG&HHhg()K298%jX<K*E{Kxhjbi=pFPGg!I3Q5P67BTdNO3WJ zlbYGL#fYu1**QB$<DYF(`WB&bFJARc2%!REv<q<^w8@C=`3;^j4RNXzZ~xw0ewcif z<EdMNfn`Ten!}7U3BnD1Ge|{IwAMI2A-Skml0I~3xxV~h)u;w#SWfeLpG)O6bXzzB z$3Inp&VfvkXBHrNc`P{pCh4X?=6;Q7V<Y==6i}?GnpL>>Gk~Iu@tAHm@|OlzKS@N` z#XzW#_^B{Z$3#ukL4vbWS8!~(D*#g4QO$&H<gb@AZk!f&`Qd`me4hAi{J$3jj#sf? zxqtgaUZR>~xF0ax1s6UslYZkWciSvpVDo@tIL`stOKg$Z`w8wsx2XZzCqfZ)>+zm~ z$c@rR#HxT|1nU5b?`kz{KMyj0&)g*yp0&djycfo^5=oU5{n2o<x8jY?EmBIP;a2L( zwsA*lKVk3@KkF@~{m)p|wn-7M45uKey1Z!wuJ2p<<%XA}r8a2yHv_OulcQgZ#}9DJ zP-7&69DPdpT}f%2E8Wex@Ldwl{Pavzb6wh;Tc9s#9}h|qZCYzr^EGm**b<&j-Gy|V zt9RwHm-vE5A8d2TOR(Yedluld^m%NdpGFBJj6{ogC!}K^UQn{HUeIE!XM-}2BJ67i zpxCtne?5qHdnH7caZeauAMw}KWWG~&FWnMGYtNO)Mn}FKaQjom5Ef)$ji+Q8{xF0? zH9ch;Ks!yOxWP}~;NMPS*u;!_`wgKO$5cY5M#kKSsxIA=NS3mx_i*r1{q~D{%xpp# z5f*>OOYy1()JU%IEotpKz3_70?s|H?ZfM_RraYeQ%dFtu2=6W>7Jwt6HQO@x=gI8g zR7p_fs?2G_V{p)&o4hb32j=l{>N<I^8P)j%7@DxuPU(F_5hJ&wE#)x)C#FnaUi~DZ zDwL~a{Abd_xm@s4Z<RZw4dcJ`XPuVs0=L!KD3wl}Ga*Gijeg(FOy8PTp>`i@??L~0 z+utV%Bxqsw<PN?SEY>b>*@chlCRlkTewn6QpCT=(IewI2FF9m8jc<=?`kPl3v`DPh zl=f`b+M2wL2gPL4Rf|!9IrC^B%_?0Of4atu5Mnbizi4_wj1W=<6*@2vF=*O(Pla6G zdzJwE$I#;|+x4uEIuXosR057=h+2V^Ds;+N?fNfP-X)AE_(fNMbo7s&lOKJGS5@eC z!kOeoL2U{-sJ)e`3u11N-L~v2D#5ogF{9Nv9eolbzB61`87l6?svM2GexV>Ns~ZCu zQJ>RLxw#*uc>l=E_kF6I$&3vhUp@hUs6k^xJp!5Yz`?v`G?E~PN%*Ui$PADp6(@2@ z47H*FU#cq!NFkPMP9&4#>9H1YM`wfOLN_V@>$e&gOw4aNvm~0rTcszmG*$W9-g;SZ zyv2q`Qu8#J0zuMh5bbJ+Vy6MwE_I5+GNkh0^PHi;>E;n5Ns~~m>XMfbg18fHzesE9 zH}M$;Vn-{dcFip4K*!K1%g;)eIDrwbEH=w9P-@D975VDnvVtpWg1`~ccsUsWi_?vE zrX8~He4ba8HT}M^S}m0SJ@Edq>T6TvB}6YSAYx9P<pLTs{aJ>q2@90&!zw=O2o0Ex zM%|itWWfeiTpa~DB>t;eAC;lxA5-365D*cyZnF*L(%bu*_Jdk78=1wRJ2e@hT?du< z@}q&71R5-pjXzPY05Qv-;yg!`<Ud8U4YzXD3p~70=00joQ51m6vh%X2K={f^*t?(p zu4Xp`y1N@6k0V?i%447(yI}vhEmRQ+<H=P8GWAbuhaY^6#U{phwWmXr=beDEhUg~C z!FTwhuf5V8s)Tk+S<-5pwHSIM_bX+8Fl**IrKpNn%jCCxj5vuUnPS=^#DHnq-Hgp= zIG*=ckGV9~;~k$;_=#)p3rWM4thp?pcF-8sN+!y+AdXPL>NbR%6O^--1$EoJXip6F z$a+Njdl?i9`Mm!IZwV{=Je1sW22<p!7B9il_oOR`DQ;T^??VVP*k-^s)XL(wJY}f! z5hg=XVl__)rI06T+?k<+5B#Jq5DCkN064=?bZu=BdQZdG!xMcWm=leK%p(OOrmPD@ z1L+AdJH;kNYT^lz2R#QfZ{XtuF?)b1<qp>wmap%JMHFz`b4KDEz}hwX8M^g&)pHiD zEGzc_!G7k*P3b4vgTDh64PS<IKLQuJ#N);?V-s#c>A5wD+(_&R&O?iIFMk0kOHRSf zTQ~iKK!|7WKNT(%12U?sXUmYzxGu>n48n0)+MYsvavZ5D9Q^-|nHJg|sFTU}BdF|2 z7C%wH=3YGw<@m)CB5rw1gy?AKYcciyGON6lnnQr!Hwkdk1(Z+Pwg%<$BS?S$Pv<+l z$*uMSgnO_m`cG5ZflWB9@q4L4?a_kkNn+sj>u<gVI4m_&zzJ`&-~AecF`OB)tOE~l ziPx%(bH^AMDVW<8f)ZP6k6j0a{zPbm_sL}r7_+L<xC(e4T<0EJ5V)j34ElkyOFusy z0GiqiW**Z<tiF=x*O|q=v_ny2Vs0omk7`(P!c_|o#9zBU#bpi%XQ6h;{kkmYaREV$ zn?jS)MgE}BeZrL){*>Q$d=$PFBK>HMVz?2RIb{?UP*StE43Ms`_`|&qjcVeyD?m6> zIBW)qR=onyj%;IOKud7&bgQXZ64o?yshbC3G=YJcn3$L+FNP2$J@5x^G<tD2Am8%O zirKf6EG_PgZ~gKpJ5WNGgadF><`XgstEeie)M2A7TzcfCm~8uhr`7(-J=>l>8mp7L zS{!7@mHrUAAhv|e;gf)UG&anGdr?@AWF%r($z%XytLza&T6^wB`#A|e(=8Q1-SK|I zuvHf&%!BldzFwI;AOOMT1&?MUw6K!sFw9BI&7Nz^pDIdAxJu%n3iYGKU_lu*Zzm?k zU<t)LG2$X<q55&ga>rmDE26Paz9kA~JvcXQVd??ta2V*WdWlr9(-$xnB{{CRN^O+r zgvnNKaC+n86J{TCaqT77HV=Z>{6(Qa3SZ@YbekL4E}|HR)fx33AUbTBf|FFh3vi`w zH2$JQNlzfyWo;^pd8m@>72@YtNkc7iBWcX|vZfg7V8Qmklc%5<w8}bs>$_pN`J__+ zaX(RB!i@ucs?W8J!ol!LV9sqM^y?G+f$Jx_8mIRN;xE2{BFO9g3+2=PDnjW(`pIa4 z5s%4e-+b4yx9?fz4+ThphrdG5KIILt*|Bh8RKLF{U9@`Qg@>e~i5HdOr_k>P@h{v5 zd>6PJd-CipepXxXf5JsAsbz2U>0y^$SD=AN_D;g-_}}4=xxG^#EJT*s6Gw8H%DbpB zLy?-M7r1+3HP^Sh6+0u5U~}a9Q2EQdC~(EO?1_s-1J!L0QOjE2e*(qMzpUNnf6sRg zp-UA|p-T}OUX5SXHWXF85+HX2B*fCie;TV7YU_c*Ch3oERA>}eRcC~X!AhiD+NHN? zSm-9PcIjAjkJ?3>?M^Cy*pZsPTcuKA%(E)m9c2rYKQPX;>-yFlHNljP_0bUb@EWtE zFBmy4NQ%PfOJm<i<1G@baZ|!mAu(K#``yi{{bEhRzMBiiZiKYc;(D;wJmLTW(CCi8 zubel($?NE%5v#S4NEg)Up`jg)a#FOBkW42K?<y<~X^Fr)6{E;at?QxXa-uClt$CU? zxSf8ba5^n&_O<t3@!`EbU|%L&)koWVQCs?{V^{S<!0-!2KClb@I`lsYVKFlCNY~OC z$K4}p=s>FTe1KsQ#PfVI@cbd{Rn+|m?>P~pqyorK%V=E|_jZ>w@{SWW(J)4Hd5IlM zTMAjf0Gg;9FH!r=*c%)S^W7G9KmR~HXo-H-_Erkz4(Cn9jRM9|rFQL>u*kY`M&kmx zUNjS3S|!lPi?%RHf<ntuBqt`^Ilg18u<4>nTPul8;Z<OC%C_CBQx`#fbZa3Dc%Qgp zpo+$prPCSQMeca$*|YO=7>>Q;hSCWULKhK-B3PP9B!+^yFw=3o6RNPwm+xekk`?XL z5UM4Je={L`r^7zx#S(|+T|C=YO`_pGEJa;d5ueguF^}OGriG77)HStBI}M%3#U00E zo<oqo)v=tC@_Sy1j8%BNDvXI$Xn^hNr~N7hWX7Fq=#PZqYOxE?R#RF#mMA-=+Fd@_ zw@C?0Z;pYoMSe7Hf#^RxD%CAn*9fDpjU6y3b^58-eB_Kyr#2A`N2#D?IgrBV=*);4 zDqOOe!hj?Zg&>ZKM~$TOCY`}$-Th<h(;~0ID?H+Uw+YvarDvUCB~LC!7@Z&q(w0iZ z7G%3Jrfj0Ypgme0Iv&F){h8+-=*-Xys%x^uKz-9vs~M98Y^Yt+D|=ukRnamV!5G$P zzlB1B<yx0Xa(!qa@UyxaVE790=CN2^kYQSCeht!M?R;_VgxLz-u)4zj8cT13JmM+0 zTZ$R_NRg;YV?<fHN8Z^?4#w@sZRFP67p4(S3mxFspR2sblf4H<4t7Wz2$3bKe+I=P z&T6&{XUfU{NQKFOq#xMk0nEoR=F~P`d*oqXMr*eg(zTK?k>ENj^Dc)?lvAatM~bGK zry2~c5unEwq73h0YObD1QB5~!ZN<8oJty-RjKZbfP6&wV2zE1~F56O3EjlF3TzpZF zLP*0Cc&@M7W<&6>8QHOvB{dkY4~iv|;2Xh;mDcY0H>Srq_KYg&@vvL{?RRoGBRsDT z0aa4@&v4gZ%(;%tYkhG_<VqDt>`??Y;;E-%3>pif!GImtvEg9NR^4w=s&<Os(Y>>x zw~)h_f>Vq6v1EQg;LpI2A5$-bjj2oXBEfEEsHNhvA7CbfJ9yxPo;|u{MhsG;lpxiW z73T=vwf_wTL#3}^npCxwy=4r7!B1I_Bm``fJn9p?9cd{Fm{|(jjL~f>Kwkw#Myf?$ zb64^rHU}`#xrtn|ShNl^xj}hVsuo#Ky<Dq31Hj*X<d*_i)fn*^_wJsiWUi2hs|r)x zZMQ*Rsv+919i@)Ci|jnF7~K62i(zq>k$6@-&i%0T7$omwkDGTC(L_16^;=9TLVef! zJs_UG*d33m#Gn%)i$B|ZdzJ`)Z7OtcLx)g-p*SZr`u5)(N)~hpU+32+c&MNxOF{pE zqRFw%`|YB-q-v_MS?rKA8kbMRt!xc{XLNL}RD5l+-?mbMxD|?U4=?3WA|J~5qMNuT zoO|+V<-)$2wrF!CFZxMBi*CjHsM3hRikakFA&P=5D-NMs{xY;TIAAZ79(ulYW>K*} zgV781oMT)Yr9*X<@pG$g<rYMCL3ShH_fyd<)&F#u&QsB2@WDdh8O<6d4r%Ubv_yVE zPOg78%u&~R1n)Er#|o;6#Wz@~GkP?oyM<c|j%kfV3f8dK&9N&lsyD@GQA@7Cn+M~S zNFdHPe@8D$^!T%z16iOG1eyy{4{DhxcX4qa<TMmdNvx^K{&hz;BNb%9H$eiGJkX(( zfZotd&m#1Ug*!wVW|-)t2c!{1k2j`PWQ*4s{EQycFTGuWsbf*C{$aC^O0Gt;)^F`j z%<D(8;-sb9fo?c#y&R+7r5GRYhOx>}mhy{ww@HPcoC8m<L(hP#0!1ArDRbt@ux8cF zwau;+lNI$Fl@@JH?<&)ZTm+x3u$%{~0Yx%0&A2k@7`$7Kt082l`@m>Fguy9=u7y`% zGs{t(SK!?2Xagz7im><l=FiC3LF=#f`Bow|YZljbT#<h<ev;mB-)?bk0{c%)H!K?W zP~!U(c=qPxWIn^?@xRw5L$+$guM&90#PHkkN4$}v)`)#SW)q_~nx(kufHj}TA<kl2 zko?3C>M#&m#*{wjTMAfC!>53uuvW~1C72XwC<ObPPm?*MH96uJ$8p9(W18PAW14M% zt931rS2B%%sJg~dNA1-tafN3!sj9an#86}QqtgJA4x`;r7FY_cF31C9R~+Aw!$;v) zrm4y8ZL;;SLIO3mZ~Y?2xO(c%Rmm2vtwcnb%g%U^72CDK!-A&ZxJLVTVxZo=n#o7V z0Dm}D9!NAag_B0eyi?}H+D7GXXv+4Kf>@X2GuC!SMr9wS)>$}<tD{+QPQt@IlW+{8 zTV)WRc1zv7GEv9G3x5$rleTP77m2vg|B%36{SPUo9rq_ljzQ_i^*x3~dsnesc?Y}l zU6D!A7pJI;zK@Hg`e?y!$iC#^P<|?+J_=s}H?+|@3oy(IYj5`UJPwLpYW~%CG>JdY zu|xXmi2>i~ap1O<ppZ9^UWTkzuplYW7ij2?W};af=mgEk(0zvKuiCN2yn-QZM6=~6 z=qmI6CZBye;p&4>t8nUMcpycM6bS1zGY0rnAy;<47Cs!}otHqNiZbd^141BI!uL4h z>Ld!wojf4yu<6WH+FAyV1`R5%X!sv&m>nd18O)~bqIg?XUN_?be!vPQvuz$RY*85$ z;$NS22{@t-?c#^p*fHwJ@*9K_yaMlF7x1Epedb9c9B2C0;`z_*FAipT*AbR?U6q$A zB(Uk_)|Nu}8guwgqVf$S+?xJrl#XQ5g3kOJ+wY_DgN|O&XXJED?H>F=v_Q%qL!CkG zv3ee@F~+cFWTzeO9%T8aFAqR(j*=)==jjR!9KU6Hq(Y5E`D$5TTKX&7VZx4QqM2av zy;n1{-k=p3HKi#C9bRrkxUhn4u<4#Oh3wKgjRtgpB7^=xJNJVE;36XpIBsFfup6M4 z6nemW18#KSUt?t?(JPlAWu9E6wY`4(B`{79qol@N<LpL8o~x%y7NarYez1~*`piza z|B02U*Z4-T3tzwHe)Z%yw-M_N`in4BP6=3b%SZoRVh&D40e=_VMBSqyag3<V{qj4K ziRALQW`%q+_ltnrtt+Q}DFBuF+N)b&+D;JFePqwMDr3?=YIKd#DJI0BHtPbP)qse$ zx0%;R!Z&8`<-D?d1k;S?Oa9gS5z1yZ!D=Xvis3u+h|wB8T&bL!oJ&)l38boPgP5G= zERb=7qkjMKmuhOnkmy~N^g6!^_@AH-f0yv`GPyDLIOK><MX4Z>gLGtxuLVJ*Mmw|L z8;<qW%CMQj_Se8%P&M&ac>yB<(g-cloYD~(wsUx*kN^p_Bk8Z*hWe=OO_cd;6~sxw zJX*1k^ju1yl>E4^jo!7MA5gU(lH<(F5mA32E6;D2gzIKuu8nhv6hX)$ARui^Qyj6_ zo}}hLlvfMol_FuU{4{}h%PibDfrT}l&CoCBR^|LCOmE8y-jpml`2HqhcJ#J;(M!=~ zbk_f7*VUo^_`lX7azue*$`cRpGG*NgIvU*gr#wqZf|~p(&w7B}4@iE+{v;mYyET<z z`<&08tLT_PYv@WT*iWVSOF+znr@-CGy?P$-S!7e*PRH2ABi+m_GX`bq3Q<J$U-0Jy z)BgVn#v~%n>aj)KK;}JsD=!Re%R43+Yw(XdK7ZW>@H=gj_Q?_ciMQV6U(ceZz)|pq z_Q@TOXyij@6%O`K$Z2L5u(Q&Q^<K~pljdO(d?Qs(#dQ9{L^Pev(Wy&BOs7pmvu&%} zKWRcEQxO7L7LL=;#&i@8${0v4ZjI=2N#ffcsrLdCg@?tV%eg$#<z9PL0f*c3$b;{D zDxq4#VK8eD3WZXV8YR9k{ow1B6CT6DhoNpY{YtK3Yu)+Pnc@NkX*&C>uG1p&P_Rbq zkjIT8(JZ6DF!_|E7@%C3-}4z|cTx0+7=CD1sxyb(5fy`*7-FW}HKY<Bhggk=X@tak zs@{uNJs-W}>$Owq8PJ4-sh07<)YI;>-z>PHV7VSchlTn~c)SqLq57*<Epj$bG}xZB zquT*8G2a>Ki1@AFg>ly}m$#m!vb0mbt})ed!WpibZr$#sgH$@P5A*x$W-P#L@hUoE zL^>{_i!<j!PaF`mInbthXGqIro$GaV5`Czt4X`PH#**YD1o^j2bE_pI98n%gq(6-O zrb}ByuI!QaMGUk(JM(Bm<`9)>$xgvVxiGYkhh+6*^WoW4dBt%*ARyyaI3YqH@kgh^ zA#H}Qzlf`D?<BbDsrPq_Er^Kih>Ox6B6#5f8nOMVxy$`?pgSuTq^)Y=1M*9Y%4FQJ z54SB<Hz_&&8G@!g*jGUlqNiYAjY?#!o*a+~BrwH>lztqi@xq6WN3zrr?b~X9StIM{ zIuI&Ln-2v{&zLjK9pNHz2mkX9%9&^aMRtjtO<j>=XQQ$@nYnV@PzS+B2OzU>dQ<}( zG0BCb0T8>4DPRH(XVgWDvA&nbF$<{9B(-k-Mo`^q_JqA3?3@MK^xh8~*p0m+Z-R*| z32Ap*QIhX7caiLgBD=UDjpxE}N1Q1f*2d6nZ^O7z!A68*C`ZOSqfzblB~QmDc%Q`g zkXk7A?!g31=QY?ttpB?fGM(^<D5Cs%yW5wEd+dPR$Te;bv&H{^fBg2Y$^W{boQ)3% zBc<J~jkBe&r4nlUZzOn&rJnzFChbo1KjIJUiH+_HqzM1#qm?T71(6avFTwtRf5Ls7 zMQ^jGTAgLRDxthsE#w@E(0Tl?2ho-4|0Bp4<IZZ9P$T1orloXY=qcKJ4S#!?Py@UV zs-BM8xU<oaU^phwXG`m+R3e=48WYh1pX0Y*nBQjMAGNIA_)x2wChIUkp_|~37075% z2W7bnoQMNZU~o9ucz{ZNjJiSTXbWh>G&Zw}{`*uJYCs|N*O~83B0mkqct3&@47VWu zUX@Ulakc3S&Nn+q<8e=L+0vXDR?JyTe~~3_f1xOjfv%MwFVPI-u(^VzztL|;Og~%b zrD6b_ygPQdu}qaL(~`UtqdD)j+UD=%jg{-`#(CPapN325Y<JZ}icU^cn9iqP@6Nq3 z@w=&xiJkS55J_=aG_7&XZHcbX8P$1G5-lxavPvq`?e^U8sp!uv=J)~Gc*gCq#sP{q z6#>$O5LwF`c6&wuW$wgft<qEG+7Sh$=CXmaFcb;<mJB_ZV^$twwtl$Hu)T6{`7tta z$Kt4aHnC)eOlK(7z#)vNAN)u_qAhva8z*(4vT#YM@u%w=?T=*Vftjmu#nbx?J_7kB zawdy6#x;dE67L`Exl8{wl-YDi+>an$YBVt;^nlmR;ZpLL#MA+3rkKz{`I(}WgpeN; zNXl6t<(*t|qy>3Iec{GH-2Ts)(v*Vj7yG5g<`*oUwRq9?Z7q7#&(}of1-^Lb3j1)K z*^MhIc>1Eb^IrY7y6jnAv8zmNmVfvLdpa+DO_l|58LzQRc;yeeR<~QRhR|8o=JH&K z$H;T|+rh<S^}~xToX}T_xrgr&cpc7$x*vvw`Dsu$b9hV!qjKXCcRM(=^_X8@Ax`|u z1x1|49SSzf<Y#5p6lr`pYi(Q1THb`bX4v^mYSVMA9Id}>?|9PCDz&#p2qSR~@aXE% zAag==Y1&2i)Wfk+wP@sKdFj=d$yLJ^i#~<!CgUk<U5Bn-f7Mm4vjIRqR-N(A2%Tf$ z$xyK!p7u$&Z=c6xecIK3Zz})o50iQ*3u5~>2q>JPS@FvznjM$)@3(cXv^)PdC95wO z7S(<NQ^rXy1DRwq0ij%;45)Gm{gw;wc@)(?rY0(@#)+T6l75Yw`jiLCPy1-J%bgWs z{J@sO^Ae&JnMssI{wLqzpOCG)vLE)|eEBlNNQ^mEvWgJ69z^hG*X0tv)X~+e{l*Ty zcWaI`&eZoHs#@giOdY1%2BZR0A3Xz;YslC4G|{CDE{jAJo?9hu;3Tx4A(6~ao_#1p zC`((%&dmWuJK|vTZR$UF?8$!GS4<COC-Y(N=iF;o$S|Xi2uPzP?vq2@v{P7GToj2w zhPG~X64O^xmU{xw1q2XXR{(0t7Zu$#DnjTBFMD7J04@J3lY8)K(dLu7z0_uUkO=H3 zgrYJH-tVqtv(z1HQqE)xPq1Y}A_#Rle)fSCroIoUWkgQ?#4=IG7nv7Kewl$k{qtk_ z_cuzt)2oA`wrdsuEn({_X=IrtgUJe;Vgqa~x@G35tb<|$_QoNI=ihS@fkEasX|L}x z`N)}to9ByIF+XKHS)GCuX*?3+gvnKqO@?7Wmz;X+!vtor2%fQUG!$Tpv_u`6UJ*AB zA#u-0+z#XZBwhzB4dh5S8*z%#c-{j7d>Nre+xyQ?lhTu*Q3(}Jk7H0g7s=K>Fsd9@ ztZt)MDi;K@vZj{0f-OS`Ygg`PbiurOhP!`H&FMHn&$^DACxq;O6c~8$fvSSjxD)8v z`4&+DEZYQvawZK=$t}O1=iL-;*~}Ji&?Vps<e<Rtp6n-sL57+4dXMG~VZ!aO_=;lc zDI3|Y{hK)$2D9$#4xYZb(9EIkFCQ472qDy%{*^nysaS@u!sqwxpUZvkbGe6nF85JR z{2r1vl#Wr(JdiL>$Ed5Qwqn!P-koP>G<Ao$99K7z-i32#NSSF|Y2_Hv-h?zq1qx6t zVqw(=%FaO!y{&ZaWCQILL~!%R%cXvbf%`m)Ej<tt(gs-ZS>?^FkcGVu(Wq`cxzH__ zUAEy5dd9&LKjtJWux?Uhz=A%zbUoQjAy^Gjb0(^tDUd8)y{#n1^3_csSZN7jFTJ_; z(?;A*ZG@w(8@88@l`#qA{N@OFL!E~Zxe$#ru<0l%O~15%3#ZEWKELYQm?1?8^yQP! zKs%F3Fo6T$&H`;SnI$``Q#SmroI;#x%*3B$yA9+pugW2OOhQhVdd)}=ESxJ|o#B!d zDbwteDo(X7NFTQxWL-YMfq&mu_V$HYXslXAT@}dN!(Mbk!(N)#ULn2y0Fqxade6d# zX%FIGpr|s_lYEx<Gdcoy1G~rv-r_&T-Zo3N102N;0xGc9F98Gon@ij8Ep;dl0tewQ zm{ghJ`cPFg<IN?Y=I!^WkMnTo2Z49W2j7G|%JkYKSQ82#q$0B0vwdnAy!Fu~DvLCH z&@^4dbMYh5r(S1T#P`N46_YjmPgGSCkIM$~6T@KW<QB1_4G;igCgYKLun#G9#UVgb ztf<V35=FXtf1()B<l7=AoddFz#LQ^BM5Z-deRd(afVlL?P6Wejow_3`hNDtlP)_O( zQpk@KXaX^;AIm_$r?7d?iK+0+Lhe7^W0p!J)FRq^;bA^2K*Co?o;#VLt<MyuBjkBP z0ePU<*r`k{$Dml`<j9aT!pDY3fkDe_R@2V?nJ|aT+FzrD#QP7Ik$HP4k~-ZqCe~Yh zSp726;~CGKyDy%4GHQ_HL3(iBa+i>~;*w*@ygpf{&!5~3#W&|XypO~W@yX0D=#g|n zk&X)~D0>0PYh6^yea*)p2w_<WECocsxa!cHSlslZSJqzymyx-6H>4v^xI!wBfzLS> zGco~TtOl7x-A^kCHP`Cefh8A+en=+gx>b$|j?DCv^Qg4xB1qLg_#tVRXn96jYpB;0 z8%Vsgm32L~L%K&S**ivp=oM~%{9JxrMHUz-5+sNt+dz`RLuDq0m&s03p7Y5=B24=x zaEizw&Q)6=z%{hMfRqA)FWb0<Cj?^ZD$Kr9mbAxJ$vba@5<>lMY8^Xn!^ZLCX(s*9 zPo~}-wjd^d*j4a$FMe)ykN4q0=VJOg8s|SwxyB`nXWT5u8pqWTCkmB2&p;5ZS{FgG z4`1DS*7h6tqT{fjI9gC2XmE)nmk#i#Ve$g6>Ky5=3|VEvdH^Kc-r?M}?^$WXiOpT@ zYy0}vW+_PE>RgqpA)4O{v{(o$b}n-mRYn$1G_=HVuURij#=vdOjE(DZh-q^_0`3g+ z^*CqbJxjz9luGA9#aoKzWWGl`fAb}~|IcLKmr}pfKAl~kLc6_~H`lLzA$%mq5*U=C zW7)ocWjRYT$?{N=IU{2IQ-kOKp$_ovDp%~X!r#}zO|@ByHU8Tve9yVcJB8a&i0Rb$ zwM%8P`8y6ba+*&06NP{&sAqx^-Um56^jqFvgwHY+I=C~JsAO^0CykGJkk{-ipNP0% z81fMm7-D7*y{O)FB#@U@&sKH!97px+Fs(=<#<ef}KYhJV(Pc&J;2g+0*8|cBR$i+X zj2+(2CW75fb;w3TUH??LMo0}7A|UV>>J~ESvE?#g4%HaYvJ#*Vg~Ba<mR@;zbt1n1 zf05-UN>fn$e&fn2ul)Eff;tiJ_DHRb(6%3v=L?~@x!q09+nbqn2{{#)veuaxB(El) zPr70^xKbyaDJORZ(>8J(mDe=ToBmJjirtOF68!%o>mB3ce8RTjjcwa@8r!zjxQ%T) z+1R$x*tTukY2&1E+GqQ}?+@?$JRkPjYv-EZ%<Rt2Idkeb*v{Q!QFA~yQTA&xQA_Bk zKls2<vb(o9<Et;-XTB%f<VGqoqt-bK4g6P{t+;!I-!RejwQ1*g#~07ncL{LDCUlwg zi%lrKnt&zRcsnqZcX9XXuyi)|-7^FvP(r^h-H}{n?V4H0JR`?rGhZJe4Q`*7r+b3H zaRQD1w6HMfZqspZ=aUX_{LBm;?wS6?_`8J!ckS^Zef>-f_3VQ{|IA;y?+*ie{m={j zT<2%kzW2ZN1+0)?pg+l<l|e#)vVHH4q+`zqB;=SXwr^5`--$@u=ic$R`<_}3{L8l; z1A_6F(jo$u(eFhvwv=fk|33oqXy1R(_QRI!dput~49gD*o_1wG{5*LZ$E!TRcLHo+ zqU)%MOl>GrNmBV4`&fE|IA7!uZvmt-H5y)Bdi!3ZrXM|kONAjbslWqaQ=;riYeD4E zDbDy`6-1G0S6~SO>vnOA18vxrUssA-=j6(Eeljy?<LI6;Ja<vJ23@6q_KyJN{g)i) z851@zmJ@SNi9Uf2w^ZA(KxJ)mnjv(ce}1w_E15GpquutIxz6T3FJ78T{Cf^!6H;Qb ziPe!1&CnwB+yv{E=Q!ws3VO<Q?E<QNn}cYBI%=mBz7ak?QQzzYYQ-u9)W8s${r^6m zlK%bwG*fTe`~Q};6W_S7Pjg8qg_p*Hp2`ylfchNu1ARowOE&4S2aOBYZv5Ya=YQRM zDus{S_x>Bw|8F$WNZ$YNH{mh_4UVJv*!+bpo1kMk?Gd5Nz<Lh^@<~#;=E+r(+4KYA z6r+>%2UQ^t+waqx#veftgnl3_(3(Rg>#xX`O;EQ%Q|Md!5xBVtf~tNr6kYvXb6PaN z`jYVoa&cy`^i=@KoM(Kxzem3_OjvsD3oT2TAZ;AaP)&x5Qp-348BdS~@fFChS|mvn z-<g?U?|#G5*`?y?VD1h4@D;_qounpc8H;(7vJwYYqtX(WqN&~N)+z9V(Qd2C>;SRv zl(rA)+SwzXP6XD-;S&EK)*+@8@^p$zbU$E;gSFYzHcDzJF=n>$M4;bJn_M^nijbJo z6{A69u;>UJaI$K8cP^qCD)EX&r003Y>EZljGk^e;O+o=?ykQkt;Gl;mWBG5HQI5<X zstW$J&<o@+F+Z(;^p3}QE2<ggOp^LbD4Rkk<zz@>bEQmC=N&061PG5MSD>*|kKDjk z+Y5QGBIg>?mhlA$OOFQ_F{?2=R`q-157%p)WvN5jBU;Q6#7q#&<A~ZgDKpH|EVNCJ zo2y^TiQ3&k>}13?Wt%D?<w7gJTNli^Ll;0{y!puqc0&i&?-NW$dhT}O18cRh|NPy3 zDG-f3>INb1Fe%8Dfzo3URnwH>T)>G(b#2IYbh(aP!|msZw=#drX^DtfnX@UGquW=; zLP61K5ISJo$^&k5upH_=UQy@Ptf5Fifs2CIewRoM%~kynPVh5jO@it`45<7L=tH9~ zdkn{o*@)^dt_VkNj{%*_`Pk4Fhug?Rw`N|mxcBpT3uIFot<keGaSHddGwG~-$O_%R zt7)HkRW9ZwN|#-_`^V9`+>Koq*$id95efc&FdWD}82wfM^OnvT@cDdTUePQ#p(CnQ z^euF~E<uVil=CW=b_kTZfVlu~%K|Y8_pu3a5qG_$`s<MY=%t%L+Cj#`i>=17efa;% zTnHD~=V;R;G#=JolPp&-NZJ8@5EXxj!~jJkp4^H}^{o-gsCyy5x1abs+#zq!lO%?V z!+U@Dn$ifMy4rty6d&ntT2Q*hVI(+VMUSx?ZVBi0W3$}K;v<3+@CcDFs{GA9vZz4# z#nUV9?;Lt|w|60BW=!$C*B7^UmUi(`#3U}2bw%V9s!lhO8PB_9H&OSEtR#u-(m#Z! zLI3YU^Wl0Ja=`*DoU>5mv^4b>jDyV>SpF=nV>xqv)kw6BcbJ7&moKKK$9B3Y%+h6v zpRhn8xHeHyDY=rbM9k*?2?H4W(U&tO+|n)Fou*Rj$2o{|Pb&B_Wa10j8Q8Xy6*L#= zqH(8|qgc|}iw3fu%!ZJ<K?7;IQsFVL-{2+w5(QN*=NOaa?m+FbhJkp~xQ@dfK0UhI z7^osoRS+hqi(`;kSoFQkl%&R(iYTD*f^!zdw9tuS4HHbd7WL?R4vMlS8V}7ms4zLW zCv%*%9qDj{EE)yKt&rI~(cuL?X*X$Ab{1r{28Lp~r|@<6?sH;3h3rwH*+s0sb&k@f zNANr}=L37@juYMe{(QWD@GcBU9wT-^{z8)*s<)~fPje(BFrmpqgb!B?&y=<&47XF= z8PH=BGY7E=vcBCIjfFyMk1i+L(shZ4*rW0-EgIvKFZf0wtXXzo)GR9Nd29-dt#ObC zl5A&(6}3?UfZCN6Bh&hCd~kYnj^@=Dkl0?nrnpS-p<kIo(^2>0@A>|7O|<C2zGqSr zzFp9KHBP|1qP1)o`jEo-o09=a>E5{^VU!t40ROTLmJe^thFxc@_d?C=s<P!eGYvLu zdv0FVvyC=qqi$17-ZjQvX9T}bLCtQKX4Mlv`a|@>Q=SV%4Gcbvk9?UU;FLx+|3>Dr z!u`d?Dg;sIi?lc6$rfPfi@x@4PAQ<5ArNKp%=4Am+=wcWWF*0^A8y&nud7r!c0VDU zZ7g*BFDw7g7>2kM8F;npbD82VZIdl$08Cfu&~0T*ca+sX)vmWx{AG)G7q(Pj@(@HV z#J7w2B^)yc1-`=)d9jas6ESeBE!za^OqGYH0_Eae#I3Sp{8tyy6C45PAG`M`Y$9xh z3TuF6Igz4C4ori{ikn0&SM9lsaRx#>0n|8$TdZs)Z@sYA0rddV_0d$lmWv?&&eT;h zBcDy=oibF@isTMg$P9l$+YH!{A?BNmS>wJr6VgSV6tMIV<IvA{?;*PJ*~F5#LqJ(E z^^2kOLi|8GIu~D*6owyAOQ!XUjD&XMx;_G6v#;~i$Q@x$3ZVfy>p{f8XXf_F-n+$> zo?-%iPkA;;q;m$20l;*CIhp!U^CucjLmB=0<2OMvg$=WV-X3`!NeR9)6Y`#@(lMRo z6e-5`&}oZ1-xEC}lRR2dm(vJ2fCp1hNRjrZJE{g_yc>iOG|&zdPdrHi<%5&wYI3r% z)sgG?8mKC8jy6Fs8q_}!QaoS5HMh5yvM0@r1=e}GsfbrRbQW(3?TKa!ci=mC-)?ys zeR&PSMTz+0TOjP@>pHG0q^II31k1Yw6X^2Q-L3I+GxhkLG$qDJB-qS+`PE?NM~?6U z$PKpdD;;p`d!zEt?lRz<Bkm>6#xwP<0v1w8RDbXr@{@_+_|59FQv30miG3~IHBj?y zP3mTLpu5P!haacs-E4CJVX!`=>wHjL0(x?}xAdep*MPq+TQ<iS{MLjsRj{`D=hrL3 z*_TCDR2Hh2R$OnmUZzgxD_<$!zO;RxPWNk6huU2J$C2;&#*p#H;|#Yu?B9=s6(1;& zxW5hSeYR-rtE09<fU8P(oXlMz1AkG8zK|$^Uj*PXx&0jq*i1Ne_mmLWLH=(M-E1TO zjEM|mvg}Us5|}Lt2yt0+*LXBYz<(DW{IlG!CeVUZ3f(!>85s=exL~z|Vk_PxS7wG% zzJDu)M>+j~k$Cx%F@_f32>?S`=krA$jhSnRnXmq}Jcb%`*CN3d9^k1?b7&-}yVXK6 zkd?>ORH)g_n0=Y~h}dthgAt>FAyj2p5W1W@fjGQ^U~UIwp6kWQ*K}=%bn8zSyF<Hk zGxe@DrNp4IG0WR8XG=yC6<?3zg$Y4PG@Zsv1UP-kJP^4EjD5BY=Gvv`{mWzQ9slH? zq<y!d>eohgz}Lwf;Yj2ZhqR^&1N%R(n+wUcL`liOtZAFx;y9)p=_?G_*w+Q0Wi;;V z;)Rz{xFL(*`@&i0K7Y~fOA^%lRsvj$Za$>b^IHE<SSRWn8r_n(Da-`84xW(Wnglp( zbkmJyTgJ}YgFCKZBD@%?w^RSUl4M)MglxPbW598UILoM%Xz0ThDGHmEeI_v(q!kY! zuk9&<UF!6T_(gdfI(Y1>zF>z~V?IHFY%Gwq4?~>zICgrKB+wYPx+iBBg(>1XY+n{+ zXRy^VRTh*Z?JxLcbZ2B}$$=`2rs;Q)q7W7!`vp>1VY`j{(u><EJ`{ssCqg2G$EU<m zp+CfNK7Jgf3x2G-Ja%ebz{y`Y_*5_kNe<vBx@Em>wP+(%)1D6k(emfw^SknYGR_Bq zXuWTQ`27RX@^8iJg0rtg@aya<aGDh`n9o3s8d+qq#3+m{oJGJVCT@Si)j&Fomn@ni z{R1Q|Q}AX+J}0Am<aftd9zCc0);Nt!m%hJXAPIkY^6c@4U#*a$Gccyxcq5!y1|5Tf z<1KRS8H?2XQkw-jOO=#Si)((FfRRIv()!4p$|7UU)SpJzuEVV=BcGG@ir51nfs8wW z2I=PoX>^CClQN;SY9n3`8%1>_j(#{}A?s^5ngYs|V~TX9<rt1)BrF;M_EV;(VY}2j zRksFuY$SzFg?9!jj(&Bl8w&y&Y`w(!lDo^p78qb8S;sT~iRMY}{DD&!iIy9lJ7{hX z=32OQ;X-;STel}m6x1kM(qgO|Emr7PS7R8C!ZZ;p2|q|m)GKw4iqx#{j*d-u^0Tqc zg<wHCIH6S$af;aZ2gAOf8`Z%#H=NtgpL{oQ6-*tSv&qg3(K7cdZp|KylU)xhUjffQ zw%BhwlDL1!7hrCtd(E;NMUGxXhgQHWq9w5wDQF#Jdo!y|kJGTMKvo_kWwm9r!7f#$ zRU?<Ggit%cB3Q9D25X2}bCjiwsB}{yaC=pL5sV@xMTukQO<9`+ixb-|ntJJ4&f0Aw zqUS`PjBAc^kD7+}OxKn5Ox%F-WoZ(^#nj)iqEsuA!L7ETjAxl+X7u$W2z*fKQ)rXx zM=aK#eb@4ysXY4xA?HkvaMUeF?ncCBoWUm&&y*lK3U~A%taFD{lN5ka*(F)Vm9&t1 zzHM#`h+NbGM~}=o)O?{Aq=L*+n%%KnUEONU|9(qFMcW&1nix|~|AXJS(|mqz;50S8 zjwrL9i03UXlO7jyIK8Q2Dls!o3uh+k*OO|I>1lY%HnsndaT0o&ab?WMJ+8MLzY$8F zFp50<J3~@Ln!X9aY1(_UBKl*Rf}J#7D{+ZRy;y|8#&=St6NMlK<8WBH(30Wk`~wkq zaUAL@$T{9z@LL8)lkYs_a)As-L`jpXWKWFM5IxDw^p04WfWGQi7X5QjNNIFVaQ7HD zlo0YaQBT1Xm={s(gon5k;MO>})i1r6x+=!~%ONueG6b13Nk!QO>DTcj0d1V*fniC$ zu@cmdDD)6EYs9D41T1VyGNLG|=IDoB=?eZE?F#}6wJ+L@kdRwyl(vAcJ`Ze;{aQ6R zlol=V*15BD2HPUS%uyw)vbn?~uCsexLJp|{J^kev{3&Ws{!)>a3UPmx%8+X+UwY=L z2v$x;ZU!_XZni!>oQ7jxsY8@s#=3flMkju7P)w+5=G3xYUr%PoNaSl920v-j5N*CG zUv0?JQ_t)v`{Gj&xl8V!g~E7??k~m0+hSSjN{Mg_{SusI6%8_#Vkl52rLK8B<bj$b z9&Wz~IaP7lene|z@VBc{hZMkV)l{2z8|1d2E0^)q)v75Omtj0Uga&ZyCJ78*D|-GK zqD#=>Y*xmJ8O$sjjxDk5-6vgZp^BLkWv;g2#O6{Mc2b!PkGy^Rmd=eiuoRifjcIP$ zRhG{aXiq_WVJNBY8KnfyNGB7qSmSK<^Vd3&%aN;BxsPh)AK?84*<&uJx<J7b?0s?V z91{E?Spd1d-A_9xc1)FTd9&+E3;O7Q@ksHjr@!5$xx#l;!+)mt;cnu03r>|kR#W!= z%w;^=fe$bwCoHdAu&K<g+uW)RNpVUvJDc9<n5(+SjlSxM(>wvMtwlELUiO7Eo<Sft zA~RYBN*t$d;L+@UBgo*JK6C~}_wN4#r`8)i+0}S(d20ixaQpQgfq289+>`CriS+us zY{3&Od2vQ2xc&=10eSALC*>-da)cX1YD_m+)6Ku*W;@|T60cWt2^F;aAWbJQ5ufs@ z_G3kM$Z0`SgIUl?%SoLtnM>0KsAMKkNN9H5aoyTq2L>BH>)8vNi$+J)Nq5q+K#+h+ zRU*r>+D)HC^X9RIM!vB?BH8G{Bf(xAW1GX2aG`aDDGQxPK5>yD<IY+McJo7BGD)E$ z4ZV?~mOSzt#^(D!Yc5P?FYSlV{kUxjnk;-a_k|QbN{*Xqsz0-nlm&sSlbcHkj;O?d zYC7ew2vS2`mJ&NIZwPd7i9_X~>N@ztf6zFgr0$Q>qL)NfApA5CeL<+!CAqRKlKtP| z6P@quvSd^=hms885*}L{AP3Mb+WAj|=qjwrvEW(+;**me!c%Od1t(@br@hQFEVNsb z(~LU3yA<A8f1>$sc3d71Z~9#0@$X=s6G<Ior_iw1xv<~Xb=cLf`b;Nc!nNef#^4N4 z-yZ#|V-7&!J0j2SmK7CQe8GU?*~~bjc--+n1A0U&+*_~9^A^VV{TusD%2_+Et=}jm z8WD_D%tOs}WmUT=dL5($z^+nZiCrO&Vz+yNr)0ZG!(Utx3pRawbf5Gvh^MqSegR0+ zF%}C?QOO%F5PhP9uJwDcI;U0%t4YSy!E*|w)GLZC1dMEuNoL71%&CUM-16b~t4^ug z<8@SBDh!ggkduogu_=$uF^WrF1jgJ{%piEwtX;`puw0349o=~K)6j;{M91DQoeZpA z!D0I&7M@0tHKnEj4bpyy!}7z^*y8aSpgd9TZ3_u(wg=at9kShRN00O9O9fVgd)MK5 zV5a`;I54x7+F}?now8%!W;iCeKbJ5_VKOHz2R_mq)h99&_jA_!aB9ldp~9%M?h5g} zdSyozp_8rIX;Gt!P}Id$fIKfQ?mv_(k2vI@JcB`+TAApr$+|u|U|rj7W&EXSq6g~* zEamFz4b*%y2xsZH>u=uq3n3U@OLn4C*9_$T)AqcA87HRiGk~M^Uij%B=bI*<JN7L@ zZ<EeWIxg<9L!A)ACNp%SnbXn&V8px?I}av)<k!eHyT5pnUwLdqzwyWh@mPeW!@}cJ z;^I<+fOc=iTSL0m7jxqj6aW^Bec`y^jc#_st*Mw>PFR_!7`>en3tE&TKa#*5-r<kq z)pZ;q_nd3K$^%YLMhyYa3@|M*b$HpSF0Kw%8wC<|#IGiH2|dUnXJ@&YCqL>2(o)Np z5b;_^x7YhfL?7x+ATR)y`#Xkv<hukUps*RCQQn8FyF1690u;_iM+eIrWWDCTw$ICu z@7Tw)d+NK+rvop>&a~<JoI=!M1Vhu#AUejy5_Y83w<~tp$CIsZ_<PL!kEltHK}F8I z>7^KyYD~G+?HO{F!7<JLlA>r~(_%rSJt*Z($oja%D6#d!de|?dk3jF=QdGmtqY+}F zxTq;2+l#R3B}92t7PpIx`w%%&8HtQ`Yi4Y8S=qz~S4}2MW=!K`26!e{p~$+aw~;v* zT!Ko@mA_^F68ZAi@{kd+EDYGI!m0+8QM15-vimySQ(4JX{lA89f|d9(2xJyXhPJJS zfq=>>Yk<*Mp->(1A=+>@1#SvSAUYrRs-DjNUMoKanj6_O4NCYmSV1&B8&F*4ub=Qn z`?9#V&eo|TVCQ<lZR21h{7}InkPaG9_j5r?<;;_ZNRPYH)p%IZY2SUxTUa$9e~V&A zk}^o!@k?Rz<5emzUtpSJ@h;UYc{kBE$H~-)a&y3Jz>YHv6NFA$;W?xR&8LXp&1>c) zC`AOm>2IpYIFPy&P?lWfnjHu#i9rhM%P{6cT={peCNm`^iEY5TA#WV=hNp(UtcF`d zZK{l?$$uN;<onvQ;drGO^lT=B&TMf56$7{~^39WFa%n1#<v{I9FAq|Pi5~wtIE^eB zHRppsGFE{gq{GMd6+hT2%mhm)u_EbSQI-);7tU3CIw=TQb8xlRGul-miEAz?;ro?} zhKR1s+G1NRzw!C8!rFYoGBL$2aXabR{I2DxVl>c8Ny(w%MMou240Vx?I5y)W2jX7y zZ09(UB0ME|wV1o&lCUTPVn+zJX>vy9%u2$P2SlPFNtkdah052ck=3Xb&aQD2#wy=G z#&oW+_N5jDO-)AC(dGs#vUlC*+oliAV?Fm2P?Ml9|0T24Xe$jdpOW;z4t7kszRYH? z9XE)|PwwZqEiEvAb&^cioa|OBF4Dg=|FA6n$mYBZWfR;r92!mpF8-~r+HWF`nm6vW zXSWDU*b~4T_%vcfm2iegYVRahz;+|_VO};OvoPK5Q>B81CM?Uu5k*cF^{C6`w*FwK zMj70!@2iyPC}UDwGLEaBCO{d&n#9>{VhY!6!Ak=sV`guX_5~n^nc$qPKshF$(PTpI zHOHhLUE)~MrjU@!zjyzNEi1ZeOsnOb4jE*iNh6H8icRScuB3|-=$76dsH!CpJ|h0^ zS1?_=tWO$8c7J>B6XICQL3vN}`(pg%Jv!!440UhukJq;N_%emQ?{GJtPBF{fN;myY zL%_wljbSQ8X){D}P|>MohbhHNJWt!ykHtxn`JXis!l>!p^hm@N-0Wf??Uj1V5XAs) z<|HJ?ERZPKdL2}s!;L(yn|{q7(#G2`HC$?ym)PC4S#}N(tztM(IL{8NzXSzLB#e{W zb&?j?`Lr#F7=L^)dHQsKNdO)i+X46<ct(=6OM@l^%5|;((_wKit39^ZEcC)UCfR7t z)V{vunSICfyhgo0XCSL>RX`K+1`qsT61Z%CGFSaurV%;^AEi*NIAx9NdjJ?shx6Y@ zxOh{jJ&R*8x7VeRve^U!oKqU{K)t7xuE^JKX3)HtOgB#p5|cTM8dQk0L!8Zb&h7`+ zC7@*s6ibfMg40XAxh13nlfuQHC^ul5(mNJg{BJR7BU)ll-8Nfd`^GG2tSY|eN|jf6 zW|?vqNjhh#!Ktb61hV-BlVlj$$agoJ@!_?sXmkXsSaY2=>WbtX8i<^kJEEFbS<Vk$ zkiyt3e1sJBq_ud72e~x;gfxQOpG=4Hox_o~;U>fDJ4V=rN!lBM34`f?4)4YCMZ;W! z3jLzL%(6TxFo0qvMU1vQx)Fm{SGq&LX*PWvvQ~P-_Fc(IGrU&Q1DLIRs;b?1Ujq&p z^dPgPwS*dB<mLi1_RZXf>4n6Mb?J&l($cFkZLUd@A{{caw+#;VlNX?;S}BP23eF#m z5m51JW1cV>9ZCx`66QyOu$-I^i{c-gVjfB@wBgj*X(af_IF=JOz)O1R|AK5o5HRQd z9c|tuzY43TH^|>z$R?a!G>23Ctm2JGE^h$i_R4Z>&f|~m6T0796Xex}6yM`Z_#?ku zrg8c?Xg#hoe60ZQds!!*bM%#u?$11i1RH!{6sjly{-K>^rZrXIs`c}T3Vn{3MUFxw z-)wsLt}#xQ*p$Pi#IN$Eq}J~+U9XJ`Xge;vny9Ah)|GIRkrj=?4sHNTD8yG!P~=TH zV?!9Bg9oo?KE+bdOVQB(er;%YJt2kA8usIKXm88JRdzV&hdlPp?D-LmxJz(|BDzki z?0G9B&k2HOJN?py-Cg?Y*M3^!Uz3KqEz=1V2s$vP+FEzxdKV@Qd0z=R00ri{>=?IQ z+@rKgP+J6)Mw!jA*{*)<g#FZC22he^iGzUOx$#P%OXE4;|L|JY2KJmnkrO*-*CXFo zc?Bh_oG;87mPuHC8gM$u)8kz%b+yDUAwngj89N5~VGwpnFWPy5xkkloS*xE6^X@Y% z9zx~682deXXAN)HQcmdT*GqrF2%PkX&DbuHwFSlrY+k~cK9}o5OY&4Was3gGO9D9t zWo^%?j%L3}l31a$+$ONYAMSwan$<$r`9gbZ)BMU{5iH%A$B3IZ*esW|&A@UZw=!k6 zLf>MA|GE4>_Dw-W)1iT4XNzO{6F{pRXz`@3dUlWPRxiqR3DMzHIy<To{Q}4BK?XDk z98o$X>(jJFZfa3hQal;zJ4?M;mqtlS`bfx4Xg5^k6uRwogO5^xwclHU?L7dyX&N<* zIbn&>fW0*?!P3W7q_O+#n|s9#3?tg1m$9OWqfRr1#37p+QFcI?U{&UyEg=S9^tz8R z;~b9~l@+6+8W*+HNNJ~P;D4oq8+YgK!|Wz$s)<kY?+&UciuHgeuru*c96NvsjFVVF zDEr*g2bf(bzkAZc?Bw{zgZQdute%j{z`nF)u~m5q9wQW;f7<b=Fr)jim7o1qi69<~ z{6!X>BQH;LT#`!#1tx_K3$&-<50D-OqBdGG9~DN|RP(M)SWDd1(T~#;njST)?&EGA z4hWSGiA~H_4UMfdl?#fZw?68#mSc%E+DCTCDr`ezzSnED;*#6LzNm~Y+i}Pk?^Bsb zG-hTj7Y@g;Bj_TBQ8I6xn@5lLs_zHVGbM46$99o1X1Z&m8`~kT3{)W{)su^hPUyuW z*P(y17b%@*O;$@%NyN%EDo~O{dZwQ1h{a?c1`OC}c?V?o#1%$vD9TmPKwv4Lr= z3C}{jlzJ*lFHSa;5W`5<W1fR!9<&PE(?E3)7d1DKjq6B8uUE1H2#E<0*&8Htzg-~D z`C*!d^2i2QUXvP6@Qq$=q-Q9h_&Tdqg}i+i-l}?w?MEt0OHWeXc^pc}%Dkb?Bv(rz z@TV(-RxG}PAiTI0!;f}QOUmc<Ghh9Hx7vu}7NIfkP$cmnJyZ?=g4iwm*ySu^E2Yy2 zH<GO@HI;Z@A=BfZaHkizX1q--YbM{1#~@`*j=3VI8&71nA1b2Q0x8jrv?JleA;I7m zH(3`$U~m>|hK(qhpNf-HAG33efFEv+!F63nJdQfG@zMw!;HGiBd9pXGN_65}5vG=k zi`z~fiVW04MkAk(LQTVI;0%*6nMx;R2!iorVf{Ldy}1iUeL`k+@md7#w7pD47(P?* z@!i1JZy>eTu}yyJ6+_*}&sXU+V-wmjd+bOIK$P#WS9Jr*{g@>|@_W|mAw%}hBl>d< zfOJ|2CT5xzAm(>$f^Ktl5i}U6FG$7tg~XPw<A)0@Z`l<o(N65Ke*9DiJNFX6=h7vD zJ~31jp|^9Yhak*(Pqbop>}=n0rC#x|87H?%$~U`aS#9gzgFw~)V0i~=xa}d7NKO9~ z%_50_Bz~3MsN??>O&O4)nRrR0lt^hqy|OVlebfNKLOyZc4pMLNuA~KBBq`;6d^u3H z6Q^}PLEEr8nC*k7K}n(kU^8*4h9i&Xm$c?v$8bxIoz8ll8Az|C41kda1pgLCt*gda z<Ra(+g9CFm4?M}*`@a=i6r@{uFh?{(<8H{Iv^wh%pnOq~=Ry=6S&7g8en({9>IxC@ z^<DhUqbFyXIO2^~qO&5b=Ugj2w2QbQ!Us);Jod4TI*88dnNxd_fGKE}t)8#HZwTa1 ziL(hv%|A}94`-7ykG#zOQ)^FiyrOSKq;$W~cr22&KoDyy_6rk<^dz70fPqwY`Vkz~ z4H0HiAP4!-{Rxzn_%x6n4#LU5JZ(Aj&!7}S`ZPJN6W;O-D2#%qm>8OSta77yV_Ce_ zp&;J{FTysbXULKy&}&@lG}jF_)ZCzl-<-j)XimH}_*~qS<Dv^$u>GPB-e6LolFxr) zBD1t5PFabh@-OY}K{c9k4Qc%?GzRqq9b@f?O&Vr<+dx=Mfyh<n&l5^x0!;%=czESJ z&4%n*L0v(fZZyS2%273L#gVACsq6!4@Pl1x6-x9d*ai&D<5lug6_sO8ja}?O^ddX@ zbZ$xNGD%p1a?;H5zw4!ydl4Fng}<DGe`2?sU2mJXCg#+&k6VmpUp7;3cCYGxo{?7Y z+=f8;qCbYe+!(#|0Wp`VbN66`A|;x?QCY5Z$6O%Eh3@$5YXir8_AUN_(QNwce=3Y; z()>9J<23xuc!Bnx8D|fJ2xS;Pw4v=m879G-9d#5L7Zb~faw3l=kTM>BM<@-(w8RK8 zWeViLhX+eRG_A_LOzjntTc0w7A^ld;J@?bhi*$)vCWIa$)B6vn2(MQ5>Kvzg1=e=g z#<hxw>$nr@8Z#dV9z@KrcS9NK77HWO>L{71_;!3z{!*5TVy%U>Auu_i*ZYu>z3ewe zRpB>~o3UM{CN7b<aWjnNhz?of5t60pxL+A6@HXRoM@s%2Gfe|sjoAs_&3w<{XSx&{ zMg)hWTRUcI5`6SF7L7KhbpdIwrmsJ8d-RX?eY5C7lb=pl{k71g8Prdf-@$K*6gEaR zIfkFcw~>dx^{na@Mf(5mehMmn45sa<FN$xELg;=CrrsUaYz|5V1|A0a=Vcj=`d-l4 zMHo(epg56eJH=G>CuU~I8%X|Qp!n3mznvki4ISzjzZ#&q@)rf-`n3k?QHV|A^!LDz z64V5DQC9{N8IF>nq@1UYir0oE_aOHpU|rrOePM}mtulsOU2#Wm&>X<{C<sn;f+_`a z(XaFBDD+NF9K@v<u=94n@#uDT)j9xsDG?Z48=Ifyo=onnmKb;q;Vv#ZYAshVRdHq2 zNL6TLq1ph%LVglD{#$n=<zp*gUZ;&~q3uic2eW|g*GKc@BqLRiJ*af1aZ?Ju{lK&= z@K#psEn!|!g^Fhb2f`ca%jiDDOI*vIt{_3pQCnI~3H<VOq}=uNZ}~)OxV#O@up&OC zm?~?geE~|rp~`lXr0sguMMoH)T~{9q^KE11I9xgZ1mt4>Se#4iyw<_`DU>g3t4QB6 z)NLV{x3;l)m{hx~<|wYbD0mf|QK&lvI$^Q0<f#V;hy7n8u(KYI(zDOVP-i{}_-Fiu z`@S%+vk$e<XDnasc=q79bMi?i*p|bXFF4OoKuFsZya7eRE`KgnpnNSszQ_z7H*q%J zskeEMFOtT1>=zgaHJWru6XI45Y0u2%DzcoO_`OSG$c3{{b*Q*d6X|b8+^j@KoKm`B z4pjDtvB+<3^x%nhFT=qn4lqkygEoBM2zrc4FsB?r_hEVR7N+n#8N29O!W;n#e?yE) zL86>XR0m`w_w(o#o&mIu6fxaFT4LTN-nN;k4yLB0V;CchN;=pNNF?P#mc-;~m}3}A znqD3e5MLie^WU#uCdUGX`FlSpHc47KvRUe8HK{Q_^BpfYCtqV3m?b95Qtx~!gSa4O z-l(UxC|;$<^bIb`f_(E7Jpj7cSegZ1`3L|Q9>Y0|jfCi+H-ho0g>)tvc{h`H??=u7 z3+~N@ba76TZLm4!w~Yuv60)d?79WvqHaLJ+MJ+Y&FSvG#mfu|81ZviA@e?gePwb6* z(DP`j;BdzZVa-{xosw|!UD%y-Fm73AWgwW^LlTb^jC*(LnZmFw=zVenao7_R=gHf1 z6$-ML)sAV|*#=P96ZOkFI+G(WRd6U~c|SA&TQFMEN2RSH5xg>9gqu~ZObqV4$e{g4 zpxzqjd4xN&Ir_xo8q7Ub_#yAq?@ZV!{N$tfAE;7f)BFz(V3P`S*%4z3OS#kFXrCZV zw-5pol#|iLiSBtM)0~)mYz_I`5$L|1AK@z20U7hPns`=>=Isw-vtBoDox_}%^5c%~ zd1?91eDMIAP8W_Z4+2rfq^@N|w5a3Yl`bttgV*sys4v*|uRSkp`o|jqgp-~)3gz8j zkOKco_)?E}6e*7=YP0`<K<JTWX<iK3+B$!ar1q7VmLWlU=nxqC3_~6x)zR!9w|L7$ z9ley%LDxywHUFT{t~uvS!252CCRb8w2m3?yP9BVvSn(Dj9^5X0ca$hz#TaMe+lXZ` z5-TB9JUJ5}9%6I%*Y$#dIN~cTXM!4<EYLaOZMo$IuM2HCG_@s*CYQX_)jvQg(Mr_3 zDYG9^fU$xQ9h}$$p{m{1U=yfC*0+Xfb<GrrgHT1j<<z57@Rb@>A<cBb+%%ZPyeJ&~ z#}t2Ng$#{NPmaM1Z5tKS3)F4By|rZ4T6CPA65X5XaI^3qFGxj;lz*;KfrcGlj|`M@ z3?fzG+zjf8A4`!iFu(B<^OXeJEBJ@C%Q5sDviFndUjYI$?@SiNN;Da$lQ%VaO4VA- zQmPi1c*Lt?Y1iK%bEy`??s69Sr}to}7tfO99x<@yWTWoJ%<-j0c_)U?OU$a19;FGm z{=6Fn*+#zP|JDEdV6^&i))$W+c}(nA*hxbd<p%VmUzx3FsFMGX-_Hw}o$~;bqKv+h zmhXEOp`H3-`38!ra{CVu_QCXae_eL_VJ@<B_80Qm8bXd+lAkSgTT0;%frJQ!&gQAv zYCGf!>e?MCF0G&*NUqg7+=LM(_kFVC$1k%N6TUaX`RjQ4Jr9HgTHqT)gxS+p?8Ov+ zGhLepoCIu!v(o$u9bIkE=?O3+jnLKzAcgSKurgnVZ=lwu?mb8t?*}LL3d>_I*C>Mb zCjBAs=&dr>UIf2EC=P9rP1w1EkI@W;aoG)+JL{r%%Lm0z!^p@^-Pwft?DGoQr))_= z4N0$l`5?a)XXqk*nXeYgS#bKmWpeh8-wPlS<9A!2iwK+6aVeu&?^j;wt(Y_*+%?>l zRum%|74hM%2}v$!8w!vXn~gf3`)kMFrT80Z7mxlm^hw%IX-oBnnm_nN=ugBpKGNe( z#HFWm`H^Ko6G~)n{r=lc-%}rp{wEYZQE+V=^!Fk0U_H~tNDupYq(iiOA(}@J`xBRU z{lUmn=s{f$sv$Z004L`Cfr)JnEy7l+5_4gQGy<M(<rwLis&0suXSaP2^O9Np+~<u^ z&3WXGwBY5fnP_uk4DP}|@K}GkmxmZcm0(JY`}5L==umJf&d`LDU;#%ZU)!hmo!9j! zrI6^7(8nV-Qk+dfoa2S@j~+qPUE(;-?!a`)%A;I=qc6vn$yJnAJtrilfxbfb=GDKA zRo-iv*N==Z!CS$sT<m8@HVekTibDlrybECKNBCS&+es;2Q#()Jpp3+!Vd+3YIPqfG z?8`kdZBWqYAO<G>#%LJwF59teGzF5q=UNql`OS-^x{Ino5im)#BIeN}h}JgujhPR# z<M$1X)cXHA<Pu0SXq@5Oy<EVP_i@7%Jp4pn#Wdn$QU^|$iazW)h)-yJ93#y7{YDL! zKIXgyjJM|Ymc|J{*~GE63{&4^@g{2D^)nDf(8DVP-0nG;jca{`&Y6BH^2|WLXV-kF z)_XK?;Be*jd|vlaK(Y9(EA<Vt+Vv;rVwE#IJfoaE?;=?@jr^?JNnzuYu7Y*=!M71l z0DFevM}!&cJ8^{pYQxdq<C4byd6%b+zi04DX|!V};B5PJ$JO4bGjaRcJZTGK@KwVS z26m<Q_$l&pMhjH$38T%&Ve^J$@+Nl%7%n9w7Pq%Cv85d#+_4^z{*jx|Cuw7V5L@~n z)v`<Ol6%h1n{PfKx577iFV*t&U2Emd48IXW2yuhCJTE+NXFGt!$>iZu?uF{(ndQgD z@qwy!oTf0<FX;%P8|R;$;`1n9J=UXqUVvk91|-`<NV~B<?E{9>`Cud3NDECztNdx> zORG;*vrAgvvu;^jd2M!vHZlQm_<&9%Nd2A-CDQHfg+(5$cCKYbrN#xsDoy2&D6`rP z;)oyR5X!($&;R_L`&VE=8L-rR2t_P3kcbZiiXV$(tyx<b3S9NSWn0=*@ltXUgW7So z(XjHSFe6WV$&c!d!P7#5gF~XhUP=KkXd?jO7;Jt*yTz`Bq9;5x|G3@&`anC4xdk5b z?t4BNFQp*09IM2)lLE1eGxQagmtW9uX=_~W(pU&Od77{j2Z3IC4bO9Xhd=(2O@1^7 zM}iC2qKd7}F@(;$rR(^5B76Fni|&ms-Q2`6Dw#W(t9}tfc{oZOiEQI-JZF+WGg3JJ zGi|C#-6b9^7Y_SVu7|&wr-3^Hd(Gdy9D8-Kqz7eg3>!k7x9!}K7glQhL6XD*fmZ0U z)cX+N@6Ohb^0Tr?#wyvaFps{<d6oPm>jh7Y(b+^1;F;3o9w>^TNI7FgT1$h=flQKn zo~nREU@UyQ5~_lrj9s>$2r%$!4!rRSHT5;WSw)H`{261|8ZWxE7%X=ZBC%M5x_It} zv*pa=v24|0>$0TUa3!HzAIxZ-Z=EnCIuBiABpdXz#$Pk34-;Uv3n|PxcNApRz<=tc z*FsxOEw$x*h0l`74Tb`KDoe3!t__xrEbGCacJ(t~dj6L8r2rDJJFfK=MO};YsGXY~ zRnx=V{cV!Ot5GH&EmQj5Jn<TJ?}gH*fxvjt!33LlgO@6p?b#46UG%O-qc3zz(~6I} zLJ>slz;cEw^LyCYV0Mjm;p|F4RJ8=VXt^*VX8vYC>UfDrL&m}_&4H2?&Pl8@`yUY$ z-&_GJnL}-wwQseaOY2CA*a91$O=4nIPu2zoxh`iKEeY%{p=U}?YM=t33oOA+4msF7 zjB0n)RMT+ZoOGU<QD4H#eR&C+>APuiyrf-2Gwm$7zJzCWTQ)WVvBz6`vkY@NQ%Jp( zhNolWNEB&j7F6Iog&WoDv2jPCH8BZ9QcZ$GLW^!9^KWQ*Nz}uRE`6RkIB^Cld`dFE z*Cgj<xX7;+He{!$5P7}YaO2^tTa9{B+L_&CO^A6OVUsK}(v12g9fiz6fO#0HpG+H? zk_mE2z8@<4J(BV03S2VKOZJ<KR!mIfirR#s*t*-3;q^T}4XRWUcvr1v&SHc*%O}Zx zOp<E^gmVdlgQ?13K)4pO1O+~A%quY+xK^b`p)&w@l*^!`;6fJ`GHRpN+PBN^YTp)X zf_`LEf>98>RC$C*Pd6-g{kT>(N>r!@58_#PKf~zD4=Fm4qxQ+`i)Z_tYy4!Bfc)f& z#*I6cF=3ZsCPiPA^pmPFtozQrNOrTV1q!^;lCjDiIchfv(2V(T4YccMetf5__bi8+ zS%ia~8)n7Fyp3JBMZOal^&SR63s&GF`MBaBF>%m*|5J$S+gIv<0c)73u*mNG)9Vky z<q74VekEus516MkNtv_sM~kDiaHUIsRVRR~S<)I$=Ce9jGXlLiv1aBP969eEN55#G z1fBWNj87gDD3;*0xX^()4Oe&$#1$6-4H61z=j#l(bSO0&9qKUTblBz+m%s=RnNLtj zqt(-n)wuj`^HRB9BoS*GDq7sY1iz&&A{J<5TXvr<(ZfhV0EgqUOI{#J2nq2sJEt7- zPr#<Qih$EUy17tDk;icjF9zBFA{dgE7f7foJ$PIl$qi}xTy^YRqXoVWL<_L-F)I@( zI44c73JRmDZg%B95dnV)v`7$rdlG~kXnx~O^1)EC8XGFy=n**R<VU=uQ|9p>^|%hy z%p1o>GQ4*hUrLP^bLHESs-l*W5ua^sy(hmZ`6=<&o?onr@2yzlH*&c~q8lVjNt?)1 zylk`vs8bD4r<z1DGJZ`+k$k09nia%AoXY!z>W$|V`jm8ze?9urd#*UKXtFgY=VSP! z(kCAnyY<s+dhXa!l0<0K_{OOHPmkvgl^-w2d@Y9rNBhLtHy3$-WbHR+c``u89zswI z!_ofO<ZO_m(#_Z;E;2}O0LD2;s%Sijs!-|?UR8W$d*6MoX?c{Vz||ImX>X4b6E7~F z?b=6Bdr%Z9hix!^PZK`^7$_#-P<)2u=j^8<?wCC&lOWZ8`BVx&<=Gpbx3sh{4!?97 zVMvF8A*2x=s6c0j?Oa)bdxFmaQT*i!<9C+z(+Fo`Q36Qt_d&+yDxY8y#OZU#vVC{x z@69qmosytP^o>=Ei8iovXzJJAbsY0LD7TfV*-#0mp`Y#oi-7T-teCyb1cHQ@(VbvV zI)-gn?~S;GR2mFtX1woj^U}Ogx;Kh4$cB{R3r>+2`!E>no!DO+zL4qrUs;yGMNY0? zNu;?rfGc6BrQ@C<n!1-H;>u5*bsuP?XY?fUgo@)wf|}mlk@5s3GEIAdn$D)7a2iMA zwpRf|4!gplNDKibEb&ouLwp!hCT%Z+{}scJL_?-(MY5+H1^!T=>EH${Ppp_iYSewt z#gmb%IOQUptz_o*`Qiv0!2!Wt&{qn6^uE1p>(F}ZW83@CT8%Dr(|XIB$F2Wjd2S6I zmnog2E@1`!O?^T(W)V^>uCTtbSUus3$tD(iIc+VGlU#8m1aWMc=xx-|^LmczqZu#! z7udKtr{04X(2vh?z=q#=jbL&ZC|zuY+WjSq=YJNM4ZPib^3^*y$S~kf2Pm7Qei^V7 zJDdxC;j!W{nUtyGeEU-g=ymQ-t|RV`I1=bWEG;T=GLY_+dgIL5oIMzvZC~Kyr}&(m zl@c%UQEis-T?F%NJhK)lbMM-8u~?~uAPi~odVq5i5ykIpZo1$iB@4c><%|0lutO`n z;p!s!MZR?YdY75unTrU91$^ebUBu%yL^0yW05%$(U8kDLu^(HQKYbv}8zWqYol+1n z)%+|mIdaNcqCF(v=8>bC&R0E)uLaU@%}s?0Jy@?MH2VYF5+b=a&#pt;-SEwB6{L(p z$EfE$6TIfySvjC+r7;g`8tH#)t~y^~mTYx9LCpWyH0Qgs^DX&mOkA`ZjBrK{lo!E1 zo=h@^SFyOktOV%X!E)?eFS@dHJiu6<5v5b?du5I3FXUQwexa2{I*Gy$hO+92gjV@o z%jSiCb#$d0L}+8$(*}&Vl#BKR1rJpP*bh(p9mM*%$IndDTOgt}?<lQXxCpRZHf<z0 zvv!ikge)W%G7)&(PAzC5tibs@+e4$V+GqoMHMZ;{=*dwD4q=Ob0c{`;iN#|@wu>1C zAm@Mr;CEyh#u1(v3iaYft}~F*=F>BuE6ed+*vqKHN7;|45~t7OD7~Si*02KAB_pgS z@`IS6*JA7mP!2yY(FC2<#_N-Imk}8{S~-~WWrn!aTQErTJslsgBZpS%lW2yCweJ5z zV&tk0El$o86{8TW4n_N436FI@F(Kgv%g`}`y+F#g3~$2M(8efNTUOnN*~8^(+EkA& zz@JOr6`E=Q1}k0iRdtlp&l%i2-45?i8T@MVDGD_Ge=N^`wp{I>Z5-(ECayB(_5a33 zoyPeWyVl)$;(EF19++HQ>g{3|9b?5>r93R}C`$=vFe*@I7cD(wG|&T95Qb~&+1*Md zPEz(Kvd3U+b#e9=pK(v?2m(06E6?>8Z6Rnc?yU>1wN?zulEPDkUU_c@&Hv=P+R6e+ zX_W_02-x@$tx2m$o`P;kR8YDxKx!-mj1M>d+e|C!9i8U*z$MHf6>k4NhvSoA>7>Q6 zB-VCzpxT77oU+=9GeVMZ15Ra>#6FF2B7F%@tJb}f%*y0gtcF`>tcD_LI<#|0g8o=f zO4Yx=db<YFBTXefC^qds6Fw}{%D}Ln-Y@QZb2M22R2IES>5^VzzXw#Ffi}4QXyKdP zuznCp0XR2+9a70r1t#Z^9iWzkJx^U7dQ+fI(#wW?-LPVbYDGAG*Ug43CH}*y9*N;% zX)8R{aVZ*NwLa;`XO&t>mM@$xY6Zl*yF7WdIex_!Xton!87=^5T7wazV4jOfjmde% zunb;Q;?L{W9Ke)9-dS#T4*X5LjHA&M78GO=F<3Q0@A+p^+@}%QTgQ_r#gg<ZAj2LF zgv)(0p437D1{jT_gR%21I(`4SXN3riFmA>pgCg4v;`BN*bPorsSvA!rZ3j1Cr+>N5 zSKbPRqZAI$>aF>hE2oN$uP!TL0*mnYT45YX#`nfvv^#~s9<s+)dVD4sjyE0UiyyhJ zBnQh(=<z<4M&QDoN)WO?D;Y)2>65o;RstGJ)fD?F9d`vbCe<_bJ_ngw2VAdUQ<@Zc zq{c`#&BQ;kO5p?&tLWUMe|jQL9+m7v8y*^on7QMnOw$QWCSU<5W*AcBFtjGNpb`|b zE!;@K7)9Jjwu7%{qwRTtOEMZ%(3#^k8<|00St;W=L~wwyc<o@HO!$}}5pDIKh(<#~ z2hy0>K+oQFZw!LyTfaDlr)mtx%VW?kdAQMm-je<DwcV%d(cge8@=;<G2tPP~R{|2C z!SHrM1)q~Kx({CjTVtTDHUiuU^N)Oo?iS`}Ey=NTwhIU928Y3zd}M1nbp>H9^&gvm zAqV?wMblepy89OW&t~awwejlZUI8w|(I1mvk9_ekybe<^IMw|61HbY7mr--*R<Dmh z?q{iqk=wzdd=2wHPRQ{CbF#+i@1(gSbT*XX-(0mTn9aq}C(I0~i>n)OI`$3YgmD9K zQab=}u0^QZBV<Y;4m)7;duJQC3#d~fGFGBbRb%gnhcx~%*Yk?vuq+&hL~)!-GP-_2 z)ck(PgzEk>%Z|uudQQY_c|{l;Gd-d2n$}UgHTmJ5iTEC&zw^E-WB~;RWC6e<H1{pY z>O*tWJHvXXsHL!2F-N`)sWNKd6gbyxyLF9E=FfjAF;mMT0ZEk$2Pt$Ca>E<oaYhg1 z8rrw?8evbkydiLwSSN=#N#?I52rF3nuq$x0&~g__73fjn?!!M+7PhC(P0{G@cdM}g zuvm+~6#BiF3>Q-Ok5H=+NRm-=MQKW{L9?kzvPF%P`!Wdb*^hk(jh5JKWd_E0<YfXj z9iCF$24zCn6WJeT57X}jCs>N3a>~isR1R4H#cW#>LG)96Urc%#0)&h-*VP{u@$09B z1abSV<JTT>U#xaVK><u-!iq#251jUX-Urn7eny+uftCKS$bN8~1jdNwET4RoVs&7D z*uwIbFK&p)L<HNu@++&x@SKehB3As_kPhnJ@lb|>ZzhWP?X8>q9yMzBpsN`0=HBG8 zp@jpR$Y-hu*fz<6VdHxF_wwEZ@$}9YHyMZJ!Gve=T&C{%zQ^m|7WdKfDiYxBAjGEu zCO|R@_)r7L2_YV<GUB;u5Z{})4o`jCPed{M=R0iHhc^HGMV7l^$b5-#V4^r%7?q&3 z>G(yAPueKD#H#0a#%wXSllp}4Psn*C+x_dF&PsuX6UA>Z1{6YLrIde%`3j6=XDjyt zLxHAtxaoUQZ~wVUD?p9})f=MwP@<+GyTLfoXZhkSnoAL6rep;_h4lqAmIX}dK@cVj z$gcz*P0i?_*xoOVU}1;%Q)-_AZ`kXp#aFL}TXKJ{gzRuhNyN(ekvUst40}TYIuPL_ zQB}hCoa}ZDg~{B9eIJ@~ICWc1J2!yg=|3TFy0<_w((5t)B`OB{2~QGwhb7iNUv=0k zI2q$PL$!p$aQM$SE&IR2%_dZ*w3n^o<;7e(vK!6QE=7OIb4yguVm9@Yv=+vl6%BwB zrzar&y2LEnl?I}J<d2LOxzHo(`)~276dD8wdl7anNnBYMBQLYRJ7zXyR0Qu1ac8lg z-1vG|eP3-SGj^G|Bz4vZZ-q`KO8Onu78KtdTx&T;iq)}M%yDwry$=`YAo`2dhu3-b z-4>HQ)Li3hpi*s1EaM(xF=NBs4TsxpPY^;O3~2;)5ofvK;6evp8;P9sKaM38{MqHz z0K;}{&*VHJT}=M><fC>CkD$xHg8e_A_O6~xH}<)(uvU}q7R)xeS9@W<n;8z1mHIEl z1y0OVyF>HnMEu2&<}t`@yF-y=fcqR&Mv?5?R7R~760Z~T84Ou?@q%7ahg6RB;}b=m za2Ox^RF64~1T2MT=4giCFx!0~M(^f<54SVQVM}9|8$^?urqB1CJS-{SbvPcs&~jI{ zD4coq(Q%XwDDN96#En$Le$YfYWklT!XJtpRY@wNc9z!8EoQ|5zT@`tP5i+Wc(i-+d z3VVVHew!XeIHxlU#pwrozVVRFBaC|8<^?-$Sa<KB%mvhZQB)?8wHc1c4P1ipocvy_ z^D0;z`;qXq`dRBw!dI&k2NCw-SXR^1-rG^3uCZ101>4Ie&{_Iv19X-?nVT=BD2}an z@R1@g*?WrN3NEr}M#B^&i>U|l?lVZTuj=zjt0q3n&3k1SjE-#jNo5PR0&(d%Ufjv) zd4$HioIk#bGmHhm?>mCq+Hr!=;2=KKzJ|sAr1fXJowL^AO6@dflEQz-@-zI70-!hh zb|_gz>+f#(eW?}S!oEn4(5j9j;qQZ4hvrQ4_g|O$5rp*lS+vnB(i%;f&Y{(B&CqLT z`HmQhP0KBvI%ECy?oM33MJ#O{X4BQ>GxL7cK<5ktLwGZy;-ar3Elo)nUvSNZGKLCJ zlI-vud4UKAl1uZo;%^)T4JwcYJ0{TG=)*Rw%0Ii4nl~Jd{x05HRW$z}p58jHjjj70 zPVfZR0>Ohrph$7o;4a0ATX87Giv;%og+g$rh2l<&OQ95PaW7Wf3-tEQz2E2e{+Z0o z{>(Wud!K#w?6sDW?bi0BtW(b7lW(1-@FGD(gw8`Q;j4{XcRI~fUo5&mjqkLdhEfs8 zEo;&*A}8CPy<w_rAYv;HTHUvuGIb&q5CIlq$YHqIvIP^heeC)1oMNk&&+FA=ua#%< z9+s|de}9emqQDn2e|hGn1jMMerfQfMXHy<Ua#V6qKL>L)%p`#cf%vl}cA>~0D@inu z_~T<EEx}<hBwQME5YQ;+GHGnp3I^27L_?dVjYo7MMY|3$MN&b`PAyoUyCf}#f7_bm z6S`|lI}1=}ly*x}0`y(x^trkeKAT_!q!<5Wki}DqKKx$|fk))J|69|*I_5?X$g!1V zCW(q-YV14WJ_3J35%aMC;AZ)uROVAShHRL^6Vml?thRb_#}D(bE&dN@8HC1J2A%49 z^|aOR1#ysDpy_yCP3!I5mqYuOv|Bgtu|OVuIHKQse*PEnuzpD1Lw^Lva-&Ua#yC-E zE$RAwN<gpD*3P(Y0n+m5mW${VTKvQ0`<{_qv!*PqFI|dz4pN?Tr|5Ke?$PkR;}tnW zz4DLtn!05eBK6Qg@yqpi<kPwr0U=w>&ZOjYZ$HYGOy9-u0{F>zs*5e8WW1Sb&f}jX zUWv<`b8#Qjqz`e(D3>3TtPgTD{(=IB$(b52J+{cPoldsNJ6zah+o=lMna=J8b4Xr6 z);Nq0DFkI2M9bNX@540Athb<BG&y&1|MIW%Jw3n9l>O(k!09qpq)9|;EbYag^m()! za0t)0=lomGnI<PL)EBx&*K@{Q=sNz?sd+oC>0nPKaO`qB++~m>lD1GTBu9l>UjLJ~ zA27!GUnM6;yhc}kajZc{E?I=-xnm<MhE<>d^HgAK2GKB29?9Gja=4h8m#Hs{6$Txt zkB!O`!MjvUm9rPPZZnx)REOaVr_;bZ-82vx3yHy`%urj2-+u{;Iyyng42l)1wXB7u zG_`pJ&JPv8oNUUp7QO^&%Jo5xmKeSSF&YKh?z03>f+mN%_Fn~lse(Xox0DMo+(TaZ z3Ak``+p2)%A}*$Kh5!uMHa6eTr4(nNnjBkHY>_23uTo8hdzpJAB6G^$%2?}`$^E~j zX68G3KT-QyY@H=%ZZ6Do^L{Nc>WOz0_@fUFdAN|{+<hW;rBzM4fFGX+JxbGSY&9+~ z+CZFye=FwKkyNMY(AOM$*4{wDn<JblK2z_|Wnea|xA1pvaj8M~pJysv=nX};))f0x zvS+73>Zb+{bnbsA?4pCt{Tn#YxxaJ+q2I6BWt>j$m&urG95z7}x~eySDwK+rn_b%? zJbE}t_rC*Krjk>WF&Tuw1d%5HE-=HDYFxS7AyBk>QofNy3CSJCX81@FMwGQ_Mq6s2 z_`f(F8wwrcgB^}06qX!Tr}ul|*2fFwlu!(9p-Yj{@Lor6YIL0=Q^g`)rA<iPPOxPs z`S@K3H(zJ|aeVEE-Q?eOm_Fe*tBVEbn#t6FV+hC76~Exc6p|c{W#2l8BdxOHd)n^h zr2@Ln;p~MY(cw!h)bNhG3NYepc|{bXrVg#L`)N!00nM!5ni4g#Ax$`#2YBV85!}WM zo1i#*+6@;W@?J8_QS>T{?f`<GQ@`Dme7AM8IPQ<olzyJ0SkeB6T&wsm&DZ{&4WlZs zD}Ee}X0MCjnj;0tf<l${SyY5tp0aCj3wo2{Gq$mxotM~<=}by63S>2$oNI1^W_-ks zcfw|j)jd8QWtNypSqcB=ZB43Yh5^T?2Ea*!GL~WW+BTh~8NgS{lQ(>NYCeT7LJ#Nn zc1?4U*QKX1)I&GzC!?`{5=jYS^pKNFooMklt2-YN6HIrk@9UfCl18dm*{Nd5<@&Q~ zQ-J}D>aP;N(qOChv%pn+LQ*bw?z&=(Q~r|mCdxl>_1gE&IF<~*C}B{+ca|j0)-h8Q z9CDL!(U{2*QEhL@osw!=dr8FX_+y}j?-Yen6FXkIJ{n!*J5ETer2q!tG3DI>`*>Pb zaMQ%^HhAunqG<qbRO0K{X*R!-U`m%tRv4qBo!p!XQWAH}v0o}%37LGw_|N?L$f)F6 zdz0k@h7<wspg-ezQd2%zv?U8P6^JP62w>U9)5`6hwRh2n`fF0jsc20<;l<>`^=6jB z7<CNL9)BlPzKbs6Z5ok>d^RRwn+;op^B(_{+2Q;S7Ju`s%jjJw7=RSW@?y05*)-B{ z-fPu))BIf{J!o$8%lIAd6({IL(zMbTCy{j$8jh@jy=3f5B&iZjcgAXz^45$6s&kTp zU&NG`_FJI}Dqcqu@z<NiN(p@DPY_5%%+F$Tij|6YFWyak&RhOr;K5LGIo8E45${Hf z$UW|fT2geyz6fI|2K;nZVc;jUM1OzV(e{gxJp09ai?5i0o3<sBrMJjL(DsCO*rk%s z_JE_e7vN!+{PFCons~W=Ya-^)V%JsP6oQT$;|mvzHC`gAGuJkDUvIz7zMF)k{*NN} zxNZysPq#=0Rb(MSP1E0EGNGO5y~OmNOT1i@wWKbLGZwXsAa~wKCW#UTECG@B*YYI9 zq8sRn4&K%#PDtz>H=Zq8<A?hCKtUUQ2(6zXPvRy%MqGy@uZb3~cpAmz%#%dA$0&`* zvcX?1yY6Z>pmAlV|Cd3xd&89rp#3idI(Sg9B_n~C>4gHvcypQ-I5H{8aptu$l!qM$ z<>w_xr`3|w87$b2)$CiLCJJbV>rteO#$8d0^I{?hA;DgP1+IZomORL(MYi0{je?n` zY9qMfzTMV@->VH&8+8PUMWwgo>LglJS%a^%cBqSmcKDZT!l1Um6>*++6*ElY4iNw= zgS!q*fXQ)#!kDYc;NgJp4kDt}lY(|0&*gL3tEK~ie&>%tsnMUT#vMjMJoYR#>k(A= z$Mf<x@LgOC=6MG1ab-?zGBc&QyfQMf*GbExwEBEAbaVW&uK*l7;rvZ{#92oak=oZ! z4Oel-+=@-I&P#)7ZD@d}KXt7kNizLc%5{~+#(!BLX>QSS&1Ie$%pVcPR7C7jyyEXm zX7yPrlPOjy|Ey!K(z-RB+3P&oDFJp!8q#oz3`{ScTLk~}g>%D0)l?T1`AJOwRvnBu zK*n-$Nfn@`clkM`v`s=5bm!vIUZ|07G}UUo0t?=c0ao-V?x}~=5^~^bQzvX_H5|g% zosk$LnbUmXIzTzf6J-1oHmHWIRp8Eh=C~g=WxShgudY5_1C{*!uT^fesKm+Mk4{si z3M(k<8)D{(2_	w9cqzYo)t##sM<4<`tTr-`{ZoXkG(bA-(o8?5qi5yP=IBT9Ll@ z9Pb575Ak7{eih|%1%9&+&|@otHAVlyj<7ifQFc+<$b-zw-hvb2@G@Slw3783Jhu)M zG3Q-c={7HRkr)a`1DtF2D*jSptE^~d@XiS{e5WOcDWC_icD7`s8s2!eguE9<{#cvo zU7iyEIL~m~%}z-@YS(_zDH?6dQ7>M>q7k=F<G)<}W*agw*-w?B*KrfB&i3|U@CO*k zk^rjs`S52y)(W&N5V~eW7Y3GNKNyc9w8w4*XPOMp)@h@{saP?i|B0<70tsmk3stb$ zOWyih^RN8qT=kU=wCxnYd|)}S*J5RLAn{2I7EqeS>nJZqcA2s%rvxPN8i|OfU^{rT z&f*u)8GjN1#EC0svkh=;B$s6?QN3yXhFt3|74c&}FiQ=#GPx@dbAQejDlGC?#?@yo zdyu#9v^P+@#b`}U|724})hO07>X**_R$#8m506|l-0Xf!JnN$|pt=(%tqHyF!7?;6 zlK|~>-)XDtK8ye6=J%+*?cp@?p(CkLZK3bx>*fVh4Cg3!LdDb|h2YFd`dc$9KfL%R z${<B%R;My$C|Dscaa>fo-ySRwA8&r~hX8pQN9EnJgZ!eV5lK`33aqfyHzscs=!j`C zu)3qxW1Jegp+Jqp?7~fVhAv^piZ&{@!p$AvS!i-91%IN@im$p}fQSSyFmqsZbdu<A zdK9P`*>g|t{4)*Obh7|V`QT`t<d&Wp)0bggtGsl{0#=Ksav1?ne<4<)T~8;j4PzSB zD{J8ZCH8Td&Ev(tD>Eu3SCn6P$*!u^90zybj^wuYf~B>ok!_jMI#>z!7bl1@<7)1? zPwSR#rOm&X)&0w`A3bLgP8nQsE8|s|TzOJTBSuqBP(D3#V=S-2Csot?vpkrX@g-l_ z{oHYvw}KfUmZpRR8T8sa;@dL@lEEWGg{AqpX-L1EqO#a{mRB8|!lhAn0QFRP#&Gey zv?IjM{0oW%GoHN~vD5ivE0UG>X|EzBf)O0jYU-jfdFiVOo-vs895&6<LN~06ESh;^ zeeLq02J#KDhV$b494na+(R7Dyz3?ELQRl_Gq(GDfM~xkFa43RI;`B%9lKA$Fn4|sy zPmj;bQ85@6=z+YQqLw-2;gZI#L<j}bi~)@RHF$-5O$_m?8mJ<-gmDK(PdWdb#a(DB z!)sGGgc;Aq*6ib?w=2E&DA4>B1<7cBlmA>u4O9@T0gMxrZF2q~yLY<AP|5k{*0&xs zq+3gR#|1r+iN6^-9r&IACxM;`sj*-DKEE+1^@ENWU`*Pgdimpp<GC;xPv7W561IQ9 zYaDF$nundgxdwxv^*f^ryVG9ar30id1e{7Z<H<QX%}#Ev9ht<S8uVhae+y6Kj*tm= zv?@D1GKs}l8|6kR2-y}~G3dpzmX5RNQxyBik^U-ueGMZSQta#m{6IL&wNBNyQx?a| zt4#Mxa;K^pm^*&+hwApbQ)3QH=8wY5aG62Mzw0T)i8Xf->%(&ZN)BrW3<+$dTDf>{ z@QT`ECL6X3nf{EPej4_{(jWdxxs#_WHh2j;=MHEzp8coFSMB*M<ObVIb48q^RvpDm zG=uIbWt{dUJGP<}*dtro`i7^Y`Idk}x-^3CirwOg&3Fm&wR#IP9QT1#F5mpb1Wczz z|I9PSNJC&Cc{bd7bub;UER81GWyE@c*xrEedFI5bu<{AL$29H+2QCTQdE;RvPU}$1 zoojt@e+UQ9%V5_j61CH15j6i_9aD>Hpz9QE!m}1=7I`q1rHFOJbmyjp9QYxtJU=q* zLx%@7g7dZ&A~=>4&P+2pm@n$94Hr3C<)*Ove%Woi54;Z8hU`22xD1HWdg<ColrsYH zw_3haNDza(el6hEqf|Ho!BW1E!9u)po^895bOADccrM|>H6}p=Ys%crc-?q;n_v<0 zEOD1x(=nrEmzPiC$dS6aa}4}_ME(UOz5raIFkO{RP(cz;v3FLAA2im<x;OJ)8rk6> zn53)?Ct^R?D<MNJ<k`Px<#oR`-GjSIel2D(u@Zua*$|FmQ8zQFZ4S+xps1PExU^*V z5k&EJHZI-@SSX`xLj@mxcu6hmAks7TGuWnAkLWuFM-oh{(EvnVvXGqFPL<}s`<E{2 zeF}kFh`JhF<_Yr9ReFX<zc>|fl%WN}E%g9A&2D_WU{GCbF>K+{F)RJ8i%QF+Vfks) zUo4Lf4FsarM!b~D@-;Q4|42`%rLzbe%AMwOH13eB%ZB~kyX#qX+#(kWnUPx?&~&=v z?8#+XB`8EmU2xVb&;XB1D9uyLdaX7T(kQ4v7-zNE$`yo@lpv;9Y!jD8E}!QHmyTH2 zT$%bJTG44CT`&^Bk{fi=DS$D3W!Zma8Mv2C9zOI5tv(ej*Y@$)Cso!=?!eq4hc4gq zY3IfU5u~6ln!W(+hKr!gw$)!+{2>|gYxG`$VLUlBbR``(XPW*mwLuq@Lxx#e3D*y7 zTN_0K<AUSc%u-S`WaWt>S&*ks-e*yOic6Y5U}K+r870i1z*GGA%S%#OC46GZu#)r4 z{Z~w+)LPQ4sk~lt^3-Z%$(B~jS4aZ9)zbn{h!IYG=5})Q%YQ7Xk=wE8^+TtnP?T`| zCq4Y|?@e?tg&RT<Y59oS$O({Igxk@Mfjj4@e6h422719%6Z7d5C^Zl&J(r2B4~^Js z5dHUuUc5EaWOT_*yFlr(mSBp@cyEEDa5zk-hypNZOwPDt>#`{dpX23nE#vZHewjTQ zKs`D{7QO;L*6clP;?h1>CMtO$_S9|1;ov>{b?}uh`#{;Q0o|9E0IG~2hVb-bT3ze? z?`8iYwyN>LW;45PIOz3`Hizo><Dc8#!6|WmW)i9$lhbtW*jJ~VxzLO>Is=|u4e{+< z^_M9W>d|vPja#HhPhr6=E8#Q|6=Rou)&g3Z6H<D<EHU~u9A;Ntwz6`CuHBd^W;T~O z(B{{lOurS(rS&hxRGe{b`U5U1MkqFAKS~=fEjgwxP94fO2H!*%oiq@RQTbkgh+!?o zhQt}=>I#igdW8ykQZ)T++kJeDVC^Pn#`HpZYzSCO#eKSOc}!BFdm1ER<Mz#ZhmOwu zXlH%jm#LaPYW<5ig`k>0ON1-=KPs$rRwY|ZIc@upuEtE))DZ{PH)e@xPjd?_GDnqk z!o1f2ofun|-o4GEPkIo`LiZ#J{Q1zD7aRV=bpf_SKgqnxj<cz}aNM7;*`7a5$zaR; z6mJBL(y#1sN4|o|pAe6AJJ-#uko<fv>_po1uI7nfGoEfB^FE^NP}d-i7_su^kVIk7 zoRwbnd%A%+t0Xz)u_z+mp9*56;A7~0!wf2BBsWe|iNj36mboVSVEWQXVMi9suHH|u zEXkUc_Eyp59iEuY*y8L-F&Pqcu%+@v*M~u{nB2IVEZZmM4yU`PgRE2R`t4Vmz46F1 zykir#xxl$xZ~ZbarA=3T<%BCdV0WgC!hlFE*jq^U7X~9@tZl(N>*=hDc8wt!3yQ#V zR=8gww`=aJt~YlInISE6Nb*kE&c@qPwtfS=^AKVeR#s-$mW?GfD65(~8wGap0A>S3 z;l5+X2!K%d2}3Iw6~`Re*60`4snT8Z<mH;bsvz&Vm0wPF4_<bTnG53`7_MP$tWTkN z?*5uh9@-QzLAEjbs<V2x2=r4dO^sdTvZifcfKRlR^XNWI6_324N+_IfAite8DWD4L zPc;cU7E3HI$Ux5ZR~1<a6IO>QlH@r^vyq$mcUD<0TN`X8Q0jLV+4t(qv+w2XV<+l3 z*sg=#0Pnmj*YqP+DEJ$$k^fewKuc&6Ig6}$6BebyskxxNTHFLpmJZ*YJT*arvXUCL zSr7ilo1Adc8dQjg*i|+o9{-8=UQNrscm1{{CBj~4FLF<XmbrxQ(D9;RL0<?(9qm;G z_%|(B4bN#dEAYc~ah%mWCl58X5Q9WKh~^6PX)VjJv=TzBI3RDSw@UM!`Pdq#ZLPm1 zQ)-VxKrrm*5p9lQ@A7HE-mJ=LM&|I|_bSF}PMIuwns1cdRo&CRGaabDUG1Al(OS6q z!|X9p`BltDXs3jj;`SHl+W;1G!@Cgie*$-P)$)<bE<?A>LPYTfBCuh^lEA&LE@Sx? zCz71ymrQ?`a6bXRkXz88QT*#ey3r~YyOvRLl3ei*w%=L!Dw1loA>d<k`&*bro)r@d zlz;=J*eC5{?uD9yxJ4iCq<61%7}-~Z8iQHHl@m$Z%Ej&s%_b@gFQnOQDqxK?AHUE! zW2#S%J&Sn_7@;Yju^ZCB&R}IeAg8dL!6W5G<z@8a^~kq(nX~|FFk2Fd<l#JA%{{sY z>8xVR22o6Y6)d!7YzW$C&wb{he{uR-TZ+jXCggo6flqLhcUu@@iT2Q1b4Dl4w4}X! zEFPq!yQ{*FB#0c`d*MgTc#`O8O_ki}p~y=b69ZHon+11q4T9)k4wZojDEy(F#E(!- zS|<90iYh)cM8c5d2DycTW@SdCPv+ydc~@S0^-uZxRFbuti0hJ}NU$Lpg|MwpvhSkn zZQoQOpKem-3vn~QE5Xj9!DfDz?Zx?#@EP<Aw_DJ}f>^R12tP28CiWMK<o3rgT#3e2 z`U_mUUk3;u#6$MvX}qoIhpmi7tbIJoC3_8vo}p7{n48(s$bNf>NX_>XYfb!uH(<C$ zC2-{POsuT@Lxpq3aANP=oF2y`7a$-!_r$|$NzbmLCBehmO!?<7b{t&9;YjZ2*WZef zuV3-~IhG2~6h7It<z)|D4bO^dsiXxVMEtod>?aVW3EUO|3dnpd1r;i}Y*KRbi{I&! zE=MVFcI=<xL)&)Y*5rKLj#G2tyFUZS!F<1!m(yJd{1>TVs8Mu}<^6E}NuL4ZOyPTQ zN0q!un(I`+qV3Rp*jt{}^eBd9bjdE&j%UbQpSMI=e<yk;43nv$cN;dH<*5d3oX1&j z{X+ZmgIZ2phF*S4Y<7whxh<!i>NYw&_`e^3g=)^Ec6hw1w}MV~X<uz$5EFr30o>Q$ zoH~7`azI2qN^fi|$F1{t)4Grjo|d`fz3;m(&qw;>qiTgPmMrMS105CR!$A59Ah4kJ z*@6ZJMiRa0@9ygGGeZlcFL(xLaDj;{cWr$Ff~}$;8MH?cJ@?Lcd_q>ZcR}jRp9{wO zn+pIc#<&fl;97^x;Ldm?{t&5QXqo4TvS6e4KGbU&sby$s>5(PC3|_NtQ?#*%q$3fu zTMYbiVtdZ98ug-V(aHg>&#AAt0A*~bj%gH8EVZsQ$8L#uz6<uuPCy#Gd+|I(Du8B6 z`$7ym9*YbJPnfC$?FhQXg5rSW6w}*RN_<Rs((bZ8!1SW6H1`1$HyRh{z#JH3Gdu86 zCUe+O&T=d*jJ@z7iE4=n#j@l0sxmxQnMR=f-l0o~EYzx%T)59SI!LzIJ^U`;kci>a zq;`?_OOA11wZ#!Dnq66W(W7tiG@4GNyJBy3gW_5L<jQNs6VnpP4CP>|Zxi}8CGym| zT)#_N;bck-iP<oTi?D$&@kD2FiV*;B0Ep8?n|~x6v)|t}ghr7D0n0dv(Fl;-FzZbK zq-nC~zW|(_!P>P9gaIsqK3?T)Bz4?T>O`%UAh1F%#$m)u#Hi9-zdto|fmEmeRy~Ij z^Lj$Kt_<!VKT<uFEWE9mYg9l2cVwu>4$+|{srMEUFq`+b&$oYJ>!WB!RIZ?ChGIwV zF`Z!JuA2-=(&xi#;+-WfA9&+XB=7bsA(h6tGq>j%s?@Qg>D*>ltZUPqOh6dr)Qs&Z zScCy4@R4wBTfoawW(vThT}?CHt*oCY#-e9lW*JL&%?Xlb$X1s56<uFsg_y%KxVAED zCVTo}*ofyxB#(ITE$h3fF@GV>Z`0Ecr=Zgp^-~Y0mW<o(xc)!ZLV~NMuKE4}#cs~f z9au_DhO^s#HbId&@OLtQrlDbN@hD1t&)+Eh(wRp&nF-h{k3j~$EI2D-Z6+Zt=P9gT zH&)vpBWdKRTwWPTag49+2oy%6JlvCGuEjuOu%U)_6lUO`VNV%wHLcWy?&pMPO$rn( zxPQfm@jXH;!_^6nB6+>aCz(Z})|-%OOO(=$5vv~At?aaM9{ZsMK28?fh0K3Ss5Wnw zMe@uwaq%kd>RI*KSn6r`Jl(NJRWraM5zrm-dlAazjW8Y`Q}ywV%z8of`|dnb(I5NG zXjfH=fa3ITLS}{$5z87cZ13~zED1b~5AHAZ@x~&*yn-U&aPqv;ju*srOm|&w?5QIv z0^-24tJf%eH$Zvrs%^o!)kEI^<UH^a=*UEk%d|7#@#$w033+&3{_hPj>&n*io6gP} z+F48Y4Ek{J5`E9RUvsL1(E6O+)75Sjx;N?=jM4HNnRp>PM)7)&DI`B~qnu+2)KcwP z=@?(t=)uCbp=sb{G}jD6jpgS6xUyy3y0<;RDuIYsf!oUo$_Xc@HLXEnoHnh*M0SrY ztP%Kvk-2d{;*l7OZd&Q#*47#xxnQE$UwIXyrxnsa)DjR^Qe84|hYid6vQeD3Bbg1m zPdtH&e=_2rj)4Ff>>?(n{?pZS$6Ba?@`DfV?m>zu$w~T|e;#r3M&pXTIKw?ytcnUy z6_Bcs+|9K_;hp0lN^zD|iV^~oQJ<FMu~fQtO^}Cf=)ts^*p!vyQ<#7Z#GhAi03&Q} zJEinbD_1A%T5OiZC#c#VOSp1oKDkL$4&|P)x&qpJ#52hQf3;gk<gPF!Nd<X)GFQ%G zp0R%Ks1XnoAmbSn`}?660gZL~M4t7D?fJCRSZPc|(a)y>5(jkenf^@2B>(;ANkguG z^52(V-~59no&8(!ce9L$V{eC2ypiUu0P@SLr|CZK!~-sw1h<dAf#WS0=iup^1Q|5U zi|(|1CgwKZ`?2#s_Us^m9qO4~Ca-U@4mC?0s2BWR-_;KDSaygHR<t+Yr7~>(B>BPa zs&Mo9{s~u!v*FQOj-}t9;l)S~NpcbOZpF@i6D2z3r`vnv5by5x$79*Q`*&<3Z{O!^ zLanId-JbtCPKT-tOu-mP`$Bf^fNk&R!68zc%9fldseVkH>;vaxCrw%=FV5)~8SI6z zQ&L4G?7b)>bj-@ONbB$DRVQ5j`RCy-lyB_vWtzJ>`_+EzK-au5HY;?iKF7S2>&+$~ zewLf|QR%}~R=RhVTlN|rtSHP+UDvQdJ`7I<(Y)0>O;qwWyT_kJ%AK%%*Vd5AtZ6E{ zGc8L#1}?6z8c6_B@pdV`iZS5q9{p)QN}nKT0jAL}s<g(YNlDO!D=|Z9uC6@gzt8*$ z%3_0)sy^&7K|Y(z^}tKSml)Gk6kH}Zb3W4c*~CJF%@DNjI4I+6lTZZLRG~c+;&<mZ zX&0Edts!UaNkp7p19=+hC^?}##hbBcg7mhyFKCqk2It=!dz{?K{W}w?n}mW9>U}Ey z+}%}r0h{z!U34M7$c+nU`xes`Y;QrGe`wcux$HwpeFbkG{1SFA_((m&vw!B3s3Rn- zM+p|QUlZ?0H3Z{USz@YM3oE4f(~m>+rpktJ&`jdPmU>s+u*?*t_ObHXQkH525h2Dj zGk@{l$A-VZk4l&zeD0JFo5-jw@0TNS++<E1<0H@J5?r#H#3&0q4T7}~61#IK;=du2 z2nfnP7zRZ_72lBBlbXOMU-o1fZ)hSZ@ho0}zoCV;@(F1UKG=5bgy8?qjznp&RG+dN z4dB6SR_J`t(%h9-tLbWgO`Rk!o}+hi8P(006XYL1B3q)9o~E9y^hby$tXW#y>PxR* z6=$T!e+4_Hu3IXEp(%3lU_(ZIc}3!p>Ni;&h1Y|5u#9J^akYa#h;9_cAQs#tb+j(& zDd$_poE>WDdM&Tg6B(3h&UN$zksxA~!e?ROargB0QZbX4q0(bFcFz=E{WUZEu7{YS zFL=j{>m|V}i_o;7@XqT1(y|W%CS#xQeL<7!>9#A_(-v&Lvl68rq=^b1^py0T6&p&E z#rJ93tZs1Wclc!}zFRIB`I9%UfFmUk@84d6oJV<Y51DF1<GgZ}ebF$L@7MP|m z&!;#1Smx>bvN@HUe2vzO-#sHgCg)_GUy3s*=`vYG*+DCoj8pQ*K8(ye{_Qw51?IAV z+!{Zt-CnkuyW>FX@xPJ<CEIPsy}c2QaX&E0NZi}E*Egh4C%MBjU=CK>*d`<FA|JVJ z&pCU(@v!735mAW$0jJOZNEJ3tH^Lvs%u!8#hn*g@CCS`J2j=w&IU0>C+bmRil<~vo zqF=G{4Pmt=bcia1d7LYMZeHknxk&U7>dc2yTVy?xUUN|DV|;Cq2=ewiE|{jCCi)wi zv%>l=;0^R_@wD_03g&Zg;Xm5MfjbF$oMTB$bT0h6wyY-pV#jM^pgJ>g$VT#dF~Q$Q z$;F!I{G5p0DI#?SuNqG#SdoZqt@{>@$27CwFRk;_4XG>uN<#vE7z?dU<<hD(#C(Nb zJHja9I}jI{=?Qg;sRikPC={<g<Mu5%W3hzT$KB5+2#qY>rRp=Y*LS+1;-C;`x>V6? z6rkM6Jl|ek9#t*Os}>=#9FPv<v`(2KV&WPd_Ka@83NHgJezrGgPE9*gQX}<!7We!K zMfJfX6IY}6@vEw$(JBWc(NKyVdyY47jL{Fh?7X=(0Tr1)os_>bOQkOZYHH!U!$6{E zEAFiCgN9WKcDfL5iGJUYrXQi;Jca02^F<uG{^pc#WSvLx$|g_8`Rndn%B+QPZd zKCgldMEv17un0Q}pMH@--*+QiUU%wkBmo48G0o!u^*WpMPGkpuN2N1=sD2yvq|F=C z%M}bXO=<mTy~Hx=;pp;Zh0IvYtT$fKOEsaHzQ4Ls3VGf?SCU_NBfX{LGKAqmeD0kQ z?3|b?B$9f|F35^=2P|$h#pDQskON3Za=&ZJRWfBuZ4GMbGqH8>AX%dKbzjQsrtO>N z;74LKe1M0saQetm0{FSWE;dp`lmONQl|fQmCLCzXfX{bax*s<w>iQcXi%Dev(k`nS zI1xeQf?33-A>)(<@S$<V^T%|i$rjOKW~Vsd8LCnk&uBV;76rAgPtYx4(CA=e`<(X? z(S<V?K^NyK#GZ+M7oGZ+qUymbQ_^9-8yDokEBjH<Yt>;)!CZTG<Ii$SZptlL=*c-& zbTs0_2l}A;ai|OvRC@64&)^6-A?w!eomj|#IaS2EkD77Bn;m2l#%J4Ca#}u*##K*2 zA<H$*8M7<^ysrufJkR(~pcA*AGG~*H@9GK0&qLe~6)~?WBA+e%VZ&Z@r8#v`Vzjrk zH@u+G8rs+GGt_5VWm4EvV#JurQ!x9LiE`uq4Hf7p<772?22V)pnRAcPc!BAC1_ApN zq`g$sW%~7T{d(G8#ZH8REqnmEB__QJS5pr4<rw<@9m=PnE9R4){-CIv=K7T@y0Mrk zIWfRfP0uH|nuU{OfwmDPevpt<vjs`mf^D&5VLvy<Ie$YoRWc%yuh_(-mRnXeRSbEX zHhCTJ5yqLeFl5R_K*W{*CxwmE`-R9jjpwiiEKhGpfyGjkSFQb681i<C0kOgXNg&X$ zAK;<;wy|WQyAeanw*d$NhrcgNIJ%K*U^Y%PB*Z*VDgahdw-=0ig)s(&d0<-l+BK<; zwY{N0d{Ql|zRHkq&-whmeYaHU#Z8>ppI-7Hf~QEvoaL77Bg9RokO4`APzmcL*6ljJ zRqGu~F3;#?KK@IOBn;YT8yC5=%!UgRkQQ&##K+XJxQH}vc5K|xQFEmfp%t|YDp`s< z=k)JFWS`aK<Z3^)7vnJiQAR1uX_VVXUo10ue4<Fy9(0AYNL1|o6H`dF{h1C#w9Roh zD*;S;fj6~yPrw-T{A0V>avtE7)K`Oi6NHFH*Su7OR_9s>>yFRB&<AT0I*vV&7sSg^ z)exLC`KWGZGn1#E(<`(|TKAa6tI76tGvj3vS(V!1!t%!gOe7&qk!H-%d2EPtv6m&R z6JI;jxNU|NIr%?hPD+P-390f;p-gqp$W&z|m~fw6y^V`)H<|vs3T%-ujF`cTKZX@| zGYzh)B|S=}6qm?Ftiwc36Z?vD-O`PjpSRSIXh(D7(O6p$S@^-;O+35rS_UfUw0HTC zhdLWb2|Bwrh(-mUNi=hHNa6uE?P>b3)~v>ktjQ9hnX7R*-q&s<qX{iXnWF}yP${Mi zdS5JmeM4qg*_n?dr6p<VYsepy24+}T+zCEoW#H9_nXWVWFfASv<b&>P1#JR<M014@ zMH_bt$dggAZpHcfyof7|H;6aNISib&BOC(PeJw^_$8`In`62CH6$%&~s_fG@L9O<p z9uh+8&Cb$WTyMwp>LKsCNw#>*ufz_kjNM6f67*JeNsx{sL?0&6?B_0tiKH`*3WYM& z(pv(;wrDvn+om)LE2xryj8wuFqTV+2rpE8V_zCZ*ILkL3p02X1xF`SA(Q7>Q&p`Tq z_gpyElm19=$E|oi3~fteRl*supFiCRtt;mx)H#l=N#*hcC_XgQiCMp=8e@=Ks>f}K z)6D0LSezz?in2fy6rRr9_54y?5`!qxg!zgUy`c_!_RLTWPQXa~Bkcsao#A*6TW`U# zmtxC+ZHCVlBXWx5eyd_KCK-rj5)Z};R~D@|RjcS1?dF(Q3N*7Kt5nB`6Zc<auqrwi zsur8010l<)=Blot61|(Fc1*rb-aARVQu%J)O0Utu)H_1?O_oq&2phKAGa5`|{X2}$ z%o=h^xw-8Gx3|o$25w!>#+e^pSK776@9X!h)EcGg_SeU7w6*Ct6(_wR@@rg8+vp?w zS2}%zi`6HA{rl7@W}#BE<)zkRuKD!fT9MMzH+?4@@5$XbTd<$?D3no^21lSf`s%YJ zKhk@@<y<eRyg}tuM-yW|<b8cyMk7$i#!u@3x@sV+>&XM4t;;D|8C?=dU#g_wj+(mN zeS>NdX+;zNoMoM_rF}m%!uk|nmvWGI{5Ug}IuIcvnRsP-<`yiPZ*x|gm$3qjDk-|~ zNT+C?A(;{Z%3=djGrE5(;FvABC&uD_b~JKXAa!tdzBU$YZc2Pmq+z0(p+Ae(9#n?6 zFgO@fS_iMJDC}z=r5lw472#B05SM-1#VU(lM5#)RwMb&}vl!wj4mij8Xe>#H3q$Ts z)c5TI;^H1NzhD`qIWk^IVBFbX^{kLMn1(@SNKUwDNL;gxQ+u;ch@8rmqo=xzv-HXD zshYSx+Ld!==JZ*KRUqf60|^_W;Du4&$o79%j2_E~%3Lx-CrXaBB8kx*12Q|bFC~9l z{ho@zK0RAek=5!Q5Oew6oQ*v$R;fNr*kd{5&TUWcck<}dMH<fE^<!q%f2#GXuWDgi zH2wKs)Q{*=u88SV@}aOERTJKDr@;Y?fMGOnHoy*eG!;D8hn=)<{%eNp)!FE~uUaoH zJ<JxrkTL%1cKLbXC2#%KIuW1MQW7TbhV!+{FQD`!8n(cNfQjYOwr>3W#HEZ=KuS#W zf99Z=qP{1Td!w3h4g7n5L6>!e`GqU3QB^;?2n)=dMHtzwbvJ6QIFT3~vU(0?x=f@3 z#}bf)1kD0%{Q&z39ToKI1z~u^2OLkpu~_q1JgahcL?}Q4amxBi-TZ<OaG8k`UR@D< zM-Q3L#x>*pva48*Hu4n%`jeK}+?MA|Ee3tox;Mt`^qyHu&a-pN8?D_6We-9DGqc(l zkx;b=CxLcz5(>(pZr3$H+SeNO-F_YUYB7Ox>@?l?!-w$?#<!(*o~x<TBa?s9Fs;Kk zalL9w$);p8wDh;Dx9|NmRzT0u^dTV9l~ZlJzg7bvQpN4?8<)^D#fLEv!Iy^;Hy(!D z5_?CHtG@y)5yfs{iOItE!@m!T)1ETvxr|uxHi&CWVN`g3dbvON$+Qe!r)yGsWdLMi z!g~JF5JZE8N3S!Q7)*u=9)5RV==VR6jl_EJKctURl7>J=T5B(gk*28%`ZEK7Zt4$K zY3%(7OX-4>VlM&~udyBY=uDUzFz7Cay>I6r?tN3uRh8KL0;z^HTz~TDRNx@~IboEa z9J_R@;Qk0bJY>WF8-49vuUJfjB*-0&bWz1qSA9c~xmFA&iJSo{=t{`pffv&Sey+$u zj@6FURY@tjdHDkXau2}P4Mp8MRh8#oEpTqM%}m>fXVA3q<<Y)sxPIyT;mOUKX?I`R zVaz?3#<i$_4Z}55-(<f1*YFJ5u$hD$JW=sb#^6N_<pRE{Y3l@U2%fqd@s{M4wytR^ zaU|LpcC-*2*UtrQtVnZeU2?4J#K9n<XR+e6;rB^Gf^$RJs)+Q+rDGlgVeRsj>wy-+ z=HMC<8CD}8@+;hQB3HB$va*l%gZJ*|15jgng|JToB=eWai@)AqCUdOc(4^;kO8st? z92DJyOqfzyx2HD$SVwu{O|BGrdR>}?@Lq@5$@fx6=Iud%o_2>mvy|sc%{R4_R6+G* zp)n*lJMR*zYK4om;AfI*FeH3ZdsLDAY=l87SA#(fxqB-6`xKU(KmUp~&3C-*;>krH zPWJ5gi%1iDi$465lpoK_UUN{g=E|ou+v8qLrG^K#m-rNjm(V&<xQ*`sp>Ou>&BrH2 zbL}?P(C2rWVlD5U!tfiX3DaXxzU~?RTr(!~$0SVK=^QEA+B;*CwclW;;1)M`hEbl= zIB&QdM}Q%ryOUMI_eEA@vZE6#J?T8+kupIOeCH+*o3ueXxrTkFz*}4VD$f3$0iUS3 zD9Lg)p<fz_X3GfdHEGjNx7EZ7W#bFij2&_xvT15V9H?m{HCH#)v(jJ6O%|Z^VHkoi zN-eRuQHYFWOax}+A8m3~jwUTbiSt=_<ul`H__Oixq^71%^v6{h%A2Os&0jE7UU>z0 zlD4vIt>~a3^wbmrfflo80!+EQxzReYLGUJJ97dSg<E;B|c;{r5DpRKd%LG!a5GTsK z`bm?`(*j2OHk-3p3`SVcFU{5SG4t+0{6-!f4-XOLhqrw8O8=;XJje1C_1Wm6z42`` zu$amATYU|p>nWdK<?&~`j&qiiv4{)n@8Z{`Q7Hw5E!sYVbsIm(Rkf#Ba70d(3WL_d z&}(?DNK3kOkds;iB<m&2En9^N6#71m{klIEqY$RjZN#I%%4)4URiKBmh@NHGirNk* zJ#5WY7ofe!*@=2!qmG^mcDYNDfg$1)3x5CGY7<cB$QCAFt%_0>3PB<gP~CKeB9u#% z_7BbEvjwd*B-%#Own%L3l{(sfEHq=;G=&<CKBam>0{1RD3jSpF4#EgyJjyGyt%p40 za~73~Y3tiBbd@RaYrZAZ8Mmy>*kHT2oxlG`;e2J9%yG3}80IOSGxPXouu{I<Kd|@A zh1gY~h>lSpj;}w&7Hjl%TE;CBqjMEkoV9G;y&*U<a@TzM4^1Ur3hkHY`n{xm0}S%% z1nOoU_s-?->k09}g8J&{k|krghiP;domANqisKy|2C~ZD@%E%g_DBqa)R%ktB}UY7 z^7?82z_j+f!TZ8xKb}yO9YAMhKna@c^o?nF2??*i1isriRrIOUef`|cA1Q7nc1qGY z_s!J8@apMK?23A5=6>Sbw>@k6AOezaeQt@wh54pC9KY;2ZQ?UQsH7$C(MK;fNDs3P zE?JDPU~XXC)W*XaH<{lu_h>!6;dn5_UTd2<l(n+7gGQrsM?HY*ud~-v!7oIxFI1)i zpBJHmb<CJ;Ojq{n4j)XTpEk43<`tJ%C{Ky2=LNyVuILc-071i43fL~ywBdZQVU$<L zS2}L8ca-9>#Mm<Cn%|jWD*ys;<K;{BygKd^zCaVZ@9>cWmzQJ+q9?n@O98UtGm*{D zC4W26S0uF^(lS3wj1v_QA6#yE{kdc)ZS<>_Mb#diH42I!%`_om>N!u0NEj2I(MrWD z<u@vnf@yW1WcgN6(VqZ-Ec`<=Mk|xQ?txsq2D}&JL56d3^qkQ=wYku>2#|v6-#V*5 za;!uREDdyp19N5F%0xNF8zuI7QrRN+KYJ$-H{hTK4D#m@r11ghX0Nljl22hGvk&Y} znEW5#?s~I}QRwy)VVNV++3Y#-RG{MvoJFD3&r<>t=!F}}#%|)9=8OIH64}Q3e#l{* z&h=$rtG{ehmw0JWZ9gQ`FF4PqzoIOD?3g3|eiHHyPpw`AVXZn%<CtzFy2MhE@|B<6 zl)ZZ>t|Xza2G(CJ*NtRC%qU|7Xx|n0Iwi6?mzi>G_&Nu44`V5JQ4hAHU4J#XY_^+} zW;nHr{}{+rU_wHOc#`Ka%QHsc{#<?%lYe39T(b}trST;D7+TC*&ibK!7;Lmnr;a;_ zEMH)fbe8|xfnR*<E7V)skvT+1M})77r`;UaPiSvYr3ktTj=O+L?2z~W@=H#$FhoVG z_an-3(m%cvd?f+P_2(M|rC%;wj`2$)qZMmhXYJyP@5`FHW@Hsto>rFB*BHIqR(qD- z|8|0zJeI;$|DDh^4Bh9O&vH{mqhB(MWb{+kO!C9ymzj=LQ5MPRd|WevdMK|hb*GNS zy40(%5<aoV{`Q-ctA|68FD-%F4wXWs9wT2#UUH;gW&21)X)J|t5Rh1wuu0iO^~ZFR z?o*Z6T^hay8k#c|8Zp>aGoi35h}`4_jmb8`nJY<HOe}jPWwqn79dNv(Xqg$rS&|V< zO0=PK_tSXi5d9B$3WjwzYgGtVVoLEhSj>XA(GC|Vl4?I|((_X}Gg7Nd$BXC>s+k6x zFZ_9x4$~=$ncS8Ehb8E6w?J~JQZt4#c+mXiSz|+*eBdmUQ)4=~tOqvCn*G!CzC@X5 z;Sh^flj+BSJV)9qgRxV({efI=_>PUEP%*Y+N{f!8W`Ba6ebu&M$nzji(Xav63)NL- z?U=~s=1Qxvw?7w<4{0*HexsrDwwNFPl)DTJCWRo8Q&3fMzs;~BI5FLsn=c8GoKpT8 zw>bg!);DvM;@FN#&OVzB5xmi3u9#wGiIap2FY#sNFW1!QvWep$-e$lk(F~rR7K8Fv zEM^bYr?l=>c=;?5nHB>w^veZI00u#3SrTr(nSaRV1cEGTf;h~TCT*xi(6SC<EytQP zQWGSG<79{&vMt+|;<RvP;$k}WN%#(@EWqW(R#`gZhGGOimDWW7o-iOPG9(z`GFm6d z;)axXX<t8_D5Jgaq5|J5`MLznw()`}%<N)|bj&~%Wb~J<#F&xe$P~R`I@eTkbcYEe z@}yK6eyA8L_s`~s3Z)<%+t($GPAOW9I4fz%>#;1tUVGRwt_;HGN1xwte!lhhar>Dy za$5NK`p#SIV!eAQ8s{01VXIdX`XaYdJ!43FEQqy>V<wUW+7{rld;W(y;@KGV%_r(@ zjCRH{WiLqu?j25;RXKH)&Kgf>&s$}Sq}kTP7iikXLlwj~tVarfnF?jgmO;#=QWzF5 zuMqoOftSeF=jyDOn%4~UQlH3hZL_=FoxlcZg9D-!ba6tQ#o`B4S>!uMdgOqSX4@O! zDWE?FM(X(-oisaNBaCi>7&-r@`_si>9+hNKybGZXn2p3x6KP7PfXh<9Pp4?#?WO7g z+Ebjb31h#=^Cwi3ucISMX2mWz-;&eP?WJS$HP#=D>o4&6gVfPoHg}VcPz=4VkHmN~ z6XWkCziB?D-hk}iy6`a)Q7m8Dj?Z*XFol2r(m1M9%L&lfS;LkRK4fF`G1XU1qT=PV zn<3@tR@{Gy`EGEGPchkguC<>Tznd;K$p26E0n*by(Nph`=_?)Cdp-OR{k*D&sq<6; zW@hmMLmNGRxyta%@YlM?5++|QBnA9?WKjhW-PqnNzLBgl=<R&>{?6aldH6$`CArR| z_iC!>-SXaN!Uo5jdra@mvi+ku!)$#C!gN;LHg|gOL9*Bt?M^fKj$cQ>IQXkUr$Te> zEIZPRMV;P(Bm6~VL-M1|O_`})b)abQ^gEG<$Va33QzxAo$ZHdyn=IB6E)|)FT;1{6 zvHvc3Ib2>9ijuy9s=J;#@=MG*>KGgG;56q+r;x(mNeTq3`V)#<DNhuvL>+lOjyZh> z+#en55hj0S82jWZ84-}%b1lBmdiMLs!RgD9OE{-(!A(;o+a_r+v*S89&mO1KDM`6= z`3`@0>|&dbsesHkhEp<I^CsJy5+V1S0LAF3+T)|KcracdMH7cZ+%il&xX^a|509fP zkhn>8Ng#761SJhtf2S<X*YqUcrHSKo1}eMca8rt@L)*^R^p_&MlDV~}D~x`NdI!(F zFz;=y!JmISRiR`Bry9P?$Kme`q$lzC(6_RY=%G=e#3SJ3Hh7N6{v=N~#V$@Nu*2Fg z_43cZBzH~pg4D1XA@Ji{=f#AZM763tz9p{o$Fl3<P{wJN%HrXm*Y_ZEp$s+cmpH z5sw6;6D`F|zLI?dyA)URA(u|#(W*n+?FV#x6|1ipe1?sMfqQ!t;X^51;g|w(p8!qU zTVx6%X7#mxb+VG{)~K0Gf|MN>@(~J~?nOt$wj|x{QS&6J$8#5BtIB!?Z|HYW!W$j1 zy|;4RnD+GWJb;qF^8yRqp-JQZ^tnF5jp(!sQ--qF1fPUYE#;7-67Jsr&;1G)%fvD7 z+GA3WObUj-n?Rn6H9r9(p#v7i(i}waP4SgUN@Fs)_Ya%{N}qp@d?6fLt;tHcoITVd z@$E089%Zu!61`Dz%OWg+0iJi>EFQ~6t0mo==z}g$YD0HL`AJd6cDqz9@%!Cg$WA=9 z0ysU<2*WHPbt_euv0=g1l+$_Om3XY0cj!OYsgWN=5jjRa2cq9bTlc$e%j8h{LH|eJ z@R=k0QMw)Mb3|@!GtWABO=;!c%-ovR@s#A7Za5~zru>-qVR-I)9sG@0qI*LCI6GK! zhr)4=obLGX1kjkc{QDng+=GzI9Ku*)q8)X1#VQ|r^0VFnvNLf1X@Du5i-km)pp8lN znFXE5ij0oWfO?ly+6RgvbU~;03$58Iwzvodx=&Hgfi3p63R7+4OO9(dd;E=pEcgPv zRb#cDj8d%knSjO0v{9_&x-`!iozkf0LcM;Z45b|Yn_<}0+bny495&j@5tIMss0ls> zo$uC0AFdAulzSv0LaTRdEdR+ANtAnwk|@egOw=6mR~j%6rAke1{YFM?s9Wnk00*Ln zMVxe{TWWQv0=k<5<O3P@tZanJKmjDfas@2UjU=gX0=C94=(p#9oayzJQ)E}w0EV0= zK4sFce~99uQ+S!{g{^)O#oTb*-D%?mvcH}=xKEzYa1DtWp%q_BMn_@-A-a&47O(B^ zFvr%-Fd!j4#Sjha*iS83Tb&;Z(NxLd;ZxyK=4VxZeGiifA2%dC_|q0>ov1^=n7X<S zYlA&&&Ni_-EAp55aeum=>EZ>tcN4#+#roy-HD_;STc@8<V&4F`;_m3(f<NhRh~8-J z({YZXh30IZ0`g<c7jbP>sF923UMCN3C~oVM!^l94|3)AR1K!x|X|FFo=Zzrj_O)I- z`v}bo$7RsgkUR5gz^WUt<c;{{^(~OEOTwufE0jB2lAg{)W8<EN4UI1LBbqWP!)}A< z<4T>U`6b4S`Mi}vnM*?|iKrzztP23>({Xpd_Mk#drMOybrehOnT7bkj0r!u`DQU!R z0ERi{gda{)PV4ngNj!a*;x?Ose5J=tsIE@yvj47CnGDSjRRaF^JbVY76ludbxai)7 z+i$L%Es7cSuAE?BiWG@_Z$26=r=EN4X~7b?3sMw)+e;Ms5>$3QxPNr^8W-yx(*&(} ztBmQnf%^l<$w_+rlY+gdgjZ+bO&j8vVT|)q?r6O>!g*W{g~51IkG0_SAT?6A270rP zem}k1-jzGN*s~iC;I^YOu2Y%Ek)e+0zp9$zQ4s-h@U)p>#q}|!mm{;HGv8Q1P6z05 z`W)IFCw!02ky-!Euc`P^<XQ?CJpv9~I@iKjrq3rB?N3yfR_qeuJV~Tb4>JEw7J9%1 z|2Ma&x1p9-U(v;$BArl=yAU|$S#P%s2yZu;urSpC_sY^zP$wK6WH2vd*m@tR&{RHC zl`<=#GU)fzdQA*BZ31F0%~(maFWF)Lzu8ajK~+=OTc}K5El%31xc5c@r(>bk;lyqj zC+Jcqp$mxz%X9d9iJg{nnI#)c3)N*O@z&t6QNpTZv5&VP&=CGnEn9ux4@hSNmjAxF z2Ghq|m{aU$$)eM%(t#neg<j&dJ%@okgB-wpB2U<7z=bUc75C@Y&mppn0s6N9h)3bx z!o1`rF+KWaJ8AvcZHf`%w#_GJ!xl@dlEed)X++=n&vu@)4|K1wL)r((bWO$mUyZ5% z=Z+uf9wZo-#elk|W1IP;mrUWwZori$p8^s*<4JN1krgzu`?>gSK%Y7Y?Yys-#QD3V z7$H^+G1zC(!q<)y@lm*py0-Im8Gk6kGcwGN36z#LFA6eX_rW7$HuMu{Xpn%T_)YNG z|9qcLGR#x;U-t0Ha2xO$vsQ1^QzD3bqgM__2uh;p^cMO59L5c6`hO1ZP0|}H3?!a_ za9|+=2k<tw4S{x-*%Qm*OQz#1g;9NZzMdY(k%XVtrjjk|71x)r9S94>Bp+9Sd!J+_ zEric-!n}GWj$dfnV8A~P9o?+gYIYStZ%&OXESX}Kk1=FcWWIeGA^!h8+hGaY)-81X z2YNc9NJAf<{OhO2{$17sUp$_~ZTfe~**UCli~hg3ivF+RI`oCzzcDrGxG?p<xm&<S zW)1M6AB}%R|Cfdl4P*7GN{sf|QMBn&dP+3^ngs5BLpa?GK<cc%@QGW%f@qk4Hoe!$ zFUT$keP)2Q)%xPl|3}z6MpwE7jl#ji6HIK|wr$(knb@{%PbQpjV%z4#$;8&gHol!X z=iKjIcfD)fAA9e9p53bIs_N?M>gurDpZ#?p>iL%7_@4#)*(>z9s)14Io7qaWDLEox zR`B4!*F7p?-tqnWh&9D|qDz_YAK*zKfYOPVvG)9Gn*{blIDI}`>B5}(#4Bmk1jkN$ z0(>ZjJ<NFjD<zMS{V-{L7|o6=^!_0|I3Ve@<<h$fodX&A#>daO*?bcyB0cpQ{rE#* z!pTwq_Zt=Tu00WpT{?OvK*SkgRBzpR#PW5byiExK?;o^fDT~tU9%8@q2}!}_$7BMQ z`%8J%aHKS0dfj0>Ctx8dCUI&1A<qcoq9(@207#~8;^U_|{}A3XL}1D+y<uOLYfpBH zQyfNl@`r>dPB^X|yZ=|>VtxPxM4mkm(P1Xf2f*3FCoXLq<?mG24y?5k0w^|bO78PP zm_B$`Uw~wh(a!qiFNq!h9};tQ?W6|V&PDIGRQ=1bvxC)^<qDvGk?j91+_?<llAbv% zhC36z2lte*^r-exMjUvR2I3~Kzh*WqX&uNq@D}UtuW^*R#F?sn`zhnd%nt9;UmJ<^ zM`$(Z@2db`akf*&X9izs(hK3=q`z*R0#i$&?qqfKANeeTx)QaPoBe=~Jq9DRkbj~y znDc*((WDd9wLAhGdBc?qG=0HePkcM80h43<Ud;&K7-(n53)U@DP^<QbhgimTNuMr- z&rJ~d1_kv4ftM?1eynxeyyL9D`M$kPK6(igms787b>*Crl4gw}3vkWdCY+KGc+%D4 z^{3_TgAGj<mIzFDKD=6oolx7w?1~7z(KmlCe@!$O7?ZCTVaI-C7JrjZs?d6i<*h92 zl{Uu9-4&^!p@0+{{qwGLN7t5G(7b%@8%0vlv#k7zd_U%!q8d|Hz;~=9Epf2s=O=0i z9ZjO{>f)weIf-e~&7Q_6DMTovnsHJTXXAxrny-3nzFHKcehC7p#Y`dN4p{F&(v{gX zk}a@BClh`aHHanEu7GU!ZU;5DZD}pRwTlV{h9Xjj{k2`tpJM`h`FTewKv%#Wac{Hb z$Kkczt}`NPq~gX%7-B3#rb>MB4xE|rGsXlSUn#;18O!^dvai4+VApyO)~|39UB-H( z3zByJQx0-_-Ss(zj}(?c6ZDgGBSy|-RoARL&|%B8uNo!5&cPH0aMYduHSd#aw6<tt zs-SWoGJ6UXf$XXpempN?%~z<2Gt};zkZTA8cZ%lZJ-7qbLMRgiNh1Y>15S!1rJL#G zk&AeF>Q}D_2(80}Q@U-cuve&wHn8lx`ua!7>wBeKLU0micXZC+ybX(iSls%TXDJ0& z-fg<Zluk&}hF?4P_it{1E;8W4!GK-iM%1<fj)Q0g<#OPMS^L{oLQw+>A{|SHtVulB zxQ{iH1Lq%CT;pfPo%BATrX5A9g(`w!`zagF<VKG>+CC}ZtKl2J+^{6uz8~9IWr#QS zGpC%JOrM;tV-G@p35}P5MY_<qo?d-}83IY_A}LX4&G-az9>V{KSr#G7pkaw~B(QsB z5aQXi2i>~<roS?I*)|~lSs&j7vOaO*ZE<C3D@+(A`=?c$B;w|Ppt*u*WGSuV6*faD zw^%=Vl$7b_L7seox{ImylQyr?ZNiKKu)bRA4iy2aj^E_T>saQ}z)gu69>U~K^#N&v zQsnQa5FFA3Q>B%GFZBa{KW~zr5L?Qn&*v1R&l_M0-5|fucnSTuL4Yo-QmdIsD-HhY z)e|!VRbL8>jJEI2vqMstGv_yKs^(ejtL#}7lVW=TErR*kdJK|1xpTAJInvWwUT9bV zl<olCnA2nh;)lrw6(nq`#73bp@{C^Q+`+m^P`rJrHZ5R(T?c@!HwS0yX(uRrjy8F@ zq~LX)`zAu4cQ1c5w9aES>+82Rt7F0flML0}5g}SZ6?Mmm6cey<hu9HOFu~7!yPC0T z5hY8__;mEib!~WR26P&gck?U%@u2)`nC@GdqJT5W@1obY*5U(OfZ^$210RZFP0bGf z>0prOY>Y5D+M&;Y|H&ZClTK`u%v>79W|GSQ_$_jXHt#dG^?Erixr9$wJtlAevhlV< zSMxXb^0KIiq1P+p?V3sk^0jpaMo7e(-f!-!3{2$s$Ji#{pYNlhdqm2a$?*w*#tQLS z?wv9QpOPV#5KN`=6pPm8yZzNx%|?mduMFyAU=QMr!sq3Uy7&<M*uU@Rtm=HEOU{Pa zSUj<RkBh_}_v{$yBH|kZKZrY?7f3svhc8CDEQnl{P;p@neD2{6zj(6;*{<V(e?9<o z5yc%}tw&;1InED(G0J$kG~&s0wS?lp+8_Aftk=p2-&OeE=ZDb{dFG~QR0Gl=ohdM@ zHzH5}sNI2r<bl@mXh0YhC}J)-@(|s^i2Ot?UZA-K<z=cOm9S^I#t;dyWLJiv79=V9 z#tmxV7Jn$JpX|quncDDL?A>qZuDPZVYOLk7Blu-<j0x)e0%RT&1&)6(IBwz>4x}BZ zqCq@Yb6k~iFN#A-$w8;g^iB)`5zGCW*jI*UsWTL7!XKXc+kOinWAZ)4-as$H6Es<N zSFIi=3>O4#jLHm%RTV1~NPnm?y_ae@g(E$TN@gbveZac&k5!jNLE+nWqYEvJ%Huo4 z$8dV@MUQX1v$fF&^hdb$^tw&>&BY7kpEr{#pw5I_ZoBoGN5}Qt6Fg=^9FL8_rRMMT zf)Ly6waWd5C0w^&@A~FK%tC766c8*i=%3;9i&M#+H|t(Q*F!R1L#IQc#`EFK(%tkZ z8}ZnuN}p;>E|f4LL!QFC7wEm0JvZrhVSm#D5Tr38J3^;bWKbY4M)dm*g=>CKwJ8p- zwp~!yo%H@n?Sp*M8I(9q1qUaf`*l|GdzkMF7FWXBjP=7ySRvMRyi6T%*e%%I!wZ)- zFRNK`c>8Cp5ATdD26=a9tS{U(zr*7jTd)_s_sv9m41eSqnXzVEw&fz!vTr-BwdDd> z=R<k$+p*A#jrZMDfNU(Fjt}0X#jsxaJdQ1g$8H7uBCCb34ED5%h^ns+7r)w2t~#B7 z02<C!6ku@!w{40t`2o(#2K&|sWMr$g`o9}#{N<)LKkK6zBwy;w?5gTrnkFyeT&C!o z1-D%ciVcLrIsOVqjLAlG4bqhDH5pS0`BDW_O{VA2*m-jfSw$X6{y7&DC30!K%QiTL z(!t*eS^lnV(*_%NvwXXeW76T&8r{v(%*GBE(Ytm7%#+4H&uL%f;z0wgmP;hIWAhH} z+JQ~`HxAiFC3L&JD?YaYS%$xtnzH1U?jU}?BAF1U|An&d>Ksd2c387__)PYpjfO!8 zHQ9~2e+JHJOgrSxb-x6JKK2xwV6TP_J2CvGP*`))uJF>IDYR7+8D)92i)JCcS$Pj& z)7?Q=y!iUR+FCU>3qd>n^y63Q+KL))3VFD*^^4W1=tHOIY9u%wfeeV2q-I@x0yY7) zmmo#MZ+C>=Ed%a3YvF48PYWI+1^!_N?4vTFv_Dvs<?*07BN%!1U=Axl5JzQppD$E1 z%Dq1Nlp(J~u^NMF0en5?{=^=db>+y;7!B+br47@e>*$JLuZ2oGQu!Ex*L#w_+0Bpp z^WC`hE{&gH4DgupIQr$%OHlsv#>-t{^Dh($i5O<RBd2w4277Y>XKg&ym-l4_G#4dZ z=iZ@RLs~=Q2guwo-dFcMO;!(402KQp#ru0!e+L|q!|D!ZX%ykeu{U3IH`l>6H#jwE z$p<g|$DGIKLL4%}m)BAe*W)rtaQ7*qXRnfvbS8Corw+A(VDE-s5%1l4-WeLwo39#v zn+p*#IO3>@A4AHJtxt*yRO@-_C`$areGXMz$GvtFNN|_I$3JKv0RQi~ntpmg{I9tn z7E5IIYzViCXk6Q^pB6WAZn*OiUwtV2ZtgpJYnBl^H)YT&FKR{69_*icINKWtzcc!4 z@|J9VZ6L6+<uQQTGHo!>lZmg69J75Vu1ult#8`EISKCB;n0t2Pr@oj0aeZccw%%j> z=C2YaeHd&8$jV6OYkNIg!{D;>KWhuQA|-v{i+h=Td7Y^_HPr!!8_qIR$<}z(aKC!u zBKcE~WDRoPH?<|w@y)F-o-lEJ%!sr7O-*}ivyd2q)cf5m5}?rOng<emZlE?yuOHsu z9R#~{FN0Pa^>?_23a>tW<Qg?m=v<%!*?QL4tBEoY!v<31;=RmA`eRW4M=ts!ebE0c zmnx|1g|Y|E;kgYX6Tz)q8!SO)IIkiD6qY2ej*c;_12OZ+bx*{wA!|<fMFO&xgm*1Z zR)jqlDJAr*sTzHPrLD(&DhU~AJpfj6J%8004}zbI+9y{(BS!H{T=Q7|OwZxgPv;9H zi9(dP=lq$7Ax~BA%Vq)UEcbGW!la4wIB6(EhyU>^XsA!=&n8i<GzC5ZZi;;LE}i<- z#@qx_8Wr&J0Xs_cd~Yp2jLnr|vw)6U-I4d?Nk2A6vMT~h&CaQU=Ja;?Y<|c>q<Qf- zZJEur{X}Z2JhoYmoUTtu;96*r+9*eFa4p^)uTgd`NJOs)8w$SBl8?rgW2QEt9>9RM zbaH*cCL;|c)&#^}J60A#t5S=DJyA52T#Ll@JMb}^oPNN71_!D%YLHcY7h5#0@rQuU ztfwVIt;%rUQHjr~VLFvbL@n!>ctHVn(bPevEqmOpCE&)@yHom4Plna1utQG3AKc)! zp57Eb_|znO0ZsJN=$=}0iD+nt99O6a`F*eI9Qf2d=A(}}(xX{{N9*}`ZH@`^!M2oH zGxfPXKZBbP60UP{gozIk{YXPs)g7OfV#~JL-c%uIk8~9=RgA}^ns)gMiSX*`nowTS z<KU?oupf6%R0K?#__k;A>ks9MKsj=e5r$|nZU-RfhSG3#a6@d8W7lw%z@Y0r0=bWF zE^7-asC~v;LF760oW51zubn+RKa$t8f6Y_}tDUV(b1v@G0-SeCq&c_D?vkyQ*j4r( zbswhRx}G6ur|{X%`_5S$&o3xEmS^2L^Q5&IzPhV}Sru3OcKj#@Y!aA|*Qwfb+$iq_ z1}VVuAaH|vrIYBXl_cn<h#H4FGKJr+X!?=5M(h-cb%v216s8G~=LIHE;#?BAE}IR2 zPYYuE1uM^D`<q1Qz}LV;zlk0|p5@gyfy+G{__PxQ{5o_baH~H4gE#a`i4SM@V7KEb z8{Tm(6RV|<+a3_~(x#ToVwN67PsEdxbu~>U5ipIV>?8i@q_}NA=&k`-0?(AX8~ail zljmvKoqH&zrLT2^g!BHQAU(48{*u%1{z&k&@va@lg$v%gL;(=U0E~~+2b)Rin!y(6 znokNyY&XJTT9r2z+dMA?v18`M?(OCbU!G^-W+hbK2=^h55JQ|k9uQ`&xJX=|L$NxM zv{{EP(9AV@2pT4;{f3Ies&DpJ-mzJjrv6zx9+tvFkiBX2n}&k(M4;<VAV*e`TS2c^ zperqBWKE*{R;q7~4WR$|Q3IVQ36cFlaG&tlHrikM($BHX8lpnV6b;P5@L76KTCV7) zJBEg3B>!;DLTw_6NnYRJiS)U(0~MCg`LJekvbtQvM!G_!{Z3-%VqkuAiU4hSR9?e^ zgo2aKXxzylnbe~Z?65%i21><PZ;{@Jm~uk002*o9uR#8!Uq$mBxeNf#k?&C(R)Ve8 zS`6^tqA^$wYD7hRUwuYDbLE4MA)uu7$9qWcu8bv(6}um=8f+kCPC)Ln#TyLj*bhuU zAaZ(CQt3pJ*~rxwx%ed@PrG;cGXe6lFd$k%<LHdak0HK&c|Wt5k0QJN3dzQ;kSMY7 zXJWI0NEL<7D&2`8AwG;fW`l<>yPD96m{iO6ou1Q|7^9`}@V9WzFqopfv&%jIqGrsO z@uq$!>#1-!C8MNm!tAG#x{(so=cQ08mcOepMM;}J{;71XOlKYhVDx^F9JW2u{ch}7 zZn51@_#$~!>=7FylFBsRi*aHchbZvfBzq@93~6dOmMKwWNz!#+>wYdPoiC`yRJ!eH ztsuT<4~JmU3((V9Pl;rlJzz#HI11mr@!W!ReqK7`VdIXBu}}1y$?`oEl&(QJpr`l+ zqTHghdr~nr&_p#O<5M#1_1>1ZHvy5Ik%{ay?dwMc+(1<!jf&n9{{Hryv<^EUKOGXY zZcg<@Z%y*&i~h*5Vt?24Vr2V$mmd%FRspk^2{gLO>Rj8)$D&(D)`VvhCLkq_WjIsT z=v(gOuCz_+4Jsj_r`{jBTQquBhKjun0?+=QA1atsUcpGKB~`-6xA%^_HmH2W@%L}{ z&-f0i4nq7lreC=tLj$kNN6tUxtF>Ukjl<u&k5Qr$slLBTIq-{GquZb!tZ?~$2~4CQ zfy$^1tcAA+HION&pUx5eUhS(nsf(Kq?q^m*)-bv^Xl(bh34KMO^158^`L*!n?fE5Z zffJx#F!$nhtJ#0T1M9piF!Jisx~}BAxT_|7dq2B>x6!4#+wuN7A^mLR!jneuhKJaK zxzGH_8R6IlrxtDQnG)gWH-#f_N=dwN7{iMjLN7Gxv3yjP+2OMGCVg4~MCx;v&qW^? zgEE&Bz{r@s&L`g9j-M7KQM6JxX5)NbA`};cu0xd|-BH_2KC>-%ty=$+>1#~`>J!RG z*^alxPWpWP51gLEQ`i{B5IwldL`iGw!Fg)uA(8%}Dw5P+1h3sA<x8J#Xn1)R8LAI% zY_#Ss!Z}m};&YaM3_n3KiCLD(LtL22?SJBdN7gF3j{WpL?dtjb`rbBOqvX+zxf1p3 zxfkW<D4&^IeAqtbD&*3xoV%v?w?g9c*K;>?p3hMo3vF*7ouNCsyrzbKf6J}G*N};E z$)F`w^*v|Tu(TFif8IDRm&H_Xb$aCTrC^c$u8`7FkZ8fQkWtgyu{9BVWD#5O0Xmw5 zI(O2K2xSM(Pq`L5A-QYP2A||Qe5{>9-acKezx!4RG`5y$@{OC;kTXyi+4{w~YW#S( zhkCuG)I6$^=qbxx`=<YiZne{vtMH9<COGSk%aVD-%gan9KbOCGc;npqDAdzRWv4o! z<Nt?}=L5?2JCRDW6(xtoxui-rRoq6W6vfxq`uNv-1~iXzzplCxhsEKB^;;ljyzCsB zvdUOro`VKk<x;SZ8&!amzfM;$_m}K9mV!C0Ef21oUM7Cn95AnZg1HZM3T}gD^X<~W zmFN_9z<sO?bj|SmQh#$-6Y?>j7GD-N&Tog<UC^Qck#i^_<s%eipaiD^l{7jEeO_ph zeqFN!hk<4D&1!z|Qk-;Mu-`-FI-otD3Rr0m^1A4*?z>xmWV@wY*T-D;xW4jT)()Ni zbb-JM?RR|*?>=ujP7hkFB&cZFs5C<`Zu7N&Fl_U!PH#N!f@JA5?H=Mk$_kz=nQVQO z?sbgqD^`EKzvMN=G8=95vBO?l6LP3Y^v*;@`K~(%=NsJ^5V-*!GtTKd6cS?CqB#h0 zX)anLYitrGLiLr7s;7W<RO?07<WYM{mHv?Vmk*^q-61u?exNpqvk)IK+)Q{lAZ9-B zOH)125wAqGTXqgMv5@@~w+7=xkiA5)fQ;*F7>%j^p5_QcS}T<%9~OQ-dO>v<_7*_M z8($iYTW$>@r&L*%2u>OL>=MwZo=-8CE*Imz$E2k<C%J=1v6@F%gxKjd1FKBMdq4p< zQ%Y!76{VdR$4bQk5tR=Sp$4a19@3_mN7xdcYN#+<D#6SY$u}^3!D%-1do3`(&^{nf zLk=}^LN+(AHdh89B&-hS=@@oe;D%P1f#2f*(fMnTRH=apVxIJse^`Z3!V=QM3Bbq= zW3V%D`Anr+G97vX;S=KNh<0<TEit&N2V4J)!^Wl6y92LwXhpZRwUwVn21buPRVtMX z-F%J}M4K?IWa|758?TbvHFjsz$GQ1MUMUX{$=#7eHk{9M97U^SRhX->u=Sar<F*z- zf*pgw$<{yh8@r_X?l13Nb3K`<@2R?u$z;3;zspr&LU@SMYfFM&kj2h2xQXEvPyjhR zi9dZ<#(_&cZkp)pF~d#d5yFAKB813@1Rde((JyN?N?wDvlpHCX#fczAJWLo5M-$J5 zn8a8t4Nj7~L#r(~tt5viT=7mcsCMo%#1J~^Cxq|~sOC$?@0J0+k5Qkox!kk(QJj=# zgx{*f`Pt6EaIhIG*(K1@%9sdccLCIpb5ib*qXSL%Sj%+1`U6Uk#p?Koazmgu+ED&+ zZ9Yr-!xq7k>DI_7ciJnER(YKKbPbJo$}{a*{`$mCI6ulVhbBm{WN7wqK_Hq>T~Tb+ zX0Ri?3*wS8$>N>*%z0tnuLqFMlHywuwl}k^p~jjcgMK?F)#QDmlOC}zpq4h|lPHaM zAw2b;gq9G6iL@Qp^<XfXexDOn>TQgJFPeBE^T%Aa>h0O~K4HK;{mngyJspo>=aOw= zbAPKsLVAt)ebl|YgMb<il_G)fz<~jVVaL~2uCN8t&c<G3+%(SIBN5_vg^y`3(^-jo zA;_!~n$K#|3zJsx0^WlWysk|Bo{J4!u0Fw%XJla138tk%7R42%P`kNYGgZP!c38>v zyPCfk2lyE~5s6y%x2%aRoc;*=nHZWH;?qk@luWyOqT(ORE_JC7gLH4Kt=Sl!eTt>W zy#j;+E4^@iY8`#fZid>}vCjvZ&7wy$D}_dhyR$Qlmt@<q_{*~1df)tjlXZ?aGnbr7 z(Z<H{c|=}A`8T~hk*9B)-_BM|L6!MVD&woC>^Z_QFr+TxzXhG^9@11WfR&F6#~t^h z5$u#h*yns}*G(ZaZ&b1-PYE4n`AyqE4*FGXxpAXNv<D%~nmwJt(NwB&WoA37_3JD` zWS@ng&9YFGmxL7>Ogv5Qu;;8`BqOEwMm<T2w(@aTp{VUVhE||4gMv`lr;FN#H8uJ5 zF^)-ZEE6rTI)`+l#4OeNPCkR84$OUjo<a97Z$G_7943aaJ4bYQ3iye8Mm}XsAqOa) zAUV|3;ftgZN4nE~QS!HLxX%|X3-TSBA?hi;+feYV)kCAW4a{zxHzxS{W0LWq5!#bB zkLh0B)BDtl;{{GGKO8UO?b+*{Cu9$%<$I+0MOC3-EQFNF4d1B5wucE~f4VV==4z7r z4Qw41*|yN+DZ<Y9R>6w>&qXT6{e%zGc|22^-PLd1Mcn@OM;U$`DE9TeX%x8{;Dj9W ziXZts<}iXC<A~C~LHo`FHD2cu$1z2&mnOl%jk76#9d9Bawr#uo^x$DlyBz6A%u*zw z`?6y{cC(rc#C*>r#=85HV)D*4Kbjp$0VfX;CJ#)TiKSw!5ry3aS8-PRyEB+$KEDE4 zmov~f6FI??6K>Pf{3Z4&aC|m~Sp!TR;_<MLtRfF+HA;tQ%QY>N%|r@`X>Sh5xRzh9 zD;(a(30k325w?S9)*!Dq8_BixT=qDTS&x<#no<)21$}j6VW!yBPe)kiv6CPd!e3e_ zXlLy+hjGszKdH%YRx9#fhrP&^{f@m3EQmvz-Hw$Wm|GSI$$h*36(HZ;!F-ueHnx%= zg+#m?13XCHft4Qo8?%YT35u=Qh&)5SajMzbERSQC8fQ)P{HGf^w)08B#IkSfMi>OX za$M)i7hKy(*;IFn?oXR6P4$yzbI@%O{4kT9Jh`)?RadnU`g^a%D9%nRGQNMNbU<y% z!G@Pat9ol77Lr?#tEm@}tNy}moma@bB+77wfKox}^iAi7EKCO)5T?GrS=E!Npj)X! z$@Il=fZYv?Kp({=_e@CxD*UqSP0HzijcOmId*R{ADOHf1)jrF#hqHs;1G8xZYdcia zXP=H_4#PtqT@{l1%A+Mix>bL<AS&aS@+&4{UC~aiK1=pS3%DJ^BZqLlJi#nu6YqZX z@YPbn-W>nnjvTP-tclYN!j^@O<&Yy*{$(3pC?ox1wHz`yBLZEbE9((xmJ<m*?PTqD zgO_!EpnWV90ghD$k!#~xlzsi3Yt5>;2brN5AT#YLCY9&n=U#M2MEyK-1%%8Bnoa|) ze;rYh(uS1>^Hf>thegqgPC?w~3j(53QAQ0dbSrV@P?<$W&3JcGs?^jBKTNVV`Hpeq zO0+4=P3UK<DsvA_+aIQ&Kx_$(^(`~>&PVI?b7<?sv=aYh_im+c_$b$L$zFJ>dAIPq z%>m?EGZAu*>fcv@V-33V+=Xv7&ogI5&%CFdimZ`d0d?6~gaV7h8xnSU%`X~1)>}b` zZ2dp>N2t2q+unVabvkl)Z>?lk>U5`4R4p=@^nNpNBBieWyr&J&LG3BJe6HGaV<sEk zy@=VB8R~FV{vBV=tq_FgJ)&xIP6rjKmo+{Fv5Xy95n<tlVQ0C5XW&m?kjkDnd%2It z9Dv1a(lbWBjg=R^cGD0yTw(0IAO}-QzEA8a1p*B5y7}x|%Q-wGn}8?gika@(jvCqP ze@8mYT}_e8eIUJ(4ve60R#AYNXjx4JCuIaQHLLB!;+z2^VdB}o6j8GsI@UL{kfAn! zMdd-h<Wla2!+qt*vtXVfEXjDg<5Zwii~a+usXNzGwlqSf@jf~wlG%U#(7Yu7+RQU) z8%zpX!SMBR-O}`#3I0IFX^fGG0GlH|?*g@uEyI7=adQh~Cf*t_$&xrYjuI!#l?c3^ z{EVpsM=ASI8;?_j6SDI!?_ZvJdoEJ^wdB63`I{0VJQxv*?;<&^1cVQbU0g<DhO;sc z8%ynQ`$HW|2ajw$?kbFz$)P@N%As2rn1(DH78s-1x?35c)IgigD#8*i-zrQSxRdsz z#EAV!!KaTJd(#dm?1FrmGDu%YDzv4uCJ&MtG$BF#g@VG4?h2Blxj55^-GrVhn;K`4 zAE%5bnu=YZZs;y0R?(gJ6I6f_77;(B8E=vCiOl*bW8eChuZa<sdu???7Mg&LW`7}D zdPPV|3RO_+cJjmt9j#bmfOty17RrUSQI-_fTzg%0d#_HLI@HsZoVMl%1F!d9B`Pd* z04>Q68laWn4uR)T#PkVjUGVx@@Ssi31A@-1KP*>+tH9l>s}WcjyfM3HsK-Aw#Tc4~ zj2b#mY}a0|_j0Gv*lv!6ax;&aqV#QFmmYF3(RSiPTcGs88vdyQ6}U-@V_j@wD$lnM zdMT~1u79GS&%ksA;|JE*M`UfHd4(`vEcaQ)mvTFSzoZAV+$9539poPp@Q(cgEEq*6 zzIwxv-u|6~=>!CymNwh1_AUr>A>l{2%Xv)5nrhK!%fwuCvd{rE`wU=~Pu_+`O!(vM zp?hn1(+%AAwrke3<^B^k(4f4Ui=AsE$NB*pRfZ72;q@TY-)swj?nSm*9IU1%q1q=8 zbveze4>x-Kw5qL%#H|Z>?e7h2e%b`qTG@MQ_{k`o&BjDCE^`N==4eI{BwM|OI1~cu zVtdX~2}IF8S?qHgXzCmGg@~V#^t{dIsNlCjJ7Z1k1UAhteNR~K_0_q9>D}a^1NUu` zpJ<IWL249F+O#!6xTY-i5UfFU(b#(KBYTVWxNL!K6x6$*^m(4>VE~K5G&fYoAX!~d zz`+SCYpnNIuZ-RWEpwo>#TbFAn?!{hF?1(|+%9(BPFovm3b?w8{XXh$$!XJG<hyAy zbnghlAm2<{i9wtj%Mv_?<7aBhc#fGpO?rll4GL@C;%xZy7P+%YbjB&q%ip}q$@JZp z%lFsG1ka76dTQP+hsN2vf4jy;)vDVSXy$J(EW`A{5U+O0NY#g(UY}kV0oVk~9V6aE zQUZ)K7%_2s5&5G0AuNd3^-fl26*AWJE01b=qpx9;C=QtOe(!GY&(_`KsOReO4T~!b zdHM3f2vzcK>)#*)|8TSIJilvc-(ioD(Ns*nlAe3L;;raV?SOyc73*TUdvNdGhOi>X zpC?Jca3pcM1#J76R-l3<5PPUOMhq+3iPrd`J>;>96C|t0GoxPSDr*1u5vO3lR+!+@ zr!|4}{QJr4LeudK-p?{;wAC;ySf?$=UONEln;Fc8wj56xA_6K>K%W#xG{4cXQ2>OQ z-GI#F>l`eEFe8oB=hvj1LZL5KHMO}eH9mU9=mmn9L>t@|@#m|A^L3kt)8neDu|1n= zYm{)ncy`Dzx^T-%)g2GWg_Hnz*-LRpQOGy*Xlm&RcJel=aN66-LkOx*bW5gMNEm}Y zdN`9dxdhXaO98Q;ei#+F5{fO=%t#BOJGV4WA~XaB1j^c#(qdX97>MD7{UlWsjC@rC zF4zL=i@$2b)=Qe7+gs&LoiH@Nki#Yt47(~HXvc?kNURq%5X#BASznyM5hn<WMgDAn zM^)XX&bAJckTBfKGaumLZN=ZKE;cXkX!#M@yY4{O43^1Y=$Zj~kS^qs(S>-m=$Z(Y zbkA)sJcZDn4o~+QL=Zbz-}L>ru{#d50V?&t@Cg(T42Nv}B^|XvWXBz2U76&zKrkS~ zY`9sdMushAu~DzC!+BWQe-6@$i8*Drg@L;xxvvTTAzlYv6j$9x8@6>sm6#ST&uHNw z{Kh7c1WSE4MOh4nNin|0LL?XD7gq;7s@u~MyG{55Cfi8Dg|hwrH**_hOXLm`P<kQo zIqaoLbd@Z~3RHS8^U|Lcqi9L9u(1d`LHh}tk}R1gO4uM;pB;bUeu4G2FCT7X^(^AK zhXF3qANU^}(Q|$^`f~n+insSygSuej1&yI1wKYs<G7dw>T|gijo)%4=BJ5aGp1K{D z-A<db?#5T>rQ(7>&`7SeBI*<3962+uFS0<Wn#O8uy&PXbdP@W01tVtTw@PP}j*?Me zN&$%h(}%hjh<a3~SqU=-B+7_c#>sOIneXx^#ax5<!GVD1s`?lqY)9%a1VlXd;#RIq z30pTN>-|D~Gt<apS6a@mDjCLtG>E8Hp~IwMruEQb)FQadj#Fpcxr(E5Bqk!M+0Z<9 zbsIn2U%@GG9+^S*IF28Y&<@y=Oe_6VeP5jt$SvTp=+BE-hzR-pkc~V@bEklJ@gUvD zEC7*Qm`nc_=r?mTbgW7*7Fie7@r=}gF2!FF1?LyOKAr#8OOSbe&aii%q!3FtwDR!U z@fMpbskSsp%ncBgN%->=PyPufw%R5tn6w$*o;ZrM9$loBMaaOSAoUQUgRKDMAdwP; z0Bsqfw&BxBg&0_B!>7>nDj{<@u<^)bC7HEk$|B;z@}K#9hdO|^%TBbG6geK=yU^nz zJfdXd6G%zO<9a!86`8Ag3#i(vbkd<Oy!V&7uiAmK&K7Af>bZ$(v2CL?kV$1@m}SV{ zI_5r;5Fm10?}<1QW7SnS3CfoXf9I#(P{h4X(7okAj^1q~CFOw`n^#Uy_D*tB_<Sm( zs?9=hzdYciQ2}x%!3TM+<<A8V!eiHSy8l}!9Nt^>JH=Mb`!XS*<Fh?QmIp&nCNCZ8 zACR=%5F{=xstH(c6>o8x_FAvoBW(~fv2`35jC=4Si`hCQvoJG!J{1MM!D!eJ<ASa= zgp-sZspg%46TA5oGkl7zREeSp^Q$m;?viJ557to4dD-`jP)QYs<Zcf6NJ_=UIC&m4 z%7;4&Y<j}88oLn}{#0QX$M7qW48F(xNEZ@ZA4m0%4c~{gfMA?TrBQwm37HYV+-!}w z9;LTPV~o6ydlfh=XVWTl8Te9DbjoM%4`m)z&5b|hyYg%QK`}V11~t8xGe5!#dxB2g zc6k6SigIMKHOMJg_KJ^(J(Buo`M%&J1gh0S!5V0Xgm>_oJf!=a*qsWMHkHEQby)i< zX|s5VYH77bI8A^hn;L98P2j${4b@Hv0K8d)3_&H{%`IPgSWw?SUz+#3SGo`Ijzt(V zdX+<&u#eS^GzJR-NTIbmC@Pi;n_49&P4CVn@ZO0%5Pa2$n7c;D)Y5+SVip`V&)TE3 zk>;Pw^+R+`rK^H+0FDd^?d$j(H+2t@%IlVzQJ$*`HP^ZrKAM+5g7s9J+e!zF_v?@X z&KvmmW2oOSmOerLl*zPd(dFoHTW!D9<ag^`_d0WDpq?0SYwn{r7&tw}ExMz9_-6$G zZOcAML4f9NA^2PH)*YEsIsx-1>K7GzuboYMHZ+ChjNUnsge3S*STFGE5Ir`^A5CDZ zR`#`{zt^+M&s-T{GuarU&xx_X5rZ5wO_?w$%Gx8x)IE4GDd1>SsdAgZcz-%-?uj)T zx!jlPI;i(Ec18g{^Ohu5)T-`Pk4823QJ<@E$yO=uL0S?&b2Za9i>sfNUxn%(IGLol z?dp`B9FX;CZ7D#t&Y$A$udi%|oxNInrvW`FzWNm?uH9tkR9p!ydQB>*d!VINToK#a zQRpn{Uwk0kp5x04z(iw-lTux^WxE_YHb!Fv5;zJ7-wUa^%=P>6Ts^8rjV%B1knmDN zxL$qy3AAX*!*dpp$UW400Qct63^-G9pnfB_Y<E{M-YV`^_movrccZIYDhk>`xK9!4 z>@~P89i2htcWZ(7J<un@Z~8LIt9#%@_fc1E*Q%*Ql4R(YjKa@}W;gO8Z2_#Vv(yk0 zUpDJNfgr|uTcz|>kLm(plP??l7q&je&O8`!N~-vq=XJO~>W_gl(ljNqZ5l0W?#No} zb?jll1A1qyi9+{L!z}?Xy#9bJ+}0aNfbNQ>O`|w!u7B~br9`HqSt9*+eVSrz5@O8< zL;@AiaU?e8A6kX_rJRDxD&wHgR$fw@u^dAU;jE1c%KNi6!)!kvtV+KJ7I+*)3rS~3 zoD@=eu;x4_D2lOuP9hA?d`>UHVR5sp+D(w7qYUzXY9nyVC5~IJn_>tAs9jaIz;SMN zzoI&PW~_iYivxv31g3!66{g_@(hvwr9AYde&=riS`?n#7t=V-zvTORY!tmtLkm=c8 zvpH^p%chkiTWm!~8Iv}{b#dJBD)2P5FYa>3-60Y9>pFei(&e+)V^%0x`aqt352ypF z3&G$aA^!vnP9Vl!V9v7P=gU73DEROt;AaEKzd8&nw4*Zvos`Yr@Xk5nT^4bqV6E|9 zgDgB}ZcF5#XWD;dDg>C5i|SmHBJpd<jK}lhts`kip_yG||51*<Ri7@WjoK2#NNZYH z*7y3hR2X;wGx#wp$j5Q8mwxHe3Cds<a*ZOR$0t~#vFsjmYn+nAz`blXSw5UsuGY<} zTugQ2m*d2^Ijx{7E<v|b-n?o?4e4cQH=yKFw%@U5kU$~((if=cNGEC1xhaQGL0CzU zXpjnF)q8u>0I!SG*}f<z(0m7-v5q*Q0sv49>Q=YZ*Oz8A><_Qcep{Twgg+A=#WsMQ zz%_wJwHp<Rpt&SN<%-mkmApk~XI4#0n6geK(h%UJ=X8>l6h)%gTBo^)NO6M6nKA)^ zW;w98=p&ssY>|!5O4-@i%2#?)q6-He@V-=bhQzndqCth2iF7tO(T$KKYx;8<Xy%vC z-FeYMC{!CY%#>(_FsqvTb6o;`kOUW63PBdTx&Yr`4!f-k6+&Zk#hRD0b060BD)+$< zDoywCE64B;_&9m)k);R^IB<cQA1(&YdNDM-?Z*8{LO|EkC$9lFg8Lx)Y3IV+tcam+ zBHzJR*^El!4ThY0tf>=C!UqA~)8?hxv<cvuIM@1qRg$XZZR)yKr3rt?e`{aTr(l3h zGh@dEz@55MpiwRNJlRpHD^*p=F!AUn(1qWNaXnBvnLDp!fDu#<Z_h_HgIZEb5|EeX z^(Y8n%KhH$G8b2`qk=a3lc&w7n45ku=(6Q-+#t>sY}0M>RXo<{F0%PVo4q2IN{1JP ziZijHuydMA*^ERhjy4=4DSCaYQO}@U3B6w)gr1rjLTYJuCFsPF_ZDp*L3<F^V<37G zM06*M!97w*o>;qn8Z21YUJmt$z)y+dnek}x(6lEl5HS`tE18$=jLsi%90nhL9AM3H z7rcsdm8)qpwe`d#r^bbhYrCIdr3y!U?(a}5f@dpOM9Y(W8GKxDj7y+hL{{091iu;R z{)cr^P770m7Na<!_A@l#UDg5r#tu}}8%Z3_!cnjqre^B9(>I|w2F4nwRhTfmg6@>B z-K?&QDG4q8Yw8s(&5r1oa<!D<G8XftDh?0B4V$pmS!To8=nhHOtL2WzZngCb*8wAO zbf2+f!lw<vpU>L?mifX{X?G2VUvB1=cVWRBr!?Z!R8wvwF%`2O)`($CFRtK7yal6Q zF|>NOt?IE3$!Pgq-SkrlhoU)kQq4s?DbQ?TNK`^Vh~JXfQ--4Lu-Q{6EcGSDQUwv_ zl7nai6kwyWo(>NVXPNk)FsqxZb7os=8h&sN#o;OVcmd{Vr1<+*@JXY;iO`T4G(#;j zth&{!*}xl=A8Z(mo>LI;!rS$Q`o4Bt7awBVVU&Br)}D=b<=mjk&N5yG;-8h<JTi2V z#Bj~)L6AgFTzxSwC!_6EPXoYsuZhxd0Jm2>bn8lZ>&Jd&jFyOW2+7U_)bT(to<$oN zHFthXD>f8j9)yj9HmMeHj4r|xBak~y;Bo7ho}0_`mdObT-g#uexqM~KUWmoYAuJ)I zMUXZ}V~~E~mx)&&28l)v(>*N{fnEGk>z12l5A9@}Oooe`A)ivGO5-23FX=;3_|%X( zjE>c}?NT*6APL7y@@Q9bkToq1-xdeIljN!VfW*3KFQ@?GXzHwdP2Xs<WJk9&!k9e$ z9i43I%7r`#YR)a|s2I6EFBWwv8u?1sNTP}*PmnrS+(WsAY$HpRU3lS8>j!K*>*hU- zyEm>mM=hd%ITOSZrpT%392<#he$m!6fBNa1888^%@c3>)HMM_vpF3_^z{dpSpJ%y` zLg^0opMM}7mep!Re>VkoL360Onr*QVvk<Bu4plh<AaVX%79_-ne<1ue8l(!l3*29a z!U2u#_AeG7Ip)<Jh`dS)*abf+>Q$Q6G~w-02je}*#DkE5vs?$H#ek&MC!Whku7JDn zq#Vz{al4wzCh<)@aD*JoCPK3mYmj2%OFraI8b17)>;=1+R&<r>G+NX@7m)18DA4H^ zN)Z@aA>$o2fB|#0Z>~?MKy?uR<_{j7lyRaDl|Rt&7v8WW<OE;10Mwh2cqF?`dsaQ+ zOGIu5>lTOLPxA59r+*YTp@L8r7ma%$vT`}_5bZVU{&t-)N#N$|fd({pq6CbQ8u0!& zztzVSytz*ZzaNOU;7{Ak4MnP0S|cD`cUQ~_$Bm}{!*=zofhmDt9>}kO41G8iR(s`p zeYm7qgAg^)yA!;JnGgLc=9%%)Rq3Awv$8soA_5dxho}AL2zg%BH1Q6z_5M>pp6?oL zK|i{cmGwqF1HwN|C;_e<baJC%#AfL3`a|fi0uV%kjpR}VRBe3Sa#Lq)F<=ug9|VJ% zpOI%p`B*vIU#ZIxoDJyNC_j`n^Y{*rgX`G<*+w!sKBgfRoJ=+(dxudoswEJ4v7<}W zpB5e#I}^CAg7D=NQt4cuH34Tarjzuye>J_sB%kNyG_Vg<5(L;&AXb@)xv=9S0mWUg zWnd>)g^(PIDDLZWKZ#5e57@C6r;ej-^8)Z5*|Ecu?9S0jKf0LnQSuISY8c^Hn?(nD zvH51fSqD1BKQ%1zT>Mp9aqb<iPJzCbz?ST|d3=DrmO19}`Jg32u1{sv+*5pQbGd)_ z6NK(gt=2yJ1I+ceKY2p2kOh!Sf2w*dyDv_J|0T09JB<JE^S3erb9+&6;h;WXwj;s& z6Xl@4#(PLEY|Z0;+*>`SyCPZrfn(AJ3dHuQhLKC|vtx<SUjuj0$uFLq927}>4DX`s zZ#yOM6WF=aNRk7}wV;`ib2}yBQTEMNH7sGVwD{|O3CvEI)x)beWAp|`PT;S<HgWZ% zO~P2ug}v?bt^_-9g9%UFMY*Ls^8Pw2jsl$(e|p2adc*nPX8%lEc=vxP&t|BolF;9Y zt_0tiX~k=T43rafY454#xur{V<h~vFbrJoUDH=aZx+^Jp1h|{5b^i41&CT_r89B^u zE46Rr51|*dd~40_QrveARI~gaQakp)vU2^~=W0w5MYZVxvaBt9g+^fXh{t5sGE0$A zRH?{aUJ=n6aL8$x<(R;*o8@9Txw*DO6YDIuT<O@mBZW^Tkn}3Z_$c^-3_{s4gDEM@ z72R$`4Lj;<^cC}kAnD<nCR1Hz9!1$^%K79XpX8j6N_M^_4AFRT*>#DvTyVlP@x~7_ zw<5aZ2J_&9dR(=?Rtr(E>F}9B7mQdN<NAQ1ncOylZ44yN_ViqnSESUbfHK!TKu5w! z=G2q?epKvFxg4$6mA4sj8!HhXe)Uv;m<^B)qWj%L^i8?9hNZJF!x;1-{L`TY2m}0~ z+G8Z#q?KB>>1R~(O;{X^mk;)%d@|;rLtXVZ{_uwNUw>2dd9D<U>=$I)Yu4Lp9~jro zr&1g`inQT#SIiOW1|{k$PU|fNfoNom;em(!@NC8ors(xbt^J2SJ$q&9T_`>%6sc+v zLc<NaVBVsqSW;LMP0*Os8@6uxA5!f}G>1WU`%8wNvt<?<3I&qjA6%*({CkWYn>3ub z%sQl+10>rp+BLriC}mueh^|YxGhVV@SL2VpZBGt>>j?pdx5IzjAltyvEUMjVS^T#m zRKYEax8(MPv(#u+?&Y15e&_)u4SW8-k_O(318ZgixHN7sOtZd7=bM5wgYOToM-(sB z2kD?@&rB-~#a=|0W`q8K%hJ%Q*);$J=&rpo`BfR{xk~{aaaxQkX-%$Sq~>q)<3Fxz z4E>KcGe$n7KyHtbKnP@5x^8d>Xlnv0HgJQ>PynjDo)!jGb7OH5zGdQI(D!V(>27w? z=;0qR=?2xBj#|qSU&_{e{?qk)&dGt)8qY6<ua0Qy5R2%poBu5EPF?{5Vrw)XqvRZ` z7$W)EJ5LBfuMl!+suDON8A|`Lq_yM+OAbS3eE0YlMnFMWgb)x$T{R9MjJ#vRjf$m0 zAB#FgaGkyexKAHd`m!eheZ3zH3E`iqAZHkpqN+IrITD3~cz(k0GCW-N$|2lM_(Dqg zUMzvQ-8o5gHsl!9hIR-8rBe4ff-?&hz>IL4ir;V6!l*Wf!sWc4F?~c07^F;R@$Vek zy;hBw#D@Csh%d>0NM+F=YXM;IWj}hqBK&`P|Nnx~rLG1H5gQ<~{P>b7I8Y`#h`?V5 z6^SgsinP+_2Q!qeF@Nr#1CAMbtvvrHU>iV+!FKYa3u+kBV_D|bso;6U^%nfLw(a=y z3}*70>n*C`hMflRuuYpM@SKkx-=$_#8AXS8wH_blua$Z4lc~l|kpw6lu-tS}d|Q5L z&wF3bf?a&NrD@?E&q2^`EN0vq-APXDO=Tvk&mhI(9TouScy-y#XimHKfnv{NE!YX* zfxum@ND>{ziWD;{um^IJ?a$dT2J(@<6%ZHWfd&TL2%L+N;<doz7(Q6$cSEidu8Iml zfmj|YGK^2%#vgX1p*|1--hSW*AM#<72=Za7MPl(j02lZVR4sV=%@1RRqbR(q`QON? zEO>Tgf-b6&9Vd6I(}g91G7!7e7>k(qK$;sGJc;jhKtTZ#9+S~`;8CELKZ5<>c3<tg zo3b7yOPc%QBG$4^`gD>|fW)A$R=-;$jjHB?C8ak}BsKVt7R0cxg5Ke_1PmblwW~A~ z&5W%e-suj94cfn~7p8rB-apg0?mPKk-Z_Pk@s8=z0Ds&m<5v4nfnFI|v5I%CU_f84 zq2pWaT`XrW;OD+)7gKFIT*Sg5J&mt?u=UsVSZ|)|D{J^k*pE_O3jP#R+QK03ykI`- z&i^vO?<>~d+(7c)Y?*r;cd`j`diId6IK=?bm_JxnR!d7bh*1p!&W83Jz>H1{^hm&2 z*7Mn8zntvT#U#lTMY8n+q@^5#M$<PL8N||wh7WH1T6sF$<Ww;}@m79O489iSf^Z!V zG`)<D?T&MQAOlUIrLdHqWHRqROUv~r>$Uol`&TMUO$T*wg=#f;u+7q^ah195I?2C$ z)tupB`duO`?n8%a$~l<+7YNUhP`liP8*VvJUTI6q)(j6E$E?X;<0}bvX8KuQ^{arb z`+WVc^<&nae_Eex|G!#4V!h`6Yr?V<P{?fv26^)Ub6+10g#!vLH>V1D7Kyo!?Y%?z zgY>#oq;7#Y!5qcfEu5cpjK6pfN6?>;?e>>rbr13<8|WTwD+BDu8|r#<5H57Nxn!Me z!U&=OED9wkKrN!ma=gJxO>dCNZX(ct8>rM~v@8sd<=xZccrl5=(@a<znl+XRf#?F! z(}6umi)@MX;Y{#Vp9C?A+Yb}Ekeug%@KSM`y@Ju|2O(NcoiZHQAzREN$2@B?W6^iT zUPx|NvuYTYwy80CCU63q{xy}VXR$)E1&+3u<}b1W*8NO~Enhg?d9C|_C!a`cFWeWy zfrp~RSEo+<#Bs0VaU6n%D1cwn^<VDU7B9n4P3p8>&$bbP_LaxBD3={~Z(qi9ksRfL zOExk32`B)H)<&~JEUnV>LobvRKYu47s?OZ6x9mfvnLf8#{sx_?*AH*a5sJNdT>fp% zKP>v!cY%KF{X^<K#oBQiwx4`%m%g|EV7Pe)9&YUr6CeJR)PP!Dq`C78lCVvFXIWa^ z9VhFCM#eo;e3Q_KZkjoSyaXP`S)Egyqen{J=EM%wRzwPrl}P(Vic+V7_Dhh+=p|@7 zgkr)m7tvm)939)KqvfBK5_7RD<syCsI-KOo)KPJj5^jxa(vwN1)FH+5{G=k$yAj-j z?>v$0QbZp1yp1Mf<{77~XvnUx6HfV)lzs@(q-5;tDMFSG{23GQgW^K@HK9V&QMKi@ zhZ-m!KJS+2i7z=WK$mx`_v@|&4vN5Yn4epcWZWZ?PIXyaN-oVSvdZ-J2RXAGiY$`k zjmvMm!;|<0KO|IYBJL?1U%V(J%nE2aFm<aP67OD|;wMg9^B?cQzqcglu_s;94wwpd zuc*2$$jk;<j6^3b6s=w*gqqL8I7kq4ziSZZC%t;GQ~imxNbDq$LJr!>Q8?OV6vBId zng5f3zSh=0qY;IHeKLxtk#s>iC~bS0AS<agB@qPmj{N@S^ujOhVP|T?AhS4OPsXXI zf%(UPML&V+t8xL!j)X0DJPubmq*Brv4S=2dR>|)*mThQr%usk|7&i%pL10DN&z;`+ zP4<gJL?Q;g;BGQ~yZ2eha8SGjv=vcl?w-^JM(rtDQs#p4!l#^=TWu!N9#*0#<5Vzf z36(SDa(ku&ZC6*N@vRVv^ZI4;04WlID$Cxma#UinOCE$9EA*#2BAnGdy)uteqpuiv z5YH~E??5Nsc~Rz<2M`?#xj=<UdDOAFen6@E=PIot!a>*ylDa+($FXzHh^A)5detE7 z8`kD%<ru4^4IHJ<b|-`zb;{#gm)|Kp(eV)cO3|+8O-U&YLL^evXh+puzqIH^8w~xn zLL^AFRf$H2aA!K;PIwQ0FbDx!-;~^FVghMVW=iXZAG&)jT-=O#6~oz9g}gm}<xOv$ z10v;H@$DvYrN!wV%@CmUuG!x!znP<MF!i{m4-M7HQ)c+x1Nf3wit_B7vD~n&iZeLP ztTDBiHuQRg`E;15Ba2};PC(X2>kqD};44w7WpKjgZdg$&)XR$mnewd(-ruJ9d9%N- z7Wu3bQZ!wc34Q6x3G@W`$xCI_hUerbxQ^uqXi8O{c#lozwtUk5Lln?}cG8-kxs<S@ z<9DF@ngmA{B(l|*5GA0knZt&{_Q(*WmzUJ~o*6?#VDWh1C%^G0u=wtBvg&nmZ8mX5 zBD4KPRtEek&Sg(e+NRU_M<r;>Tc5PvrG0D_O#>SOqG5rWaQPu}iq?{5P@zm?AmUm7 zbBR>eI<aV8M9Y<dpP5@kz4YvPR$OtVU@^33^O}@d7C#}kWTM~j!j4U+TDCt2ZEeC0 zYtpbb%v%9K!9Tb7(zLo<-)|C<!Ckt;)SCd1xT)~9U_0fz+QhBfU3CQanhamk#AlbH zO@&4{t^*DJ-2@h9_wpMA81;*z*<OQ}32*z7Ms%sJm-WY;{Wcb3RuwCso}jPC=k8YV zqtN{B+Ey%Kx`ZMkB&t(klGEu)p5biMveMgbM;n2Z_IpXWYz)W08u?^M4!=++)sr4Z zDTFV5@{wXKXFu&-CqdSvy}=Kv=46sL_gq5%Rn@h_SGOCMt<kqsVX{)pZwF;}VXHp$ z=0CtvGhoX;kI)9|hhI)gkYO2oC)W^*zrAFq{isvmj+3HT;9?7noXPhKO*^MzfEj|_ zJ?2rH_RbjdhkLv&ox1t7rt+L6Nz?-VAHApqh)ezwVdFm3=@?40lH%&n7S!=VN1^ZK zs0$<eOX3oPnq|{O&UrmVu!&;1oB+Dv$Qn?@0UK76%iiMOY9<aCJm~=}{$a@%>~)*p zh{cqqOK?Y$NWLfF%D}ka%Q}|3cTiQncE{waiCL5T&`FL(W@Z5c1aU|Dm}3vKbMhjK z?TaylSC?T<L+T2~EJmW@ipVsW&a+SHTF2!?1ag*_RF>ueNXKg(k+`p-xRzWhqXXTW zhsW_2L9wME6;dj2<ANR3(I8gp5M&lo@`v*NKeFCAI<h8u7mhQrZJQI@wr$%^CY;z4 z+qOBe?T(#HY)mql+nM)wzjeQR|LC)NomHp0Y8U$KXFvO?WpVA4GJqVJl1E2bZGn2% z`jOW&az&|GKW2cB{)oeqSU<+gcBYt0EPJIipQpI#z%NUqI|FEecp+xNH3-S$s2a@% zM$Sk5=)E6pY?t=Y#uQ4`1jB1uYftSNyOspQTFyz1##R;X6y`J$B@P7@T4})!jjY&l zjeD3o;0uQuw#Dugt+?iRr~pb!j>27O&NQ_WrD9q8cn!>{0)mN3NNavezjgHLR@4fE z`cnLf(D-04@J6qi{Gz~!sm>)_g*mx~$`yQr-xZ}3!HlG9Y&ODPR6`4e#M%(J#Z~1F z==5v5iKelXoZI11Nv5QDF{-Tc=qfsL?qsll)$F252OFM_ZDL8NnuGClTz9j%%1z>v zG-|0Thjw3ewQh@;@GS8I|C>aO0TsGrdF@J_pqhq;CGh}(r5~1MV!2~;zE&UPCtsrJ zotqM-pk|d_jWqUt@0O>Ucn!{lm8{`+CVXRRh;qSPB|<h-gskx8!+Ow?GM1}_^dA<F ztz3~>!S=K<>p$?WtZqq=6T3esA_h;%9*{7{tZUslg?}SQ|4ucIlBRF9)c`7`>*b}P zrd}>8%V1Mw+k9DKs$9Ph+H%2;qZ_4Kse$h1<=$ZdXkvmSO3p20KLZ<|KiK=l(}{jd zhjW1f?_J!HqOSlBz9HmH!xc=@*oR|l$oOKBzyDQ~FG2mrNbg%hTBV4%C>)n*RXrlr zUWeccarZr<>qf>;HY03KT!8u$<P|N2Zg{P+XoLssS;F|bY~0eD84E{dh1NC~H;w_U zKrn~oB7X|PXyB@A@Vc~Ah~;3ZbIPXKjQAzF8S}_wqDVX#_N}Q1eI0_n<IP<K0HfI2 z%!1#L3eMn|vWeU>WAsYwi+WAs<&BOLWGmFVxgv>FJAYS^)m%b2XGnJ12w@x4;Wf?< z!Qi*Y9UvN&3Tj4IW@CLCYXbR!3fEDhRe~9=lxo5!VZE27W7Uf}X?7H%gZC@!7^BmS zMiOxVTc^qDQG3S)T5R5K6X}a{r87i4_d%5r$%JfwS4#rqa&pFO#oy)fI?J!I#k<@~ z+Gy*0Qz@CLjfbJFmUPoZCRNK?lo#Ol10kh+e=flZp-G75^n~Y|>x?Cx|Daips9b`7 z$x!>zYKc9KgjaowkESq%h8i>|R9i$YX%>Uv^5Za+bD-4OAuBVSs&u!7l6%fMx!&M- zSqJ$Z7SYrG1cY!MAfWd>5B<{Z`-K*xs;dERUo_YSJ}LhCER&A1sjYM?8d3+|!4l4; zPPcKl5_c+UMxn(x3jEDLJ7tt)sndzMaQs)srdH#1aqGm8X7kHrDr-GT#n^-P=6PI1 zM*X=K4L+AY4(nQ^9(}>(w<WuS{0k-n3hanKGZRj>Z4VF(8k?v4OY%qCelwW;M1LqU zqQS;9$@j5~Xt$`E4XPBANAJ;!Vw|wZH{tz`*{;D#)R*#V<66(6ntl5zpAfW<OP3{g z&J>bnk@7+4-~;5{=>ENQw&XSRa9!Vm8MLhmEXteuF?!rFd_L7a%@H8TUH4PbbKc^I zdFSCluH!Vq{8)9r4?epiwNH~%5$Xx}nyn%RZ!lDApdCwNDlq6%j5wM!sNDl`b)f7> zsl5NJO$t2no&#hCh`CE566uVTfjUJ7+onsW5}#mXX8r2Z1?}}85(Tw_ip6WBLVV`8 z=fl6$>q{;ubh`9e=GJIbb{-6n<u{B0YMCBA8J|h-Ont$V=r6luxP*&OcA5;a>uh)e z4m8mDTyZ=?<3=1Hh(C-Z_a_E&AC82l?x}ur!FcjDGPJ9{O&ySL-U)rbR(x<qz4F>k z;Pfl}S3|bqNLW}r)VlOEk#6WyIy1Kb#I%1cP`iRPV?J3M%k`)SllWQeym<=p@R^SH zPVng7FxKz+RgLVz<`m;28-#tZ**<?JXrL~4-65PP3R0=EDS~yC5}p{sPT`UtOXUwh zPBybIbjuZ#G#=C9SYJ<vAS0N|9i^=;SwbYzd-ueW6PCPLL791mM(f;cpZZ1F_nI82 zl2Q1~^J;qi2;1?TaMCP?Z`Z}+Ao0uq!8c$oP0K~jUc{R**Q_YdL-Hpq^``|P5_%Iv zY1R_2)*N>ED0s{>Jz^(AbX7Y~bW>0I6%zt_k&Sv0HgCu!0{M4vNWPWu_}BsI4`4!Y z{n=ssV5R2TBMJ?lO%`5GNYP`#bM+Vo(b=c~K`JFs@B*1GOrV`PbXn#oTpUb;GDK12 zxLsHvHUzO4U5Ajf685<czZ0~LNVIxzV7HRV15M!!6TLB(h6~QU@sSUgv1Vs2-N5N9 zHWWEeVkZc1SRUf{<afo_i2k{8B52XN1bcW!+TA;`6QM-<8n%&Yof~V$^{0{)s{s(| z54Vm}La<d6=TbM+nI6lWwy&=9zF5vR7lj5+i@xBfI-|J=!ykD*5&tUOK0l1_S*1fK zEOb@k7h|H~gGlqcLq1*MXd|+_mu~xd4QY9`E!f0$+Dc!$e?~v^<iI~vDM6@Sg*&{4 zW9LZBf=^q!Ui^RA<&*Mq>Jxv+l7Oc=F$2_Y2!^D}M#uc^fT*z=NSBB9iVXt4TLeG! z(N+semBf_-WY^@%o!ja}b+OrCYlMgQS0WLd=IjJbw`0%kB<-17qf+h`slW0+c52Zk z+6>}E>ZQaZ|1wse;XADK1IlWo0I?r+0WZGl323ASTB1&Wt(31w9kf8OMdJvVvYdjX z`B+bDN$B!_lo`4F-;ckTsS9AsSKTpf57MF=wt{cFuSV-BPApIA*F}|uHw<@P`PB4r zE{I~?eL2_ItZV6$yg$$NvF5mIC$e;Q31BG-e`WU?1AaDV>mtL`4MRr%yk~kvyt2Cm z2>ygZ;{FL0|Mtp$i+msL%{NuoFFI4#e-IEL&o}gLLWp#4dy@eCych+@$8dBRtVJ@~ z?=@Wjf6%j7y?xYnx-0go1LW!%f*1B;Ff9c*1Ku^sGzZcOz8mb}%<L_~n(E=>Q)fs2 z340?DMnc4Qh#Wo@$D<?$p2xF@$=*&I6hD&gBnGjj8{^fXyc7kkmq?ZcB;x&<zdEX= z@GCAqUTfnGGz9A-%N!<iM2M~asUknVfwDq23zk7sPf23y{&v8CtWiBoj~4ghp_);M z9uF>vPnZ+xs-}Q3SJyG&5L50#_@xK0%V(??gA*yRj#mnP6#JI7{b;Y<@S^7M8!#9D zT;YSO+BZy}hzrclGCv1gd|^0G`q~qMk5)|Dynz!XQ^|Ef!v=AOinK(iEDLJbXz%v2 zqg5qK3*Su_Q`6ZU)6)0Em_mr9y4Hrx<pREyGXWd%<#-3$_^7*PEQ@^lLHPezk^jv+ zPPPmLhZ4p{MIk%GzMX4uo)GpYF@YE6Kzw#7R+pwVvg9n8vD}IcfnDa#6g%70Sf`Sn z3C71g8Z!|I2;~8)7(79sRixUf@;U$&YaU$}R!_`5=%UR8dXi0}TN&F%ng0ARmWx&D z9jk24cVAz32SJj|cl#50<xTH*nh91ze#^<;>sYQ-st}ysSAb_#a1gVITOlsU4EW=w zXMb8nt_5h7WuGv+e(5U2JRdhi#E^nc<7UiY7M(;GsIMm0gAhhsY5CBU6pQU1a$HaR zR#Di77RLi>wRcepXB3=&IEf3M!7SKL1s?jSUi0oy{;ZA@z13+_^EsX5`|KL1c<mb8 z&4Xk4nXfh;Y`*m-JDdo}G6Q_<M?FlO=j^rhhL^RoFSmSl)noa9hTTjL>wkhm9R%Ge zNs@eBqW{-M_^Qv5^9eKU5ux1p-5-SM*L=~s=yN2)yh1ll@|<rq2vH1_#JFnHcNU(S zJ`6zu&ybODy(a3e03Ga5jknk2Q(W$~JHh?_O0p3mrm4cjr%>wyh)FhZ`Kkc*@H|4K z-)0DXGyXIO{@7^~Kfd2}HT^V)o+Mz0#Ddho&vxszMu^L|a#;{LI`}lV+u(pC-|4?b zXhLY>Yqft{&(G#ny&;->?eqWKYViI4ZUHMdasvdIdt_U>b@rE+Q2YVEYw}T$?R2<~ z(@iJ9ww9&|yu^}=G#zr^-hhXdPEy1{U*Ih59*>(hJto5-1bj6a2ZrA}{9z9v{YSpb z*9P~RnF-wOd+OMt<2CK7Zk+yjSlKlRNC_rw!>V~GF2*DxC38;#Nie0-Ak$8yk;puh zhp{W0syU|sTS=!t1OlQt7%um_(dycysynm$E(B(><6^QJ<9)RDYDrF18xCqB7WAw7 z;MN|+jW|#oWP@WC_*|9Tdz0%e5Da~MwUO|<_^n{+bxgDM{UuguD{qtDQ*g&Zu4IW+ z{H*j>)HB*>8(CTCYC<$YG2b2A>Jq$oS`Fl3ILmJ3hkmuRQdrGt;Hnk&T{j60og8ZE z<U(d@A@td>hJrqzMh*!0Ig-kdV?%Q`07KcHjN3Slp-Mkjz{tH>85w73_t6IMDc%?! z?S$~y#l2rT>r@rbEF{LD9Yg>+_n)s7qhwm5$76!`pYbpgW-}^*U1wwmZzVl6iTx|+ zlI$h2`~g>CDU-za)72Gu1F-t?>6A+e%W_~a>@Ua25G052JCH*c!k1opsE_=UYzOMr zoe<A5>@%RXLzO^~@i(*N0^W<ffHFM#+H;&YXGco=Y!n$954PMoXnF}AJ^C7U3#3<z zk{-8VAFE~#R0m~*3-lB71X&}LjHW4Jl4W7rr4$gP3ak=*sf~S2fR<ZvvenRoPB*>7 z$!j;@$|QmHPPWqDYS92jRr=C|37^s0YKEz-Ytw1XT-&v!_6CaCMHPtCwrPducsKV( zTJoTmfWWkV+`f9$ikZH?j31G@$tJZ3Fr!RJW+Twf)mMCOZKSKuWK0@3?)sq3jRWRc z@{t%XCoo^eU`|^Rc7&#jGXb0Pg3YiN=M<i;9)~=64n2o6E2(~#J-8%zw?Ir6ZEW7y z)6+?6?Toi~ZDWsTj=Pbf!|8z@7BBoiB)bpFyv~4w`X5fc3zUosD{akrx(;A5W-bLd zL>Y<f{^?4!tAhUS8G4V2cUo!f`ylt6m;19fDD?x5;!Or@<WfMt=-!@X%xy7Y7>)nx z3+q^N@ujhDk?6MF&^Z;sPOF1aTUk}9d%mtL;14jY45GVc|BM9J1uq|-wP!y+Jott3 zsGF#sY%XXf3E|g7Bix{ba<eAT2u7lvj!ap@;;X3tg_oMBWvcrG6+wXYd<G62sG>3L zee2#R;Wrb{{T`T|WP90*Jy?r-K0BQ|pa-F!BPxX1Plh#)D5!==-1e{w{t0MDF<g{X z4zM=1TtNQI`{N|hCA+q8PKhOBO0^HQ<NX}ZHuA5MU&V|Mh;`|J41vv1yLknul6z&K zZrb~m5bL%h)CB~wudf3K71r4Y;d^}S+gcJkrA{6mC6Q3^5y7Se^fp+&v()e-fxl96 zM>LG>-((*xe_os(bs`{@Qr<1;lUR$Uz;WlWDE40{&#TqCa0vGO9-_V?891ypzwXbt zaU_ksyPJX)l8F2``f@Nf6CG>vv#O2iZcZT9CfpI5FgAhVi7m5>{{jTM{j%y|=4R0= zaR2i8uBw4$cWF0Jx`z9qJ0hm6mZF+)<MQc&Va>p*v*TM8bt4?WlJvhojpy;a{D?!M zJ-wE8&SI2@<lG}OW^FVf`P{k5V$;fUiJ2=YI!S>mA?)r9M8|l(8!$$EhEe?)@CzaR zZ$vgSO7?tD9mj7P+pvyX?xA(-fxJiuvf&VvGMp@iwf<9MIFB1--Fnrmt2QIxD;6a0 z`H=^l$9{uDKQQ}bEjR~TUbo&bgdlGzb`a#z==vXiZ{)ajMKp>=fDP^I%(F%|C{D;2 zwUiz4VqypF%OZW}T#toDb#-yda{cRBDkwHmm4alUkGnKFl(*}mQnIr*g@CYV_^7Xc zh8WA0N#aR>*z=bTyk+p!!jdhEU#vzWwFUyC5dw|VJdWa8&M+-Zd^~vjn(v>SrO0s3 z#9!SK(QKGri%#oQ4p~kaYL*Pid1+rwcvZ=nW%{cT=GC*pba2X~3UVkeDI^DYcV>*S z=BYrO?IV`bqs&4DAXP(8>*FsW&WZ_zO3$1w)`IG`4=@3oO=<pS<LQ=sKU-QW?#19S zRWVG5_t_hf4~ZMSbmpdOF4X7k#`}3&XwCkzJ8RZ!98?=H&pXj@o$HHBXIuocB$2f; zBvi>Bq&HEZb<m_If(xEPTA%%9i_bw+>xN471TjFMK?NSBTD)GpqYl-mLI{Jyj*}1= z-E2%D8Ga2Jl@^Fp!7o5od53drrd$<u2yI0{2bc6#dZiJL0Z6{EU5^lf6Hr-1B-U0* z08d;od&wq~&L?K@Shs35(khmBg+quwGjsjqUs|haH8o^k)<|A24&9o7J9lON_CozA z0Tm?ZQ>RL1oAx<JTTq=078C0gyF|U_<4`}UC&6<_2-O11^`SdL=wozBF^1$STfe}e z>xezv*Z=NEI!d+!+2fnkbZwirS{x}a^Xlh--aB=GAx0N9FOnA%GarSqInEY<e!e|6 zcdhZ^kf>3oMMF5ldK;Idf#RJf#aDG`<qTKo0D|7vl@2CU>CUH5WA=p-uYDvMK0u4b zZ}aG&mUx;*RgFRWu0L#rQRRn}{&y-12qD`_<fIgk4kO$%g$X5i7jrH3@4=qjixP?y z$syzFF2zpR0ZIo_@|5y3IkTzQj&eR_n9YYIi)`iX#0o|J<u<~wc&a&Y9>jAu!*HO% zrb31NEwWT`5qbl)#E)_foRH%I${@(*!ri43-xcx1%!c7sLK=x<WwMvb*;k%~gc2Zc zEA`<G=%mi!uWv9XE7`jh!;yp`B=u0Myo$vSybc*sOveu>G|~>WNSQL%@icKqjS^rt zrQ`mn^TN1gc~{WN8d=KmKbchKq~ToB$<Tj2t=mdR&C;{AaN%gofbC!oxRz*L04c@! zy4D6g2^dRSFHb4Nj@=B@lBD@gH!mS2EWy!M^212-Tp$|DSJR`8pU=*<A1=}Y#1S+h zviK!cPj7<ak;@NTDteR1EQDvz`&*4LoBr97$0mKF{$d{;JL|;ATxF5b06pX)^L@pf zi=)j96X@>gSo=qct;EN{hs|??K>q6*Jh7cKFUyZS9fD{uy{#6xwbA8PR&jB)6%rIX zD!WP7S`fvSVPfBW@T!P3Brja!0WwQ#%-dn)TqW4X9e-Z4?eg3QyBk#as@&3w=^|nr z&CQ84d@=#@N(q;tXs3wzl*BmMpP)2TkdoE?;~&y-IFTCq>fD%(ejIA!D2{K~c@(2j zZo~G-Uq?j>#+`iGd~W9Zbmo-j;)@LB(ZeBdBJ?$tGj%6dWa0<`VYX`At)t(v)zW0O z93%iXxMz@#vSXDuu&33#Ewqh^<CkW|(w76VF)69@)(-5F7vX91uqL64NR5;HU|f7N zMHqInLmjd3yJ5m~mVwXcPuy*wolGdK)qUIJMttdI5d_aq6*Y3(=MiQ|MR|Z?Y<#?4 zEm%THjA5sxaLbb)CNvVBT(M1B&+^C}P`A8=sMw<|xUkm^3<c^TZNC0ZAgd-AlTKO9 zCiWp^?px}x*+xD(YhMB|-`K{XVo4gO#2t&@FH?ptmZ7vXb*PEO`^~@c(s-qd9#V{E zf!M0E$-*tD+Nx7zR?|RfGan(>*UrIO@GbqSM5j0aQ;bV8WuY;~sdg@=Tx=9Ylqg4e z%aHBg`#Ij2$V9Dz&iWH-vL3^VO4uD*X;iIxRs+XK=+>t{q2H9KACXta*3Zs6BDmRT z0Pj|(YNOY`yzzt@Yz+NJ75{1~62+wOzLm95BM_gvuAFW1KT5yh=t%~iWpxl@gJ{)m zGN|IwF=%QaP_BP<QyH{1)$tT4e(U14$BuKhNDivQjA3?+6<E|a2*C|Eez(s;;*P1{ z;Xwlg)WBmvMSHEI?p)nR(~KyK$3Ye&@D2w-l1)Rxj5vnTXB$cIgh!b5qmClB=BhF1 z%mflvy%@d=4Ig!)AHaN93-LnFh;A@1KH@dlF?gL930<kDv34;6Hb0$&OQ$>cAO?b& z?e-xV#E*XLkly^pD+F-L3ZbKIM&>RB4wJ=DiF#WIB~F%w+a&Ff>a0u#d2@;Hs*0Qz z<*+2ar#4)aS9n`u@{8K{JA5`mdu)?N7$3s?QcKln%+MSAJhV3Q%E&D1!W82+0<XkO z&v$CL@B15+r5dL6YmL&4!~j~CZUuBd8ZX0!vEb&HN3*ZBUzJpnJ4n%92#o#iyoWMm zDm=t~s6BjnRW!+b`3d2+vd*+Z*pjJSAR_f`bVJUxi&9<ZPie(Q{J~Nhlq=s>ZWnyz zh^$>C>tT72Y!x?L+?QEn{g%W_1Puy}I9$h@8Y{L;YA>=Oj=Z0k7mj|`kou(s*@t69 zBi=_qTUW`;OgH;@!)DEn{^a5Q8zAt}@}Zz3&tPB>a2+3fdu=!3JUWfwOg%)iSQ;bG zIKAwuhhLFsKqv7r)XL>Sqd~T9*(A#%c$uYX)^AYkxUti_>wb_zvMfSof$D@3daOXZ z)`yPIpA^_!CXY$nzJFU#Tuz$+JsSc2qtfc(b-$!G!IIOWj27+{#%WIpQx1LJtEh@j z^-vB?37DnHn^C<Q0bPQcy}#gPnMC!K{4vH<(##_3drd##Q-sC%nK<2J%!vS5ZVMK^ za}zvGUCIb|X4rTKf+W(cNjC)b6YO*mTs}JLiY(3;hxbWiDOI-9awl4@1>|w7PJO#; zv>QXjxtn^PV=Znrg#!<WBlM~koBN&%JPrXsBHosoVPtJJf+|TSnq?(;tZZ>*LZ=^f z+*iBc%J@Sgj;_8X8r^(eMej;`meVOB`y;7g*dxhPlOo{y?TZ%(s%g>R4}))`gZScG z53xgSq|IEvMq(2WH;PPx?_UT;!IZbAhVCQ1BzhJR+OkymJWx_w51%|1mr@_)j82)~ z%o1|`5``6>|AhY|DO<F$Qt<5p;cpc(0aj7~qMMVUH~ym|^~`To*{``M$p?+uC6LzE zbxM*u-9dg)7P??m3C(vu;#Yx;?Pe_Vd1%W>N=<Mpdu8Joo;g{iyt!-T)O?SW*2l%5 zHZUXE%v2?b)`L}@V0_5hjI#`l+=>%lmsnhG3*`KqrR0GO6o=L%DuBUy*FS=zO&`=R zXg(lNj1;9jHtzQyQVh`>@cHEcR8muL{vURn%o*^B504h9&|Cg@3q@Zh@AMNyCic~I zeRTrXeXwme3@>!H#7rrR_gfl_3%n9w4DG=AYg!EqdbPMyS;RnSdwz#mMG#^w=~@87 zDwOYF=6|?E#JjBMejl`NAU97Pb-y)lV>7MDNGp;vgCb(UwK_d_qs<5WCr)eZ!VnW` z93-j!hcW1<H#gSsr3USj<LV``DCbwISnbh{$SjF_z(AYHok=3Y(aW#jYhClnIl4y> zCM$D*0Z0LuHT9^01PI439uS**Vc%mj{&V-%YKn&ItIvNVrGldGY&0u}0=<F2kXdvq zV5k`)>}~iU<w2c`UPcEqyI@YrWA0G{ru#hTJN~eX!kI8w4{Z|mTd}Nqs(JBPx`w)Y z8Pq2OH{c<epRJ{4SQCKnV7)%hCZD%*;iLi1(BR^-Kq{TDd6Xz_wJ`f`EkDTbVEZEn z_fx&rkvyzKysHojwoiXUSIb<KN8`ZKbf4fAW41;IMhmIg0f|EDo;b(=E2*~>_0v1e zJa7Ji$SZD_Ukc01odN%6l`T8#eac(%+n|(uW<A9Y4<~Q9qGgyM6*4Je-{dYch5Xt- zceCi9yZILPKg6kIwt_^@Z;SsD&$eOf<um8L&^at830R>X9tcBZu<gY;DQJLnh7Q@Z zYq~EuFNA^@i}U@6X$!l&E!aqfX_Ows%5hsvmv8s;f`^f{-w?=JJJtD4KkN4XY6src zrO#dib|Gi}{7Ho3lt#n#_Ut>KD+XC@>%k<HP+bTm2tssAy|C0wEn^<EjCzs*7Q3)) zyCewkKyi3cUfDRb<n+3}-&4Tim&(^14tP>YF~<Q|{>KJ=ZVGq-sB=6O<;-4Ka&lD# zZT+f*0)41ln>DC}r6+rntN0v^z&{rT2*6(eti>WyvA+TkK+iu5LW4eZuFclEyVC$N zWd2!^^Q{XO&*x{v=G+eR0#+h0#WBylDG!+9$PJpk*G8dx!t5{KJBYLeK31`d$p-$( z-9>=r(^S_Q*^`_7kB!xpusUtvni#ukPruQ;yRpmDhYy&S!=FYre?gqr`J5UK{U;XR zT<<=8*N5$yCHyA5diaDR;q{xWY}^WSbSE=jhGZmSZ&hS<w_OGhzBf~c?HWk-SoKwo zVZ}2P^mYIh<L|k^@x7WH@=uyRgT&Sac^$ZwOK?vU6;(%n7b2yh*QGwpL*@76?5alk z11B#Lgir4HpQ-HZL(&bWV5&TTw1bnz;7wRGF2r0Fu7XP~ZGFt(9?XBfXS6aW@3?sD z9ynl7PQgXA&j-8LX+8wRM}JV75ooJ$D)gu|A$g2|?JS1&Fg%Bx!|xy86R*gDd6HDW zPWT@_5e_4&HSQ?|mk^@P=VYdfPp+T(1v!&CMrtB~0n`7ad`1PhBvsjsPB0+|+^cQw zR)05@PAkTR=u>yU2EIVo$6Uaa{96^g*T1L?+b2f43aV$kyWD{7+0~y{M*=%_Z?M!k z=PAM8miPzIwBIWQ+$sGBns`FHbj5d|L<Y&6zoYhA3&+o@n$LhKwfSDk>q9?+Sp9~` zuKe6uOo-ZAMW8#OlPfWRB)O}y^&21Ap9kfYM!c5kK{SM0yPx2UYZh=nf#szI{2RTQ zj@R*yn#P7}++1T92RyJVrzhhoLI|K|e$x8snIlnRGz4YR4mh#CP?t#HIeO}FK5)i7 z<g5_9u5^U$ZMFl=b2<~vJvCzwG!N2XI13OBGf?+*SgnMeTqD5vkNv%AKN7kJL^-y+ zS@HlK_D&k2&&I$}+^tkN@u&eBXG__BiTD!;u^0dTubd}>`^=0z&^V_8a;L%|J+)Vx zV)|u2F3O8Z$$?u-7yksa-ZCxzD>mw;{34jNl-^YhDsaCXU7XkBro=3Hi<7tgOptk- zpZ)m$zc&KGK&#M#R@plYPpQ$avQ_X1yn)G)Z>My<V{Qi^q|Lkr6a!hS3%!Aw8D_Y? zH{w)V%tt4`=aeVm0jb^o2MBK4>1xU5oeitV-@7m}SArHZ96AkwI9&TiFv1{cbU~zI z(11CmgkRo7lL7LnkR{+xwGklf*NofZHo}q)pZ*PuREEsQg$D`_#h-pF@J$9%;1m<Y zqY~WsT#vvdKL}j%FDx_rhYGx(HpF-X`~zI_0RIEHkZy3j{=b`plls>GZ*$mnK*6CB z?3x&H__56W_J8jUIVy;GG(fE7bD@zQ99m-SdEvQIyR9E@?&>3TXLbDh1MuietE8VC zn^F6ZWtxXMXj|L(=)RHOxESmhaxQc-7H4s6^_}{H*UT1};%W%G$?&p&==jMNeT3Bj z<~}9RIdOB*EPy1SAk{fjHdel<JZ$o$BN7WKY;Q>p9)gd(aP=eZGJtX|XIb*7z9|88 ziNI9zo_~Xu{J6!rFW-yKnx45UEawf>KV0wy!an^sKCT?IoCyN$Y#%~Bn@7W%{(#;6 zo_00?Y<@jlAZxkg7I<pH=f%g`Z~eaaC!2s*gzN!O>-Y2WxbU(h_?$KZ)Q-0H+jss3 zyfhd9pCV+8MIzi^co{nQ0A5Uc*aU80c7fllI@vzh*PL~>odxx#_urroEg!RoJ^!4U z`jsvOB@T1qeZT_G@!YMM_SE)MO*tfsW-8#1c9cZ=CiGKs=dL?W#)SH@xf}KBg1We` zjXhYO@`T7ZJ)PhMU{H;%nb>Z}pn)ITq}O7S65}nejV^jtlMdCzjm5Z|&Zlza-0*zI zi@=$DyBC-_oK`-rMS7iRe)km#i&)kna`S{7MBvbrfkfL;++s%E>9=MSbdoMCC1ZqJ z^x6w1WTG8Go?7jnVJ=8QhqDuLij{-MLhB!HIq-d|`SyAr5))*8g*0vJ!UQ)ZIu>W3 z2}Ogd>F|D!1!792r>tWfkSEq6So5VbU&-UI1%`=-&{jIsTV0AzLo^}`j-+f8)>EZy z`!^eDELw<T9gEKr3(d^%Vq5|eiJSLfT!J5iOVG)4lOXBbGL|^Fx@Qx*v(e46^z0`2 zN{De_Vc$#24_}=eMKP8O@Dg~n(dEphZKQ03bs`q?#I0hhEnrxnVU*0&6GSDzFo-56 za>;xZo&6H|pH*&V=Ck0_7#>d%GH5MNjJ;W8u#?SZOEr4f0%gT;-SBuNT#;BF%n<od z;cndqC$E-M<f}w|F@y=~E{x6kA$J|kEJqJ+-!sNNJHR9Op!^!LGP+k$5@R7sqX0&0 z2v{PZb>djhCU%bUeb^Z9V{0n#(F{xcqP8l&1mZ43C$H=dm5plK#zwUu4A4@o)aLol zVxXaDtlj8-*dr0pRFn+Pkz!Dzj+y6hHI<dyn^t_AiS*d|#o{I^a7mW^nh%Y{)5<$5 z&N9M&oSQM53tZK|2~>P#0v{YKAw83gt%kB9msQk#zeeI0(nl<@PDks(Vlqm7t77<} z1xLD5{9LJ#a0PCtKgp4>I2uq2F-Dka#Cayf`i6aUO2Q;b(veaWen~Q2mCkuaE2XjT z?w%s2>as9VpLR6{*A7NVGrc~t1*?^uIH)oPa^SeQG#(8vwRdTi!30-W3|Dzv@EH8S z(n!qRhiPz0mDLvxxKEJ_%C;N4m{w0jK<ir}+>a$)=&KLEL^R<lvP&O0lxq&T(=tq^ z8EOPSF8;f1Z&WxAx(N7&weOTtVV2%D;w(8o>@K<)DxYr@_L{qb0Fb$Ba3KD%34_x- zc1l9>C%0($0J11aZU0xp7YP|dT{9N3I<JdAI`oewVScq4y9U)>c1h$ltx;Y$Mc-&N ztOJKSVaHn%he>r$B^&NNZ4+X_H{{_2UC772oU?P&<A@X=CO}5&Pd?{kJRDN%BdVa^ z-2|+%x!?h|o2OL_+q%CM5_^Zo<XFr9hzRGGOMy(b=N4GP{mPMAod`MJwbw3Dl~@X2 zdo{+vBif389c%^3-x%V{1eb(T^K}%{+GnK_PU<W&(1-yWwUO6c`9QWGdQ^sRQsFEB zE)bqY9`_F*WwTdl?9x43fj=-9e2OcODK)Zi{j_n3_ikmsg-qRl$ykbo5pMr*5!XF6 zNmV#$J@&T^TdBApR!<X)wXCRFtN|S9qGf@V92&+iwz1|34pM(=@r-jT3+3?|Wa$*s zN#Af+9qv{GAS9aTIw8*F;{!I6tD!j;o7ss|ms!mpi+_12`d(TFL&~%t{Ub7`e|-W2 z+rj=0P3vLdx8a82Z~uhF%*K*}tHTQtnUV9M{bxDT@-T8B5j1IB{--CNV^N*)yTTsj z6JU*f4z{bEHaambA^uV)#<nV5Nh_K`MN4)N3dc_)0CRSLglL|2RJK3-c61xlVtQhJ z9t`H~Tgbs$vbC3N5xezM38>vW0_5o5pN*Wq=Gi#!_^w}RN&~sXz_b~zWc7TZLb&1Q z(rpQ0m)V0=A~d8IlR!XYe_xpj3NWRmNpwn%7d+gAzq^*r$26C$>y{<bxODBQ^aVp0 z*5+(1o;Z^VmQD#gsQ)AvQXCk4n2r)s-O$~jd**Y8Ph4M+!>-zvNc`f;6;s8g_QK~$ z09ouLC#-JCdW*7#L0hn;O)$cM2Gf1!d@clFUr??KDxsVmekh4;9KJa&Ez^P>g<R^b zm5fy==be{D>We}5tWz$RVH0*FKS9w`?WsXX5ttQVlt}H*C_Bn!MlRSwI1L>;_n7K* zPR!cwR_ueYAWIU&e=;yhOrD_RUnON_XA0`944!G2Tuls5lYU}0Cv`=y&StWI_%hhu zyc5L0r-S%Qqsa2KX<n7mlr%f@C#s-GnUP}wkKk-r&k+Bfml1kMn=XS^^|OcrgyI>% zmtY)?mxgKhOP8^PW7A2?C{4N(YCP!_o}KY}*#3|iI^r-23eQxHK=i07p9kV@ej(2F z^=$%iwbr<XW|(Josm?;xU8)lvxYUrcURfn7%z%a6GK{v4Qknr1x-?J0che_W%}OqC zjlL+8Cg(P1Hz=fTVNS^0*)~y2#a)JS{S^mwZokZtPEB^tB&N#@QE-^uq_j|ii00J? zOON~n7`(I$0B;(svvM%hF=iEup6yg)tDiuOjBr`)sq^vi@Jl17xq}S~#%+8>piAq$ zpEoq@Dq-f?Bx1AEd+RpOb;o{`_H42z&4fwE%py4~uahE|YIIa}r&6@o(!x93I%27Z z4a%HtP@BIw(JI=;^XlW!DnGli-(?mv4(HD(<_f4)U++WTo;_uel<zJs&v$=cb9j>p zvO>#eJRac^B69O|JE@9L<Q-dO0&Jh;{uBe+gO5rz*mV&_t=)S$cyYLQ8y#AuKnIeR zbeq)gbek;CMyD0pXACUNIkFM}*xCkJ)9OZiY+c85goBLJ+sQjw{3?PD9+<e<-MnnP z_vzM?EdcEmcM-m=Oop$0VY@3A4XyvxLp9A9W|UKAF?d9ZZ<ra&?nW=puDfQ#ZChun zOYxK4w=`hW?wz8`NoRw>?t53A{XhZo7gtA*;b9M6_PA+{amVT03L;Kjj-2d|y*azY zvD~Vs9>7n7h4~?oHd4)fk?GXt=bQRgSF>NSQizjf++c#U4%u|xKPyuG8t11P=d)zw zuD=*3T%<^pA3i(dR}jUUE{aSZiIE?kl7Nf`$-Mha_VH_?iEME7yv)@Vl}c%?#zUzg zqUb&3N<8QQY^5|y+c4BJ%Wf9?TqdnIJ4tpVHOhV>TqeB(*7lJDw5QJ3j-Pm5`q!>- zx-S+B(<;<ZGh3G>2iHmQ!|&@2&H$RU1)MhYX(;x%LU2cyWITOJ^Q@eI$^*#NHU@D0 z;etFb48<&l!=JO!Qf~bfQejbZtM|H-Z@O>rNDt{5NWL64G3$(^*;vRXIomb9S4DY$ zCBMUG^p_mSmh>v`L>*t9XJtyUftxGi5kQp~)gP0`Ds_K%H@@Fsc=o+c(-FAhkMEf; zQ@w_nz)YBZ+V)+ISgLp?6@k?(mHyLi$=X<uGv7l5Q}p~!>$9#t@*Ky6;kW5rC>-ix zP#(v*kR5f^?nDRWdsK2j7HQ-Lx5Mc$t~MZqZsIDR$yzrn){O*bNe2cYEM6*SBS*6G zgI4*l_yTJtU^{p`zAc<1qS<1-Wo8?yK(T;-$>2C~jl07pU~VF5d<dZ%jP8~)#wMy> zt$(>V9GEzq7qZ;^I!WQ58gVznqagZTQkeqqw=^w&R~cOIU}_6hHu31)_GNG>NKUN4 zrH1dwM)@uE*F`#yV&C0zull4*L$RDxiR$^*Hrxrq;CLr)^D7BTfH7uMuPw#?wH3## zvDxMMc82&E7LH)b;O5CtiS-;z*oFq4yE;Y0m%Lgxs3RJjFVingLvx|sh%dPUvelPC z!c4F!%uJ{zQzV3_QQsJA+D4>%PR~<x>-bX9dI@EI%#zCdLg>|luv5Q;8O00M$!3<% z+oBpdf$}lSOKPvMzl<|6Gw$q9MB$woD7C96*V8+0eS)V;4;G=~NN4`LfcP!U7~y0x z6d_fPoI&K{@~9vB=*NTx@SqebS=v?`VoVN_VqIDKN=%NkI5Z&HPfye6*rm{GE1VWz zGWqW_s_oE+Jq|ke`lc+nK$~XV5PvBx%E7kL3O4}^q=6>V&-)e5)zq{RS?{{C1_JCa zq~_1gxqXMWaE}$4!G2qAInSXBKeD51D|g?guD_}t6OP_oF_*-t)@+xlrBfRyxSg0) zp%GlJb93iL!0xj<brWv}{(&?;f8Sj5jr1L`9+gaHiRayffz7hoTDxU(ugvwoco7*x zYeHZAZf+n*5wCKAC<{0=Ifrt+Cxm?DD>H&@Av$+#fqABlrH7^D&Bwk@)0i;AJck-> zEn_Msb>*81-C>03^5RMo<t4q|Cuz0rjftu9qAsh&$~9MO*y=$}<t{P5DBI*h4YeIM z$XZ*(RyZM*b+xysAyn)w$`Co*>mlg>bwJDFoveJMm-+gr0iZdPrvsP0J(C#m++&IQ zq8pV7*m3xkb;_9}h~t<=R!UrUJA%s%^^M38j3`y_(Q7tTM$Z1Pyp|n6@244<^M<-a zGH6>I?M-CNR^o*-)|;0j(?j-60Yf3xGwW&P$VPq_ron7njAKaLrAFo3vAgR2<|1dL zEBQCp)7pFw4aJZv7rPOqRbfdO4MctZ)2{_}T~Rp|28X=>rXll0UAET;QY;^wsW*dn zpPCES?QJxL%{(k_e7w%&Hu2hpol#%PZ>-x|zhU$RV%wNp4#j<mu8pFDG|F#tVe*hu zhz}+<-pa%vS;*7fa2?eF_T6FHBbz6D+n|L;&$qefx+RWSaAdE^w{Zi{(SZTD*GlH< zM@S>Qt@$?L|7yTMS?RV`{Y@q&-l~go{6|bpEw)WqQp6t7L_thEt|`H;m(eBVL*Vr5 zYqBtw^uUiKg^=9P19!N$d?^0$F9VE~!g-(V2#wA<6`-PZ;(7FE3h2@Bz_}(5PDcM` za5%7ge9ETyu)*-hzuWST>L5qFa%?$gBrCm%Bkj#=k{dJOX&Gp9#fYfpdDORE)k4x@ z$wRzv|MkVyp%-W700Aj;P+&W`y!-*!qw%~LPGO){SzMdb4BzF}C?2#dfM~>*(oaO~ z5M8!K{#QJ5N^p;~sXB(TGW#}EPejbV3J+QeE&p-Fb?cb=?>FFC9*R&s6KN)Ytmo)t zx~lq`k$l9nCM1DFvxiow@-=`8vtmy|jX90_+V}RnrE$_r^C4SBfYD{F41ZR$0g-_r zmouf<9Yg{J|2H4^5P@q>8O7^?w+pEmoT5i2m1X<WU!z=np2lNlMcIMTp)Wh~%RSSJ z8Q9!-tgT?--U})E$I|KJ<Vm~cxtW|H&DYVwF>b%#ynwA5*=WU^J@C>cX<rUt-j<?e zB>e1`TucNUwn$F!T=>vf3v!`+@mgeJ?JdVCBXXpBqX=-?aha;9WgWEX{!iDoT-}cb zt>?lb+W;AF`Mw4}O%_4~&;%$YRK9A|M7w#CNGSNIhVbXKhfgpbTxK;z-Sv)1nn-_K zq8?8&7;p078b`+VesK{_9qGhm!EiS2XtX=$`-N(HFMs47*`2oD$n@PgIc&kT{tDzr zBCWRl)*}PSXea(187Ozc+gguUd>v$M9h3a+X+@D=NnkCx=~NHRA3|l&=TMLSmv)~a z7KNWCL%Gn3@%PFk4gJ4O-U_mJ^0HN86XZ25G`JlKo#>b@hpDJFd{usN^SHHY2!C^! zK0e74n_#*s`&<7}_O0=$?5{aEFO~N*gION_-H4qjrf^Y4z>-qp->KZ^M_<&ywjr%B zr&Ju}*B@iKvhiuzf8}@s-pUDj^562YuBMt6y$yfvh>Cyv6U6uPk5Fz)^6G~5)Q405 z9M){oDwf@;8n&}ypktSyeviv+8XX?JSTz<Y-*2@A#RdV*5T?2IQcNC)X#)+GJG3cZ zZPhI}BFBVuPh{9HtZ3ej{b{aug@))R=?I4E!MWE3TT$Q04t?+Y+#4ZL1xhd>j;Zbo z4+FPwm>7L;54zmj1v_>GbqHN;W}j=>(e|^yU=MS~qIHjWvn$G@QDpdqsnZ)y2L9>% zrbyk@A%L$v#FtUA>J$^*YGH6-apHib)yNt>D|^x#ptm)RI(cx}U}-Qb5UtTN>GMAN ztT-YlqsmOOauDx$kZ^%5HB};;-bWi#)?)MS{0GOTyFb*1T+jdNK(N;o=G=}5nL{b^ z?d2eMnS(@RE$`&8b24|cF4Ti=owe?n?u2JHnHYWH?)YWmodbqDCFZPO0OsJ0D!C65 z`3m=eoQ*w4$+0NXMLfOOp2ggC;Qa*;euEMRogG*x-YysxZrJ|ibW<FYp+u*aXqmEI z%~M0xTA-sy&>qZyFf3M$%^~2g*L$SCv9?81WKPJB%wR(qLJ<V4QwqH}a9C;Mf<0BB zNOhg+PKNkN>~BW=$ZC$3@lY}h33EW!HC4nHIOfVIj!rG+U)=;IE>o)~HO?XC08uTp zT*X{|Z-Eg`hA8dLw8`g0!2=hHs<SXCr(3=%Cf4|--wfWy)%JZlW_7(Z?U3%&a6cK! z^jh2cD_$rbD&1Y+A^qu*jtcm_U9L$E*6bV!upTKT+<*Hfd)q0M{WaS1rg#!oKd7pw z&}JAKKXX{N+fjrCm5$p|*|)?MVp3GC+w9pNBiDT7Hhw1tllc3t(j`aQIHsZ6QKBj_ z;xNgOoj;0gI~hB<l3Ddzucv;XGGQRhQza~4JC3;9vTX!f+dshX8^X$mKgMm^63Z0R z$CLQWR(1pnP<#9Jg7CQ^9Ns@SIEEry{{u1)^0);h`*!f)Xi~k8q3vP9Gr-xEp14C+ zZa5?N&06l|dn1%Y!=HOP&$vWr_!QpJ5fZx&SyS=%TwO7*c*kG{P65$&<*U4(4tXed z)qnf+&7y}6mBT0aJy)OYuUc;3PM>vZ*eg;iajkEuiQ$81cH$y`=jK@$qoWqlj=my? zVJRKut6(SBVmacKV5aPF=7^Ww%epRPUnLTip^*xezmq_}?^e7gDuGPiJO@Y@;xpS! zD95;l{sl}*V=e}_D;~TUnC&dzC63s@Euv<M|E0TsH`t?+AknvhiQT(vWL5hr&gfbm zc`^ON@$%AmmMMg(vE?eYzRyd4;T3MCZP|%K^P*mB11KLU$O>;Ii<WCl1hr?3{1!|2 zeUv0xxoV<-c(&+aTaL;vAK5I$(5zr3pI?x285`^Bm1J?4=uY!X<jgE@=<0)bX2>EK zI|CxpAS)#8w+Akzr9butM<JOWqi8PGo%}G*BnHaR+9cTXX6&(l-jL)?2ZY6AZE#&( zQFD+MwT$A5*4;MAiZ%-~Y2LjMq&=hO>wKDc0rUWLaeOC^)FgxH?UzvY*IXh`iWv=d zJ3>5aqNQdw&k<78)As?Yl_NbI$(@_0O~s}z$5W!&E!)f5g6EZo5U*AXuJ1D;)=Aum zT=Qyiz6L4HWkJPFOo-bHZ4n2cBxn4O#+Zj)^yD)D?Z}ICC7zfsFwz>&h@y40<5wMh ztQP2vR-V{AmPaT}@%2%O;%dx(P<vR9V95dF8Cl%}+78M_U^_wHAo`2YEV$Iw@H$Sb zxaOn2j4kNMo}$>rn}PG>1(M;oWV+Nlwqik8RAb<4Xky>3XYne<^dc#~<&foWDFv(w zB_7OW{sgDno=>ug62;lXKMpz&=P2q)IgOb^H_Tz2M`7mq<?P`#!(n4#8F{+Vze$}> z#VX$(2a7KyGAIWsIus<^0~Q7sHDGI<e?i2@xPwU&3NGn^8zGmK3bSteV=Fk>5&^wd zoqXYZ*K6?JZ~lG=G~9X>!^(N-<l*cwRDaL=6zV})BVexR%>U`pJ%J!7M}&4amw9+P z%*EsyPa_&lT0FxlMedH%4l~$EkN+({g9dB%#c}7WC;tH6)efA`8-2}3PcjpqXD@qM z$JJH643dlnbFOjhj<JKCD2Wo`Wg0=aVa;JGSle$WI?A%TWg(H&zJpDhhZ1{9gu^FB z=&eDfv<GR)M6BuR+l>A;h=Q0#M!_4-m2wCBpj4kLX?6k+K5xo*zIE~q0NX;NC)6v1 zdhG^v-{|kf_Oc)A{FC;ZEKs+TJn27pOlB?X*fq2x+U3>ybV7f(1>}wTE9OD8;cR)U z7c#SR|7e~vgZsuQp_96KPQ4w3nWveZj+GzNJ7?SDVMfKR2g%qczCp~6MuH}yA!{a` zuxv6A4#xYCHTum_;wiv*VF2v)Sk;CN^yj(*>8-eZtOE}@B($<)JHSQ3km%7b+U*R6 zsI1h!cy%mx#9d0o*Ov=^T<#@E{~#&*qn6?DSznYGBRu@kd^P54B(e<L<yslHrrQ#` zeSZtPqljicJrDhfd!EHWm7)OVUMZ75ZTg5-6Nf*3n!x1Wnp$JZZcG*Qnf|WJ+PoNy zJ%(D@(@80t0!_7_&ZPv-Wxjxoq#vPs)VS32A*0R{=8jbl%7yjYk-iH(d9njYF~!-C zLC-gXq=6u8Uu!4ze3<srvJE;FA(Dj&enA~(M|{jZBnEy}%)pQHnxgNK$9W?*K3E+1 zN<Q0VHp^FL?SkOQFv+u*^-BF~*m}x}?+ZMu(d0D8Z`R=f>#@A}7!9{4aiB1<F~$4% z^HLe)kuFEOv$QP5fc1kUdd_C_WaK1+;LmRze%H%tzbc+}*^At@hE}Z5tC53ce0;38 zayO%^T>32Ic0T@`f9PW-N-ghzNlZ3MnL3Zp_E%zm7d|q4{eAZXo$>S?f5dV6TH=?G z_A$(`@-m9UigFAf&>KwL1l2+vp<LmV0(NVrUz44qM+~cDrV*F=Fi8rvtpi!1I=`$+ zLcJYVrIL{aRzGH2FDofD$YuE#YM6TU41vsHVa&8AUBhp3(#Az0!dLIO9uR^vJQpz9 z{2S~qsz)5OGsZ2-h(dc9w2b!-?1hQ(-(Vphu*cteMqtn_s8i6C%6*=QKv+VDNrJ&B z@!P8UGyLgCjChNKBHjef1p+#XXHmm!ea_!CQv%2E4>*71Ow`KJ;%I+h{JKtYz7jWP zoo{1r;~(yjHj-H;AQXgiduWVKq~e1z0Dq~H85{WG^(>DYdyV`499n?2#>%1oENyL| z_)hKeJ&fKokBT%~TY7rc*8GGdiB-%j@T;%69nTj-pTZXTB1wec$7R&n-;Ggx*QEWw zj#lCOZKrH7{6AZyI*`$+0}p)ljs{hAi8tLhXL-;ucZ(g*{4vHDQqi4+3XoDs;brs8 zp8oV<Z|5YQD_^|2wEm1H=VVbTD%V{cv_CbDM`!F9x>Jb=HMRKO#<<@cXg!rq^iikd z`;d~PB4CbqYhIF#JJi%?e^577K#UO4f#d{gVQ1R}jr|S1jBZPvw1H>Xt^$K1#jPgm z1O*oWK@uJNn$;{3UqG=y-`gk=+0gMTr%Z+7y>gynqCib0rgKQe&Nrc>8AUh3EX_Kr zOhE+e>kefp<Re9HCfHrQIQ6S;>_FVf?js+URPyYqcY--`!?AKs8mzbin*o&=ITqI) zKZ&tnO0@&HMbOBFeR|Jv?#7S8Ab{v@wat5)>~DJI89ySR*xDxQabjAQ%bk68M0(;` zfor$&KGX};Ax|dNO;2o+yq8<m^A9SS8J^YTP|H1cmCo2AHL|km)hg&bfkwr;Dod4i zf_5r=X~RC+0srbqQ6Vz1B<4n>h0&(StYP?tH0Qyqw0*b+V(4GVIpal}hzI`A2lt+9 z=opy=a!U14A+~FAuJ)LQwH!WSO<$6!tMt!ARR>M$8$Gk0$-_snauW7*kknyhbr5tP z7e=Ur(iVjfHz-XF*Rj7`qg6V<GCtpK7s<$FAhWKHH{cw^>$pX}$WhE?(<X8;_pj;V z<rsH2US)p`3b;n=O<0<O^i`909`c0$rBrx>nX+rzhH9?8;Stse4&FZ%)AbbeLVuYL z$RfQ{8yBvVDd2*{N?R=*6DA5?wuPLT1Ni8t)^?cC`8=W|B9w%Q21hWp^Qx=EtP*UX z^_RpB;7n>4hRco!0whvq?1vP-Y>*)|FN^J$8rq;&{G6yL9raFX`h>HkPDp*Io>Y0l zsi;;q=-!C6Fez|3fBr4FcVaQ4p3OCU()0yg@5NFZ!k+o#YpqbV>`C%|Dqrry(9dMD zf}zzshCkRvHrMP}y&8uM*h@TD51y@;;UVGj8$4an=~ilfe(rI3b@1a^LW$(QDw2pm zM~(z5Lhg7SRK!g*|5dz;7(uU34^*fq)Wy~Bn6qhqcR%8D@DdrLfhhC!Mc+oDE)~mS z2NMnU!xkIO_}wbOLt3D21AHhtyuK8c1U{_ZQJ8F(*7-XpYOmn=x2uv~Lo?9~)CJW; z5@2q13XT>sM@9k>QAGuMQPV7)l60(<I;&mX(uz>;A|bV&BuXp$Dq`|BPzSvKOYHp9 zJkIx)cm|37FAy?g%W&0fya8oK)8DdNIMY*_7TQ9L2l@9F<a)vUdAr<sZxb!;=<(|1 z@}0OZV~wEi+M`&nYDOXi(EP3tV<6;2eR@Dp^afzG=0tnI!|L-dE3?j=JTVdF|9ql? zE0`SKly0GO#ie+qm8c8hgnKQqHx#j&J3(uS`}kL|L+FRh_qD@1J+s|YIobH(Ve-xp zaGl`FV<CWzpiltp<o;GrV+q{+PYh)Dtfv4U1KV~}aR!4~(TQoU6D1S4JO69H<F_E} zd>xC499*t_l;Op4_5T%JIHJck{0E~Z@)ZV02VfEj?}OD#NH}kT0{RvywD=ov($yWf zCk*apCAnN62<N9m`WX?KAMU1Le=4+``^#7MM${py1haq(@87>%zIQ6?Fq5$J``7(@ zCZv#U-qMS(#;*s|<zW%x8k%3Ak^6N&*iu4mdS_cZW&M;|tZI+Y+h|b$*z#97xiGxi z^H+kmWv}wv=Eg2p1wfMqtEU4ZVZ&%NLi);arx9F4+Mov&ufENqS0QBTj5#3^Pux}a zyFEg+m%VL5b;2OmF3N~hHKj|!kIbnpC~dKE)TBxh0@R^y>>Cq@*WQg%F`W+z;m}|; zUJn({PHdCQw~p(Cc{retpodB)^g3|u*qDO7C}g%q_;!S&=l0MK*K7#%vT7l=;$c}~ z!6VDzfC!$LlLrJ&FB(PK5i!SrVYx!2kexk^E)JdjX%Gn?Yfc@^LALCvgBe%<rw(Ew z@wNrOKeTJo!A|QEqg2aN<RL>RlYWv(oHbYCXq<(>#+f>uec?>qw-%Ppn34L_Pxw2Z zh+Z(hzw&2KAn%~^=R`bbqw@0rBp9y%mOx=mKXgY3*I@}NsSr-sUgLF}q^Uw+q0~Eq z5bIbdDnypU3nL_jD7gPbWZn@KkJQ$x1cb3jl&ifcXOas!>dNIW;iuPxj%Zh#$!mn1 z;DU)7;T@r!mLYkq5tXo5+r1?ddnp^gncEe=EWloZh2+Ha7$cl=^d%}{mh8pcVzr|= z+HOT;KR5kjZ-mbKUutszdC#ACPi!~RZ~6c6<d;2xpPZ5ZX;LJZ6rT9!_g8-6?a4%` z{3W5cZdHCl+u^uueE-_NW5Yy#8)W3t@oklSkr)_$<a?=WkpkB!Ov~PqT1v(|YHx|f z$Wo-hLqf#nGpUj+#{JwiC<N{>gb&mRlpLK~iu(1EfTF)^*IlUC%N~87#+e_*17F?9 z-~AB4cq|R#igL+5%NYsLhw8ZR5$T+Ac&RJDWL!XxVz@m`u8!Qp+T_D7<cPPXUu5Eh zVSiRV*+sl)Hv3~G@`xK|aXsB+;>k6O$<)jcAN3xCm3tmdlLG+voFjYRU#-<Ka51vi zbZ9#Ao56JR)%5W=JzLFMurnty7V{iv7-jC4d-~EoZrJ=xP_26_@o_TMmkmzyaksSZ z5|!{W%7C)<?aafw)d2bz3OeddGuX8dO}s%+_n7Y-U|U9RY1FTK(x~}0J-3QSQ8DBe z2<Mf5C`pb15mp@s!6PS5aVAB=BT1>xB5dgc7&5Ne%R6wM=N~oteTnKe|IiYg^^YZZ zsJfkcZkFZIL^Nyv3-7^c=1jzPTx#L2wv1%m{S{~4))5vh_y$z#XiwlmJ2!(r*E|SF z8$&WWyGiZY5(NvPs;^aKiA(C{(vO4*jcMebG+NGPoT@oZ4`)JZKDD^mgN?v1q3NFB zo{U)tn41R$u_9zEk6|5E)ri`{dQyD-q_Q`aK{6)c?oAt}C*yDgLLz+>dZGI=6R?-^ zwrjrN?9IfbFT4S!oIdXhKGv`xIP~RK*_)cpQwILm;>h^6P;z>d@zu#DR2FCB`eY*j z8G@2VRFMl#!!i@3&mv}h%R)UxuBZgjHOsKb2}Py9;P^yF43Aea2@QJ<%PL96rW_cI znYov-Q8nJiM!1hqp0Q~e-{!d@U53LZnhEbb%bOZF?i36$#ELykpCk#F6n=1LNhbMm zZ#(PfJ|j?}$d%JRBf|X3M1`Q{(9s&Z?#6*YJ1^<;XGw_o?~8YhaB??SnQbDU+)HDH zfe&wO`t_3V$vHFge|F9gjn5MsV&wGrG)|+n-V!CtsdL83f{>M(H(*?5@!II)IkU9+ zN6wk0etpi&vOYU!9F|SC#>+W_0i*!4I%j6}*K@|<^u3tFdf5}c6*(A-Pv>)HX8)nx z;49DD@o>(Fpi8h#&37*eFLHTxJN4ui={J~Vhaa4;wT!iz+87PB!*4a7w@k#cC~j1G zB*w&jj~?ck@ChZtkf=17XSB1=p_G6es)<30!hRh@LdW&VNgQ(cW*06%kN!+}5#+1q zwU(RM>UB8>uCCWw?hG644(GtN+Vd0?^EjJ39R{vo`f076f|>Bi6cnzl-X+*RplBT0 zm0jx?G~>OidJ1Z6M!yO{@Hb(dikgBY;RiMV+bxFZ)?R7HYb~RkJTaX%z_rHX=%dLf z^gSOp0D8|Qq^w4NN%(m5QIKw?wTE_M`=2S}M~DyBROO-J%TfGQCH{caC8u-KIA5i% zwXp6vVjeD6M-%^v?7i~tX+o`_eg`!YMyryY&LhyXljXTwl_osCSMI-}G1u%kEho}L zGKBzfh82CvNOSle8;@q@_g8+LvNUm^fB(57g!fAs>aig#I^{$P+N(eTgMc3zfhs{k z1ltk3NLG=W6hcl)!{f9<M7)}YrB&abggM+}gz!3$yzOPG9DOpT@{-GlE4F-~pHB9E zGu^X4Z7AP_=ou8sXEAV&<$<A-WC+NsU?t+aBivwE!4aTD;bd4tQ%}1AWxqA=xC-cT zx?t-D%mdgwDZ|R_Kz!~MSfERdBJX89Qz@WGPKLYo8!#K8aq-Z{ObCK{?_);eB+tPc z2?agSs3!?8N5aZpXURc{bJU~8Z8YXNSD^JJqFc5%1)>yq;Zh}H5rP)YtwfLiwtQ%c zmq~E@l6m6$wRD`&+H?R0UTn<04+K0lRZn2EkR}q#4TwHksD~OedK3O$W1*AFA|449 z_liYNU~{$+Y`(2toGoMwH+CSAByhxVYYHyaMV_u2=t|Qfy8<}`+8x3U6n<RTSEqnq zF6pzxTAIT2NcgG}cmz%6bWpd9p~;SBWPBcoUr9B)weW%I6msv!p3rq8-ic?$h`oHE z`Pqo4h`<$%iC6Ys2R<nAbTW&vHJjAiCW|XQ+xZ21eb4x~<`Qo!4zm3a)njqI3*oY0 zhgE!zArhTomfL(>3hp@AryAcz;T<Tlq33Q)0dbp+Dc?IVPLhgDm-Kj9;rMyoz1Aqx zgo8E>%t8Rd(gy{sC<8b()XjxUV=ea*Wlh9~x*tpAjvsDO0lB8)Mdb=aMcyQH0HSEk zo$m$co3>rjKp&gd_Z7%p01m7aQ20t;?Y+jBWW|}FMolPZG0q+m5)s&))m6z_M`FBI zm3aYQ`moSi5h3gjj1$O(MUA>C1=YQLXi6bKMZPxWVbhjnKNB*-pWa~D;$>n)-b$2N z^EvA_3eV!2mq}HkjF)rOUQ6Wh3U^Qn*bRPez)AHs;GS?KheS^iV(}?C6bi;E_sTx# zov%%;X?*{~>pOAgU?R8taw2*hJ?#0hjA-v`TYl~#t<mKZUz(Up3SiMVBY=`ZxaPIp zYlOoQ$C@w@vb_B=Mw4R=)}+H|5b7kgmAe-e<y2_zi#via*XTHmgzwLQ&&lf(WQo)) z^Z1l`$nlz7H}wF8$FN2S#Rm#5a+c}rL&1gAE=Kg!)<TDNpW)_aqS!Mrbyya<2g9_( zgxcfneuL!><GJ3!zV0|H11P-YwLXg@L%f(MpoMtHaIMkdh%!_SL`gH4c&#y@MjfIC z3PVE}s4GwyJWMh*ke4ES!rq!HLnkC~c4Z{g7t_C&h`XNr!KgWuAb54vKoLuFxi$rV zt`7el3g}Rm_W4>P&cxtN_C7pn8ggE!66K`BNA$Hs5n2MLr~*d(vZw1>bMQK0Ngu!j zJ7ep$MiiE02WeozlF{6O7?2isXe#<wspzJDxuo|JMR=w$b8sFS@RoplQjT%3o{YEy zZfobs_+r7IByQe|YOXZS@St_;CXRaOB-;^Ch5HYFaaW|Q8<(&|XS$7_wDJsDd) zK%Gpg68D60JgyWJA|TXNU$qENl%M+^qI?J!OJdJHh+weKBTfJQsvE8&1iKV3?AN0+ z|DutR0K<E6g$TH=s^Ut*<h5+Y)k#we$CXt$3|gCs`reK&m-I<&v57Z%Cj6=rg75_< zb}t*La>?}y-1MT#(n*Sz;g{SeO|U0pMWnJLW1pmBW#=UhQ_!@Qd&cf%<DvhC8+kpd zmirg%5H7QXFDs-Q4fM9~-gO<;J$;nulPohIXTn#NfHg(FZe}dSQb~DaoSRub7y@<b zS_AI9bI|<=1o!Z>gWu3$iE{u%7)CQn1EXvRbnb2ol2w&YBbO@jk{-DZEZ%tdK?M|2 zz%Ak(SQA@ObzWF<T(#&WE{9ulf~~6J_#)cYt#cS+nox8bd6hFhUfbB-g}C@pz>0=x z^j9D*RxxMOz>0;@wML<Qh>KZuUj7zx=kx@5OB8OiQ?9zuZ`<C-6j11ZG)9w}NxvUE zU)7XBruP!}gd_b%1UK%=0l(;X7jJs@Ub%>=a)vJ7|M2>rQ4vTg|KkBR=<m4Qjrx0! z46>ImY-i=&e9zCtATOMIei_-+R@Ro^auXzTsQ`^z_J@{YjYsTPjlg#r0m>A@i}-=L zjY2>j+OpjdA=>8ZLnk1mn?q5sjCi0`2$Z4_juoQ$0W60h$u2Z&ABD)FG;1G)D4{f8 zR0>gqUpGlF1Kck~oObUBVYfxnD0<k1rNH(wYD9~H8}wK?Jh7n6uMk2<s_@Jj!3J<q zchHFxgT<Xrh;lTZrnYHyoTk>5@OaN13E!U`Hg{{^kx7n{^cW`}GxW_o4KRE(Ek?pe zkC4ag2qY=IKSCZdKAmviVwU`fHvRi6e?oN`Zmxg-xg#>#ikx>_Nd+%{PJfpptU~Tp z6)>XB$GSoU6d&Bu*zZrm9Jk(G%e8q3rI)F4^pTBo1hQ{$W*@yMqCMKL0$$mlHiQ;x ziD&syjK$sSi@FB9BA}Y4U|CkSMQ!Q~!!x`s8dhAj*eG0J7~W^jybUIz7dAFGm`n+* zx|_I>Kp>BBNU(%dc6vC_aThVKY*kGlwiH;nDIhUbqPw?|S*c6<0OE~8&etnY_NEAI zSp)HiN|gE=P`)MUsP4ST6PVEH5`~ox?JD9@Vnvs|9Qr`Kq!_P#Xli*W>Kb`_%<DYt zK#QB2T2vp}izix{Dgpgm!bzzFFZ9zor`v$$XD#*Gh7f!txSs-sWSjNV4Hzq|gWd%M zRu&?1-3Bf<1NcMdGL{TgPk_rAcRqWG6DVx2!xlr8DAR3l0lSw-JZxz0t&QH{yCdu2 zM7bsKs`>^rqsHMFaBs?_b$f|>!sHegGFZ5TGM|w_MEA@9zOoN8DC-wZ=UI$!rH_}5 zM(%_O<br>P$q5?>a`6sJll~B4$QXqa)<b5?##?>Z9LrAh6W9}cvzM*9L^<{%{%&qf z@ghLty;K1MmTl2rn<5+(mU+4<u#UW0s}h@2s<e;FEU{!(&Y>wN`?fpMb04@7_36<0 z$J0dIfpG!}v}N>gVs+@72)UPNo6LC~PUoVqeAVg_VH+^JR3*x~k4*r$v@v*szBpZC z46)WzuVa=&_=8?!8E|ZhaK*$Aymihu=cryUTTd{`9Ine&h(b)wJYwqu&PjRM)g_8# zU2?hZAav!panQj2w03LCAR0SxPdHMO+Ekl9Wvb*rjBaM{l_%msvv~UV&NUGqj%)H> zd{fGt%vK`q?*Yb}VYtFd6^5Q^-eA==|F}1pMTrwXb~}zcE{~f10LHc(CMn56oe;ye zZgWlbT%YVE22ARfs`jP`Z|+deR>0WIL9Si5*rXFWP60Ckikw}52-9w1j)*tpbRT$1 zkLFM!x~T2Z?9vqU1?*uOh>Q#Yx&fWB*nkGr6qL7wHPLP4okj$Dr>cS~i9A@ZRS}CV zN25#hmFR6=mnbvmu=;&3aRQ0&P2d>?OabfIa&1b+U!zO9DLD}2`j8-Ud{c8!RblsR z)859(s<fEXUau}sl+IGFt80>q9k?f)Xh@*7LfvjO<jYgmo_){|A^X8C-@l)~e>0PO z<fc5cBlhnTQ3+BSyh7~X1@YT0<(HQM%LO+W8ex<Wr}wH<!io`jq-5PZm9SuhHhDa& zDa@WQ`*cWJJ9R=%-bh%gV0CSK!cv<~daLb#95l<IJa!nvJz>S*uP+_OV^3HxrRE|M z$i#fPB@Egpgi)j+T}x$eihMU}!MA#>lf=p9#o68t#2$@Uv&$~ZIp&36B_YNpXrRY) zSn(Th)));IHdgh4D}L!-(Ituyou#^KQ!us?8mWP@ZXC`$ZcPz3xRFTJ6#PY`Wz<HA z(!eGTUz*}uxG&)#_7Z)2Ci6}wbV{~Yr4r60t`eZ>Lk%P>%1X$kEzc)=|1Rqf_uXkG z4DqO<@M>oTD9E}+Jc=F_>#f8_8Sq4XNWk~AV01#l(OY%84bpoNebUy3Fn1QQ0YlOy zig;5Wda;$*qCqaL-g?Edji|xwK!@hDTN=LuaY8~w1_gAOz4>tK0|A0la#aI8osT;( zF1v`=!=izaxIWh3fpX${Z`7!@uvNzE3Bq-Pd+Xfb2Sm~eOB>hAj#8G@Gq+Ep<?%Kg zzS$O-sDQW-Y>`$jy;?TQ2HX>lyGVG>Ae`(cyC@NC+@z6x3LAKN3hH}qH#>2DA9t`q zbh4e*dR}{m#6>_XT&(WJS>xcegDTIO5M^_vr5`SgSHS0luTrT7T1dP|#P2}6>{$`e zywgB0tSYew-+*?q;=*1zZo?E%WYdIo$*rl8OReH{=Q-Xy6nQT(w&y{6?E|hLg(uR$ z%&T0uk6M+6;xSDD(QS{a4|Y-!LPHxp@0gun+k2}K3-o5}qktZ#*meib8gU<uU8e%3 zV13BpTBFby0?%q-&d;6Gtw!u_&|XkLJQbjWa;Z_6^=wh3*nu$qsU7m?8ii1zlHt_K zz#F$ihEOG<_qERa-jqQacHo|Hq!})Wa2PesFyn3lS1YvZmGgO03g4of#TClkzjrdi zt2j%4%a5*@h)*j2;}<)s?}evh*6mhK!F_QyDt|2|wW;3n<0vtf;1s~}szcy7g}|c^ z=1~ga(a5*D4@AB!JgcgrP)QfQKqF*wBEip90=`ty2T(=Hf0{yoLKF_lxXi@&XXfSt z=#xx*QsRj|Wgc?$1v2C0hS2<+eXKv6boNDmIDJEbFtCJQsr`GFS`%DW|Ne*9ci}Z~ zD7ojamJ#qOKT=EM{<r*Sy=9a*cK~xwG%by2e4Nou;u+GHLmyC~NL)!OgqLpT>@)() zjm9eO2-zS$*P;;-9iE(Yg3MmA`Ov|{J9jyBun^O|EMxfnnee$5`V^9ndyJ>dLyo>$ zs%-j*Q@39NK}};u2>{g#4)eFw(y|ww9i5*d0#|>S*ID{^=rz}B`}eT``}eQs@7y8A zrW(;J{Qjzt$QZ$@jHAtax=}^M{DjCJS^n7*CB-~)uTFpFL>JxjtM4x#Fvs!vxtE5L zKoga>S_&TRV95ISSE~uLgx|o~aahvYVHiF+Vt?#7*<7{xX1oEdP<BEeDj?ziY`O!z z$<63O0SP?HqxltBP)dm!7>M79{Bi*j00i}reatK}gI}ktmza=`tGSjaTr-@228v9P zn+$dV%82=D^)x~H5^skWAi+;eIn0woU(ep>2?3a+Py-2Yf}-CI7`P=aNdp63oI|_< zBcUyV(LmvX>-%nf2WC?%L5KEv!XG#R4|IvoMaOl?h$tuAl{@sIdYp<~`+$Xf!FTZv z^yt-<aGhX6?PimM1`^s5!{r-rkl!7+Crn0fq0AYj)pVuI|9G+s*Xul|+$(!0H-o73 z@13Y5IkLFP+rB?qiihu>aJ;&F1{3wwJ-<*NUKo=CSR)KyW2AS4!y|h!8X?Rc-U2j2 z_M64mmO=ysIe(}lw%0_b5sf~jazKa-hD!yNkeq31wyG%1JCi#UmE{PpC2ItV7Fe+< zgvgfo{68RM+<DsD5zgR#$Lo1=rs8`?PZSYmY&lGn!wTLUCdzq?uDqTou3j;9(FkEi zxaHS~NY!31x8@H8hjJs~`?JpHp6UA{Riw`sYkbJ?+EU)kErrsn5V8-MovO3%%#O~| zzYk_-`#zYO{{8Fu`-R!5le5?|jyCV<JF`<KGt;xYF*`cFQ<%Nzo?m?*%+6taejcS& zRC$Z4r4W$_`qRI^T8$3}^mymo5ktp!Sgkw&It9a7Q$f$>f)ie->DOr>OTTi7djaD8 zL+Fp{fW_x6wg);PJWiHWRW6l4eEavR+yG*VP1JS;giG^FiF+GSSI%A!a_e$Fm6(DP zB5^MfXCdv?We1jk9bdizYqbwcvH^)Fhtj|eC}rl{t{-+_yC10T3Pf25y<P<*<O@oU zHz4FYRXtC<6Zl~46&Q)!bl5o}qlcJJC1zqWnCr~rINT9LQ2{GKs#b#W-W1;y$&0R0 z7;zg@z4pON$${uzdmjjz?VG^5m)P}iZY2(SyaV@yZzob+6C$f7)z3*GInh+X_N3?R zq^AhWkm0)f_p#$WCN~<uW2g|q1H!p>hoBL%qg(t8g&=%cN<kygv@2_C=T?<wLBRHe zgijprbWy^K%1K`|0xxUTT8)s3(PGqyD)UwBp^jSd;-u?v%_CemBsjd$L2tLB9w(U2 zYD92YoGq1qe<pUWkG=+)JNS|wvx8HPW*XR5&@>Pb!4eMDF85&V#qVX#_+vT0KRGcR z<w<vDef(Ithu3d8s?Rmd9348^s-Zu(X7lq;0k+|%|FGewf3o(c|7Dv`K-ml5gp4<f z{H2XKwK%y=QJ4!!v*&&Np1}{^60se(tM0)e5%D{f*1Z2rJAV799lfCYpc802WvBDL ze$T9Hzdp+I+YjVfJK5VN+eN7C+k!Acma6NE#|}dE+#|=2SjvU0_1qgrsdMztouS-5 zkCwhZe?5LabCXo|V%@fUqqSSIQ3Z5fvFBJ>NuAtD_Ev7sy?^d}<Y82P9z_w;RH)-t zLzW}Ogt~u5Qs9BBe}46%2I9}SIft2Rt`33|j2HlJDBDbdUrrkjFxTQHSq0<vC5Xs# zfyoFGWJbY!k>f$O*9FGK^wNg`<Hf1k`VPwjmS8+fQLy%=Y{IQJ{0X9ewZpgt3Z>p) za+*lb^+<LP7-yIqHW*;2W#q77#^P`*&JiIR$Ca1jTxln|f(a*0O!6DdH-lWYc<=^~ zm(&#&UwWp##pc7OwQjs@4a0T*UL0mJ>)w5Dg*QSjaa+2<xYepI-G-2Nri@Rwtrf!2 z@dmHPLU^i*OUPSsLJ(2kR4`r_xW~P~eDNhm-HLHGZpCfiCxbZYZek$ImG1uI$(?1@ zv7BGI2R#s07;W|b`9*E8R>7KV%WaABTzuTKW6Y1qi^`9wLe<4%bX)DAd>l)28M5b( z2ywxy{E6t-!j0_t6UKsG^_Hl*8D*b6f9B?E>DS0#g^9MRUffZ+7*#p2Mkqz8{4NsE z)2sZ%W5q+oo*ySrvR?J~*p{m*$D_HNbvr|j>=%_^1Qw}VjZZWFKh-M|Z?4OH^>T>D zfr0jx-y4s?o*Cc2KZ|fI=e}lzdPSjMPkB1MFLpN;d(OC~tsgQOR^{HA43(pQ?o7t^ zxpNc!^Vj3&3zK2TvA*RSt=*D$Cc_RcqUU&HGE{Qk@>{t*_x^b>8G2NH9z|7RyQ>;X zK~>0%&#&fI-Vv5@aU#&C0cws=a#bjtk_G$_uCUiT3CThPJPMIJ3{`n7E-tk>S<<+E z++nT+i+|2bZ2?28Ln8y)Gx6Ft5dbO%sXGi84LreLY9riU3c7D{tS0WoF12MerGwe0 zg==;++*ENydm^atr4@2A8Fc@4SY=n_aBBtfo-ex36=kY;>$BsDNcQ^<6Zx{r7?(?J zsB>b-xA&Q=#e$vlUR)@#`Q^H_0@w5et=wU;MbYrLR-iZ@oL8_XKBB+XRtc!=lY-Ue zH#}Zy!vUl$akYlMk+#E4oNI#@$tRePIDgEy+By;5VcYk~i%jy2V<1;Fc{crapg+>R zGIqk#-{|`1S5vAdwp$sW_nU-KU9^b@#HTo&p*M62ww9q2((sXPkPkZh)D4o<h(27J zsZaaDH=HQ8(DtK}2#xBnf_p5&W^XW*Rh{t3?=atC#6HI7iGr1YLffr2%Zo0KBX*o6 z%&8}2@dfBmKrgy`mf(>nl3yB1l)q+Gr+|3qwyKA-MuNDO=rk}H>(G+F0fo{Chnx;T zV%ykyZE6)_9^IkF+H8WaH9A=q1(z;65R0|s!gW*~*301p^j-vtu-7=6$}Ko#LIab? zbBH3h8b#iZ^{{Xp+A-$7a*z@YT3`b>5(2MHho;EV7O{CRarQwrbZn7Yw-Rxb&wafr z5%+!~_Ah%$2wrxhjhNauLrn$5H37zTm(I=Tr8{s>m~?I-9~Rr2a3vrAc(TV7o4$C@ z-s`{@APn9tMs~)_qR?X_TX9vQV6y#T9B(jqM$~h5Smlx?)eV*>fk2nhS%qsB_(lOo zeHK?OZPIq2!#4$ScQ3$z_Z*|g#bR(_;&otz1+2aj8+Zr80yiRf0TzenJg<Qz62I46 z2L}$Ogjw(;03!Nu^|F`fT5NSf2%npR+{L4U1_~E|`^YO$MCs;HMgar1D*n1IT5N1Q z0V-guv~>s0KC%zII{;I0w#7@o)R>D5Y}WIH-wS-dUx9L96K_uscV&Y`z1G-(!sskb z;W;j)Nm&Boh#qb^`Fwi^yfme$yYt?zfXJp?cin)4fb76M;Ye8=ZcqKEl%-aJc8u(U z^^m34cHSrk1FkU|8E>>A$L}y%l7unYU~zIRau(DDHb{rTI=ia!EDs`bM%>yV!W?dN zk_OsB@CAEoNwZ*cQFpw_d01%NY7BT?g6rD*5Q22VM_po5vnG_|r74L(N%_$E6d}|1 z&Swj2u4e(YXAv;V6)4ANss1o(wb|fYM-3kzBIp<eY|)9sQsP#l&?JY02o3c3R)VX% z)QEjT<AJx~Mh&*TR;v=Dl$SqfN)q;0R;dOG8{<s6E?#1pi41)J7C9HC*jtUBR}T?= z6_6Mw5V%{79^H0h^pX-z#YCI;c}kje?7%(YNIE2!jKyc9LwIEzagXee(1evs)3TZ0 z`{w7I^Ht@S6<69S-|}PPX<}6Qs|-sMZ?^mvMakfGgLq!@*u`js{Dl;$5`<;9Xkw_M ze0g4Z6e2d0RNXs^hk;sj_aIv$F&q*y&VN(UMR83-_#}<sK44Agh{APoF&a@}%Izru zg{DJuiQS4wqUzwH6O$2*aM=2@wN-+UNmKMh5oa&(&aDuhN64t><B5tH^?b+>;wJx) z5P4%dEJI;pj6bbI+1bM0ghO*PYO~?cTp_NqMGs?DnOt)iD<Ngp93~20t`?`~T-Xlz zyXbA;4djRetS5Yb_UqjHeSgdJ)UHB$%Fs!}G=*w<aPCdVKwozxoqf6PNF%6FPkkDg z2rA^-?2k$;e$oew7*mkv4tssixRK_}+P`y45Ui>uCm!(Xdo?fLD3V-I)mV}{tPqUG z=NpVToEVoY9L{G$6LQ~xbpUabLzFKCM4=B|w_A<4$0CZ?-f@equk%rt=!vK7{k256 zH!d+1FcN^t?ZDXwkqjIrV;WfT&zi0^%DyJRg6;#Mhg+1?y~K=yce(eWple#Q29{_X zArdcr5V9BRIyfDO6)=|rw;G+nAkyd+gU7|tF2*iEVpn30uYhpZ)?8=ap?F|}o_XPw zEKhrfgqV@SbX5^=uJJx9r8#HTyU4-l`+D6*c;n9K)oUQC4aMDn9>-oj>!x}RUi1(z zO%-_xeSJL-UK+{+<F&>?_jcf(FuA3LB;uhjrYlMO$CEwDfH)TVEBl~Q%~y7u-#eAc z_^I$q@j^E9q*5Zj@KC$MT2Mp8nlr4L;2KHUT7m6{;VNGzv{OH;ig0W%yiL5-L_7iE z?5zf(Gn`7j0?`FZ<p9LFXkuVjVCR;bO(`+qt?q-65@*-3?<I<q8*EJ1rpUf`?E-BF zW|59-3|C-#?YC7orNWEWpi6ANJh&r0mk5!;J)0`gp&ccgQI&`>Ty0XxrNkD`E$StN z-YLzz0zEcFPLGO%-7DrgD(!V8dEI%D<t#c`SD-8h-+1U9m`#FcUxApJl~awm##%n8 zkqc%QodzNyJ8y14ZyN8U*IElAlj?P?iBQA!Q`JBs`4J)W29(*T_|)B3#-v_*iF?A4 ztjT6dC4NfQ<n$)!Y0uv4z-Tl=pGGkmIbl#e0>nX8I;?-s#^XD7FD}<CRLyP04c4#{ z5)Zy*gW+i9x#j6NVKGbRl^+{;*g6d)#ERht<=lS6M$;Ig9mwl|TbiPP75zM?dM-zd ztvGd1C5j}<CEcy>7B#_?4o#824TgrdrsSqDei$`5le}!KE091txL;Mkg5!_4*EpMs ztNWC#>OAiK1GcMsiMV5mZM&VDB9qHKaMVCT)F;^S3(#``Sc7hgk7)Mmc_2K%TjTc< z2~_P5qvF~t?R`|*wR(1kJ_xstmF2a@#Qm{P2OypeeZB(mDUZ>T0v2B!wnw+7$^@Hs z*zCaSh-H5r968#Afcv6=SOFEA-Ux;8Hc=BX1>6#jL`)b0k>?g7CRAT&`%c7CE$t=c zm3<H~*{k>hoW&I5UxqyJS_WrsM!^UXi~Hzz*yvK>eU1IxVT08wRkmwZ<u%<z!^7IS z9Tu~X##HP;;lG8CELWhcpFrd{1r#zFiof<;<h{g2xCSQf&das$l7<VUq=9((^=lsk z@dhT4sCcm+2B-RF_kOLhmLjv^)o>G282RgvAZyY&U6r%Vdhj|A4mSg4Nnhl-5PaT8 zWdX{lSZ8!oJOOzQOUwm>7y585vE2>%dH`}6X?I|pG$kM_9r{3Uw?=8V8oyl9Cl3~Q zRa_FjssxeO<uGkGHn_omqItzI6rLN&LI<^u%&&-EPf~gGPxdCacrN8SU*0sc_o#q` z!mB9X-+(q6U#io<rZJcHeKV;UQC)CTses+|?^ffWb~|uSIFdmEdj|h0FV}P|{K!7Y zU@_cUF2%T}Y`fgES&pv_mWh6b81V)hGb)U9AOOY=6Smx77j&u3Hox}9DIC^_(VKb& z3Q2ZN*z3T-c^QLghb~dhbKmaK&OJc<<t0X!*lg$!g!U5UT!velC3<`{Oa>`q@mH+| z3K`D<@^@(p{>h4sswrINqadkDbZnXIuEXU}yKAiYUZSJK5Dp1)m=o1WRmGiqsryQp zRq?j&4!w2=5%%6|hnE=C(iJes+||6#+^i9oQSGW=2PV9>gmMMSLh+^~4MgLts%5*- zFM~Pw0Z4cNynNnjtcHgHtB1Qb$2^D53xUVe#;rtYe~nnr??5!lgx3hSJ~YGSbyPL= zy3{y`)DGMej?}A$AOz?KF4#(At6tfkR}G<F5sQ^FzmI!<;i-@;w)|*^w3qBHKY@UW z^rOBr^QNeB+M7`ek@}t=wRMNPogH8ekB;7HL~}kBsz%s=Pw1!-UO3RE{jej1<v|Bq zBSMX}UFYqHh@+LYs6ph|L&j@FCMvn98X<gIi}9ckO$*5DemIP|v5wmjD5CnNGqEEA z*2`Jf;X+KYoi{ro$)2xX&j-FFOuJ>@5g8X6K5GO~y-m<-1jqkubcJY?uN{&*!pd1j z0C$z(nuhAq-0#o&pL?nA7oMI)mVN3vWawLMI!$p#c&n1)htGROXJ4N8h;R`I_cl_W z2FiDl0I}hkm0)}lI!xLTv1;F8$g;tQ4dx&2PbZJ!2!JD^&G`Q1^8J-R<FYDM{hgqP zPWPq|?9E?$BVQu=!h3NdPqxrOdvR45U#?Ux#aUxw^Y6Rk;IKT-R<A$;Mi#Gu+yL-K zy^m`L5=j6<KLwQLL#VDb%KQssmo+d3<D;=xpvZAJztzAj6f2c`jl^y{_OW>DKk6gA zrbu22NSL^4gc@FIBo>Uv!I=VjUQ*(9I-G}@_Voa)vi_sL0)xyJ7m^AH;U>tzrH?Jp z3KF*h5~oXgd99J_4ZQm+U?HwZy$=o%tKyPAfU@;u4b&@;8+oiA_f3NpBhhJ8iC!4d z7Ut*DdEr<B=3pAwIhIRP2CY=UJz;Vz3mN5x)W(I3HW%<j{Y|zTG*^+U2+o>E_Fe~; znFtA^7<4_lF^iBEqUgDqJV;C6ZqBRXYJQ?jUy5rkh6yRK<3uv%r9-#l%O!o3=n!gH zIX&UmJpl$mR+lhm5&uAmw?wr0iGJ~nX7gfa3<^>XFRZzpV9Cqrikgs*^T4qL5Gw>t ze`V}5@<EMK6d^ocHI9OEi1>TyxtlACLHFc*u&kxaIAV~GGP>&ZNFXYKudcU2CfOhh zzW3S-{lt!(<G>h1M291~-s`Q!zPY9kBlptvTeat|V=>vz(O2%bt_#0_{ou9hfxwe4 z>#mQ4ADZw$SkG*i2}c*l=m{tGIF^Ek3BT2N?lrQ39KG)oJ`$55SlH~<ms`R(;qWIP z{dJtGA)=<!K=j41XSo8=e=}8WHN^YsY*i%^*f3>tU9C<yI)X%KAnG2aZhfd`o?tPd z9HxODr>^GO2jR@4!HK&9;xE#g>!`WN<4`Rc7%L`A`9`2r`aBbbdPkeo%<6=BiV`*2 z>4XgV%uzQ^xI>wOaP3uTvC0mOD?CS}q)RMv;`kV^CCb7UVf4@xP5{g^E<hrgMKo%6 zpb&Rr%9<+>^`?4QeZ#cj1{|m84%`!t$E!oi3hVKzA_{W6zMiIg_90MsVtl+6V{Fb- z5WqWeP%s{_D$Dx}D~WfAG-3Tz7Kv9@f-25J3Q(WEl!uu*0WdX?I|42=Za_4e%aT5T zPDX^=f*Vlifv`(fbpfMuSs;fJV<7I~y~IT5rBhQf?qfe_O5tWB8VwY_yV^$Hk3eTc z(!~MC4#XIo9d`v{<JY+1t@9YKddvw_iN2}-dR5|=OZq|xoyXthNcgG}q7l}I^AC?G zzn~8u76}{o{Fb1{J)`WADGs=R_uX4RBYvWd*Of;vv)_jNlgeW(rovC^%2A=NAIwgY zK}pNBkIEA~4s`dk$~g)ecQh*>Nx6AhnT3D3B@9H(C|&5O&BS}PGl2`7>Siml@DlLz zs>BjoL~xyeK9M)41bk@N!-B1-99F$xzg*HMHE)i9m*w^ACE;5ZqUmwY7Koi;`fT8J zMdXiVcjBP9>5`dQOT=O7GIl>t_-FOZGEmGkYB?+kA1?=VMVr5|WjQQ-tDvC1dOiMn zOBX2<sqod()fr4_5#gW(9}Wwihhk2rVfnGjW<etH7pKPtsS8uNPshd<TtwL0*fi5x zldfZ<($TIght(niR<`STdKeZVO9>AWhhh1&o>2xiBR=R65z<xLeZyxX!b|aUc)X3s zxGX@`Wv$@LEn(au$dS38m>a#D+{_N#6OL>SMo7Z&eZuCHcFv@c{kiUiAt5H9o8P}& zzIO&js5<U^#`j;(-)~f-2#Jj{+#{b}1{GwSS>`JEw31N*63<e?*Zn(3uDvb+jA>9b z?fG6S;5B3wgR_#<5bWPSBomc@svnO-bETb*1My>3&2pNlfEo@A?n}F?_+&hA%`NPJ zxeN$l@=D@Lb{i3uaH9?_ctN{;`d~P4Ai|Ts9*)oJ8D(I+wJz(gBSCfv7yh3Oh48;z zrtU*A`SBc1`$;GC!9xRwm%)9fVYK6U%vT5zJzZnYb_80w?Jia&;2^zPT~xv%cder% zxb-#l&|DF4qN|7IqI`R-Tx1^WjL}7vk`0gD3Q;rBqpM1AZO;_l5A=6^li_!S{KdV5 zMnpVDS6z8q=)vm_3fCsICl*~)!6!fp3gJz2+NozyI3ke(gPuWbR*N~1>E`*=ALy}1 z{f+QdDgkFkajoO~a}vx`rEeBtISBjn)OE=4+Gt_Apu@=~F(7V-PV@h3boTiID5(*z zBdm*8YHOf;Pp(<rPm~<p@~y)#c)>a8fc5XC+3Tq9nZN--e;4l4wPSv(Uc{nDc6h7a zc32Im*;MbvSz*IWf~VUPWKJDEz4wY3_MC#bbyTQJ%8g^$OGH%xe}}5X&{UM{t?gVp zHYXGs$a@G<=%p!%`+~J89mtIrX56<LQwhX})P2Z!%*jqC;Qq~(s;jF0b?ts`qvH(0 zlxzn&q3tb>>kY_t01BH5=uqEND{*vAjsP5s8r26vnx<IGAt42P$LOkr&|`ObZDR`9 z9eWK-#Wr_Kw>F~kYYxjCvnyQYU281F?F@(Etmr+ac&pJjA6JLY6Vun>Z)-1+Xu~X% zTT_Tio7~!mkpOW&Y(_bwWtfi%owmKT!Rmy;Yp-OFIDhi5k9cj#o(nQy8QCX^2n17% zI>8drm8HEWIMn6MDIxe4b6_O&UE*3qF}t)CAG&7J4wnm-;tEI@fyArC3Uqa$9iC2W zU?41XF4r1m?AU-Bh)YA_<=tu|bUQ&E6cF{<MpP~}7Ca5XP41&siLwph+!El9QqxA* zs&a%pX;=N{Hac8b+odTZK?r8T0klrY&9RD3ko*{&=>)6@r4c$I;<i7W5;C{AdUZG= zwUu&R9VjKFdKhwCFx7k?a#>WaIU-lU!ZVS*PO__9)>%Cq!o8GayjLai+z?Bc<Md6a zv<U2z{<!u`sev}2A5w2kfq`^5%27bfr5iJR?);=3J8(}p6BRB-;%7ufNGiI}BYUqS z$|h--3!|7^yX_iW5$-eFV7<fenSvhV1y&43vsu9kFOW6dU@ZW8NE6n-6Cx#5^<5}p z;NJC+AT5aHkbvibrsA}<jCYGbG`shvl>v;kop`!L6pBJVl!#TRdz+!R&f4NyL|YBS zbfR6lUVy}Tt3{8l2tL)|xAy`RYJ@j>-3K8<ueZBBfp>bhERTh^N!~OvbgnAcAj@8_ zH=;GUnyw3ugBSX%fx=>89)Fu4$7N1f3Z4n!rMR&tlp<VFFuJO0o42J~8@)lzKj|sw z`CNA2b;><XI$YK>hf_#`_g#VAQUBhDg+y#6?g>ZQkxRnC-)FQ#;O$B8m3<P2C(`)- zUAC%itYQD&i3XN#2-BllM5QSjx!4@t>@Y||VY#1S+)oJ?XB4jKK;s<X2DHtksMA1a zjKK@v4Tu6iM(umY(e7-v9I8ZNw+uG^w-Tj5k*yBE<f@2d9{}+JWRh-*a6hpr7w!o{ zU2Nkl_JoQ;WjeH>qH1TZZ6L&)Z#o$pkU$`qOkaUQSu*Yj_NFwGi>5cSClEFTn-^7; z@c-E_-QBBt{Ouj8N+>)=qZ2YOxi;&nimW(O*JUN#;>(KaAuG8VzwIS@uJ?`A`^8)1 zTg;KYDjtK-^}O{;m~lB`vYzC*`}Y#}gd<rf87<n+$U>5%w>?9?vQOTC@ETzj!=uXN zlQ1@H%BdYTw!cWdy#H^-)n))NzkkDNubtdF?)wvqY%9-NUu(M*-U`IfH5BCTw+5DF z7dyh-YhaMkXb;Heo}o+;@ExLnA~w`UzAwNegw#V&_CBPh5L9)E2?qeNTubCKgZpn) zq8w}$pPMS7wy<u8;X<JvJ-SO(PL4c-f%pzYxQST!-++*!oQwt%mL!*Y1>$SR93}{t zMaAAHh!Cd9Ry~};6S`)Ndsz~4+!Mf24~|ShaP@=1K_4(2R=a~cEQcu<VibL2koE+w zwM+7<4b4LrhN71?c<5~Py4SpErkbvc2xdLJwQ)!^U9tHB98_ip?g>ZoBNC(>C=2;{ z^UDuI;(ZMa`YY$4NV0C)JI?++W4*7xXKpR3{$4QmKw-0g|HDgs!JjEJ@Rr{+&$6{W zmu~>hmTF)Kb_C8EGFqoQ!bV*ACXH}7N91)|B?xESj5GEGUoc?ux(?w|6K2i|AriC5 zIm>{k>#aUFwwXN}|CD*i(dX5VdBv5ooYVdzyPx26_T|>!eUtT?jL^NF+P}*L`z$Qm z`2PL%9k<BIFO?J2VHAgD2Cqm8XANwUY{Pe;9Y7n{!Bzut+a%}WwMO|f$#JTBz<Xiy z?ypMp1gHpmA7)d8TPipURzM+l?I!Wol;-s1FleaUg_6Rx#)5*bOtu0FMK?H5xYbCU zO6(Q)&NtcZF<y8t5x-Lw=c1RUIFALp)tz@jy|`h&HHDM9-M*`)M0}g)Ly2;lVSamU ziZIDsrfVSdC)#~DM^mH=xRujuNf>*Bhqhadh>a``4dkhlN7Gx4eYYy$o-hgYvXO=3 z_c>iR@;{#JA|Z1PG_v<PV!>mGU5YVSY>pjHg!{0-Uf)Yh1Zq;niOeGO(rv}fZ6(aQ z5LB<qLqSD`U02jz?zzR>YqFRGh-iCjISv|gTL62BuEiWYl!)9STj^S&mx1CYRsqoi zCPcsu$OCc82VirTP~!v=M)4J*qU~TA79olnSR5`;;<d)=g!L6MTmfsyME$q{c|Ln6 z=?3KPi6An!nZ=y9Ii=f&TNq={6`3y4H7&5~(nB%1U_7XR&EPj)ha0y{VQuQ93C(SY zo_X9V6_HA>of8IF)^*e+=H~tD&_>SsobGKT`j-4pmnd}Cb2qF?EX_Lax;kA&yTu)v zBD*K!IPwCNIS2uZxgFTnqH+5Kjiw4+GtJ@t-Uneg2<D!3i6Y4vnBQAd2Ep5bd%~F# z;(0cHN(n7OuNm0~sf#ue&SQN4!|OY~x*An@&;Pjb4Ej3`UZeirysEb4{$73w#BRze ze>DM}d6mDqLacR_AM*k<Ky?CMiU<+6mqavOS!%lK=JP)WUAIs=E`tu0N8Eil-D}QZ zo|AM@vKia^okC<0i*2-rgn-AmLqBpVxTe<#>?Rs}w<F~IA`qfR5Pl1%n+kywKOV() z1P7#$fT9q>xX5xk3<=IQT{TrBe7oP*Gl=m=3+t#5$i?<BA2^Z=ggsS=<T(5e{SX-f z2aXz1n$@^h2-KTf2-1=8{n=s5Zhh@Y{vq=6Q{*ATh&}&taPu|x{Ey}Q{^a~5_I%56 ziaj3|7wI3yp7*@?{`4O<{`7zS`(OV4H^jYfzx(aafBOCJ{_?N?<M;pg-T(gQfBXBN ze*f=(`|I!i&p-a{pZ}lV|K-nr{o~*M{6GKr`@jC~Pk;HhfBxHF|M>roJpcN)KmPgO zfA?R0_ka9<e{cW%>%aWp|Lwp2i*x^C+`r(<<G=jt-~T~~`|#6$`}1G__OE~X@BicX v-+ub9fByTw|E+1Un4kX1m6r6s{q^7e=O6#_x4-}C+fV;L-D+lpn_>+B*T0@v diff --git a/scripts/Documentation/Equations_MPC_22_02_2020.tex b/scripts/Documentation/Equations_MPC_22_02_2020.tex deleted file mode 100644 index 7940bca7..00000000 --- a/scripts/Documentation/Equations_MPC_22_02_2020.tex +++ /dev/null @@ -1,645 +0,0 @@ -\documentclass[a4paper,11pt]{article} -\usepackage[utf8]{inputenc} -\usepackage[english]{babel} -\usepackage{url} -\usepackage{hyperref} -\usepackage{fullpage} -\usepackage{booktabs} -\usepackage{graphicx} -\usepackage{caption} -\usepackage{subcaption} -\usepackage{enumerate} -\usepackage{color} -\usepackage{capt-of} -\usepackage{geometry} % To format pages geometry -\geometry{top=30mm, bottom=25mm, left=20mm, right=20mm} -\usepackage{float} % To place figures with [H] -\usepackage{apacite} % To cite with APA convention -\usepackage{wrapfig} -\usepackage{todonotes} -\usepackage{array}% http://ctan.org/pkg/array % Add spacing in tabular -\usepackage{amsmath} -\usepackage{amssymb} -\usepackage{bm} % To use bold in math mode -\usepackage{apacite} % To cite with APA convention -\usepackage{geometry} -\geometry{hmargin=2.5cm,vmargin=2.5cm} -% End of usepackage area -\renewcommand{\d}[1]{\ensuremath{\operatorname{d}\!{#1}}} -\newcommand{\PRLsep}{\noindent\makebox[\linewidth]{\resizebox{0.3333\linewidth}{1pt}{$\bullet$}}}%\bigskip} -%\renewcommand{\thesection}{\Roman{section}} - -\newcommand{\fM}[2]{{}^{#1}\!M_{#2}} - -% End of title area - -\setlength{\parskip}{0.9em} % Space between paragraphs -\setlength{\parindent}{0em} % No indent start of paragraphs - -\usepackage[utf8]{inputenc} - -\title{Récapitulatif TSID-Rigid} -\author{} -\date{\today} - -%\usepackage{fancyhdr}{\headheight=15pt} % This should be set AFTER setting up the page geometry -%\pagestyle{fancy} % options: empty , plain , fancy -%\renewcommand{\headrulewidth}{1pt} % customise the layout... -%\lhead{Printemps 2019 | Pierre-Alexandre Léziart}\chead{}\rhead{Pense-bête pour l'oral de l'agrégation} -%\lfoot{}\cfoot{}\rfoot{\thepage} - - -\begin{document} - -%\maketitle - -\section*{Récapitulatif de la méthode MPC 09/04/2020} - -\vspace{0.8cm} -\PRLsep -\vspace{0.5cm} - -See \url{https://arxiv.org/pdf/1909.06586.pdf} for the original MIT article ``Highly Dynamic Quadruped Locomotion via Whole-Body Impulse Control and Model Predictive Control'' - -\section{State Estimator} - -The role of the state estimator is to provide an estimation of the position, orientation, linear velocity and angular velocity of the base of the quadruped as well as the angular position of the actuators. In the case of a simulation with PyBullet this information is perfectly known and can be retrieved with the API. - -The position/orientation state vector of the quadruped in world frame is: -\begin{equation} -{}^o\!q = \begin{bmatrix} {}^o\!x & {}^o\!y & {}^o\!z & {}^o\!a & {}^o\!b & {}^o\!c & {}^o\!d & \theta_0 & \dots & \theta_{11} \end{bmatrix}^T -\end{equation} - -With $({}^o\!a,{}^o\!b,{}^o\!c,{}^o\!d)$ the quaternion associated with the orientation of the base in world frame (usually written $(x,y,z,w)$ but $x$, $y$ and $z$ are already used for the position). $\theta_{0}$ to $\theta_{11}$ are the angular positions of the 12 actuators of the quadruped. - -The velocity state vector of the quadruped in world frame is: -\begin{equation} -{}^o\!\dot q = \begin{bmatrix} {}^o\!\dot x & {}^o\!\dot y & {}^o\!\dot z & {}^o\!\omega_x & {}^o\!\omega_y & {}^o\!\omega_z & \dot \theta_0 & \dots & \dot \theta_{11} \end{bmatrix}^T -\end{equation} - -With $({}^o\!\omega_x, {}^o\!\omega_y, {}^o\!\omega_z)$ the angular velocities about the $x$, $y$ and $z$ axes of the world frame. - -%With $({}^o\!\phi, {}^o\!\theta, {}^o\!\psi)$ the roll, pitch and yaw angles (Tait-Bryan Euler angles) associated with the quaternion $({}^o\!a,{}^o\!b,{}^o\!c,{}^o\!d)$. - -\section{MpcInterface} - -The role of the MpcInterface object is to transform data coming from PyBullet (simulation) or the state estimator of the robot (real world) into useful information for the rest of the control loop. - -Data coming from PyBullet is retrieved in the world frame $o$. The position of the base of the quadruped in this frame can be noted $[{}^o\!x ~ {}^o\!y ~ {}^o\!z]^T$ and its orientation $[{}^o\!\phi ~ {}^o\!\theta ~ {}^o\!\psi]^T$ with $(\phi, \theta, \psi)$ the roll, pitch and yaw angles (Tait-Bryan Euler angles). These angles corresponds to a sequence of rotations about the $z$, then $y$ and then $x$ axis such that the transform from body to world coordinates can be expressed as: -\begin{equation} - R = R_z(\psi) R_y(\theta) R_x(\phi) -\end{equation} - -Position, orientation, linear velocity and angular velocity of the base of the quadruped in world frame can be transformed either into the base frame $b$ or into the local frame $l$, as defined in Figure X. The transform between two frames $1$ and $2$ can be stored in an object $\fM{1}{2}$ that contains the translation part $^1\!T_2$ and the rotation part $^1\!R_2$ of the transform. The relation between position $[^2\!x ~ ^2\!y ~ ^2\!z]^T$ in frame $2$ and the same position in frame $1$ is: -\begin{equation} -\begin{bmatrix}^1\!x \\ ^1\!y \\ ^1\!z \end{bmatrix} = {}^1\!R_2 \cdot \begin{bmatrix}^2\!x \\ ^2\!y \\ ^2\!z\end{bmatrix} + {}^1\!T_2 = \fM{1}{2} \cdot \begin{bmatrix}^2\!x \\ ^2\!y \\ ^2\!z\end{bmatrix} -\end{equation} - -Based on Figure X the transforms are defined as follows: -\begin{align} -{}^o\!T_b &= \begin{bmatrix} {}^o\!x & {}^o\!y & {}^o\!z \end{bmatrix}^T \\ -{}^o\!R_b &= R_3({}^o\phi) \cdot R_3({}^o\theta) \cdot R_3({}^o\psi) \\ -{}^o\!T_l &= \begin{bmatrix} {}^o\!x & {}^o\!y & {}^o\!z_{min} \end{bmatrix}^T \label{eq:oMl_T}\\ -{}^o\!R_l &= R_3({}^o\psi) \label{eq:oMl_R} -\end{align} - -%\begin{equation} -%{}^o\!R_l = R_3({}^o\psi) = \begin{bmatrix} \cos({}^o\psi) & -\sin({}^o\psi) & 0 \\ \sin({}^o\psi) & \cos({}^o\psi) & 0 \\ 0 & 0 & 1\end{bmatrix} \text{ and } {}^o\!T_l = \begin{bmatrix} {}^o\!x \\ {}^o\!y \\ {}^o\!z_{min} \end{bmatrix} -%\end{equation} - -${}^o\!z_{min}$ is the altitude of the lowest feet in world frame i.e. the $z$ coordinate of its center in this frame. Position of feet in world frame are retrieved from PyBullet. - - -To get the position and velocity of the center of mass (CoM) of the quadruped, Pinocchio requires the position and orientation of the base in world frame, the angular positions of the actuators and the linear and angular velocities of the base in base frame. All of them are directly retrieved from PyBullet except the linear and angular velocities ${}^b\!V_{base}$ and ${}^b\!W_{base}$ in base frame: % /!\ Assumptions? Wrong? /!\ -\begin{align} -{}^bV_{base} &= ({}^o\!R_b)^{-1} \cdot {}^oV_{base} \\ -{}^bW_{base} &= ({}^o\!R_b)^{-1} \cdot {}^oW_{base} -\end{align} - -The resulting position and linear velocity of the CoM in world frame are noted ${}^o\!C$ and ${}^o\!V$. The angular velocity in world frame ${}^oW$ is directly retrieved from PyBullet (assumption that ${}^oW = {}^oW_{base}$), just like the orientation ${}^o\!RPY = [{}^o\!\phi ~ {}^o\!\theta ~ {}^o\!\psi]^T$. - -The position, orientation, linear velocity and angular velocity of the base of the quadruped in local frame can be retrieved using the transform $\fM{o}{l}$ : -\begin{align} -{}^l\!C &= (\fM{o}{l})^{-1} \cdot {}^o\!C \\ -{}^l\!RPY &= [{}^o\phi~~{}^o\theta~~0]^T \\ -{}^l\!V &= ({}^o\!R_l)^{-1} \cdot {}^o\!V \\ -{}^l\!W &= ({}^o\!R_l)^{-1} \cdot {}^o\!W -\end{align} - -The projections on the ground of the shoulders of the quadruped are supposed constant even if in practice there is a dependence to roll and pitch. Order of shoulders is Front-Left, Front-Right, Hind-Left, Hind-Right: -\begin{align} -{}^l\!shoulders &= \begin{bmatrix} 0.19 & 0.19 & -0.19 & -0.19 \\ 0.15005 & -0.15005 & 0.15005 & -0.15005 \\ 0.0 & 0.0 & 0.0 & 0.0 \end{bmatrix} \\ -{}^o\!shoulders &= \fM{o}{l} \cdot {}^l\!shoulders -\end{align} - -Positions of feet in world frame ${}^o\!r$ are directly retrieved from PyBullet and transformed in local frame for the MPC: -\begin{equation} -{}^l\!r = (\fM{o}{l})^{-1} \cdot {}^o\!r -\end{equation} - -\newpage -\section{Footstep Planner} - -The desired gait for the quadruped is defined in a gait matrix of size 6 by 5. Each row contains information about one phase of the gait. The first column contains the number of remaining time steps of the MPC for each phase and the four remaining columns contains the desired contact status for each foot and for each phase (0 if the foot is in swing phase or 1 if it is in stance phase). - -With a time step of 0.02 s for the MPC and a gait period of 0.32 s, the matrix of a walking trot gait is defined as follows: -\begin{equation} -gait(0) = \begin{bmatrix} -1 & 1 & 1 & 1 & 1 \\ -7 & 1 & 0 & 0 & 1 \\ -1 & 1 & 1 & 1 & 1 \\ -7 & 0 & 1 & 1 & 0 \\ -0 & 0 & 0 & 0 & 0 \\ -0 & 0 & 0 & 0 & 0 \end{bmatrix} \label{eq:gait0} -\end{equation} - -The first phase is a 4-feet stance phase that lasts 1 iteration of the MPC, followed by a phase with 2 feet in stance phase and the other 2 in swing phase during 7 iterations, then again a 4-feet stance phase and finally 2 feet in stance phase and 2 feet in swing phase. As the quadruped moves forward in the gait, the gait matrix undergoes a rolling process. For instance after 3 iterations of the MPC this matrix becomes: -\begin{equation} -gait(1) = \begin{bmatrix} -7 & 1 & 0 & 0 & 1 \\ -1 & 1 & 1 & 1 & 1 \\ -7 & 0 & 1 & 1 & 0 \\ -1 & 1 & 1 & 1 & 1 \\ -0 & 0 & 0 & 0 & 0 \\ -0 & 0 & 0 & 0 & 0 \end{bmatrix} -\text{ } -gait(2) = \begin{bmatrix} -6 & 1 & 0 & 0 & 1 \\ -1 & 1 & 1 & 1 & 1 \\ -7 & 0 & 1 & 1 & 0 \\ -1 & 1 & 1 & 1 & 1 \\ -1 & 1 & 0 & 0 & 1 \\ -0 & 0 & 0 & 0 & 0 \end{bmatrix} -\text{ } -gait(3) = \begin{bmatrix} -5 & 1 & 0 & 0 & 1 \\ -1 & 1 & 1 & 1 & 1 \\ -7 & 0 & 1 & 1 & 0 \\ -1 & 1 & 1 & 1 & 1 \\ -2 & 1 & 0 & 0 & 1 \\ -0 & 0 & 0 & 0 & 0 \\\end{bmatrix} \label{eq:gait123} -\end{equation} - -Additional rows could be added to be able to handle more complex gaits. - -The gait being defined, let's describe the way the location of future footsteps is computed. The footstep planner only works in 2 dimensions as it outputs the desired position $(r^{x, \star}, r^{y,\star})$ of each foot on the ground which is assumed flat. It only considers as input an horizontal linear reference velocity with an angular reference velocity about the vertical axis: $(\dot x^\star, \dot y^\star, \omega_{z}^\star)$. - -The default position of footsteps in local frame is on the ground under the shoulders: -\begin{equation} -{r}_{sh} = {}^l\!shoulders = \begin{bmatrix} 0.19 & 0.19 & -0.19 & -0.19 \\ 0.15005 & -0.15005 & 0.15005 & -0.15005 \end{bmatrix} -\end{equation} - -A symmetry term is added to this position to make the gait more symmetric compared to the shoulders when moving. If the base moves forwards at speed $v$ then if a foot lands under its associated shoulder it will spend the whole stance phase ``behind'' the shoulder as the base keeps moving forwards while the foot in contact does not move (in world frame). During the duration of the stance phase, the displacement of the base is equal to $t_{stance} v$. That is why with the symmetry term trying to land $\frac{t_{stance}}{2} v$ in front of the shoulder feet in contact spend half the stance phase in front of the shoulder and the other half behind it. -\begin{equation} -{r}_{sym} = \frac{t_{stance}}{2} ~ {}^l\!v = \frac{t_{stance}}{2} \begin{bmatrix} {}^l\!\dot x \\ {}^l\!\dot y \end{bmatrix} -\end{equation} - -A feedback term is added to the footstep planner to make it easier for the robot to reach the reference velocity. The only way the quadruped can interact with its environment is by pushing on the ground with its feet (cannot pull). As per Newton's second law, if the quadruped wants to move in a given direction it has to apply a force in the inverse direction. So the feedback term makes it easier to do that by shifting the desired location of footsteps in the inverse direction of the velocity error $(v^\star-v)$. For instance if the robot is not moving fast enough forwards then the feedback term will slightly shift the footsteps backwards so that it's easier to push on the ground backwards and as a result to increase its forward velocity. -\begin{equation} -{r}_{fb} = k ~ ({}^l\!v - {}^l\!v^\star) = k \begin{bmatrix} {}^l\!\dot x - {}^l\!\dot x^\star \\ {}^l\!\dot y - {}^l\!\dot y^\star \end{bmatrix} -\end{equation} - -The feedback gain $k$ is equal to 0.03 (MIT's value). - -A centrifugal term is added to the footstep planner to make it easier to compensate the centrifugal effect when the robot is turning about the vertical axis by adjusting the location of footsteps accordingly. As the formula involves the desired angular speed rather than the current one, it could also be seen as a way to help the quadruped reach the reference angular velocity in a way similar to what the feedback term does for the linear velocity. -\begin{equation} -{r}_{c} = \frac{1}{2} \sqrt{\frac{h}{g}} ~ {}^l\!v \times {}^l\!\omega^\star = \frac{1}{2} \sqrt{\frac{h}{g}} \begin{bmatrix} {}^l\!\dot y ~ \omega_{{}^l\!z}^\star \\ - {}^l\!\dot x ~ \omega_{{}^l\!z}^\star \end{bmatrix} -%k ~ ({}^l\!v - {}^l\!v^\star) = k \begin{bmatrix} {}^l\!\dot x - {}^l\!\dot x^\star \\ {}^l\!\dot y - {}^l\!\dot y^\star \end{bmatrix} -\end{equation} - -Finally, another term is added to the footstep planning to take into account a temporal aspect. With all previous terms, there is none: whether a foot is just at the start of its swing phase or almost at the end, the desired target location returned by the footstep planner is the same. If the quadruped is moving forwards at the reference velocity then during the whole duration of a swing phase the target position will be $\Delta x$ meters in front of the shoulder in local frame. Except since the base is moving in world frame then the target position in world frame is moving as well. At the start of each swing phase the associated foot will target a position $x_0 + \Delta x$ in world frame but by the end of the swing phase this position becomes $x_0 + \Delta x + t_{swing} ~ \dot x^\star$ due to the movement of the base. With the assumption that current and reference velocities do not change much over one period of gait feet could directly aim for their final target location by taking into account the movement of the base during their swing phase. - -With the assumption that the quadruped moves with constant linear and angular velocities during the remaining duration of the swing phase then the predicted movement is, if $\omega_{{}^l\!z} \neq 0$: -\begin{align} -{}^l\!x_{pred}(t_r) &= \int_{0}^{t_r} \left( {}^l\!\dot x \cos(\omega_{{}^l\!z} ~ t) - {}^l\!\dot y \sin(\omega_{{}^l\!z} ~ t) \right) ~dt \\ -{}^l\!y_{pred}(t_r) &= \int_{0}^{t_r} \left( {}^l\!\dot x \sin(\omega_{{}^l\!z} ~ t) + {}^l\!\dot y \cos(\omega_{{}^l\!z} ~ t) \right) ~dt \\ -{}^l\!x_{pred}(t_r) &= \frac{{}^l\!\dot x \sin(\omega_{{}^l\!z} ~ t_r) + {}^l\!\dot y \left( \cos(\omega_{{}^l\!z} ~ t_r) - 1 \right)}{\omega_{{}^l\!z}} \\ -{}^l\!y_{pred}(t_r) &= \frac{- {}^l\!\dot x \left( \cos(\omega_{{}^l\!z} ~ t_r) - 1 \right) + {}^l\!\dot y \sin(\omega_{{}^l\!z} ~ t_r)}{\omega_{{}^l\!z}} -\end{align} - -If $\omega_{{}^l\!z} = 0$: -\begin{align} -{}^l\!x_{pred}(t_r) &= {}^l\!\dot x ~ t_r \\ -{}^l\!y_{pred}(t_r) &= {}^l\!\dot y ~ t_r -\end{align} - -The remaining duration $t_r$ for the swing phase of a foot can be directly retrieved using information contained in the gait matrix like the contact status (0 for a swing phase) and the remaining number of time steps (first column). - -The desired location of footsteps is the sum of all described terms. Symmetry, feedback and centrifugal terms are the same for all feet contrary to the shoulder and prediction terms. - -The desired location of footsteps for each gait phase in the prediction horizon are stored in a 6 by 13 matrix (same number of rows than the gait matrix). The first column is the same and contains the remaining number of footsteps for each phase. The twelve other columns contains the desired location of the footstep (if in stance phase) or Not-A-Number (if in swing phase) for the 4 feet. For instance for the $gait(1)$ matrix of equation \ref{eq:gait123} this matrix would be: \vspace{-0.6cm} - -\begin{center} -\begin{tabular}{ccccccccccccccc} - [ & $7$ & ${}^l\!r_0^x$ & ${}^l\!r_0^y$ & ${}^l\!r_0^z$ & $\mathit{NaN}$ & $\mathit{NaN}$ & $\mathit{NaN}$ & $\mathit{NaN}$ & $\mathit{NaN}$ & $\mathit{NaN}$ & ${}^l\!r_3^x$ & ${}^l\!r_3^y$ & ${}^l\!r_3^z$ & \\ - & $1$ & ${}^l\!r_0^x$ & ${}^l\!r_0^y$ & ${}^l\!r_0^z$ & ${}^l\!r_1^{x,\star}$ & ${}^l\!r_1^{y,\star}$ & 0 & ${}^l\!r_2^{x,\star}$ & ${}^l\!r_2^{y,\star}$ & 0 & ${}^l\!r_3^x$ & ${}^l\!r_3^y$ & ${}^l\!r_3^z$ & \\ - & $7$ & $\mathit{NaN}$ & $\mathit{NaN}$ & $\mathit{NaN}$ & ${}^l\!r_1^{x,\star}$ & ${}^l\!r_1^{y,\star}$ & 0 & ${}^l\!r_2^{x,\star}$ & ${}^l\!r_2^{y,\star}$ & 0 & $\mathit{NaN}$ & $\mathit{NaN}$ & $\mathit{NaN}$ & \\ - & $1$ & ${}^l\!r_0^{x,\star}$ & ${}^l\!r_0^{y,\star}$ & 0 & ${}^l\!r_1^{x,\star}$ & ${}^l\!r_1^{y,\star}$ & 0 & ${}^l\!r_2^{x,\star}$ & ${}^l\!r_2^{y,\star}$ & 0 & ${}^l\!r_3^{x,\star}$ & ${}^l\!r_3^{y,\star}$ & 0 & \\ - & 0 & $\mathit{NaN}$ & $\mathit{NaN}$ & $\mathit{NaN}$ & $\mathit{NaN}$ & $\mathit{NaN}$ & $\mathit{NaN}$ & $\mathit{NaN}$ & $\mathit{NaN}$ & $\mathit{NaN}$ & $\mathit{NaN}$ & $\mathit{NaN}$ & $\mathit{NaN}$ & \\ - & 0 & $\mathit{NaN}$ & $\mathit{NaN}$ & $\mathit{NaN}$ & $\mathit{NaN}$ & $\mathit{NaN}$ & $\mathit{NaN}$ & $\mathit{NaN}$ & $\mathit{NaN}$ & $\mathit{NaN}$ & $\mathit{NaN}$ & $\mathit{NaN}$ & $\mathit{NaN}$ & ] -\end{tabular} -\end{center} - -The first row is a phase with two feet in swing phase (feet 1 and 2) and two feet in stance phase (feet 0 and 3). Feet 1 and 2 in swing phase receive a $\mathit{NaN}$ value while feet 0 and 3 in stance phase receive their desired location. Since the first row is the current active phase the desired position of feet in stance phase is their current position in local frame. Due to how $\fM{o}{l}$ has been defined in equation \ref{eq:oMl_T} and \ref{eq:oMl_R} and the fact that ${}^l\!r = (\fM{o}{l})^{-1} \cdot {}^o\!r$ that means ${}^l\!r_0^z = {}^o\!r_0^z - {}^o\!z_{min}$. For a ground that is completely flat ${}^o\!r_0^z = {}^o\!r_3^z = {}^o\!z_{min}$ so ${}^l\!r_0^z = {}^l\!r_3^z = 0$. However if foot 0 is on a small step then ${}^o\!r_3^z = {}^o\!z_{min}$ and ${}^o\!r_0^z = {}^o\!z_{min} + h_{step}$ so ${}^l\!r_3^z = 0$ and ${}^l\!r_0^z = h_{step}$. That way the fact that foot 0 is not strictly on the ground but on a small step is taken into account. - -For the second row (the next phase), feet 0 and 3 are still in stance phase so their desired position is still their current position. For feet 1 and 2 that will be in stance phase (they are currently in swing phase) their desired position is the one outputted by the footstep planner. It only provides desired position for the $x$ and $y$ components so for $z$ the assumption is made that the ground is flat (${}^l\!r_1^{z,\star} = {}^l\!r_2^{z,\star} = 0$) since there is no \textit{a priori} knowledge about the environment. - -For the third phase, feet 0 and 3 are now in swing phase so they have a $\mathit{NaN}$ value while feet 1 and 2 are still in stance phase compared to the previous phase so their desired positions do not change. For the fourth phase feet 0 and 3 are back in stance phase. Their current position is not used since this stance phase happens in the future after a swing phase so instead their desired position is the one outputted by the footstep planner. - -\section{Foot trajectory generator} - -$x$, $y$ and $z$ in this section replace ${}^o\!r^x$, ${}^o\!r^y$ and ${}^o\!r^z$ for clarity purpose. - -During swing phases feet have to be guided from their current position to their target position on the ground outputted by the footstep planner. To generate their trajectory in the air, foot trajectory generators are used, one for each foot. Each generator takes as input the current state of its associated foot $[x_{ft} ~ \dot x_{ft} ~ \ddot x_{ft} ~ y_{ft} ~ \dot y_{ft} ~ \ddot y_{ft}]$, the desired position on the ground $[x_{goal} ~ y_{goal}]$, the control time step $dt$, the time $t_0$ elapsed since the start of the swing phase and the expected duration $t_1$ of the swing phase. This information is processed to output a command $[x^\star ~ \dot x^\star ~ \ddot x^\star ~ y^\star ~ \dot y^\star ~ \ddot y^\star ~ z^\star ~ \dot z^\star ~ \ddot z^\star]$ for the foot. Generators work in the world frame and use data provided by the MpcInterface. - -For the $x$ component, what the generator does is to tune a 5-th polynomial to have $x(t_0) = x_{ft}$, $\dot x(t_0) = \dot x_{ft}$ and $\ddot x(t_0) = \ddot x_{ft}$ while having $x(t_1) = x_{goal}$, $\dot x(t_1) = \ddot x(t_1) = 0$. The generator can then output $[x^\star ~ \dot x^\star ~ \ddot x^\star]$ by computing $x(t_0 + dt)$, $\dot x(t_0 + dt)$ and $\ddot x(t_0 + dt)$. The same happens for the $y$ component to output $[y^\star ~ \dot y^\star ~ \ddot y^\star]$. - -Command for the $z$ component is deterministic and there is no feedback like for the $x$ and $y$ components for which the current position, velocity and acceleration of the foot are taken into account. Trajectory for $z$ is a 6-th order polynomial that does not change and defined in such a way that $z(0) = \dot z(0) = \ddot z(0) = 0$ and $z(t_1) = \dot z(t_1) = \ddot z(t_1) = 0$ with $z(\frac{t_1}{2}) = h$. $h$ is a constant value defined when the foot trajectory generator is created to set the desired apex height of the foot during its swing phase. - -Due to these characteristics, the trajectory generated can be described as a bell-like trajectory that goes from the initial position of the foot to its target trajectory while respecting non-slipping constraints during take-off and landing (no horizontal speed) and trying to land softly (0 final velocity and acceleration for $z$). - -To keep this slipping-avoidance property, the target position on the ground $[x_{goal} ~ y_{goal}]$ is locked $t_{lock}$ seconds before landing. Basically $[x_{goal} ~ y_{goal}]$ is not updated if $t_0 > (t_1-t_{lock})$. Changing the desired position on the ground just before landing would create a non-negligible horizontal speed to correct the position of the foot in order to land at the new position. It is required because the target position is always changing since it is linked to the current velocity of the robot through the symmetry term of the footstep planner and this velocity is never exactly the same from one time step to another. - -Since a 3D tracking task is in charge of applying the adequate torques to follow the command of the trajectory generator depending on the current state of the foot (more details in the Inverse Dynamics section), there is already a feedback for the position, velocity and acceleration of the foot. To avoid having two feedback loops that try to do the same thing, the feedback of the foot trajectory generator is not used. What that means is that at the start of the swing phase the trajectory generator receives $[x_{ft} ~ 0 ~ 0 ~ y_{ft} ~ 0 ~ 0]$ to update the position of the foot and then the command of the generator is supposed to be perfectly followed. Therefore at the next iteration the generator is given the command $[x^\star ~ \dot x^\star ~ \ddot x^\star ~ y^\star ~ \dot y^\star ~ \ddot y^\star]$ as the state of the foot. That way the feedback capabilities of the generator are not used. - -As explained earlier, the trajectory for the $z$ component is deterministic: it always starts at $z(0)=0$ m and ends at $z(t_1)=0$ m. That is why a small offset is added to the command $z^\star$ that is sent to the 3D tracking task to take into account the altitude of the ground the robot is walking on. This $z_{offset}$ is determined by taking the minimum altitude of all feet in contact with the ground which uses the assumption that there is at least one feet in contact when the other feet are in swing phase (equal to ${}^o\!z_{min}$ introduced in the MpcInterface section). With this offset the command received by the tracking task will start and end at the correct altitude. - -\newpage -\section{State vector} - - -The reference velocity $\dot q^\star$ that is sent to the robot is expressed in its local frame. It has 6 dimensions: 3 for the linear velocity and 3 for the angular one. -\begin{equation} -{}^l\! \dot q^\star = [{}^l\! \dot x^\star ~~ {}^l\! \dot y^\star ~~ {}^l\! \dot z^\star ~~ \omega_{{}^l\!x}^\star ~~ \omega_{{}^l\!y}^\star ~~ \omega_{{}^l\!z}^\star ]^T -\end{equation} - -The velocity vector of the robot is: -\begin{equation} -{}^l\! \dot q = [{}^l\! \dot x ~~ {}^l\! \dot y ~~ {}^l\! \dot z ~~ \omega_{{}^l\!x} ~~ \omega_{{}^l\!y} ~~ \omega_{{}^l\!z} ]^T -\end{equation} - -At the start each iteration of the MPC, the current position and orientation of the robot defines a new frame in which the solver will work. This frame is a copy of the local frame so it is at ground level with the $x$ axis pointing forwards ($x$ axis of the local frame), the $y$ axis pointing to the left ($y$ axis of the local frame) and the $z$ axis point upwards. Instead of working in terms of rotation around the $x$, $y$ and $z$ axes of the world frame, the solver will work with the pitch, roll and yaw angles defined in this new frame. The solver is working in a copy of the local frame, initial conditions of the solving process are as follows: -\begin{align} -q_0 &= [{}^l\!x ~~ {}^l\!y ~~ {}^l\!z ~~ {}^l\! \phi ~~ {}^l\! \theta ~~ {}^l\! \psi ]^T = [ {}^l\!C_x ~~ {}^l\!C_y ~~ {}^l\!C_z ~~ {}^l\! \phi ~~ {}^l\! \theta ~~ 0]^T \\ -\dot q_0 &= [{}^l\! \dot x ~~ {}^l\! \dot y ~~ {}^l\! \dot z ~~ \omega_{{}^l\!x} ~~ \omega_{{}^l\!y} ~~ \omega_{{}^l\!z} ]^T -\end{align} - -With $[{}^l\! C_x ~~ {}^l\! C_y ~~ {}^l\! C_z ]$ the position of the center of mass in local frame. - -The state vector of the robot and the reference state vector are then: -\begin{equation}X = \begin{bmatrix} q \\ \dot q \end{bmatrix} \text{~~~~}X^\star = \begin{bmatrix} q^{\star} \\ \dot q^{\star} \end{bmatrix}\end{equation} - -The reference velocity is supposed constant over the prediction horizon in the local frame of the robot so it has to be properly rotated to be consistent with its future orientation. - -For time step $k$ of the prediction horizon, the reference velocity vector is defined as follows: -\begin{align} -\forall k \in [1, n_{steps}], ~ \dot q_k^\star = \begin{bmatrix} R_z(\Delta t \cdot k \cdot \omega_{{}^l\!z}^\star) \\ R_z(\Delta t \cdot k \cdot \omega_{{}^l\!z}^\star) \end{bmatrix} \cdot {}^l\! \dot q^\star -\end{align} - -with $R_z(\psi)$ the 3 by 3 rotation matrix by an angle $\psi$ about the vertical axis. There is no rotation about the roll and pitch axes due to the assumption that the trunk is almost horizontal. - -%with $\forall k, \dot q_k^\star = \dot q^\star$ since the reference velocity is supposed constant over the prediction horizon. $q_k^\star$ is obtained by integrating the $\dot q^\star$ starting from the current position vector $q_0$. -%\begin{align} -%q_0 &= [0 ~~ 0 ~~ z ~~ \phi ~~ \theta ~~ 0 ]^T \\ -%q_{k+1} &= q_k + R(\psi_k) \cdot \dot q^\star -%\end{align} - -To get the reference position vector for all time steps of the prediction horizon an integration similar to the one that has been done for the prediction term of the footstep planner is performed. If $\omega_{{}^l\!z}^\star = 0$: -\begin{equation} -\forall k \in [1, n_{steps}], ~ q_{k}^\star = q_0 + k ~ \Delta t ~ {}^l\! \dot q^\star -\end{equation} - -If $\omega_{{}^l\!z^\star} \neq 0$: -\begin{align} -x_k^\star &= {}^l\! C_x + \frac{{}^l\!\dot x^\star \sin(\omega_{{}^l\!z}^\star ~ k ~ \Delta t) + {}^l\!\dot y^\star \left( \cos(\omega_{{}^l\!z}^\star ~ k ~ \Delta t) - 1 \right)}{\omega_{{}^l\!z}^\star} \\ -y_k^\star &= {}^l\! C_y + \frac{- {}^l\!\dot x^\star \left( \cos(\omega_{{}^l\!z}^\star ~ k ~ \Delta t) - 1 \right) + {}^l\!\dot y^\star \sin(\omega_{{}^l\!z}^\star ~ k ~ \Delta t)}{\omega_{{}^l\!z}^\star} \\ -z_k^\star &= {}^l\! C_z + k ~ \Delta t ~ {}^l\! \dot z^\star \\ -\phi_k^\star &= {}^l\! \phi + \frac{\omega_{{}^l\!x}^\star \sin(\omega_{{}^l\!z}^\star ~ k ~ \Delta t) + \omega_{{}^l\!y}^\star \left( \cos(\omega_{{}^l\!z}^\star ~ k ~ \Delta t) - 1 \right)}{\omega_{{}^l\!z}^\star} \\ -\theta_k^\star &= {}^l\! \theta + \frac{- \omega_{{}^l\!x}^\star \left( \cos(\omega_{{}^l\!z}^\star ~ k ~ \Delta t) - 1 \right) + \omega_{{}^l\!y}^\star \sin(\omega_{{}^l\!z}^\star ~ k ~ \Delta t)}{\omega_{{}^l\!z}^\star} \\ -\psi_k^\star &= 0 + k ~ \Delta t ~ \omega_{{}^l\!z}^\star \\ -\end{align} - -%\begin{equation} q_{k+1}^\star = q_k^\star + \begin{bmatrix} R_z(\Delta t \cdot k \cdot \dot \phi^\star) \\ R_z(\Delta t \cdot k \cdot \dot \phi^\star) \end{bmatrix} \cdot \dot q_0^\star \end{equation} - -Previous equations could be used in a general case for which there is a velocity control for all linear and angular components. However, in our case, since we want the quadruped to move around while keeping the trunk horizontal and at constant height, we want a velocity control in $x$, $y$ and $\psi$ and a position control in $z$, $\phi$ and $\theta$ to keep $\forall t, ~z(t) = h$ and $\phi(t) = \theta(t) = 0~rad$. To avoid having too many feedback loop (reference velocity for $z$, $\phi$ and $\theta$ depending on the position error) we set $\forall k \in [1, n_{steps}]$: -\begin{align} -\dot z_k^\star = 0 \text{ and } z_k^\star = h \\ -\omega_{{}^l\!x}^\star = 0 \text{ and } \phi_k^\star = 0 \\ -\omega_{{}^l\!y}^\star = 0 \text{ and } \theta_k^\star = 0 -\end{align} - -To sum things up: -\begin{equation} - \forall k \in [1, n_{steps}], ~ X_k^\star = \begin{bmatrix} - {}^l\! C_x + \frac{{}^l\!\dot x^\star \sin(\omega_{{}^l\!z}^\star ~ k ~ \Delta t) + {}^l\!\dot y^\star \left( \cos(\omega_{{}^l\!z}^\star ~ k ~ \Delta t) - 1 \right)}{\omega_{{}^l\!z}^\star} \\ - {}^l\! C_y + \frac{- {}^l\!\dot x^\star \left( \cos(\omega_{{}^l\!z}^\star ~ k ~ \Delta t) - 1 \right) + {}^l\!\dot y^\star \sin(\omega_{{}^l\!z}^\star ~ k ~ \Delta t)}{\omega_{{}^l\!z}^\star} \\ - h \\ 0 \\ 0 \\ k ~ \Delta t ~ \omega_{{}^l\!z}^\star \\ - {}^l\! \dot x^\star \cos(k ~ \Delta t ~ \omega_{{}^l\!z}^\star) - {}^l\! \dot y^\star \sin(k ~ \Delta t ~ \omega_{{}^l\!z}^\star) \\ - {}^l\! \dot x^\star \sin(k ~ \Delta t ~ \omega_{{}^l\!z}^\star) + {}^l\! \dot y^\star \cos(k ~ \Delta t ~ \omega_{{}^l\!z}^\star) \\ 0 \\ 0 \\ 0 \\ \omega_{{}^l\!z}^\star - \end{bmatrix} -\end{equation} - - - -The solver will work around the reference trajectory so we define the optimization state vector as follows: -\begin{equation}\mathcal{X}_k = X_k - X_k^\star \end{equation} - -\newpage -\section{Dynamics equations and constraints} - -The MPC works with a simple lumped mass model (centroidal dynamics). It can be written in world frame as follows: -\begin{align} - m ~ {}^o\! \ddot C &= \sum_{i=0}^{n_c - 1} {}^o\!f_i - \begin{bmatrix} 0 \\ 0 \\ mg \end{bmatrix} \label{eq:c_linear}\\ - %m \begin{bmatrix} {}^o\! \ddot x \\ {}^o\! \ddot y \\ {}^o\! \ddot z \end{bmatrix} &= \sum_{i=0}^{n_c - 1} {}^o\!f_i - \begin{bmatrix} 0 \\ 0 \\ mg \end{bmatrix} \\ - \frac{d}{dt}({}^o\!\mathcal{I} {}^o\!\omega) &= \sum_{i=0}^{n_c - 1} ({}^o\!r_i - {}^o\!C) \times {}^o\!f_i \label{eq:c_angular} - %\frac{d}{dt}({}^o\!\mathcal{I} \cdot \begin{bmatrix} {}^o\! \dot \phi \\ {}^o\! \dot \theta \\ {}^o\! \dot \psi \end{bmatrix} ) &= \sum_{i=0}^{n_c - 1} ({}^o\!r_i - {}^o\!C) \times {}^o\!f_i -\end{align} - -With $n_c$ the number of footholds, ${}^o\!f_i$ the reaction forces, ${}^o\!r_i$ the location of contact points, ${}^o\!C$ the position of the center of mass, ${}^o\!\mathcal{I}$ the rotational inertia tensor and ${}^o\!w$ the angular velocity of the body. - -The first assumption is that roll and pitch angles are small, it follows that: -\begin{align} -\begin{bmatrix} {}^o\! \dot \phi \\ {}^o\! \dot \theta \\ {}^o\! \dot \psi \end{bmatrix} &\approx R_z(\psi)^{-1} \cdot {}^o\!\omega \label{eq:assumption1} \\ -{}^o\! \mathcal{I} &\approx R_z(\psi) \cdot {}^b\! \mathcal{I} \cdot R_z(\psi)^{-1} -\end{align} - -The second assumption is that states are close to the desired trajectory so in equation \ref{eq:c_angular} we can replace the position of the center of mass ${}^o\!C$ by the desired position for the center of mass. - -The last assumption is that pitch and roll velocities are small so: -\begin{equation} - \frac{d}{dt}({}^o\!\mathcal{I} {}^o\!\omega) = {}^o\!\mathcal{I} {}^o\! \dot \omega + {}^o\! \omega \times ({}^o\!\mathcal{I} {}^o\! \omega) \approx {}^o\!\mathcal{I} {}^o\! \dot \omega -\end{equation} - -With these assumptions, equation \ref{eq:c_angular} is simplified into: -\begin{equation} -{}^o\!\mathcal{I} ~ {}^o\! \dot \omega = \sum_{i=0}^{n_c - 1} ({}^o\!r_i - {}^o\!C^\star) \times {}^o\!f_i \label{eq:c_angular_bis} -\end{equation} - -The local frame that the solver is working in is actually the world frame rotated by $\psi$ about the vertical axis $z$ so equation \ref{eq:assumption1} becomes: -\begin{equation} -\begin{bmatrix} {}^o\! \dot \phi \\ {}^o\! \dot \theta \\ {}^o\! \dot \psi \end{bmatrix} \approx {}^l\!\omega \label{eq:approx_angular_velocity} -\end{equation} - -Equations \ref{eq:c_linear} and \ref{eq:c_angular_bis} can be written in local frame: -\begin{align} -m ~ R_z(\psi)^{-1} {}^l\! \ddot C &= \sum_{i=0}^{n_c - 1} R_z(\psi)^{-1} {}^l\!f_i - R_z(\psi)^{-1} \begin{bmatrix} 0 \\ 0 \\ mg \end{bmatrix} \\ -R_z(\psi)^{-1} {}^l\!\mathcal{I} R_z(\psi) ~ R_z(\psi)^{-1} {}^l\! \dot \omega &= \sum_{i=0}^{n_c - 1} R_z(\psi)^{-1} ({}^l\!r_i - {}^l\!C^\star) \times R_z(\psi)^{-1} {}^l\!f_i -\end{align} - -As cross product is invariant by rotation these equations result in: -\begin{align} -m ~ {}^l\! \ddot C &= \sum_{i=0}^{n_c - 1} {}^l\!f_i - \begin{bmatrix} 0 \\ 0 \\ mg \end{bmatrix} \\ -{}^l\!\mathcal{I} ~ {}^l\! \dot \omega &= \sum_{i=0}^{n_c - 1} ({}^l\!r_i - {}^l\!C^\star) \times {}^l\!f_i -\end{align} - -Once discretized and considering equation \ref{eq:approx_angular_velocity}, evolution of state variables becomes $\forall k \in [0, n_{steps}-1]$: -\begin{align} -\begin{bmatrix} {}^l\! x_{k+1} \\ {}^l\! y_{k+1} \\ {}^l\! z_{k+1} \end{bmatrix} &= \begin{bmatrix} {}^l\! x_{k} \\ {}^l\! y_{k} \\ {}^l\! z_{k} \end{bmatrix} + \Delta t \begin{bmatrix} {}^l\! \dot x_{k} \\ {}^l\! \dot y_{k} \\ {}^l\! \dot z_{k} \end{bmatrix} \\ -\begin{bmatrix} {}^l\! \phi_{k+1} \\ {}^l\! \theta_{k+1} \\ {}^l\! \psi_{k+1} \end{bmatrix} &= \begin{bmatrix} {}^l\! \phi_{k} \\ {}^l\! \theta_{k} \\ {}^l\! \psi_{k} \end{bmatrix} + \Delta t \begin{bmatrix} \omega_{{}^l\!x,k} \\ \omega_{{}^l\!y,k} \\ \omega_{{}^l\! z,k} \end{bmatrix} \\ -\begin{bmatrix} {}^l\! \dot x_{k+1} \\ {}^l\! \dot y_{k+1} \\ {}^l\! \dot z_{k+1} \end{bmatrix} &= \begin{bmatrix} {}^l\! \dot x_{k} \\ {}^l\! \dot y_{k} \\ {}^l\! \dot z_{k} \end{bmatrix} + \Delta t \left( \sum_{i=0}^{n_{c,k} - 1} \frac{{}^l\!f_{i,k}}{m} - \begin{bmatrix} 0 \\ 0 \\ g \end{bmatrix} \right) \\ -\begin{bmatrix} \omega_{{}^l\!x,k+1} \\ \omega_{{}^l\!y,k+1} \\ \omega_{{}^l\! z,k+1} \end{bmatrix} &= \begin{bmatrix} \omega_{{}^l\!x,k} \\ \omega_{{}^l\!y,k} \\ \omega_{{}^l\! z,k} \end{bmatrix} + \Delta t \left( {}^l\!\mathcal{I}^{-1}\sum_{i=0}^{n_{c,k} - 1} [{}^l\!r_{i,k} - {}^l\!C_{k}^\star]_\times \cdot {}^l\!f_{i,k} \right) -\end{align} - -In terms of constraints, friction cone conditions to avoid slipping are linearized to the first order: -\begin{equation} -\forall i \in [0, 3], \forall k \in [0, n_{steps}-1],~|f_{i,k}^x| \leq \mu ~ f_{i,k}^z \text{ and } |f_{i,k}^y| \leq \mu ~ f_{i,k}^z -\end{equation} - -An upper limit has to be set for contact forces to respect hardware limits (maximum torque of actuators). This limit is only applied to the $z$ component since it will also limit the force along $x$ and $y$ due to the friction cone contraints. -\begin{equation} -\forall i \in [0, 3], \forall k \in [0, n_{steps}-1],~f_{i,k}^z \leq f_{max} -\end{equation} - -The quadruped cannot pull on the ground, it can only push so the normal component of the contact forces has to be positive: -\begin{equation} -\forall i \in [0, 3], \forall k \in [0, n_{steps}-1], f_{i,k}^z \geq 0~N -\end{equation} - -To be sure that there is no slipping, we could impose a minimal non-zero vertical component of the contact forces because if it is close to 0 N the friction cone is small so on the real robot slipping could happen. In practise to due the way the MPC is currently programmed to disable a foot when it is in swing phase we set a constraint that its contact force is equal to 0 so it is not directly compatible with $\forall i \in [0, 3], \forall k \in [0, n_{steps}-1], f_{i,k}^z \geq f_{min}$. We would have to change more coefficients to temporarily disable this $f_{i,k}^z \geq f_{min}$ for feet in swing phase. - -This minimal non-zero vertical component of the contact forces is taken into account by the inverse dynamics block (TSID) so even if the output of the MPC contains a 0 N vertical component for a foot in contact it will be equal to $f_{min}$ after being processed by TSID. - - -\newpage -\section{MPC matrices for dynamics and constraints} - -\textbf{Goal:} create the matrices that are used by standard QP solvers. These solvers try to find a vector $\mathbb{X}$ that minimizes a cost function $\frac{1}{2}\mathbb{X}^T.P.\mathbb{X} + \mathbb{X}^T.Q$ under constraints $M.\mathbb{X} = N$ and $L.\mathbb{X} \leq K$. In this section the construction of matrices $M$, $N$, $L$ and $K$ is described. - -The evolution of the state vector of the robot over time can be described as follows: -\begin{equation} -x(k+1) = A(k) x(k) + B(k) f(k) + g -\end{equation} - -Matrices A et B depends on $k$ and $g = [0 ~ 0 ~ 0 ~ 0 ~ 0 ~ 0 ~ 0 ~ 0 ~ -9.81 \cdot \Delta t~ 0 ~ 0 ~ 0]^T$ - -The contact forces vector $f(k) = f_k$ always include the forces applied on the four feet even if some of them are not touching the ground. In that case we will set the problem in such a way that forces for such feet are not considered in the solving process. -\begin{align} -f_k &= [f_{0,k}^T ~~ f_{1,k}^T ~~ f_{2,k}^T ~~ f_{3,k}^T]^T \\ -\forall i \in [0, 3],~k\in[0, n_{steps}-1], ~f_{i, k} &= \begin{bmatrix} f^x_{i,k} \\ f^y_{i,k} \\ f^z_{i,k} \end{bmatrix} -\end{align} - -with $f^x_{i,k}$, $f^y_{i,k}$ and $f^z_{i,k}$ the components along the $x$, $y$ and $z$ axes of the solver frame for the $i$-th foothold at time step $k$. - -\textbf{Let's consider a case with only 3 time steps in the prediction horizon.} - -The goal of the MPC is to find contacts forces $f$ that should be applied to have the state vector $X$ of the robot as close as possible to $X^\star$. The QP solver outputs at the end of the optimization process the optimization vector $\mathbb{X}$ that minimizes the cost function locally (globally in the best case). The QP problem can be written in a simple way by putting both $f$ (the output of the MPC) and $\mathcal{X}_k = X_k - X_k^\star$ (quantity that should be minimized) in the optimization vector: -\begin{equation} -\mathbb{X} = [\mathcal{X}_1^T ~~ \mathcal{X}_2^T ~~ \mathcal{X}_3^T ~~ f_0^T ~~ f_1^T ~~ f_2^T ]^T -\end{equation} - - -Matrix $M$ is defined as follows: -\begin{equation} -M = \begin{bmatrix} --I_{12} & 0_{12} & 0_{12} & B_0 & 0_{12} & 0_{12} \\ -A_1 & -I_{12} & 0_{12} & 0_{12} & B_1 & 0_{12} \\ -0_{12} & A_2 & -I_{12} & 0_{12} & 0_{12} & B_2 \\ -0_{12} & 0_{12} & 0_{12} & E_0 & 0_{12} & 0_{12} \\ -0_{12} & 0_{12} & 0_{12} & 0_{12} & E_1 & 0_{12} \\ -0_{12} & 0_{12} & 0_{12} & 0_{12} & 0_{12} & E_2 \\ \end{bmatrix} -\end{equation} - -$A$, $B$ and $E$ have a size of 12 by 12. - -Matrix $N$ is defined as follows: -\begin{equation} -N = \begin{bmatrix} -g \\ -g \\ -g \\ 0_{12 \times 1} \\ 0_{12 \times 1} \\ 0_{12 \times 1} \end{bmatrix} + \begin{bmatrix} -A_0 X_0 \\ 0_{12 \times 1} \\ 0_{12 \times 1} \\ 0_{12 \times 1} \\ 0_{12 \times 1} \\ 0_{12 \times 1} \end{bmatrix} + \begin{bmatrix} I_{12} & 0_{12} & 0_{12} & 0_{12} & 0_{12} & 0_{12}\\ -A_1 & I_{12} & 0_{12} & 0_{12} & 0_{12} & 0_{12} \\ 0_{12} & -A_2 & I_{12} & 0_{12} & 0_{12} & 0_{12}\end{bmatrix} \cdot \begin{bmatrix} X_1^\star \\ X_2^\star \\ X_3^\star \\ 0_{12 \times 1} \\ 0_{12 \times 1} \\ 0_{12 \times 1} \end{bmatrix} -\end{equation} - -Matrix $A_k$ for time step $k$ is defined as follows: -\begin{equation} -A_k = \begin{bmatrix} -I_3 & 0_3 & \Delta t \cdot I_3 & 0_3 \\ -0_3 & I_3 & 0_3 & \Delta t \cdot I_3 \\ -0_3 & 0_3 & I_3 & 0_3 \\ -0_3 & 0_3 & 0_3 & I_3 -\end{bmatrix} -\end{equation} - -%with $R(\psi_k = \psi_0+k~dt~\dot \psi^\star)$ the 3 by 3 rotation matrix about the vertical axis. - -With the assumption that roll and pitch angles are small the inertia matrix of the robot in solver frame rotated according to the orientation of the robot at time step $k$ is: -\begin{equation} -{}^l\! \mathcal{I}_k = R_z(\Delta t \cdot k \cdot \omega_{{}^l\!z}^\star) \cdot {}^b\!\mathcal{I} -\end{equation} - -Matrix $B_k$ for time step $k$ is defined as follows: -\begin{equation} -B = \Delta t \cdot \begin{bmatrix} -0_3 & 0_3 & 0_3 & 0_3 \\ -0_3 & 0_3 & 0_3 & 0_3 \\ -I_3/m & I_3/m & I_3/m & I_3/m \\ -{}^l\!\mathcal{I}_k^{-1} \cdot [{}^l\! r_{0,k} - {}^l\! C_k^\star]_\times & {}^l\!\mathcal{I}_k^{-1} \cdot [{}^l\! r_{1,k} - {}^l\! C_k^\star]_\times & {}^l\!\mathcal{I}_k^{-1} \cdot [{}^l\! r_{2,k} - {}^l\! C_k^\star]_\times & {}^l\!\mathcal{I}_k^{-1} \cdot [{}^l\! r_{3,k} - {}^l\! C_k^\star]_\times -\end{bmatrix} -\end{equation} - -with $({}^l\!r_{i,k} - {}^l\! C_k^\star)$ the vector in local frame going from the desired position of the center of mass at time step $k$ to the position of the $i$-th foothold. $[r_{k,i} - {}^l\! C_k^\star]_\times$ is the associated skew-symmetric matrix. - -Matrix $E_k$ for time step $k$ is defined as follows: -\begin{equation} -E_k = \begin{bmatrix} -e_{0,k} & 0_3 & 0_3 & 0_3 \\ -0_3 & e_{1,k} & 0_3 & 0_3 \\ -0_3 & 0_3 & e_{2,k} & 0_3 \\ -0_3 & 0_3 & 0_3 & e_{3,k} -\end{bmatrix} -\end{equation} - -$e_{i,k} = 0_3$ if the $i$-th foot is touching the ground during time step $k$, $e_{i,k} = I_3$ otherwise. In fact, if $e_{i,k} = I_3$ then with $M.X = N$ we are setting the constraint that $f_{i,k} = [0 ~~ 0 ~~ 0]^T$ (no reaction force since the foot is not touching the ground). - -Matrix $L$ is defined as follows: -\begin{equation} -L = \begin{bmatrix} - 0_{20\times12} & 0_{20\times12} & 0_{20\times12} & F_\mu & 0_{20\times12} & 0_{20\times12} \\ - 0_{20\times12} & 0_{20\times12} & 0_{20\times12} & 0_{20\times12} & F_\mu & 0_{20\times12} \\ - 0_{20\times12} & 0_{20\times12} & 0_{20\times12} & 0_{20\times12} & 0_{20\times12} & F_\mu \end{bmatrix} -\end{equation} - -With: -\begin{equation} -F_\mu = \begin{bmatrix} - G & 0_{5\times3} & 0_{5\times3} & 0_{5\times3} \\ - 0_{5\times3} & G & 0_{5\times3} & 0_{5\times3} \\ - 0_{5\times3} & 0_{5\times3} & G & 0_{5\times3} \\ - 0_{5\times3} & 0_{5\times3} & 0_{5\times3} & G -\end{bmatrix} \text{ and } G = \begin{bmatrix} -1 & 0 & -\mu \\ --1 & 0 & -\mu \\ -0 & 1 & -\mu \\ -0 & -1 & -\mu \\ -0 & 0 & - 1 \\ -\end{bmatrix} -\end{equation} - -The $K$ matrix is defined as $K = 0_{60 \times 1}$. - -\section{MPC cost function} - - -QP solvers try to find a vector $\mathbb{X}$ that minimizes a cost function $\frac{1}{2}\mathbb{X}^T.P.\mathbb{X} + \mathbb{X}^T.Q$ under constraints $M.\mathbb{X} = N$ and $L.\mathbb{X} \leq K$. Matrices $P$ and $Q$ define the shape of the cost function. - -The goal of the MPC is to find which contact forces should be applied at contact points so that the predicted trajectory of the center of mass is as close as possible to the reference trajectory. With previous notation, that means we want to minimize $|X - X^\star|$. Function $|\cdot|$ is not directly available with a matrix product $\frac{1}{2}\mathbb{X}^T.P.\mathbb{X} + \mathbb{X}^T.Q$ so we can try to minimize $(X - X^\star)^2$ instead. Since: -\begin{equation} -\mathbb{X} = \begin{bmatrix} \mathcal{X}_1 \\ \vdots \\ \mathcal{X}_{n_{steps}} \\ f_0 \\ \vdots \\ f_{n_{steps}-1} \end{bmatrix} = \begin{bmatrix} X_1 - X_1^\star \\ \vdots \\ X_{n_{steps}} - X_{n_{steps}}^\star\\ f_0 \\ \vdots \\ f_{n_{steps}-1} \end{bmatrix} -\end{equation} - -then the upper left portion of $P$ can be diagonal: -\begin{equation} -P = \begin{bmatrix} -c_{X,1} & & 0 & * \\ - & \ddots & & * \\ -0 & & c_{X,n_{steps}} & * \\ -* & * & * & * -\end{bmatrix} -\end{equation} - -With $\forall k \in [1, n_{steps}],~ c_{X,k}$ being 12 by 12 diagonal matrices with coefficients $\geq 0$ the deviation from the reference trajectory is penalized by the cost function as it push the solver into minimizing the error $(X_k - X_k^\star)^2$. For safety reason, for energy consumption and for the actuators, it is better to keep the contact forces low if possible. That is why a small regularization term is added to slightly penalize the norm of contact forces. Since the $\sqrt{\cdot}$ function is not directly available in the matrix product of the cost function, we regularize the square of the norm instead ($\Vert f_k \Vert^2$). - -\begin{equation} -P = \begin{bmatrix} -c_{X,1} & & 0 & * & * & *\\ -& \ddots & & * & * & * \\ -0 & & c_{X,n_{steps}} & * & * & * \\ -* & * & * & c_{f,0} & & 0 \\ -* & * & * & & \ddots & \\ -* & * & * & 0 & & c_{f,n_{steps}-1} -\end{bmatrix} -\end{equation} - -With $\forall k \in [0, n_{steps}-1],~ c_{f,k}$ being 12 by 12 diagonal matrices with coefficients $\geq 0$. There is no cross-coupling between $\mathcal{X}$ and force components so the upper-right and lower-left parts of $P$ are zeros. - -As there is no focus on any part of the prediction horizon, all $c_{X,k}$ are equal, same of all $c_{f,k}$. Coefficient at position $[i,i]$ in $c_{X,k}$ weights the deviation of the $i$-th component of the state vector from the reference trajectory. Remember that components of the state vector are in this order: $[ {}^l\!x ~ {}^l\!y ~ {}^l\!z ~ {}^l\!\phi ~ {}^l\!\theta ~ {}^l\!\psi ~ {}^l\!\dot x ~ {}^l\!\dot y ~{}^l\! \dot z ~ \omega_{{}^l\!x} ~ \omega_{{}^l\!y} ~ \omega_{{}^l\! z} ]$. Coefficient at position $[i,i]$ in $c_{f,k}$ weights the $i$-th component of the force vector for regularization purpose. Remember that components of the force vector are in this order: $[ {}^l\!f_0^x ~ {}^l\!f_0^y ~ {}^l\!f_0^z ~ {}^l\!f_1^x ~ {}^l\!f_1^y ~ {}^l\!f_1^z ~ {}^l\!f_2^x ~ {}^l\!f_2^y ~ {}^l\!f_2^z ~ v {}^l\!f_3^x ~ {}^l\!f_3^y ~ {}^l\!f_3^z ]$. To regularize properly the norm of contact forces $\Vert f_{i,k} \Vert^2 = (f_{i,k}^{x})^2 + (f_{i,k}^{y})^2 + (f_{i,k}^{z})^2$ coefficients for the $x$, $y$ and $z$ components have to be equal: -\begin{equation} - \forall k \in [0, n_{steps}-1],~\forall i \in [0, 3],~ c_{f,k}[3i,3i] = c_{f,k}[3i+1,3i+1] = c_{f,k}[3i+2,3i+2] -\end{equation} - -If no leg is privileged (to mimic a wounded leg we would try to apply less force with it) then all coefficients on the diagonal of $c_{X,k}$ are equal and $\forall k \in [0, n_{steps}-1],~c_{X,k}=w_f I_{12}$ with $w_f \in \mathbb{R}^+$ - -Matrix $Q$ in $\mathbb{X}^T \cdot Q$ only contains zeroes since there is no reason to push $X_k - X_k^\star$ or $f_k$ into being as negative/positive as possible. For instance if a coefficient of $Q$ is positive then the solver will try to have the associated variable as negative as possible to have a high negative product between the coefficient and the variable since that minimizes the cost. - -In the 3 time steps example of the previous section $P$ has a size of 72 by 72 (12 x 3 lines/columns for $\mathcal{X}_{1,2,3}$ and 12 x 3 lines/columns for $f_{1,2,3}$) and $Q$ has a size size 72 by 1. - -The cost function during the optimization process is then: -\begin{equation} -cost(X - X^\star, f) = \sum_{k=1}^{n_{steps}} \left( \sum_{i=0}^{11} \left[ w_{X}^i (X_k^i - X_k^{i,\star})^2 \right] + w_f \sum_{i=0}^{3} \left[ (f_{i,k}^x)^2 + (f_{i,k}^y)^2 + (f_{i,k}^z)^2 \right] \right) -\end{equation} - - -%Matrix $P$ in the cost function $\frac{1}{2}\mathbb{X}^T.P.\mathbb{X} + \mathbb{X}^T.Q$ is diagonal. That way the first term of the cost function looks like $\sum_{k=1}^{3} c_{k,X} \cdot (X_1 - X_1^\star)^2 + \sum_{k=0}^{2} c_{k,f} \cdot f_k^2$ with $c_{k,X}$ and $c_{k,f}$ with size $(12, 1)$. With $c_{k,X} > 0$ it push the solver into minimizing the error $X_k - X_k^\star$ to the reference trajectory that we want to follow while $c_{k,f}$ are small positive coefficients that act as a regularization of the force to get a solution with a norm as low as possible for the reaction force. - - - -%\section*{Update of solver matrices} -% -%In the $M$ matrix: -%\begin{itemize} -%\item $A_k$ matrices are constant and all the same -%\item $[r_{k,i}]$ need to be updated at each iteration since the robot moves between each iteration -%\item $\mathcal{I}_k^{-1}$ need to be updated if the reference velocity vector is modified -%\item $E_{k,i}$ in the lower part of M need to be set to $I_3$ if the $j$-th foot was previously touching the ground and is not touching it anymore. And to $0_3$ if it was not touching the ground and is now touching it. -%\end{itemize} -% -%In the $N$ matrix: -%\begin{itemize} -% \item $X_0$ need to be updated at each iteration since the robot moves between each iteration -% \item $- g$ never changes -% \item $X_k^\star$ need to be updated if the reference velocity vector is modified -%\end{itemize} -% -%In the $L$ matrix: -%\begin{itemize} -% \item Columns of $F_\mu$ matrices have to be set to zero or set back to non-zero values depending on the states of the contacts (just like the columns of $B_k$ matrices) -%\end{itemize} -% -%The $K$ matrix never change and is always full of zeros. - -\section{Output of the MPC} - -The desired reaction forces that need to be applied (by TSID or the real robot) are stored in $f_0$. It contains the desired reaction forces in local frame so they will have to be brought back to the world frame that TSID is working in. - -The same applies for the next desired position of the robot that is stored in $\mathcal{X}_1$ and can be retrieved by adding $X_1^\star$ to $\mathcal{X}_1$. As the next position/orientation is expressed in local frame we would have to rotate them to be able to use them for the inverse dynamics. - -\section{Inverse dynamics} - -The goal of the inverse dynamics is to make the link between the high level control (MPC contact forces and desired position of footsteps) and the low level control (desired torques sent to the drivers of the actuators). To do that, we use Efficient Task Space Inverse Dynamics (TSID, \url{https://github.com/stack-of-tasks/tsid}). This library allows to perform task-orientated optimization-based inverse-dynamics control based on the rigid multi-body dynamics library Pinocchio. Unlike the MPC it does not consider a prediction horizon but only the current state of the robot and the current defined tasks. - -Currently four kind of tasks are being used: -\begin{itemize} - \item[$\bullet$] Contact tasks for feet in contact with the ground to inform the solver that these feet should not move and that they can be used to apply forces on the ground. - \item[$\bullet$] Force tasks to have the contact forces close to the desired contact forces outputted by the MPC. These tasks are associated with the contact tasks. - \item[$\bullet$] Tracking tasks for feet in swing phase to follow the 3D trajectory generated by the foot trajectory generator to land at the position desired by the footstep planner. - \item[$\bullet$] Posture task for all legs to get back to a default position if some degrees of freedom are not used. -\end{itemize} - -One instance of the first three task is initially created and assigned to each foot. Then during the gait these tasks are enabled or disabled depending on the state of the foot. In swing phase only the tracking task is active while in stance phase only contact and force tasks are enabled. There exists a single posture task which is always active and affect the whole body. - -A weight is assigned to each task to make it more or less important compared to the other ones. ``Contact + Force'' and 3D tracking are never active at the same time so they do not compete with each other. As the posture task is just intended to be use as a form of regularization, it should not interfere with the other tasks. Its weight is kept at least $10^{-2}$ times less than the others to mimic a hierarchical solver: the relative weight is so small that it does not impact the other tasks even if in practice all tasks are considered together during the solving process. - -If the $i$-th foot is in stance phase then the force reference of its force task is updated with the desired contact force $[f^x_{i,0} ~ f^y_{i,0} ~ f^z_{i,0}]$ outputted by the MPC. If the $i$-th foot is in swing phase then its tracking task is updated with the desired position $[x^\star ~ y^\star ~ z^\star]$, velocity $[\dot x^\star ~ \dot y^\star ~ \dot z^\star]$ and acceleration $[\ddot x^\star ~\ddot y^\star ~ \ddot z^\star]$ outputted by the foot trajectory generator associated with this foot. - -The inverse dynamics solver is first updated with the current state of the quadruped (position/orientation/velocity of the base and angular position/velocity of the joints). It then tries to find the accelerations (base+joints) and the contact forces that minimize the cost function (weighted sum of task errors) while respecting the constraints (contacts, dynamics equations, torque limits). Joint torques can be retrieved at the end of the optimization thanks to the accelerations and the contact forces. - -Retrieved torques are sent to the PyBullet simulator that makes the assumption that torques are perfectly followed by the actuators. On the real robot they would be sent to the drivers that would have to modulate the current sent to the actuators to get the desired torques. - - -\end{document} \ No newline at end of file diff --git a/scripts/LICENSE b/scripts/LICENSE deleted file mode 100644 index fa966dac..00000000 --- a/scripts/LICENSE +++ /dev/null @@ -1,25 +0,0 @@ -BSD 2-Clause License - -Copyright (c) 2020, paLeziart -All rights reserved. - -Redistribution and use in source and binary forms, with or without -modification, are permitted provided that the following conditions are met: - -1. Redistributions of source code must retain the above copyright notice, this - list of conditions and the following disclaimer. - -2. Redistributions in binary form must reproduce the above copyright notice, - this list of conditions and the following disclaimer in the documentation - and/or other materials provided with the distribution. - -THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" -AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE -IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE -DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE -FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL -DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR -SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER -CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, -OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE -OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. diff --git a/scripts/Logger.py b/scripts/Logger.py deleted file mode 100644 index 86048232..00000000 --- a/scripts/Logger.py +++ /dev/null @@ -1,944 +0,0 @@ -# coding: utf8 - -import numpy as np -#from matplotlib import pyplot as plt -import pybullet as pyb -import pinocchio as pin -# import scipy.stats as scipystats -from matplotlib import cm - - -class Logger: - """Logger object to store information about plenty of different quantities in the simulation - - Args: - k_max_loop (int): maximum number of iterations of the simulation - dt (float): time step of TSID - dt_mpc (float): time step of the MPC - k_mpc (int): number of tsid iterations for one iteration of the mpc - T_mpc (float): duration of mpc prediction horizon - type_MPC (int): 0 for OSQP MPC, 1, 2, 3 for Crocoddyl MPCs - """ - - def __init__(self, k_max_loop, dt, dt_mpc, k_mpc, T_mpc, type_MPC): - - # Max number of iterations of the main loop - self.k_max_loop = k_max_loop - - # Time step of TSID - self.dt = dt - - # Time step of MPC - self.dt_mpc = dt_mpc - - # Number of TSID steps for 1 step of the MPC - self.k_mpc = k_mpc - - # Which MPC solver you want to use - # True to have PA's MPC, to False to have Thomas's MPC - self.type_MPC = type_MPC - - """# Log state vector and reference state vector - self.log_state = np.zeros((12, k_max_loop)) - self.log_state_ref = np.zeros((12, k_max_loop)) - - # Log footholds position in world frame - self.log_footholds = np.zeros((4, k_max_loop, 2)) - self.log_footholds_w = np.zeros((4, k_max_loop, 2)) - - # Log a few predicted trajectories along time to see how it changes - self.log_predicted_traj = np.zeros((12, int((k_max_loop/20)), 60)) - self.log_predicted_fc = np.zeros((12, int((k_max_loop/20)), 60)) - - # Log contact forces - self.log_contact_forces = np.zeros((4, k_max_loop, 3))""" - - ### - ### - - # Store time range - self.t_range = np.array([k*dt for k in range(self.k_max_loop)]) - - # Store logging timestamps - self.tstamps = np.zeros(k_max_loop) - - # Store current and desired position, velocity and acceleration of feet over time - # Used in log_footsteps function - self.feet_pos = np.zeros((3, 4, k_max_loop)) - self.feet_vel = np.zeros((3, 4, k_max_loop)) - self.feet_acc = np.zeros((3, 4, k_max_loop)) - self.feet_pos_target = np.zeros((3, 4, k_max_loop)) - self.feet_vel_target = np.zeros((3, 4, k_max_loop)) - self.feet_acc_target = np.zeros((3, 4, k_max_loop)) - - # Store information about the state of the robot - self.RPY = np.zeros((3, k_max_loop)) # roll, pitch, yaw of the base in world frame - self.oC = np.zeros((3, k_max_loop)) #  position of the CoM in world frame - self.oV = np.zeros((3, k_max_loop)) #  linear velocity of the CoM in world frame - self.oW = np.zeros((3, k_max_loop)) # angular velocity of the CoM in world frame - self.lC = np.zeros((3, k_max_loop)) #  position of the CoM in local frame - self.lV = np.zeros((3, k_max_loop)) #  linear velocity of the CoM in local frame - self.lW = np.zeros((3, k_max_loop)) #  angular velocity of the CoM in local frame - self.state_ref = np.zeros((12, k_max_loop)) #  reference state vector - self.mot = np.zeros((12, k_max_loop)) #  angular position of actuators - self.Vmot = np.zeros((12, k_max_loop)) #  angular velocity of actuators - - # Position and velocity data in PyBullet simulation - self.lC_pyb = np.zeros((3, k_max_loop)) - self.RPY_pyb = np.zeros((3, k_max_loop)) - self.mot_pyb = np.zeros((12, k_max_loop)) - self.lV_pyb = np.zeros((3, k_max_loop)) - self.lW_pyb = np.zeros((3, k_max_loop)) - self.Vmot_pyb = np.zeros((12, k_max_loop)) - - # Store information about contact forces - self.forces_order = [0, 1, 2, 3] - self.forces_status = [1, 1, 1, 1] - self.forces_mpc = np.zeros((12, k_max_loop)) # output of MPC - self.forces_tsid = np.zeros((12, k_max_loop)) # output of TSID - self.forces_pyb = np.zeros((12, k_max_loop)) # forces applied in PyBullet - - # Store information about torques - self.torques_ff = np.zeros((12, k_max_loop)) - self.torques_pd = np.zeros((12, k_max_loop)) - self.torques_sent = np.zeros((12, k_max_loop)) - - # Store information about the cost function of the MPC - self.cost_components = np.zeros((13, k_max_loop)) - - # Store information about the predicted evolution of the optimization vector components - # Usefull to compare osqp & ddp solver - self.T = T_mpc - self.pred_trajectories = np.zeros((12, int(T_mpc/dt_mpc), int(k_max_loop/k_mpc))) - self.pred_forces = np.zeros((12, int(T_mpc/dt_mpc), int(k_max_loop/k_mpc))) - self.fsteps = np.zeros((20, 13, int(k_max_loop/k_mpc))) - self.xref = np.zeros((12, int(T_mpc/dt_mpc) + 1, int(k_max_loop/k_mpc))) - - # Store information about one of the tracking task - self.pos = np.zeros((12, k_max_loop)) - self.pos_ref = np.zeros((12, k_max_loop)) - self.pos_err = np.zeros((3, k_max_loop)) - self.vel = np.zeros((6, k_max_loop)) - self.vel_ref = np.zeros((6, k_max_loop)) - self.vel_err = np.zeros((3, k_max_loop)) - - # Store information about shoulder position - self.o_shoulders = np.zeros((3, 4,k_max_loop)) - - def log_footsteps(self, k, interface, tsid_controller): - """ Store current and desired position, velocity and acceleration of feet over time - """ - - self.feet_pos[:, :, k] = interface.o_feet - self.feet_vel[:, :, k] = interface.ov_feet - self.feet_acc[:, :, k] = interface.oa_feet - self.feet_pos_target[:, :, k] = tsid_controller.goals.copy() - self.feet_vel_target[:, :, k] = tsid_controller.vgoals.copy() - self.feet_acc_target[:, :, k] = tsid_controller.agoals.copy() - - # Shoulder position in world frame - self.o_shoulders[:, :, k] = interface.o_shoulders - - return 0 - - def plot_footsteps(self): - """ Plot current and desired position, velocity and acceleration of feet over time - """ - - # Target feet positions are only updated during swing phase so during the initial stance phase these - # positions are 0.0 for x, y, z even if it is not the initial feet positions - # For display purpose we set feet target positions to feet positions from the beginning of the simulation to - # the start of the first swing phase - # Instead of having 0.0 0.0 0.0 0.19 0.19 0.19 (step when the first swing phase start and the target position - # is updated) we have 0.19 0.19 0.19 0.19 0.19 0.19 (avoid the step on the graph) - for i in range(4): - index = next((idx for idx, val in np.ndenumerate( - self.feet_pos_target[0, i, :]) if ((not (val == 0.0)))), [-1])[0] - if index > 0: - for j in range(2): - self.feet_pos_target[j, i, :(index+1)] = self.feet_pos_target[j, i, index+1] - - index = [1, 5, 9, 2, 6, 10, 3, 7, 11, 4, 8, 12] - lgd_X = ["FL", "FR", "HL", "HR"] - lgd_Y = ["Pos X", "Pos Y", "Pos Z"] - plt.figure() - for i in range(12): - plt.subplot(3, 4, index[i]) - plt.plot(self.t_range, self.feet_pos[i % 3, np.int(i/3), :], color='b', linewidth=3, marker='') - plt.plot(self.t_range, self.feet_pos_target[i % 3, np.int(i/3), :], color='r', linewidth=3, marker='') - plt.legend([lgd_Y[i % 3] + " " + lgd_X[np.int(i/3)], lgd_Y[i % 3] + " " + lgd_X[np.int(i/3)]+" Ref"]) - plt.suptitle("Current and reference positions of feet (world frame)") - - index = [1, 5, 9, 2, 6, 10, 3, 7, 11, 4, 8, 12] - lgd_X = ["FL", "FR", "HL", "HR"] - lgd_Y = ["Vel X", "Vel Y", "Vel Z"] - plt.figure() - for i in range(12): - plt.subplot(3, 4, index[i]) - plt.plot(self.t_range, self.feet_vel[i % 3, np.int(i/3), :], color='b', linewidth=3, marker='') - plt.plot(self.t_range, self.feet_vel_target[i % 3, np.int(i/3), :], color='r', linewidth=3, marker='') - plt.legend([lgd_Y[i % 3] + " " + lgd_X[np.int(i/3)], lgd_Y[i % 3] + " " + lgd_X[np.int(i/3)]+" Ref"]) - plt.suptitle("Current and reference velocities of feet (world frame)") - - index = [1, 5, 9, 2, 6, 10, 3, 7, 11, 4, 8, 12] - lgd_X = ["FL", "FR", "HL", "HR"] - lgd_Y = ["Acc X", "Acc Y", "Acc Z"] - plt.figure() - for i in range(12): - plt.subplot(3, 4, index[i]) - plt.plot(self.t_range, self.feet_acc[i % 3, np.int(i/3), :], color='b', linewidth=3, marker='') - plt.plot(self.t_range, self.feet_acc_target[i % 3, np.int(i/3), :], color='r', linewidth=3, marker='') - plt.legend([lgd_Y[i % 3] + " " + lgd_X[np.int(i/3)], lgd_Y[i % 3] + " " + lgd_X[np.int(i/3)]+" Ref"]) - plt.suptitle("Current and reference accelerations of feet (world frame)") - - return 0 - - def log_state(self, k, pyb_sim, joystick, interface, mpc_wrapper, solo): - """ Store information about the state of the robot - """ - - self.RPY[:, k:(k+1)] = np.reshape(interface.RPY[:], (3, 1)) # roll, pitch, yaw of the base in world frame - self.oC[:, k:(k+1)] = np.reshape(interface.oC[:, 0], (3, 1)) #  position of the CoM in world frame - self.oV[:, k:(k+1)] = np.reshape(interface.oV[:, 0], (3, 1)) #  linear velocity of the CoM in world frame - self.oW[:, k] = interface.oW[:, 0] # angular velocity of the CoM in world frame - self.lC[:, k:(k+1)] = np.reshape(interface.lC[:, 0], (3, 1)) #  position of the CoM in local frame - self.lV[:, k:(k+1)] = np.reshape(interface.lV[:, 0], (3, 1)) #  linear velocity of the CoM in local frame - self.lW[:, k:(k+1)] = np.reshape(interface.lW[:, 0], (3, 1)) #  angular velocity of the CoM in local frame - self.mot[:, k:(k+1)] = interface.mot[:, 0:1] - self.Vmot[:, k:(k+1)] = interface.vmes12_base[6:, 0:1] - - # Get PyBullet velocity in base frame for Pinocchio - oRb = pin.Quaternion(pyb_sim.qmes12[3:7]).matrix() - vmes12_base = pyb_sim.vmes12.copy() - vmes12_base[0:3, 0:1] = oRb.transpose() @ vmes12_base[0:3, 0:1] - vmes12_base[3:6, 0:1] = oRb.transpose() @ vmes12_base[3:6, 0:1] - - # Get CoM position in PyBullet simulation - pin.centerOfMass(solo.model, solo.data, pyb_sim.qmes12, vmes12_base) - - self.RPY_pyb[:, k:(k+1)] = np.reshape(pin.rpy.matrixToRpy((pin.SE3(pin.Quaternion(pyb_sim.qmes12[3:7]), - np.array([0.0, 0.0, 0.0]))).rotation), - (3, 1)) - oMl = pin.SE3(pin.utils.rotate('z', self.RPY_pyb[2, k]), - np.array([pyb_sim.qmes12[0, 0], pyb_sim.qmes12[1, 0], interface.mean_feet_z])) - - # Store data about PyBullet simulation - self.lC_pyb[:, k:(k+1)] = np.reshape(oMl.inverse() * solo.data.com[0], (3, 1)) - # self.RPY_pyb[2, k:(k+1)] = 0.0 - self.mot_pyb[:, k:(k+1)] = pyb_sim.qmes12[7:, 0:1] - self.lV_pyb[:, k:(k+1)] = np.reshape(oMl.rotation.transpose() @ solo.data.vcom[0], (3, 1)) - self.lW_pyb[:, k:(k+1)] = np.reshape(oMl.rotation.transpose() @ pyb_sim.vmes12[3:6, 0:1], (3, 1)) - self.Vmot_pyb[:, k:(k+1)] = pyb_sim.vmes12[6:, 0:1] - - # Reference state vector in local frame - # Velocity control for x, y and yaw components (user input) - # Position control for z, roll and pitch components (hardcoded default values of h_ref, 0.0 and 0.0) - # if self.type_MPC: - # self.state_ref[0:6, k] = np.array([0.0, 0.0, mpc_wrapper.mpc.h_ref, 0.0, 0.0, 0.0]) - # else: - self.state_ref[0:6, k] = np.array([0.0, 0.0, 0.2027682, 0.0, 0.0, 0.0]) - self.state_ref[6:12, k] = joystick.v_ref[:, 0] - - return 0 - - def plot_state(self): - """ Plot information about the state of the robot - """ - - index = [1, 5, 9, 2, 6, 10, 3, 7, 11, 4, 8, 12] - lgd = ["Pos CoM X [m]", "Pos CoM Y [m]", "Pos CoM Z [m]", "Roll [deg]", "Pitch [deg]", "Yaw [deg]", - "Lin Vel CoM X [m/s]", "Lin Vel CoM Y [m/s]", "Lin Vel CoM Z [m/s]", "Ang Vel Roll [deg/s]", - "Ang Vel Pitch [deg/s]", "Ang Vel Yaw [deg/s]"] - plt.figure() - for i in range(12): - plt.subplot(3, 4, index[i]) - if i < 3: - plt.plot(self.t_range, self.lC[i, :], "b", linewidth=3) - plt.plot(self.t_range, self.lC_pyb[i, :], "g", linewidth=3) - elif i < 6: - plt.plot(self.t_range, (180/3.1415)*self.RPY[i-3, :], "b", linewidth=3) - plt.plot(self.t_range, (180/3.1415)*self.RPY_pyb[i-3, :], "g", linewidth=3) - elif i < 9: - plt.plot(self.t_range, self.lV[i-6, :], "b", linewidth=3) - plt.plot(self.t_range, self.lV_pyb[i-6, :], "g", linewidth=3) - else: - plt.plot(self.t_range, (180/3.1415)*self.lW[i-9, :], "b", linewidth=3) - plt.plot(self.t_range, (180/3.1415)*self.lW_pyb[i-9, :], "g", linewidth=3) - - if i in [2, 6, 7, 8]: - plt.plot(self.t_range, self.state_ref[i, :], "r", linewidth=3) - elif i in [3, 4, 9, 10, 11]: - plt.plot(self.t_range, (180/3.1415)*self.state_ref[i, :], "r", linewidth=3) - - plt.xlabel("Time [s]") - plt.ylabel(lgd[i]) - - plt.legend(["TSID", "Pyb", "Ref"]) - - if i < 2: - plt.ylim([-0.07, 0.07]) - elif i == 2: - plt.ylim([0.16, 0.24]) - elif i < 6: - plt.ylim([-10, 10]) - elif i == 6: - plt.ylim([-0.05, 0.7]) - elif i == 7: - plt.ylim([-0.1, 0.1]) - elif i == 8: - plt.ylim([-0.2, 0.2]) - else: - plt.ylim([-80.0, 80.0]) - - plt.suptitle("State of the robot in TSID Vs PyBullet Vs Reference (local frame)") - - index = [1, 5, 9, 2, 6, 10, 3, 7, 11, 4, 8, 12] - - lgd = ["DoF 1 FL", "DoF 2 FL", "DoF 3 FL", "DoF 1 FR", "DoF 2 FR", "DoF 3 FR", - "DoF 1 HL", "DoF 2 HL", "DoF 3 HL", "DoF 1 HR", "DoF 2 HR", "DoF 3 HR"] - plt.figure() - for i in range(12): - plt.subplot(3, 4, index[i]) - h1, = plt.plot(self.t_range, self.mot[i, :], color="b", linewidth=3) - h2, = plt.plot(self.t_range, self.mot_pyb[i, :], color="g", linewidth=3) - plt.legend([h1, h2], [lgd[i] + " TSID", lgd[i] + " Pyb"]) - plt.xlabel("Time [s]") - plt.ylabel("Angular position [rad]") - plt.suptitle("Angular positions of actuators in TSID and PyBullet") - - plt.figure() - for i in range(12): - plt.subplot(3, 4, index[i]) - h1, = plt.plot(self.t_range, self.Vmot[i, :], color="b", linewidth=3) - h2, = plt.plot(self.t_range, self.Vmot_pyb[i, :], color="g", linewidth=3) - plt.legend([h1, h2], [lgd[i] + " TSID", lgd[i] + " Pyb"]) - plt.xlabel("Time [s]") - plt.ylabel("Angular velocity [rad/s]") - plt.suptitle("Angular velocities of actuators in TSID and PyBullet") - - print_correlation = False - if not print_correlation: - return 0 - - R = np.zeros((12, 12)) - - plt.figure() - lgd = ["Pos CoM X [m]", "Pos CoM Y [m]", "Pos CoM Z [m]", - "Roll [rad]", "Pitch [rad]", "Yaw [rad]", - "Vel CoM X [m]", "Vel CoM Y [m]", "Vel CoM Z [m]", - "Ang Vel Roll", "Ang Vel Pitch", "Ang Vel Yaw"] - for i in range(12): - for j in range(12): - plt.subplot(12, 12, (11-i) * 12 + j + 1) - if i < 3: - x1 = self.lC[i, :] - x2 = self.lC_pyb[i, :] - if i == 2: - x1[0] = x1[1] - elif i < 6: - x1 = self.RPY[i-3, :] - x2 = self.RPY_pyb[i-3, :] - elif i < 9: - x1 = self.lV[i-6, :] - x2 = self.lV_pyb[i-6, :] - else: - x1 = self.lW[i-9, :] - x2 = self.lW_pyb[i-9, :] - if j < 3: - y1 = self.lC[j, :] - y2 = self.lC_pyb[j, :] - if j == 2: - y1[0] = y1[1] - elif j < 6: - y1 = self.RPY[j-3, :] - y2 = self.RPY_pyb[j-3, :] - elif j < 9: - y1 = self.lV[j-6, :] - y2 = self.lV_pyb[j-6, :] - else: - y1 = self.lW[j-9, :] - y2 = self.lW_pyb[j-9, :] - - plt.plot(y1, x1, color="b", linestyle='', marker='*', markersize=6) - plt.tick_params( - axis='both', # changes apply to the x-axis - which='both', # both major and minor ticks are affected - bottom=False, # ticks along the bottom edge are off - left=False, # ticks along the top edge are off - labelbottom=False, # labels along the bottom edge are off - labelleft=False) - if i == 0: - plt.xlabel(lgd[j]) - if j == 0: - plt.ylabel(lgd[i]) - - # slope, intercept, r_value, p_value, std_err = scipystats.linregress(x1, y1) - - R[i, j] = r_value - plt.suptitle("Correlation of state variables") - - cmap = cm.get_cmap('gist_heat', 256) - fig = plt.figure() - ax = fig.gca() - psm = ax.pcolormesh(R, cmap=cmap, rasterized=True, vmin=0, vmax=1) - fig.colorbar(psm, ax=ax) - plt.suptitle("R coefficient of a first order regression") - - return 0 - - def getContactPoint(self, contactPoints): - """ Sort contacts points as there should be only one contact per foot - and sometimes PyBullet detect several of them. There is one contact - with a non zero force and the others have a zero contact force - """ - - indexes = [] - for i in range(0, len(contactPoints)): - # There may be several contact points for each foot but only one of them as a non zero normal force - if (contactPoints[i][9] != 0): - indexes.append(i) - - if len(indexes) > 0: - # Return contact points - return [contactPoints[i] for i in indexes] - else: - # If it returns 0 then it means there is no contact point with a non zero normal force (should not happen) - return [0] - - def log_forces(self, k, interface, tsid_controller, robotId, planeId): - """ Store information about contact forces - """ - - """if (k > 0) and (k % 20 == 0): - - # Index of the first empty line - index = next((idx for idx, val in np.ndenumerate(fstep_planner.gait[:, 0]) if val == 0.0), 0.0)[0] - - # Change of state (+1 if start of stance phase, -1 if start of swing phase, 0 if no state change) - if not np.array_equal(fstep_planner.gait[0, 1:], fstep_planner.gait[index-1, 1:]): - self.forces_status = fstep_planner.gait[0, 1:] - fstep_planner.gait[index-1, 1:] - - # Update contact forces order - for i in range(4): - if self.forces_status[i] == 1: - self.forces_order.append(i) - elif self.forces_status[i] == -1: - self.forces_order.remove(i) - - print(self.forces_status) - deb = 1 """ - - # Contact forces desired by MPC (transformed into world frame) - for f in range(4): - self.forces_mpc[3*f:(3*(f+1)), k:(k+1)] = np.reshape((interface.oMl.rotation @ - tsid_controller.f_applied[3*f:3*(f+1)]).T, (3, 1)) - - # Contact forces desired by TSID (world frame) - for i, j in enumerate(tsid_controller.contacts_order): - self.forces_tsid[(3*j):(3*(j+1)), k:(k+1)] = np.reshape(tsid_controller.fc[(3*i):(3*(i+1))], (3, 1)) - - # Contact forces applied in PyBullet - contactPoints_FL = pyb.getContactPoints(robotId, planeId, linkIndexA=3) # Front left foot - contactPoints_FR = pyb.getContactPoints(robotId, planeId, linkIndexA=7) # Front right foot - contactPoints_HL = pyb.getContactPoints(robotId, planeId, linkIndexA=11) # Hind left foot - contactPoints_HR = pyb.getContactPoints(robotId, planeId, linkIndexA=15) # Hind right foot - - # Sort contacts points to get only one contact per foot - contactPoints = [] - contactPoints += self.getContactPoint(contactPoints_FL) - contactPoints += self.getContactPoint(contactPoints_FR) - contactPoints += self.getContactPoint(contactPoints_HL) - contactPoints += self.getContactPoint(contactPoints_HR) - - # Display debug lines for contact forces visualization - f_tmps = np.zeros((3, 4)) - f_tmp = [0.0] * 3 - for contact in contactPoints: - if not isinstance(contact, int): # type(contact) != type(0): - start = [contact[6][0], contact[6][1], contact[6][2]+0.04] - end = [contact[6][0], contact[6][1], contact[6][2]+0.04] - K = 0.02 - for i_direction in range(0, 3): - f_tmp[i_direction] = (contact[9] * contact[7][i_direction] + contact[10] * - contact[11][i_direction] + contact[12] * contact[13][i_direction]) - end[i_direction] += K * f_tmp[i_direction] - - """if contact[3] < 10: - print("Link ", contact[3], "| Contact force: (", f_tmp[0], ", ", f_tmp[1], ", ", f_tmp[2], ")") - else: - print("Link ", contact[3], "| Contact force: (", f_tmp[0], ", ", f_tmp[1], ", ", f_tmp[2], ")")""" - - f_tmps[:, int(contact[3]/4)] += np.array(f_tmp) - - for i in range(4): - self.forces_pyb[(3*i):(3*(i+1)), k] = - f_tmps[:, i] - - return 0 - - def plot_forces(self): - """ Plot information about contact forces - """ - - index = [1, 5, 9, 2, 6, 10, 3, 7, 11, 4, 8, 12] - lgd1 = ["Ctct force X", "Ctct force Y", "Ctct force Z"] - lgd2 = ["FL", "FR", "HL", "HR"] - plt.figure() - for i in range(12): - plt.subplot(3, 4, index[i]) - - h1, = plt.plot(self.t_range, self.forces_mpc[i, :], "r", linewidth=5) - h2, = plt.plot(self.t_range, self.forces_tsid[i, :], "b", linewidth=3) - h3, = plt.plot(self.t_range, self.forces_pyb[i, :], "g", linewidth=3, linestyle="--") - - plt.xlabel("Time [s]") - plt.ylabel(lgd1[i % 3]+" "+lgd2[int(i/3)]) - - plt.legend([h1, h2, h3], [lgd1[i % 3]+" "+lgd2[int(i/3)], lgd1[i % 3]+" "+lgd2[int(i/3)], - lgd1[i % 3]+" "+lgd2[int(i/3)]]) - - if (i % 3) == 2: - plt.ylim([-1.0, 20.0]) - else: - plt.ylim([-8.0, 8.0]) - - plt.suptitle("MPC, TSID and PyBullet contact forces (world frame)") - - plt.figure() - plt.plot(self.t_range, np.sum(self.forces_mpc[2::3, :], axis=0), "r", linewidth=5) - plt.plot(self.t_range, np.sum(self.forces_tsid[2::3, :], axis=0), "b", linewidth=3) - plt.plot(self.t_range, np.sum(self.forces_pyb[2::3, :], axis=0), "g", linewidth=3, linestyle="--") - plt.plot(self.t_range, 2.5*9.81*np.ones((len(self.t_range))), "k", linewidth=5) - plt.suptitle("Total vertical contact force considering all contacts") - - index = [1, 2, 3, 4] - lgd = ["FL", "FR", "HL", "HR"] - plt.figure() - for i in range(4): - plt.subplot(2, 2, index[i]) - - ctct_status = np.sum(np.abs(self.forces_mpc[(3*i):(3*(i+1)), :]), axis=0) > 0.05 - ctct_mismatch = np.logical_xor((np.sum(np.abs(self.forces_tsid[(3*i):(3*(i+1)), :]), axis=0) != 0), - (np.sum(np.abs(self.forces_pyb[(3*i):(3*(i+1)), :]), axis=0) != 0)) - - plt.plot(self.t_range, ctct_status, "r", linewidth=3) - plt.plot(self.t_range, ctct_mismatch, "k", linewidth=3) - - plt.xlabel("Time [s]") - plt.ylabel("Contact status mismatch (True/False)") - plt.legend(["MPC Contact Status " + lgd[i], "Mismatch " + lgd[i]]) - plt.suptitle("Contact status mismatch between MPC/TSID and PyBullet") - - return 0 - - def log_torques(self, k, tsid_controller): - """ Store information about torques - """ - - self.torques_ff[:, k:(k+1)] = np.reshape(tsid_controller.tau_ff, (12, 1)) - self.torques_pd[:, k:(k+1)] = np.reshape(tsid_controller.tau_pd, (12, 1)) - self.torques_sent[:, k:(k+1)] = np.reshape(tsid_controller.torques12, (12, 1)) - - return 0 - - def plot_torques(self): - """ Plot information about torques - """ - - index = [1, 5, 9, 2, 6, 10, 3, 7, 11, 4, 8, 12] - - lgd = ["DoF 1 FL", "DoF 2 FL", "DoF 3 FL", "DoF 1 FR", "DoF 2 FR", "DoF 3 FR", - "DoF 1 HL", "DoF 2 HL", "DoF 3 HL", "DoF 1 HR", "DoF 2 HR", "DoF 3 HR"] - plt.figure() - for i in range(12): - plt.subplot(3, 4, index[i]) - h1, = plt.plot(self.t_range, self.torques_ff[i, :], color="b", linewidth=3) - h2, = plt.plot(self.t_range, self.torques_pd[i, :], color="r", linewidth=3) - h3, = plt.plot(self.t_range, self.torques_sent[i, :], color="g", linewidth=3) - plt.legend([h1, h2, h3], [lgd[i] + " FF", lgd[i] + " PD", lgd[i]+" Sent"]) - plt.xlabel("Time [s]") - plt.ylabel("Torque [Nm]") - plt.suptitle("Feedforward, PD and sent torques (output of PD+ with saturation)") - - return 0 - - def log_cost_function(self, k, mpc_wrapper): - """ Store information about the cost function of the mpc - """ - - # Cost of each component of the cost function over the prediction horizon (state vector and contact forces) - cost = (np.diag(mpc_wrapper.mpc.x) @ np.diag(mpc_wrapper.mpc.P.data) - ) @ np.array([mpc_wrapper.mpc.x]).transpose() - - # Sum components of the state vector - for i in range(12): - self.cost_components[i, k:(k+1)] = np.sum(cost[i:(12*mpc_wrapper.mpc.n_steps):12]) - - # Sum components of the contact forces - self.cost_components[12, k:(k+1)] = np.sum(cost[(12*mpc_wrapper.mpc.n_steps):]) - - """if k % 50 == 0: - print(np.sum(np.power(mpc_wrapper.solver.mpc.x[6:(12*mpc_wrapper.solver.mpc.n_steps):12], 2))) - - absc = np.array([i for i in range(16)]) - if k == 0: - plt.figure() - if k % 100 == 0: - plt.plot(absc+k, np.power(mpc_wrapper.solver.mpc.x[6:(12*mpc_wrapper.solver.mpc.n_steps):12], 2)) - if k == 5999 == 0: - plt.show(block=True)""" - return 0 - - def plot_cost_function(self): - """ Plot information about the cost function of the mpc - """ - - lgd = ["$X$", "$Y$", "$Z$", "$\phi$", "$\\theta$", "$\psi$", "$\dot X$", "$\dot Y$", "$\dot Z$", - "$\dot \phi$", "$\dot \\theta$", "$\dot \psi$", "$f$", "Total"] - plt.figure() - hs = [] - for i in range(14): - if i < 10: - h, = plt.plot(self.t_range, self.cost_components[i, :], linewidth=2) - elif i <= 12: - h, = plt.plot(self.t_range, self.cost_components[i, :], linewidth=2, linestyle="--") - else: - h, = plt.plot(self.t_range, np.sum(self.cost_components, axis=0), linewidth=2, linestyle="--") - hs.append(h) - plt.xlabel("Time [s]") - plt.ylabel("Cost") - plt.legend(hs, lgd) - plt.title("Contribution of each component in the cost function") - - return 0 - - def log_predicted_trajectories(self, k, mpc_wrapper): - """ Store information about the predicted evolution of the optimization vector components - """ - if self.type_MPC == 0: - self.pred_trajectories[:, :, int(k/self.k_mpc)] = mpc_wrapper.mpc.x_robot - self.pred_forces[:, :, int(k/self.k_mpc)] = mpc_wrapper.mpc.x[mpc_wrapper.mpc.xref.shape[0]*(mpc_wrapper.mpc.xref.shape[1]-1):].reshape((mpc_wrapper.mpc.xref.shape[0], - mpc_wrapper.mpc.xref.shape[1]-1), - order='F') - else: - - self.pred_trajectories[:, :, int(k/self.k_mpc)] = mpc_wrapper.mpc.get_xrobot() - self.pred_forces[:, :, int(k/self.k_mpc)] = mpc_wrapper.mpc.get_fpredicted() - - return 0 - - def log_fstep_planner(self, k, fstep_planner): - - self.fsteps[:, :, int(k/self.k_mpc)] = fstep_planner.fsteps - self.xref[:, :, int(k/self.k_mpc)] = fstep_planner.xref - - return 0 - - def plot_fstep_planner(self): - """ Plot information about the footstep planner - """ - - self.fsteps[np.isnan(self.fsteps)] = 0.0 - index = [1, 3, 2, 4] - lgd = ["X FL", "Y FR", "X FR", "Y FR"] - plt.figure() - for i in range(4): - plt.subplot(2, 2, index[i]) - if i < 2: - plt.plot(self.t_range[::int(self.dt_mpc/self.dt)], - self.fsteps[0, i+1, :], color='k', linewidth=2, marker='x') - else: - plt.plot(self.t_range[::int(self.dt_mpc/self.dt)], - self.fsteps[0, i-2+3+1, :], color='k', linewidth=2, marker='x') - - plt.xlabel("Time [s]") - plt.ylabel(lgd[i]) - plt.suptitle("Foostep planner output for FL and FR feet") - - def plot_predicted_trajectories(self): - """ Plot information about the predicted evolution of the optimization vector components - """ - - t_pred = np.array([(k)*self.dt_mpc for k in range(np.int(self.T/self.dt_mpc))]) - - #index = [1, 5, 9, 2, 6, 10, 3, 7, 11, 4, 8, 12] - index = [1, 4, 7, 2, 5, 8, 3, 6, 9] - - lgd = ["Position Z", "Position Roll", "Position Pitch", "Linear vel X", "Linear vel Y", "Linear vel Z", - "Angular vel Roll", "Angular vel Pitch", "Angular vel Yaw"] - plt.figure() - for i, o in enumerate([2, 3, 4, 6, 7, 8, 9, 10, 11]): - plt.subplot(3, 3, index[i]) - for j in range(self.pred_trajectories.shape[2]): - if (j*self.k_mpc > self.k_max_loop): - break - # if (j % 1) == 0: - #h, = plt.plot(t_pred[0:15] + j*self.dt_mpc, self.pred_trajectories[o, 0:15, j], linewidth=2, marker='x') - h, = plt.plot(t_pred[0:16] + j*self.dt_mpc, np.hstack(([self.lW[1, j*self.k_mpc]], - self.pred_trajectories[o, 0:15, j])), linewidth=2, marker='x') - #h, = plt.plot(self.t_range[::20], self.state_ref[i, ::20], "r", linewidth=3, marker='*') - if i == 0: - plt.plot(self.t_range[::20], self.lC[2, ::20], "r", linewidth=2) # , marker='o', linestyle="--") - elif i <= 2: - plt.plot(self.t_range[::20], self.RPY[i-1, ::20], "r", linewidth=2) # , marker='o', linestyle="--") - elif i <= 5: - plt.plot(self.t_range[::20], self.lV[i-3, ::20], "r", linewidth=2) # , marker='o', linestyle="--") - else: - plt.plot(self.t_range[::20], self.lW[i-6, ::20], "r", linewidth=2) # , marker='o', linestyle="--") - plt.ylabel(lgd[i]) - plt.suptitle("Predicted trajectories (local frame)") - - return 0 - - def log_tracking_foot(self, k, tsid_controller, solo): - """ Store information about one of the foot tracking task - """ - - self.pos[:, k:(k+1)] = np.reshape(tsid_controller.feetTask[1].position, (12, 1)) - self.pos_ref[:, k:(k+1)] = np.reshape(tsid_controller.feetTask[1].position_ref, (12, 1)) - self.pos_err[:, k:(k+1)] = np.reshape(tsid_controller.feetTask[1].position_error, (3, 1)) - self.vel[0:3, k:(k+1)] = np.reshape((solo.data.oMi[solo.model.frames[18].parent].act(solo.model.frames[18].placement) - ).rotation @ tsid_controller.feetTask[1].velocity[0:3], (3, 1)) - self.vel[3:6, k:(k+1)] = np.reshape((solo.data.oMi[solo.model.frames[18].parent].act(solo.model.frames[18].placement) - ).rotation @ tsid_controller.feetTask[1].velocity[3:6], (3, 1)) - self.vel_ref[:, k:(k+1)] = np.reshape(tsid_controller.feetTask[1].velocity_ref, (6, 1)) - self.vel_err[:, k:(k+1)] = np.reshape(tsid_controller.feetTask[1].velocity_error, (3, 1)) - - return 0 - - def plot_tracking_foot(self): - """ Plot information about one of the foot tracking task - """ - - index = [1, 3, 5, 2, 4, 6] - lgd = ["X", "Y", "Z", "$\dot X$", "$\dot Y$", "$\dot Z$"] - plt.figure() - for i in range(6): - plt.subplot(3, 2, index[i]) - if i < 3: - plt.plot(self.pos[i, :], color='r', linewidth=2, marker='x') - plt.plot(self.pos_ref[i, :], color='g', linewidth=2, marker='x') - plt.plot(self.feet_pos_target[i, 1, :], color='b', linewidth=2, marker='x') - #plt.plot(self.pos_err[i, :], color='b', linewidth=2, marker='x') - plt.legend(["Pos", "Pos ref", "Pos target"]) - else: - plt.plot(self.vel[i-3, :], color='r', linewidth=2, marker='x') - plt.plot(self.vel_ref[i-3, :], color='g', linewidth=2, marker='x') - #plt.plot(self.vel_err[i-3, :], color='b', linewidth=2, marker='x') - plt.plot(self.feet_vel_target[i-3, 1, :], color='b', linewidth=2, marker='x') - plt.legend(["Vel", "Vel ref", "Vel target"]) - - plt.ylabel(lgd[i]) - plt.suptitle("Tracking FR foot") - - return 0 - - def call_log_functions(self, k, pyb_sim, joystick, fstep_planner, interface, mpc_wrapper, tsid_controller, enable_multiprocessing, robotId, planeId, solo): - """ Call logging functions of the Logger class - """ - - # Store current and desired position, velocity and acceleration of feet over time - self.log_footsteps(k, interface, tsid_controller) - - # Store information about the state of the robot - if not enable_multiprocessing: - self.log_state(k, pyb_sim, joystick, interface, mpc_wrapper, solo) - - # Store information about contact forces - self.log_forces(k, interface, tsid_controller, robotId, planeId) - - # Store information about torques - self.log_torques(k, tsid_controller) - - # Store information about the cost function - """if (self.type_MPC == 0) and not enable_multiprocessing: - self.log_cost_function(k, mpc_wrapper)""" - - # Store information about the predicted evolution of the optimization vector components - if not enable_multiprocessing and ((k % self.k_mpc) == 0): - # self.log_predicted_trajectories(k, mpc_wrapper) - self.log_fstep_planner(k, fstep_planner) - - # Store information about one of the foot tracking task - self.log_tracking_foot(k, tsid_controller, solo) - - return 0 - - def plot_graphs(self, enable_multiprocessing, show_block=True): - - # Plot current and desired position, velocity and acceleration of feet over time - self.plot_footsteps() - - # Plot information about the state of the robot - if not enable_multiprocessing: - self.plot_state() - - # Plot information about the contact forces - self.plot_forces() - - # Plot information about the torques - self.plot_torques() - - # Plot information about the state of the robot - # Cost not comparable between the two solvers - if (self.type_MPC == 0) and not enable_multiprocessing: - self.plot_cost_function() - - # Plot information about the predicted evolution of the optimization vector components - # if not enable_multiprocessing: - # self.plot_predicted_trajectories() - - # Plot information about one of the foot tracking task - # self.plot_tracking_foot() - - # Display graphs - plt.show(block=show_block) - - """# Evolution of the position and orientation of the robot over time - plt.figure() - ylabels = ["Position X", "Position Y", "Position Z", - "Orientation Roll", "Orientation Pitch", "Orientation Yaw"] - for i, j in enumerate([1, 3, 5, 2, 4, 6]): - plt.subplot(3, 2, j) - plt.plot(log_t, self.log_state[i, :], "b", linewidth=2) - if i not in [0, 1, 6]: - plt.plot(log_t, self.log_state_ref[i, :], "r", linewidth=2) - plt.legend(["Robot", "Reference"]) - plt.xlabel("Time [s]") - plt.ylabel(ylabels[i]) - - # Evolution of the linear and angular velocities of the robot over time - plt.figure() - ylabels = ["Linear vel X", "Linear vel Y", "Linear vel Z", - "Angular vel Roll", "Angular vel Pitch", "Angular vel Yaw"] - for i, j in enumerate([1, 3, 5, 2, 4, 6]): - plt.subplot(3, 2, j) - plt.plot(log_t, self.log_state[i+6, :], "b", linewidth=2) - plt.plot(log_t, self.log_state_ref[i+6, :], "r", linewidth=2) - plt.legend(["Robot", "Reference"]) - plt.xlabel("Time [s]") - plt.ylabel(ylabels[i]) - - # Evolution of the position of the robot in world frame (X, Y) graph - plt.figure() - plt.plot(self.log_state[0, :], self.log_state[1, :], "b", linewidth=2) - plt.plot(self.log_state_ref[0, :], self.log_state_ref[1, :], "r", linewidth=2) - for i_foot in range(4): - plt.plot(self.log_footholds_w[i_foot, :, 0], - self.log_footholds_w[i_foot, :, 1], linestyle=None, marker="*") - plt.legend(["Robot", "Reference"]) - plt.xlabel("Position X [m]") - plt.ylabel("Position Y [m]") - - # Evolution of the position of footholds over time - plt.figure() - for i in range(4): - plt.subplot(4, 2, 2*i+1) - plt.plot(log_t, self.log_footholds[i, :, 0], linewidth=2) - plt.xlabel("Time [s]") - plt.ylabel("Position X [m]") - plt.subplot(4, 2, 2*i+2) - plt.plot(log_t, self.log_footholds[i, :, 1], linewidth=2) - plt.xlabel("Time [s]") - plt.ylabel("Position Y [m]") - - # Evolution of predicted trajectory over time - log_t_pred = np.array([k*dt for k in range(self.log_predicted_traj.shape[2])]) - - plt.figure() - plt.subplot(3, 2, 1) - c = [[i/(self.log_predicted_traj.shape[1]+5), 0.0, i/(self.log_predicted_traj.shape[1]+5)] - for i in range(self.log_predicted_traj.shape[1])] - for i in range(self.log_predicted_traj.shape[1]): - plt.plot(log_t_pred+i*dt, self.log_predicted_traj[0, i, :], "b", linewidth=2, color=c[i]) - plt.plot(np.array([k*dt for k in range(self.log_predicted_traj.shape[1])]), - self.log_predicted_traj[0, :, 0], linestyle=None, marker='x', color="r", linewidth=1) - plt.xlabel("Time [s]") - plt.title("Predicted trajectory along X [m]") - plt.legend(["Robot"]) - plt.subplot(3, 2, 3) - for i in range(self.log_predicted_traj.shape[1]): - plt.plot(log_t_pred+i*dt, self.log_predicted_traj[1, i, :], "b", linewidth=2, color=c[i]) - plt.plot(np.array([k*dt for k in range(self.log_predicted_traj.shape[1])]), - self.log_predicted_traj[1, :, 0], linestyle=None, marker='x', color="r", linewidth=1) - plt.xlabel("Time [s]") - plt.title("Predicted trajectory along Y [m]") - plt.legend(["Robot"]) - plt.subplot(3, 2, 5) - for i in range(self.log_predicted_traj.shape[1]): - plt.plot(log_t_pred+i*dt, self.log_predicted_traj[2, i, :], "b", linewidth=2, color=c[i]) - plt.plot(np.array([k*dt for k in range(self.log_predicted_traj.shape[1])]), - self.log_predicted_traj[2, :, 0], linestyle=None, marker='x', color="r", linewidth=1) - plt.xlabel("Time [s]") - plt.title("Predicted trajectory along Z [m]") - plt.legend(["Robot"]) - plt.subplot(3, 2, 2) - for i in range(self.log_predicted_traj.shape[1]): - plt.plot(log_t_pred+i*dt, self.log_predicted_traj[3, i, :], "b", linewidth=2, color=c[i]) - plt.plot(np.array([k*dt for k in range(self.log_predicted_traj.shape[1])]), - self.log_predicted_traj[3, :, 0], linestyle=None, marker='x', color="r", linewidth=1) - plt.xlabel("Time [s]") - plt.title("Predicted trajectory in Roll [rad/s]") - plt.legend(["Robot"]) - plt.subplot(3, 2, 4) - for i in range(self.log_predicted_traj.shape[1]): - plt.plot(log_t_pred+i*dt, self.log_predicted_traj[4, i, :], "b", linewidth=2, color=c[i]) - plt.plot(np.array([k*dt for k in range(self.log_predicted_traj.shape[1])]), - self.log_predicted_traj[4, :, 0], linestyle=None, marker='x', color="r", linewidth=1) - plt.xlabel("Time [s]") - plt.title("Predicted trajectory in Pitch [rad/s]") - plt.legend(["Robot"]) - plt.subplot(3, 2, 6) - for i in range(self.log_predicted_traj.shape[1]): - plt.plot(log_t_pred+i*dt, self.log_predicted_traj[5, i, :], "b", linewidth=2, color=c[i]) - plt.plot(np.array([k*dt for k in range(self.log_predicted_traj.shape[1])]), - self.log_predicted_traj[5, :, 0], linestyle=None, marker='x', color="r", linewidth=1) - plt.xlabel("Time [s]") - plt.title("Predicted trajectory in Yaw [rad/s]") - plt.legend(["Robot"]) - - # Plot desired contact forces - plt.figure() - c = ["r", "g", "b", "rebeccapurple"] - legends = ["FL", "FR", "HL", "HR"] - for i in range(4): - plt.subplot(3, 4, i+1) - plt.plot(log_t, self.log_contact_forces[i, :, 0], color="r", linewidth=3) - if mycontroller is not None: - plt.plot(log_t, mycontroller.c_forces[i, :, 0], color="b", linewidth=2) - tmp = np.zeros((k_max_loop,)) - for k in range(np.floor(k_max_loop/(0.3/0.005)+1).astype(int)): - plt.plot([k*0.3, k*0.3], [np.min(self.log_contact_forces[i, :, 0]), - np.max(self.log_contact_forces[i, :, 0])], "grey", linewidth=1, linestyle="--") - plt.xlabel("Time [s]") - plt.ylabel("Contact force along X [N]") - plt.legend([legends[i] + "_MPC", legends[i] + "_TSID"]) - - for i in range(4): - plt.subplot(3, 4, i+5) - plt.plot(log_t, self.log_contact_forces[i, :, 1], color="r", linewidth=3) - if mycontroller is not None: - plt.plot(log_t, mycontroller.c_forces[i, :, 1], color="b", linewidth=2) - tmp = np.zeros((k_max_loop,)) - for k in range(np.floor(k_max_loop/(0.3/0.005)+1).astype(int)): - plt.plot([k*0.3, k*0.3], [np.min(self.log_contact_forces[i, :, 1]), - np.max(self.log_contact_forces[i, :, 1])], "grey", linewidth=1, linestyle="--") - plt.xlabel("Time [s]") - plt.ylabel("Contact force along Y [N]") - plt.legend([legends[i] + "_MPC", legends[i] + "_TSID"]) - - for i in range(4): - plt.subplot(3, 4, i+9) - plt.plot(log_t, self.log_contact_forces[i, :, 2], color="r", linewidth=3) - if mycontroller is not None: - plt.plot(log_t, mycontroller.c_forces[i, :, 2], color="b", linewidth=2) - tmp = np.zeros((k_max_loop,)) - for k in range(np.floor(k_max_loop/(0.3/0.005)+1).astype(int)): - plt.plot([k*0.3, k*0.3], [np.min(self.log_contact_forces[i, :, 2]), - np.max(self.log_contact_forces[i, :, 2])], "grey", linewidth=1, linestyle="--") - plt.xlabel("Time [s]") - plt.ylabel("Contact force along Z [N]") - plt.legend([legends[i] + "_MPC", legends[i] + "_TSID"]) - - plt.show(block=False)""" - - return 0 diff --git a/scripts/MPC_Wrapper.py b/scripts/MPC_Wrapper.py index 32a93c83..320b27c8 100644 --- a/scripts/MPC_Wrapper.py +++ b/scripts/MPC_Wrapper.py @@ -1,17 +1,13 @@ -# coding: utf8 - -from operator import pos -from typing import FrozenSet import numpy as np from multiprocessing import Process, Value, Array -import crocoddyl_class.MPC_crocoddyl as MPC_crocoddyl -import crocoddyl_class.MPC_crocoddyl_planner as MPC_crocoddyl_planner -import pinocchio as pin from time import time from enum import Enum -import quadruped_reactive_walking as qrw import ctypes -from ctypes import Structure, c_double +from ctypes import Structure + +import Crocoddyl.MPC_crocoddyl as MPC_crocoddyl +import Crocoddyl.MPC_crocoddyl_planner as MPC_crocoddyl_planner +import quadruped_reactive_walking as qrw class MPC_type(Enum): @@ -221,7 +217,7 @@ class MPC_Wrapper: self.f_applied = self.mpc.get_latest_result(oRh, oTh) else: self.f_applied = self.mpc.get_latest_result() - + if self.mpc_type == MPC_type.OSQP: self.last_cost = self.mpc.retrieve_cost() diff --git a/scripts/__init__.py b/scripts/__init__.py deleted file mode 100644 index e69de29b..00000000 diff --git a/scripts/bauzil_stairs.stl b/scripts/bauzil_stairs.stl deleted file mode 100644 index c75c11b9c75eccda0502c24f645bec841a864c69..0000000000000000000000000000000000000000 GIT binary patch literal 0 HcmV?d00001 literal 32684 zcmb8136xz`nT0PX5Yl0Ki7XTiL8dT;5LlU@-bsLfA|M12SVVzPfK7x15M@ra8XB1* zgFqo58ni*$s0^kIow`qGF(oAmNLOe@2~dK94Xt5PI_bObsqdWs-1lA)?^@Q|@BDk8 zfA9a?`zn<b&N_d={Bu5cYUjAq&Y6GaxC1_W>RFwqp0nqq2~(zw8-MP3bH`2GHT#FI zt2WHCQP(}$G5XUl)PH-^Dek%DwZ{K^V5S>2=?<42Rcp-LWTrc5>>cjDeTwy;^tm&y z`=raVZBIPZowfGL`qm#Cm9T1C*BYBHoZ*hU@f#JztUE4pjVJG3alowcy_R+9?zP6T z_d3_pcf0%b*jnR_DSfUn?-NCj{~Yn%`lQ=d^<Mk<vAJbUy}Q=<?Of+>yYO~*<5y~p zbN;^4^;~dtq4?F9arwL*?(1E9?WEkYR<Ely-0z+1f8%!d_}jI{^a*`#%q;b|;-rOn z|2f%;o{<YzSk{djk8bR6<qY?kZ+*jkXT<2nge&{ps%6I%iZO>y&yU#Rw)zp9eaKms zo!dQqwZ^_r_PNguXjaE>+%s*$vz_^7pBk)NS2mN~Da*dH<!e9ge5KPJxW{0xO=!KR z=h1)PhV`eHJYV1W&AHBYx2{sfE=w<QSDblK$5Z#L>97@hHtBghxyhz(^TU49+dF?| zZYxQS<UIB|;>F%;x9{)$_m3Zz+Z=WZHdB_}G4GQ6*^~ce#n*niL9eaYvq{h6_$xn} zchA4N-ZOTy<fQCG?L@Nd=aYW(<E__p=Ks3cVBMy*ce~A$WjlOf{L~j->CBJZZLn@x zcDlA-mc4V$qA8F4p)>#H0fTj0u{rD%vTWj`mrNaawKKnJY}&)BQ&*RL;&0RPr#sz) zpC3$SW#^M7pWpTOY1cg4>8?Iuu-BfsJxzN~S$6XyU+Fpf_nmIUNrSz1FRQlalw~{5 zJ<v^i@cR0u8;o%aPp>szxpSsle!=PPM<Z*E?q_GX{C`h%+Z<kNT>k1xH*v(;dX}v? z{Af4xeP8U|Z;K6b%ewHCT4VpWoV#rMPWPKFYK_@vt#m8ay<I4dTzysVA!DBDeP!^3 z+_KL9d#$m}!86>r6`k&+8;af^Sm|y!_02*t>bgtw7e2XP$90c9)L~hN{IS;9_JW!2 zxDTK1-q>Pv<K}Z$x-ED6TcOC#8N2MRKX&HRrwrDu!aB6-EPLVNj^2g8d$xYo<|jK_ zu~T^D(OTn)H7nitNlO0A;Pjr4ztrh&-G8vx`n68d<p1{{9UWJEbg(}6#!hGVvOUu2 z-gfsqxA5Y9>-7unt=o#tk@nbf@6qmwKQHfHc=mp|t=LIhw^_F5*5mT+_qezB`o|{a zwqoaIGiBMoeeU#p*(S5<`yTyp-B#?}Y`)@?;ihe;{>z^`^Z(u@JrC>3X3Da!uDN~c zOV4%Yd(IxL+xgfYsp7J)Z$9m$;&b;?#pkZ=Zs%qvl4U=<Vn)wvgPrdE2d4_lviY*? z=qLYH-)_$n-L>;aP5bLjwZ@k=J;3d}_Z@EY9cqn7Hk|2pE$|b?_rbRdyz>vPEAEo| zZI`;g{^HjiM?ZPxG|Sq4n_A<WCpouUlOlU{s$2fvz4L8<GI_dXJ#}iW@uzL;ZeZda z?wz9F>{sh<Y}uoGt3|!5_W43S>FFiYE$hZLwZ?4^)ZLCnk6GQd#u*#b-MCV5#+jGq zTix~CiV-)>o@!aQzGrmfgvV#NT?)n48;x%C{BedGUn+KTTj!6?`ncQU*v2%=vQtPE zYd8MovIDO_v?t5Dob6#V*`2a%_s4IUyx$hbPg%EaVQ&3?@ts=Z!Hu2UzHpLG_vOiN z)xZ7XiEi|irBnC0rq+1r?U`<ef@NK$iXT0;(9L~p?20e%HEFr6SXb$EmtOs1ebwyF z{J3WqFSo8N%T7JZCjWF)e)JQ^<mcaVWTLQBu$i*#j1v~-8*Fy%iXVRJzoyxWRixA1 z_>*gU51#O8cgMLSmfMO=ZYPpuTRrvcv~6zv;De8?TbP`O^=_w-W&7oq_dId;{3$v? zTe0`C?U!XAIO2E9W`Ae<sZ!XAJ!iX9mgV=nzHE<qtJEX6$!(@I$AM4(V%b&)t}PYz z1nqg)bIP*&H=H|V)ctE8P!GG8RomXhbAI#5?ydLyrGEcsKmTL*vEqBtFZ<k|jyleL zeal+o;MZ5WmkYf2s9NLDftBuu51qGvmR-H`k?w<=yf44yv@@q$)-Gq&8f#wtnR~5C z@%_*Lq4$*T&V1R1bEjKYU-1m~U$(MTEO@i{o_NwqcU9Tr_}wndcR%s?`uC3c?sUs~ zcy+BYrqSpAT=Y2ity<&Wul2dNOT}@|oHFIT@5{>*v^}gttIo2W4mozkXTH7AJ^#U} z({060;mi|ijpJ7Lx$Daw-@j{c^4f_vEYoz?T~hq{{EeTv?BVnFx8BoP^}Tk2+j@id zxU1efdAZ%o_DB^!ShtURV8rD7Z>zhO+ltL(dlx?&T-V>b;CpA}Pw%j3nypxcb(m#~ z*DlQWo-pv>;Wx}%ZYy@u>2z;D^qW&Y^v_q9)3vj*3fnKsUVi?~DIeMV_EKTfTD3i! zEW7Hl`Mrx)pYJw0@%rVqyH(g37WeMi8!y{&+fB>!unNnvGt9DYPw%^b&GdccDz^&D zvJ=sds9nX+M*cdxV`Sr{;+YsfXK{z{#DRws3{S6JxxQM~FZxFX1y~$io-IU0J%s58 z7Kh6_!<AMo3#^?~YtErn)HajWxzZe3ZIvly>z%r5J{H?dDD;}<z=@KhW(tul^ziF< z<y3?@53o2~J_i-`xM<AMpa7?Ay`zGHep<(2P?dghg&GzL?W9^f532x+g<JM7RpotU zD_|Tl^~e??hs7vxsG2VCtm*_-`y9G6-dXa4@Jt-E=$-`o-Tl{iU%}EHQ^hFK=fkq- zC$%sNy~g{Bie-VD&x0J=11y%XdTX64&7oCTQjjTS>z%EDQQ$VH%8pehu-fO)35unC zg_#?e{q-834_G?qDn=2{qspS6)^QkAWe!|v)v~~Ht6KVeuor5ZNo=k(hgL}|1#VNe z-q{Km1-*kR$$=AC?Q`e^_ZnE@mL76)UHA(<w<nnW^&0OhSUTq_MiI}W%A%jvg;A6} z!hJ=>vcPg1*+S&7*k;l?SDHhsHaTunw%*waSUqrsLa*^TC#`jeqB)1|3>3ml7o7CS z^^S`6(mA65qlo801qJ=I&eVe{+*edA3*0^j4(Wkg_SdU-W-DMEDiez49ICX+ghH?J z`-gQ>&D5Mjr}pCOmxpI!uYoTmIO$QIhd*b}^5>jl6fsAYML(?zqtI)-uc%lSxP1=o z(JGVHxx6!SXceq|ahtOB&Q`!Ea2r%*s;U!M?Q`hP5KH?Ca~@#!*K545VEOyip9dI4 zJP#`BAxu9oin2$U16NwHEU<QpY$2-v+f3qcr8%@pS{y20%GNt|rvgU7q=PESffHEm zbLa%GU45aubHR%8`^WZoE=Vx@>owk2uyoE<j3S;#l|?_T3!^A|l<#n*70Uw4ZDb2s z1=wa1hbzsYRVmg#hZL<cX`L%R=cL7z80~ZD&OjlID=_=(HQraSbk0?bBA!Q;ML(^# zJ`Y@JFUtZqpNCa|#d`M~>H$j%+-hA{a}KS-LNR;}oWN?IL#MXkcC*4Waoy_a307~e zcwfQNIahJY*1IZ;ep(ksq1Sj{QL!wr@<p}~IV=`S>vE`dt~7^MVM&48l&yER0!D$` zpbF19X|2QdIdo^B5N5hy_SdV=K}Ak<&M3er()-G?=qE+%9Jtb6mIYRC)%@uRSp`@u z+=|1M=FloEn<-`MolOWvF?<f3z-pgEr*>=4Sl2UlBPYDaMPm|-E4{}13YN~fic!S# zsIus%bzu}`k8od6u`ICMMz#<+EVh}n&XwlSs!fjDl&yER0#*-Pq0no5&Pi(>qG+At z@`F$A#ruw97bQ69k?WoIg{6I~7)5#>mPJ3Qg;D4==AdF(;PyGRhaA!aw_4|l=OI^G zg~fDPSFJgRR;$TztD3Gf2h)YsK8K!EybCiou;1N(_0FiMhn_nWU=%S26%_Q-Iu3)X zyzg<PRm%cvC)Lu=EA~Py7H-AnN^@ux77kmV2RWnwqoB8Hy1cWh6IjFN;E9r&Pam+~ z-G7ZaU}@hfMv<O}WzkP+K9zzhoCg)l0=GU76!K1wch8~Du$Zpg21hxFw0aLlL2tP6 zJggH~?Q`rtXL0Xg+bt@7hiM}xyy_z-Cz$>9>L+Yj|1_{9D8MM<c~DUgVfuklls(Eh z;7Ti&1=dcHEo2p7n@Jq5G>2AOWlGt4r|z1M#WoWPz54U0I#F`eOd+y`>LYK;sR(l( zU~#y74k~i;#`s%<0-Un-jtUC;X&r|_Rn8e#s9~YdPO8PvE2{vDg<JM7Rk^;}3K)k> zJ+g(!VKE9Es;0|3t2%)-e2#5?+24Wpi9b6p!G3rDHJ%47?OVkt;`32u(NF8bDD)b0 zP_Znq+(x#LlA{3IOyY2*IkYOp`sa|MRVJ--r8#hd!}dA!M2RJZFs{JtuUDUgiWGW+ zQGijz^Pqx)ep<(2P?dAWl~yeatesSg&xcijZ6>j~(i~cCl__QG9XTwvnNaA}JF7Y& zZTlR5I%=xZQ>1-``Md%rJ<8{tiWC=)nGh6U6!AQ$prD`Dd4hwgoHMSpYFS|Iq*^== zs{q?fV*5+K-z7v2i*eZc^NJi&fKjA5iXKT0oWN?IW4Ae5gzvAyoCjFFx%`Bw4D|?# zB47A!Cq+CDDkwM)t>ZBCD0ARStCj`UPO8Q8unMqPxD}f#&7oCTIBb0$<d6c4V)z_5 zfi-*%K0oA&Pam*)bHyC6v~LxsY`v?p=%;m_;GhcULB+Db$|ps79w_9U9`Bw*`@mwl z%A|E&>3v0|RVL5(U%j)c6CAeBQB)k>h0SzJob<@`&a(8}p#Y<ZIjAVDF#W(N^y+iq zN-LHHZaxpI01r*KlEZ#pnd$xmIdEl@GilYb%zj>x7FVjb&+*3i--hoW!hBwVrRMSz zrlPd<kpn>iPT6`#1qGj1TIUH4s`9?a6>3;0n$N>3z+&N+{q>sW&<ZRZw*I^#hZJBG zI8;rSzptuJV71S&X8fFR9>Sal*zfMY`W#f`<jXG~6%=3;@%f;FLar=Ep;w;+S6Y#p z9AK#<TgWQFV&PUCt~7^MVd1Lvd5}X2FbW*1rYp^X6IjFN;E9qeo<XqR-G7ZaU}@hf zMv<O}WzkRS^f|XVs8|+Q`P9d!7Ls2SV5Xqn;&7!ov`Sj0YZc8oq^KsRw`#iLd8mRD zSnYG@i9#XF+`xW!|J6IAq8@tgP=Hay98^%yPwO}gs_=P5#j?QKNs4$L<j^WuEZl0H zE6t%*SU7Bb9^{Y$i~_f+>GIC1PGGgq@zCopxp$WQs{A((;e!@Enqa@X|LSvC*2sb9 zg93~qo(C0q7p5N=g<gFQTxrF!z}hLYg{%TB7H-AiN^@ux77jIql&yE_P6doYnNa98 z&4CkG!{^xdnge=KtohQs1SdUmy_0uX+P8{Pq~~E-^pjc`g<fM0DwYM7+sGD@D->Xx zNgS?t9&)ACR+&<^-jUW~^}rPhy{0*Ef<qLoa*UrLmRF3Q!Q38t-Q%Rk(0N4GX{YTR z6krtbJgBILF#W(N^hyrzN-LHHZl6O6d8fy_=RiSn_28UTYtErnST>W^xzZd=m-DFR z@GAXDTz+{5#j=>Eiyr>Z)nf69gMxlix1JRW`dLNXpY)bxdw@}-v!Z*|VKqmb6%`cP z7fcS{i&>$-p;dS$U-dJHSR}XmqNay;Bqa)q*KbxR>=Zan)tYCeRk^YX@~NgPofS@C z*-ViwG-vTcZl@0)?m9*e)P)~-;eZ5-!{wb>R`L4=K><$LdPhY)gy{!Hp;w;+S6Z<w zuy%@UA*%q}OyY2*Ikeg;Q_9vmb=Q0>wwX}qHO+w&B}dH^B3r0nhWQ9{9$;~}d=4tb zYkkqnj|T-fW$PUk6gbg34uh)ns~%J=3#^@_h|h;rfW;DKhM`CK{liwkQs6da>z%ED zQQ$VHk{n{G2dv?9jCYTf&x8~U#`Ptb{q-8p1D5u!VicaOcU2bsv@VQ7uYSUELdCMc z$`{!}Rsj}ESPsSEN^@uxmK3;6*?MOyU=+9ws&F2pRS#J0bLdG$A<T5a?5|g!gNmH! z2}S`%5zm7P3i@dshe1{5z?D`l3#^?~i_eEufW^YC*j#B2t-`{gJ;CN2QnbpXb*}h% zMOs{m(LP7<FK*>iG;&}`U0Bby#q3}HnIzXc%PRhTFetz%Vh$?WS6EN2#VF$6C*n#K z6c$UZ_whWe0=#}Xv`?!{TG!Q_L#wSaY29D^y=c`5pI2mR&M{E@H(ty~nDYSBL9gB! z745ZM@n5u|0HcUGsGy*q)^QkA<@13nty&hieGVy5i-lXQ`%8b~6S5UB4()fG<{VPD z%A|FFaUNACq#Ztoo+!NQNwt^`dX47+OZ!$aiZq91(NF5upI6F3#j?P1SUM_CPsl33 zt#jD(kSo;IA?sz2^7MpAYq5IZO6&fz=RsOriGiXyhn^@D!ngttH7H)lK}CD%xkCX) z5zm7P3i@fCse2VUaHUnt0+S=Ca;v~$RUO$vmIcOP>+>K7``YBg=g_{^VKqnm+#S1U zUiq1!|MEpxPpZW}ga7I$Y*_^}D8MM<c~H^5!g^{gMxj^l3|Cq~VX@SD-<(6MsKvsq z*16IgT7`wH)}L2$LIsS1PomJHeD11FU`fpsq=-2dbX*ZC!kh<~{YzE(<WiB7p0SI9 z0*oS_2Ne`J(K-%;s?32aty&gXJE_*3L#wF8!mZZ1yfa$?<B+LK(VRo8tukqy%R8$& zA?@%v^sM1s&!ENZuh*CZmiDb;6lo62qMy|1bIyd7gNkK=<*;;Ao}Q3ZfY&bvYU@x~ z>$;kAXtkOgx2oxi=RsOrsoFk=o+uQ;xB^Sf<(*Mc+Twpf0Z!R^M+F7_wB9-gu2925 zp`BEV&xcij#lo%FTxkxi!jeKgTAzolfKlKu^eE4>>I9b5!ct2SbIdOOI}$xbiywNu zLs(C$#q3|Ia(%U|=Pn!*6krtbzM`Uih3N-Ip;zw=S6Z<wuy%@UA*%qdUk=nHSC7`8 zSGEGSnY0sEngb_%UbW9LX6YeeKEk*Hv%g;bgsG^<oeMgG0*oS_2Ne{Yht_czRONkz zE3H}<SUaf}?<=bSi-lXUxzZe3g@wb`=RpoBz$k{#ffHE6=g^abLQks2>dh5%z|y`| zoU-+<%A%jvd4hu~oCg)l0?VNk>3N{gbm<{%KYdD7`JCGdSo`8OI4aqCXDeV7^bV>d z2NQ+WK8K!dybCj3F#GG(p9dB7&~t|Zj3PcCR8Y`Q>o^RmG6$}-YFS|Iq*^==s{o6I zTd}#)99o5iLwkbFIizTnN$Xtk^NO^%5~F<%{iISpMFUIr7cQSvi)j#k9<;38<}411 zfQJ+@N2nD03ezuO+oL>>;Hs!tR=~wh62<edih$QIN3l=KOlnYEEpimAa>A^FtCFuT z{9Idg!sk^`H03Dnh%g^vdIW5HluvG`6niZ_WOYykJfw&@LS;z7d1xJnUPO-Is#vzH zfZOLN6hU3Eg4-ci@$VUIC19IrNYNt4kSk^tT-hGweN}Zr+MsBeqx{Sm@?Jiv7TX@- zJYZ?xCfqWIWzkRS^z+J|2NlZ-xP6YIyQV-7;j(x897780&??gNpi)haTi>QB$IwJ! zwa=j^3h%<W3b-jps1!Z)+@T0~ND*^{%8-J7TE}6UBe*J-Ei2%r^RSA53s!L3K1Wdr zESqUa(IUr?E1UdXatt|vRn399u6)koZ{=5=_MP%46XBhT&t(5I&Q=XDY`v=LE8X4Q z#lQA=1z0-?qwt^aQc$6vRW$!pRAtEtimEF=FYClQ1cx5wGcJF)s-{I@bNEj=tH5DZ zO>+M|1cmmp`=Yiz(pj-@b#5U?`FW^r?4=5L{bq%N>EbZ-Xqpu{xMNV*9P;GvtH1R3 zyIqU_r#iX1vbZyZr2vb`<?kz1Zti}6nZsi3r1i)a(q2^5ql(o}y!fY#D$Dk$x{CJ| zEWFDJIP^$nMRLmm+Z^$}LV?5fv(jg;_9Cs_7q#sX?<;y(HHwfUxvx;b(!RpO&q{m2 zTEAJrqMyx_Wd|H|&^|gx?yH@P6D|Hlw{&vpKKqndii?ME@#phnp1N;HQO-)0(@y(C zP=K|QaJl#W+$q{?$DxXHzyhmxsYqsJS#m`W9F~6eRR$sL1q<&|fJ2YuzLG0dEDP*& z9CyqyB+perVZEcEN9nBi;-5j1!y*Uy#O`XE6|PX*ex;&mR#L#C$MCa4QJot(;&)Dx zGf}2sGszW~|Gd&&qTf7|s}bGZ<?oJ40fwztKPy$byWbxaVC^J~B0hsu)T4@<e@m~* zs`f)sItup{EWFDJ7)3fOl3Nzo=J0(~L4iZ<i-I08JqqhY7`5$@&We54e^yf1eTAzh z7@t8Zu&hIJG|vhaQy{s`;b%3!<BHzBZs{)mWoaWPoMksm#vzzFm5S24D%uMLSUdS1 z8)sd`bM9v)?|Tka=w}rnN4OuWtZF|LK7+nmC+dd+j3UkoSJkvAd=BmHFaHcGhZH!h zs$uK3tDF_d?Y^jek2UKSHqDBCQKQhh-<wXh0%p3^6ZGlDq5_rzhoMLL#HtUog2fb2 z_#8MYlII^O{=d_>uY~D$w&@-DniUo8g#z6AzLJ9Z(9bGDj&fq^R%LOQ&<};UepXbp zuXPAU5$`KpsbX1R?WFy=x^k<)VO0%VuYOh}xBH^@J?wpDdw|z(R&rwZWg;Xm9hG;A zt$^*^P&Cg97Wb9SlqApZT<}b|uY|d;=tmD!UCF(KLjBlDILqwkmG)w~mIbDV|8!F) zD(uUBrF9$zN9C-jNP%~YLywXzEv{5SVX@Ca7oI^TibJcQ2O2*slGB4s@fo!DRn--0 z+fVy9&r024(PQ{op<uc=BuBijaK%KK0*dBY&F+~nqqqC%^3PYoeBYHrFmv*GsAw+~ zVC`gk`1Ddxp`TTR9K}83uPRGUP*h#{^wx=W2o62MeT6Hg%f2XVjxu@q4BA<NQP6`F z`k5dmheZx164^p1a0QEr&?DYgwgRRHnL>{;J+snYU@34IdNj=nRyDcS>7m!Ia#j=H zo>=})dwt|GXYtJ!uPWCQMe*OFE_14^Teq(GeK@ZWmMf`+%e_M<RZv(KnBR`}j`WpE zwFmuB#3zah3i{y|MRbNMRV)ik4k>i`SuqnFR@I*Czxw;C>O}jZrboO>tShipBst1+ zXD?O2QZNw|&9lNgr$%xVW$N-2t4^2#3UZLXE2q2urgmV-SIavCEVVFf-$yJ}`uqEX zLYSR|qaz`@S6L`*51*b&wTE?B_9!PSL<NO)Sk2*25m(i;HlKFp^0Q(u99Gq^_1YDl z!Ky3NTK7zJ))iPR6zylF3M~5RjzJOcD`tgvu~3i?Kk2M+0;~P3Rt?=t`a9O=F8oA! zUxB6O?_Ogcu~gCDv7!)WC;sj=K7*>Duq?3c;nP#8_Mjh%I4deB=!aVr@f2~Tie-Vx z5t8Rtfy1gAw(o<Y>IyYInrEebtr|s=qkO7t1x!EPF({g6g?F(~RL|Tyt2%+zepaez z-{Ri`i{J6tB*9W^J)M<Us`U3CR!1SsPQrew=;&T$p|CxCdMec(^g|J6MFoX*Sk2*Q zg)5T7viV3*=E<!BhgEf=a44#-P;0&1yZmk=ghKm*#X>>y`0wYo0;V4)TlNT_?aT`A zVxeFPQuu$1(reWTtoE~_NAa1s|8|S!)zt$mwXk;P>T+VK^7H=w4iv)dBrJA(2I*d9 zp|CytokFGBgMKLDeMJR@by&^eo#CpQ*5)I1nJ2dj99Gqd!l9_TLap_3?{HtC(7s@? zP>|d^(pOsn(~r}PY$0Zacd<|mKP#NTYCEgq|9kw_8QXp4lo{%`^pKeiiyzwS>2Qy$ SuB)p_0c+Pe-<Sc;vi}G7dLKam diff --git a/scripts/config_solo12_bis.yaml b/scripts/config_solo12_bis.yaml deleted file mode 100644 index 11144139..00000000 --- a/scripts/config_solo12_bis.yaml +++ /dev/null @@ -1,58 +0,0 @@ -robot: - interface: enp2s0 - joint_modules: - motor_numbers: [0, 3, 2, 1, 5, 4, 6, 9, 8, 7, 11, 10] - motor_constants: 0.025 - gear_ratios: 9. - max_currents: 12. - reverse_polarities: [ - false, true, true, true, false, false, - false, true, true, true, false, false - ] - lower_joint_limits: [ - -1.2, -1.7, -3.4, -1.2, -1.7, -3.4, - -1.2, -1.7, -3.4, -1.2, -1.7, -3.4 - ] - upper_joint_limits: [ - 1.2, 1.7, +3.4, +1.2, +1.7, +3.4, - 1.2, 1.7, +3.4, +1.2, +1.7, +3.4 - ] - max_joint_velocities: 80. - safety_damping: 0.5 - imu: - rotate_vector: [1, 2, 3] - orientation_vector: [-4, 3, -2, 1] -joint_calibrator: - # Can be either POS, NEG, ALT or AUTO - search_methods: [ - AUTO, AUTO, AUTO, AUTO, AUTO, AUTO, - AUTO, AUTO, AUTO, AUTO, AUTO, AUTO - ] - position_offsets: [ - 0.17135490311516655, - -0.2380975882212321, - -0.27943841616312665, - 0.04930730660756429, - 0.6213272942437066, - -0.42891038788689506, - 0.44484631220499676, - 0.1533108287387424, - 0.02831502093209161, - -0.32956356472439235, - -0.15770453876919216, - -0.25019770198398167 - ] - calib_order: [1, 0, 0, 1, 0, 0, 1, 0, 0, 1, 0, 0] - calib_pos: [ - 0.0, 1.2, -2.4, - 0.0, 1.2, -2.4, - 0.0, -1.2, 2.4, - 0.0, -1.2, 2.4 - ] - Kp: 1. - Kd: 0.05 - T: 1. - dt: 0.001 - -# - np.array([-1.542194128036499, 0.4437657594680786, -2.5149457454681396, -2.142878293991089, 3.8601934909820557, -5.591945648193359, -# -4.003616809844971, -2.9660720825195312, 0.25483518838882446, 1.3797974586486816, 2.251779317855835, 1.4193408489227295]) diff --git a/scripts/main_mcapi_solo8.py b/scripts/main_mcapi_solo8.py deleted file mode 100644 index e96fa489..00000000 --- a/scripts/main_mcapi_solo8.py +++ /dev/null @@ -1,280 +0,0 @@ -# coding: utf8 -import numpy as np -import argparse -import math -from time import perf_counter as clock -from time import sleep -from solo12 import Solo12 -from pynput import keyboard - -from utils.logger import Logger -from utils.qualisysClient import QualisysClient -import matplotlib.pyplot as plt -from math import ceil -import curves -from multicontact_api import ContactSequence -curves.switchToNumpyArray() -DT = 0.001 -KP = 4. -KD = 0.05 -KT = 1. -tau_max = 3. * np.ones(8) - -key_pressed = False - -# Variables for motion range test of Solo12 -t_switch = np.array([0.0, 3.0, 6.0, 9.0, 12.0, 15.0, 18.0, 21.0, 24.0, 27.0, 33.0, 36.0, 39.0, 42.0]) -q1 = 0.66 * np.pi -q_switch = np.array([[0.0, 0.66 * np.pi, 0.0, 0.66 * np.pi, 0.0, 0.5 * np.pi, 0.5 * np.pi, 0.5 * np.pi, 0.0, -0.1 * np.pi, 0.0, 0.22 * np.pi, 0.0, 0.0], - [0.8, 0.8, -0.8, -0.8, 0.8, 0.8, 0.0, -0.8, -0.8, -1.4, np.pi*0.5, np.pi*0.5, np.pi*0.5, 0.0], - [-1.6, -1.6, 1.6, 1.6, -1.6, -1.6, +1.0, -2.0, -2.0, 2.0, -np.pi, -np.pi*1.4, -np.pi, 0.0]]) - -def handle_q_v_switch(t): - - i = 1 - while (i < t_switch.shape[0]) and (t_switch[i] <= t): - i += 1 - - if (i != t_switch.shape[0]): - return apply_q_v_change(t, i) - else: - N = q_switch.shape[1] - return np.tile(q_switch[:, (N-1):N], (4, 1)) * np.array([[1, 1, 1, -1, 1, 1, 1, -1, -1, -1, -1, -1]]).transpose(), np.zeros((12,)) - - -def apply_q_v_change(t, i): - - # Position - ev = t - t_switch[i-1] - t1 = t_switch[i] - t_switch[i-1] - A3 = 2 * (q_switch[:, (i-1):i] - q_switch[:, i:(i+1)]) / t1**3 - A2 = (-3/2) * t1 * A3 - q = q_switch[:, (i-1):i] + A2*ev**2 + A3*ev**3 - v = 2 * A2 * ev + 3 * A3 * ev**2 - - q = np.tile(q, (4, 1)) * np.array([[1, 1, 1, -1, 1, 1, 1, -1, -1, -1, -1, -1]]).transpose() - v = np.tile(v, (4, 1)) * np.array([[1, 1, 1, -1, 1, 1, 1, -1, -1, -1, -1, -1]]).transpose() - - return q, v - -def test_solo12(t): - - q = np.array([0, 0.8, -1.6, 0, 0.8, -1.6, 0, -0.8, 1.6, 0, -0.8, 1.6]) - v = np.zeros((12,)) - - q, v = handle_q_v_switch(t) - - return q, v - -def config_12_to_8(q12): - """ - Remove the shoulder roll joint from the vector - """ - assert q12.shape[0] == 12 - return np.hstack((q12[1:3], q12[4:6], q12[7:9], q12[10:12])) - - -def compute_pd(q_desired, v_desired, tau_desired, device): - pos_error = q_desired - device.q_mes - vel_error = v_desired - device.v_mes - tau = KP * pos_error + KD * vel_error + KT * tau_desired - tau = np.maximum(np.minimum(tau, tau_max), -tau_max) - return tau - -def on_press(key): - global key_pressed - try: - if key == keyboard.Key.enter: - key_pressed = True - # Stop listener - return False - except AttributeError: - print('Unknown key {0} pressed'.format(key)) - -def put_on_the_floor(device, q_init): - global key_pressed - key_pressed = False - Kp_pos = 3. - Kd_pos = 0.01 - imax = 3.0 - pos = np.zeros(device.nb_motors) - for motor in range(device.nb_motors): - pos[motor] = q_init[device.motorToUrdf[motor]] * device.gearRatioSigned[motor] - listener = keyboard.Listener(on_press=on_press) - listener.start() - print("Put the robot on the floor and press Enter") - while not key_pressed: - device.UpdateMeasurment() - for motor in range(device.nb_motors): - ref = Kp_pos*(pos[motor] - device.hardware.GetMotor(motor).GetPosition() - Kd_pos*device.hardware.GetMotor(motor).GetVelocity()) - ref = min(imax, max(-imax, ref)) - device.hardware.GetMotor(motor).SetCurrentReference(ref) - device.SendCommand(WaitEndOfCycle=True) - - print("Start the motion.") - -def plot_mes_des_curve(times, mes_t, des_t = None, title = None, y_label = None): - colors = ['r', 'b'] - labels = ["Shoulder" , "Knee"] - legs_order = ["front left", "front right", "hind left", "hind right"] - # joint positions des/mes - fig, ax = plt.subplots(2, 2) - fig.canvas.set_window_title(title) - fig.suptitle(title, fontsize=20) - for i in range(2): # line (front/back) - for j in range(2): # column (left/right) - ax_sub = ax[i, j] - for k in range(2): # joint - ax_sub.plot(times, mes_t[i*4 + j*2 + k, :].T, color=colors[k], label=labels[k]) - if des_t is not None: - ax_sub.plot(times, des_t[i*4 + j*2 + k, :].T, color=colors[k], label=labels[k] + "(ref)", linestyle="dashed") - ax_sub.set_xlabel('time (s)') - ax_sub.set_ylabel(y_label) - ax_sub.set_title(legs_order[i*2 + j]) - ax_sub.legend() - - - -def mcapi_playback(name_interface, filename): - device = Solo12(name_interface,dt=DT) - qc = QualisysClient(ip="140.93.16.160", body_id=0) - logger = Logger(device, qualisys=qc) - nb_motors = device.nb_motors - - q_viewer = np.array((7 + nb_motors) * [0.,]) - - # Load contactsequence from file: - cs = ContactSequence(0) - cs.loadFromBinary(filename) - # extract (q, dq, tau) trajectories: - q_t = cs.concatenateQtrajectories() # with the freeflyer configuration - dq_t = cs.concatenateDQtrajectories() # with the freeflyer configuration - ddq_t = cs.concatenateDDQtrajectories() # with the freeflyer configuration - tau_t = cs.concatenateTauTrajectories() # joints torques - # Get time interval from planning: - t_min = q_t.min() - t_max = q_t.max() - print("## Complete duration of the motion loaded: ", t_max - t_min) - # Sanity checks: - assert t_min < t_max - assert dq_t.min() == t_min - assert ddq_t.min() == t_min - assert tau_t.min() == t_min - assert dq_t.max() == t_max - assert ddq_t.max() == t_max - assert tau_t.max() == t_max - assert q_t.dim() == 19 - assert dq_t.dim() == 18 - assert ddq_t.dim() == 18 - assert tau_t.dim() == 12 - - num_steps = ceil((t_max - t_min) / DT) + 1 - q_mes_t = np.zeros([8, num_steps]) - v_mes_t = np.zeros([8, num_steps]) - q_des_t = np.zeros([8, num_steps]) - v_des_t = np.zeros([8, num_steps]) - tau_des_t = np.zeros([8, num_steps]) - tau_send_t = np.zeros([8, num_steps]) - tau_mesured_t = np.zeros([8, num_steps]) - q_init = config_12_to_8(q_t(t_min)[7:]) - device.Init(calibrateEncoders=True, q_init=q_init) - t = t_min - put_on_the_floor(device, q_init) - #CONTROL LOOP *************************************************** - t_id = 0 - while ((not device.hardware.IsTimeout()) and (t < t_max)): - # q_desired = config_12_to_8(q_t(t)[7:]) # remove freeflyer - # dq_desired = config_12_to_8(dq_t(t)[6:]) # remove freeflyer - # tau_desired = config_12_to_8(tau_t(t)) - device.UpdateMeasurment() - # tau = compute_pd(q_desired, dq_desired, tau_desired, device) - - # Parameters of the PD controller - KP = 4. - KD = 0.05 - KT = 1. - tau_max = 3. * np.ones(12) - - # Desired position and velocity for this loop and resulting torques - q_desired, v_desired = test_solo12(t) - pos_error = q_desired.ravel() - actuators_pos[:] - vel_error = v_desired.ravel() - actuators_vel[:] - tau = KP * pos_error + KD * vel_error - tau = 0.0 * np.maximum(np.minimum(tau, tau_max), -tau_max) - - # Send desired torques to the robot - device.SetDesiredJointTorque(tau) - - # store desired and mesured data for plotting - q_des_t[:, t_id] = q_desired - v_des_t[:, t_id] = dq_desired - q_mes_t[:, t_id] = device.q_mes - v_mes_t[:, t_id] = device.v_mes - tau_des_t[:, t_id] = tau_desired - tau_send_t[:, t_id] = tau - tau_mesured_t[: , t_id] = device.torquesFromCurrentMeasurment - - # call logger - # logger.sample(device, qualisys=qc) - - device.SendCommand(WaitEndOfCycle=True) - if ((device.cpt % 100) == 0): - device.Print() - - q_viewer[3:7] = device.baseOrientation # IMU Attitude - q_viewer[7:] = device.q_mes # Encoders - t += DT - t_id += 1 - #**************************************************************** - - # Whatever happened we send 0 torques to the motors. - device.SetDesiredJointTorque([0]*nb_motors) - device.SendCommand(WaitEndOfCycle=True) - - if device.hardware.IsTimeout(): - print("Masterboard timeout detected.") - print("Either the masterboard has been shut down or there has been a connection issue with the cable/wifi.") - device.hardware.Stop() # Shut down the interface between the computer and the master board - - # Save the logs of the Logger object - # logger.saveAll() - - # Plot the results - times = np.arange(t_min, t_max + DT, DT) - plot_mes_des_curve(times, q_mes_t, q_des_t, "Joints positions", "joint position") - plot_mes_des_curve(times, v_mes_t, v_des_t, "Joints velocities", "joint velocity") - plot_mes_des_curve(times, tau_send_t, tau_des_t, "Joints torque", "Nm") - current_t = np.zeros([8, num_steps]) - for motor in range(device.nb_motors): - current_t[device.motorToUrdf[motor], :] = tau_send_t[device.motorToUrdf[motor], :] / device.jointKtSigned[motor] - plot_mes_des_curve(times, current_t, title="Motor current", y_label="A") - - tracking_pos_error = q_des_t - q_mes_t - plot_mes_des_curve(times, tracking_pos_error, title="Tracking error") - - plot_mes_des_curve(times, tau_mesured_t, title="Torque mesured from current", y_label="nM") - current_mesured_t = np.zeros([8, num_steps]) - for motor in range(device.nb_motors): - current_mesured_t[device.motorToUrdf[motor], :] = tau_mesured_t[device.motorToUrdf[motor], :] / device.jointKtSigned[motor] - plot_mes_des_curve(times, current_mesured_t, title="Measured motor current", y_label="A") - - plt.show() - -def main(): - parser = argparse.ArgumentParser(description='Playback trajectory stored in a multicontact-api file.') - parser.add_argument('-i', - '--interface', - required=True, - help='Name of the interface (use ifconfig in a terminal), for instance "enp1s0"') - - parser.add_argument('-f', - '--filename', - type=str, - required=True, - help="The absolute path of a multicontact_api.ContactSequence serialized file") - - mcapi_playback(parser.parse_args().interface, parser.parse_args().filename) - - -if __name__ == "__main__": - main() diff --git a/scripts/main_minimal_controler.py b/scripts/main_minimal_controler.py deleted file mode 100644 index 83b545ce..00000000 --- a/scripts/main_minimal_controler.py +++ /dev/null @@ -1,212 +0,0 @@ -# coding: utf8 -"""from utils.logger import Logger -import tsid as tsid -import pinocchio as pin -import argparse -import numpy as np -import mpctsid.test_bug -# from mpctsid.Estimator import Estimator -#from mpctsid.Controller import Controller -from utils.viewerClient import viewerClient, NonBlockingViewerFromRobot""" -"""import os -import sys -sys.path.insert(0, './mpctsid')""" -"""SIMULATION = True -LOGGING = False - -if SIMULATION: - from mpctsid.utils_mpc import PyBulletSimulator -else: - from pynput import keyboard - from solo12 import Solo12 - from utils.qualisysClient import QualisysClient""" -#from matplotlib import pyplot as plt -# from utils_mpc import PyBulletSimulator -import numpy as np -import argparse -from example_robot_data.path import EXAMPLE_ROBOT_DATA_MODEL_DIR -# from solo12 import Solo12 -# from pynput import keyboard - -# from utils.logger import Logger -# from utils.qualisysClient import QualisysClient -"""import os -import sys -sys.path.insert(0, './mpctsid')""" - -DT = 0.002 - -key_pressed = False - - -def on_press(key): - """Wait for a specific key press on the keyboard - - Args: - key (keyboard.Key): the key we want to wait for - """ - global key_pressed - try: - if key == keyboard.Key.enter: - key_pressed = True - # Stop listener - return False - except AttributeError: - print('Unknown key {0} pressed'.format(key)) - - -def put_on_the_floor(device, q_init): - """Make the robot go to the default initial position and wait for the user - to press the Enter key to start the main control loop - - Args: - device (robot wrapper): a wrapper to communicate with the robot - q_init (array): the default position of the robot - """ - global key_pressed - key_pressed = False - Kp_pos = 3. - Kd_pos = 0.01 - imax = 3.0 - pos = np.zeros(device.nb_motors) - for motor in range(device.nb_motors): - pos[motor] = q_init[device.motorToUrdf[motor]] * \ - device.gearRatioSigned[motor] - listener = keyboard.Listener(on_press=on_press) - listener.start() - print("Put the robot on the floor and press Enter") - while not key_pressed: - device.UpdateMeasurment() - for motor in range(device.nb_motors): - ref = Kp_pos * (pos[motor] - device.hardware.GetMotor(motor).GetPosition() - - Kd_pos * device.hardware.GetMotor(motor).GetVelocity()) - ref = min(imax, max(-imax, ref)) - device.hardware.GetMotor(motor).SetCurrentReference(ref) - device.SendCommand(WaitEndOfCycle=True) - - print("Start the motion.") - - -def mcapi_playback(name_interface): - """Main function that calibrates the robot, get it into a default waiting position then launch - the main control loop once the user has pressed the Enter key - - Args: - name_interface (string): name of the interface that is used to communicate with the robot - """ - from IPython import embed - import pybullet as pyb - import pybullet_data - - # Start the client for PyBullet - pyb.connect(pyb.GUI) - pyb.setAdditionalSearchPath(pybullet_data.getDataPath()) - robotStartPos = [0, 0, 0.235 + 0.0045] # +0.2] - robotStartOrientation = pyb.getQuaternionFromEuler([0.0, 0.0, 0.0]) # -np.pi/2 - pyb.setAdditionalSearchPath(EXAMPLE_ROBOT_DATA_MODEL_DIR + "/solo_description/robots") - robotId = pyb.loadURDF("solo12.urdf", robotStartPos, robotStartOrientation) - - print("PASS") - embed() - - ######################################### - # PARAMETERS OF THE MPC-TSID CONTROLLER # - ######################################### - - envID = 0 # Identifier of the environment to choose in which one the simulation will happen - velID = 0 # Identifier of the reference velocity profile to choose which one will be sent to the robot - - dt_tsid = 0.0020 # Time step of TSID - dt_mpc = 0.02 # Time step of the MPC - # dt is dt_tsid, defined in the TSID controller script - k_mpc = int(dt_mpc / dt_tsid) - t = 0.0 # Time - n_periods = 1 # Number of periods in the prediction horizon - T_gait = 0.64 # Duration of one gait period - N_SIMULATION = 20000 # number of simulated TSID time steps - - # If True the ground is flat, otherwise it has bumps - use_flat_plane = True - - # Enable or disable PyBullet GUI - enable_pyb_GUI = True - - # Default position after calibration - q_init = np.array([0.0, 0.8, -1.6, 0, 0.8, -1.6, 0, -0.8, 1.6, 0, -0.8, 1.6]) - - #### - - # Create device object - # device = Solo12(name_interface, dt=DT) - device = PyBulletSimulator() - - # qc = QualisysClient(ip="140.93.16.160", body_id=0) # QualisysClient - # logger = Logger(device, qualisys=qc) # Logger object - nb_motors = device.nb_motors - - # Calibrate encoders - #device.Init(calibrateEncoders=True, q_init=q_init) - device.Init(calibrateEncoders=True, - q_init=q_init, - envID=envID, - use_flat_plane=use_flat_plane, - enable_pyb_GUI=enable_pyb_GUI, - dt=dt_tsid) - - # Wait for Enter input before starting the control loop - # put_on_the_floor(device, q_init) - - # CONTROL LOOP *************************************************** - t = 0.0 - t_max = (N_SIMULATION - 2) * dt_tsid - while ((not device.hardware.IsTimeout()) and (t < t_max)): - - device.UpdateMeasurment() # Retrieve data from IMU and Motion capture - - # Desired torques - tau = np.zeros(12) - - # Set desired torques for the actuators - device.SetDesiredJointTorque(tau) - - # Call logger - # logger.sample(device, qualisys=qc) - - # Send command to the robot - device.SendCommand(WaitEndOfCycle=True) - if ((device.cpt % 1000) == 0): - device.Print() - - t += DT - - # **************************************************************** - - # Whatever happened we send 0 torques to the motors. - device.SetDesiredJointTorque([0] * nb_motors) - device.SendCommand(WaitEndOfCycle=True) - - if device.hardware.IsTimeout(): - print("Masterboard timeout detected.") - print("Either the masterboard has been shut down or there has been a connection issue with the cable/wifi.") - # Shut down the interface between the computer and the master board - device.hardware.Stop() - - # Save the logs of the Logger object - # logger.saveAll() - - -def main(): - """Main function - """ - - parser = argparse.ArgumentParser(description='Playback trajectory to show the extent of solo12 workspace.') - parser.add_argument('-i', - '--interface', - required=True, - help='Name of the interface (use ifconfig in a terminal), for instance "enp1s0"') - - mcapi_playback(parser.parse_args().interface) - - -if __name__ == "__main__": - main() diff --git a/scripts/main_solo12_control.py b/scripts/main_solo12_control.py index 311ee36d..1450b12c 100644 --- a/scripts/main_solo12_control.py +++ b/scripts/main_solo12_control.py @@ -1,22 +1,20 @@ -# coding: utf8 - -import os +import numpy as np import threading +import time + from Controller import Controller -import numpy as np -import argparse -from LoggerSensors import LoggerSensors -from LoggerControl import LoggerControl +from tools.LoggerSensors import LoggerSensors +from tools.LoggerControl import LoggerControl + import quadruped_reactive_walking as qrw -import time params = qrw.Params() # Object that holds all controller parameters if params.SIMULATION: - from PyBulletSimulator import PyBulletSimulator + from tools.PyBulletSimulator import PyBulletSimulator else: import libodri_control_interface_pywrap as oci - from solopython.utils.qualisysClient import QualisysClient + from tools.qualisysClient import QualisysClient def get_input(): @@ -84,44 +82,6 @@ def check_position_error(device, controller): return False -def clone_movements(name_interface_clone, q_init, cloneP, cloneD, cloneQdes, cloneDQdes, cloneRunning, cloneResult): - - print("-- Launching clone interface --") - - print(name_interface_clone, params.dt_wbc) - clone = Solo12(name_interface_clone, dt=params.dt_wbc) - clone.Init(calibrateEncoders=True, q_init=q_init) - - while cloneRunning.value and not clone.hardware.IsTimeout(): - if cloneResult.value: - clone.SetDesiredJointPDgains(cloneP[:], cloneD[:]) - clone.SetDesiredJointPosition(cloneQdes[:]) - clone.SetDesiredJointVelocity(cloneDQdes[:]) - clone.SetDesiredJointTorque([0.0] * 12) - - clone.SendCommand(WaitEndOfCycle=True) - - cloneResult.value = False - return 0 - - -def launch_clone_process(name_interface_clone, q_init): - print("PASS") - from multiprocessing import Process, Array, Value - cloneP = Array('d', [0] * 12) - cloneD = Array('d', [0] * 12) - cloneQdes = Array('d', [0] * 12) - cloneDQdes = Array('d', [0] * 12) - cloneRunning = Value('b', True) - cloneResult = Value('b', True) - clone = Process(target=clone_movements, args=(name_interface_clone, q_init, cloneP, - cloneD, cloneQdes, cloneDQdes, cloneRunning, cloneResult)) - clone.start() - print(cloneResult.value) - - return cloneResult - - def damp_control(device, nb_motors): """ Damp the control during 2.5 seconds @@ -153,13 +113,13 @@ def damp_control(device, nb_motors): t += params.dt_wbc -def control_loop(name_interface_clone=None, des_vel_analysis=None): +def control_loop(des_vel_analysis=None): """ Main function that calibrates the robot, get it into a default waiting position then launch the main control loop once the user has pressed the Enter key Args: - name_interface_clone (string): name of the interface that will mimic the movements of the first + des_vel_analysis (string) """ if not params.SIMULATION: params.enable_pyb_GUI = False @@ -186,9 +146,6 @@ def control_loop(name_interface_clone=None, des_vel_analysis=None): device = oci.robot_from_yaml_file(params.config_file) qc = QualisysClient(ip="140.93.16.160", body_id=0) - if name_interface_clone is not None: - cloneResult = launch_clone_process(name_interface_clone, q_init) - if params.LOGGING or params.PLOTTING: loggerSensors = LoggerSensors(device, qualisys=qc, logSize=params.N_SIMULATION-3) loggerControl = LoggerControl(params, logSize=params.N_SIMULATION-3) @@ -205,7 +162,8 @@ def control_loop(name_interface_clone=None, des_vel_analysis=None): put_on_the_floor(device, q_init) # CONTROL LOOP *************************************************** - t = 0.0 # Time variable to keep track of time + + t = 0.0 t_max = (params.N_SIMULATION-2) * params.dt_wbc t_log_whole = np.zeros((params.N_SIMULATION)) @@ -267,9 +225,6 @@ def control_loop(name_interface_clone=None, des_vel_analysis=None): finished = (t >= t_max) damp_control(device, 12) - if not params.SIMULATION and name_interface_clone is not None: - cloneResult.value = False # Stop clone interface running in parallel process - if params.enable_multiprocessing: print("Stopping parallel process MPC") controller.mpc_wrapper.stop_parallel_loop() @@ -302,14 +257,7 @@ def control_loop(name_interface_clone=None, des_vel_analysis=None): if __name__ == "__main__": - parser = argparse.ArgumentParser(description='Playback trajectory to show the extent of solo12 workspace.') - parser.add_argument('-c', - '--clone', - required=False, - help='Name of the clone interface that will reproduce the movement of the first one \ - (use ifconfig in a terminal), for instance "enp1s0"') - # os.nice(-20) #  Set the process to highest priority (from -20 highest to +20 lowest) - f, v = control_loop(parser.parse_args().clone) # , np.array([1.5, 0.0, 0.0, 0.0, 0.0, 0.0])) + f, v = control_loop() # , np.array([1.5, 0.0, 0.0, 0.0, 0.0, 0.0])) print(f, v) quit() diff --git a/scripts/main_solo12_demo_estimator.py b/scripts/main_solo12_demo_estimator.py deleted file mode 100644 index 5f5b1745..00000000 --- a/scripts/main_solo12_demo_estimator.py +++ /dev/null @@ -1,225 +0,0 @@ -# coding: utf8 - -from utils.logger import Logger -import tsid as tsid -import pinocchio as pin -import argparse -import numpy as np -from mpctsid.Estimator import Estimator -from utils.viewerClient import viewerClient, NonBlockingViewerFromRobot -import os -import sys -from example_robot_data.path import EXAMPLE_ROBOT_DATA_MODEL_DIR as modelPath - -sys.path.insert(0, './mpctsid') - -SIMULATION = True -LOGGING = False - -if SIMULATION: - from mpctsid.utils_mpc import PyBulletSimulator -else: - from pynput import keyboard - from solo12 import Solo12 - from utils.qualisysClient import QualisysClient - -DT = 0.002 - -key_pressed = False - - -def on_press(key): - """Wait for a specific key press on the keyboard - - Args: - key (keyboard.Key): the key we want to wait for - """ - global key_pressed - try: - if key == keyboard.Key.enter: - key_pressed = True - # Stop listener - return False - except AttributeError: - print('Unknown key {0} pressed'.format(key)) - - -def put_on_the_floor(device, q_init): - """Make the robot go to the default initial position and wait for the user - to press the Enter key to start the main control loop - - Args: - device (robot wrapper): a wrapper to communicate with the robot - q_init (array): the default position of the robot - """ - global key_pressed - key_pressed = False - Kp_pos = 3. - Kd_pos = 0.01 - imax = 3.0 - pos = np.zeros(device.nb_motors) - for motor in range(device.nb_motors): - pos[motor] = q_init[device.motorToUrdf[motor]] * \ - device.gearRatioSigned[motor] - listener = keyboard.Listener(on_press=on_press) - listener.start() - print("Put the robot on the floor and press Enter") - while not key_pressed: - device.UpdateMeasurment() - for motor in range(device.nb_motors): - ref = Kp_pos * (pos[motor] - device.hardware.GetMotor(motor).GetPosition() - - Kd_pos * device.hardware.GetMotor(motor).GetVelocity()) - ref = min(imax, max(-imax, ref)) - device.hardware.GetMotor(motor).SetCurrentReference(ref) - device.SendCommand(WaitEndOfCycle=True) - - print("Start the motion.") - - -def mcapi_playback(name_interface): - """Main function that calibrates the robot, get it into a default waiting position then launch - the main control loop once the user has pressed the Enter key - - Args: - name_interface (string): name of the interface that is used to communicate with the robot - """ - - if SIMULATION: - device = PyBulletSimulator() - qc = None - else: - device = Solo12(name_interface, dt=DT) - qc = QualisysClient(ip="140.93.16.160", body_id=0) - - if LOGGING: - logger = Logger(device, qualisys=qc) - - # Number of motors - nb_motors = device.nb_motors - q_viewer = np.array((7 + nb_motors) * [ - 0., - ]) - - # Gepetto-gui - v = viewerClient() - v.display(q_viewer) - - # PyBullet GUI - enable_pyb_GUI = True - - # Maximum duration of the demonstration - t_max = 300.0 - - # Default position after calibration - q_init = np.array([0, 0.8, -1.6, 0, 0.8, -1.6, 0, -0.8, 1.6, 0, -0.8, 1.6]) - - # Create Estimator object - estimator = Estimator(DT, np.int(t_max / DT)) - - # Set the paths where the urdf and srdf file of the robot are registered - modelPath = "/opt/openrobots/share/example-robot-data/robots" - urdf = modelPath + "/solo_description/robots/solo12.urdf" - vector = pin.StdVec_StdString() - vector.extend(item for item in modelPath) - - # Create the robot wrapper from the urdf model (which has no free flyer) and add a free flyer - robot = tsid.RobotWrapper(urdf, vector, pin.JointModelFreeFlyer(), False) - model = robot.model() - - # Creation of the Invverse Dynamics HQP problem using the robot - # accelerations (base + joints) and the contact forces - invdyn = tsid.InverseDynamicsFormulationAccForce("tsid", robot, False) - - # Compute the problem data with a solver based on EiQuadProg - invdyn.computeProblemData(0.0, np.hstack((np.zeros(7), q_init)), np.zeros(18)) - - # Initiate communication with the device and calibrate encoders - if SIMULATION: - device.Init(calibrateEncoders=True, - q_init=q_init, - envID=0, - use_flat_plane=True, - enable_pyb_GUI=enable_pyb_GUI, - dt=DT) - else: - device.Init(calibrateEncoders=True, q_init=q_init) - - # Wait for Enter input before starting the control loop - put_on_the_floor(device, q_init) - - # CONTROL LOOP *************************************************** - t = 0.0 - k = 0 - - while ((not device.hardware.IsTimeout()) and (t < t_max)): - - device.UpdateMeasurment() # Retrieve data from IMU and Motion capture - - # Run estimator with hind left leg touching the ground - estimator.run_filter(k, np.array([0, 0, 1, 0]), device, invdyn.data(), model) - - # Zero desired torques - tau = np.zeros(12) - - # Set desired torques for the actuators - device.SetDesiredJointTorque(tau) - - # Call logger - if LOGGING: - logger.sample(device, qualisys=qc, estimator=estimator) - - # Send command to the robot - device.SendCommand(WaitEndOfCycle=True) - if ((device.cpt % 100) == 0): - device.Print() - - # Gepetto GUI - if k > 0: - pos = np.array(estimator.data.oMf[26].translation).ravel() - q_viewer[0:3] = np.array([-pos[0], -pos[1], estimator.FK_h]) # Position - q_viewer[3:7] = estimator.q_FK[3:7, 0] # Orientation - q_viewer[7:] = estimator.q_FK[7:, 0] # Encoders - v.display(q_viewer) - - t += DT - k += 1 - - # **************************************************************** - - # Whatever happened we send 0 torques to the motors. - device.SetDesiredJointTorque([0] * nb_motors) - device.SendCommand(WaitEndOfCycle=True) - - if device.hardware.IsTimeout(): - print("Masterboard timeout detected.") - print("Either the masterboard has been shut down or there has been a connection issue with the cable/wifi.") - # Shut down the interface between the computer and the master board - device.hardware.Stop() - - # Save the logs of the Logger object - if LOGGING: - logger.saveAll() - - if SIMULATION and enable_pyb_GUI: - # Disconnect the PyBullet server (also close the GUI) - device.Stop() - - print("End of script") - quit() - - -def main(): - """Main function - """ - - parser = argparse.ArgumentParser(description='Playback trajectory to show the extent of solo12 workspace.') - parser.add_argument('-i', - '--interface', - required=True, - help='Name of the interface (use ifconfig in a terminal), for instance "enp1s0"') - - mcapi_playback(parser.parse_args().interface) - - -if __name__ == "__main__": - main() diff --git a/scripts/main_solo12_replay.py b/scripts/main_solo12_replay.py index 0c3ebebe..73dccc57 100644 --- a/scripts/main_solo12_replay.py +++ b/scripts/main_solo12_replay.py @@ -1,25 +1,23 @@ -# coding: utf8 - import os import threading import numpy as np import argparse -from LoggerSensors import LoggerSensors +from tools.LoggerSensors import LoggerSensors import quadruped_reactive_walking as qrw import time params = qrw.Params() # Object that holds all controller parameters if params.SIMULATION: - from PyBulletSimulator import PyBulletSimulator + from tools.PyBulletSimulator import PyBulletSimulator else: import libodri_control_interface_pywrap as oci - from solopython.utils.qualisysClient import QualisysClient + from tools.qualisysClient import QualisysClient + def get_input(): - keystrk = input() - # thread doesn't continue until key is pressed - # and so it remains alive + input() + def put_on_the_floor(device, q_init): """Make the robot go to the default initial position and wait for the user @@ -29,7 +27,6 @@ def put_on_the_floor(device, q_init): device (robot wrapper): a wrapper to communicate with the robot q_init (array): the default position of the robot """ - print("PUT ON THE FLOOR.") Kp_pos = 3. @@ -54,36 +51,61 @@ def put_on_the_floor(device, q_init): print("Start the motion.") -def control_loop(name_interface_clone=None, des_vel_analysis=None): - """Main function that calibrates the robot, get it into a default waiting position then launch - the main control loop once the user has pressed the Enter key + +def damp_control(device, nb_motors): + """ + Damp the control during 2.5 seconds Args: - name_interface_clone (string): name of the interface that will mimic the movements of the first + device (robot wrapper): a wrapper to communicate with the robot + nb_motors (int): number of motors """ + t = 0.0 + t_max = 2.5 + while (not device.is_timeout) and (t < t_max): + device.parse_sensor_data() # Retrieve data from IMU and Motion capture - # Check .yaml file for parameters of the controller + # Set desired quantities for the actuators + device.joints.set_position_gains(np.zeros(nb_motors)) + device.joints.set_velocity_gains(0.1 * np.ones(nb_motors)) + device.joints.set_desired_positions(np.zeros(nb_motors)) + device.joints.set_desired_velocities(np.zeros(nb_motors)) + device.joints.set_torques(np.zeros(nb_motors)) + # Send command to the robot + device.send_command_and_wait_end_of_cycle(params.dt_wbc) + if (t % 1) < 5e-5: + print('IMU attitude:', device.imu.attitude_euler) + print('joint pos :', device.joints.positions) + print('joint vel :', device.joints.velocities) + device.robot_interface.PrintStats() + + t += params.dt_wbc + + +def control_loop(des_vel_analysis=None): + """ + Main function that calibrates the robot, get it into a default waiting position then launch + the main control loop once the user has pressed the Enter key + """ # Read replay data # replay = np.load("/home/odri/git/abonnefoy/Motion/Logs/push_up.npz") - # replay = np.load("/home/odri/git/abonnefoy/Motion/Logs/one_leg_position.npz") + # replay = np.load("/home/odri/git/abonnefoy/Motion/Logs/one_leg_position.npz") # replay = np.load("/home/odri/git/abonnefoy/Motion/Logs/push_up_position.npz") replay = np.load("/home/odri/git/abonnefoy/Motion/Logs/full_push_up.npz") - replay_q = replay['q'][7:,1:].transpose().copy() - replay_v = replay['v'][6:,1:].transpose().copy() + replay_q = replay['q'][7:, 1:].transpose().copy() + replay_v = replay['v'][6:, 1:].transpose().copy() replay_tau = replay['tau'].transpose().copy() params.N_SIMULATION = replay_q.shape[0] N = replay_q.shape[0] - replay_P = 6.0 * np.ones((N, 12)) # replay["P"] - replay_D = 0.3 * np.ones((N, 12)) # replay["D"] + replay_P = 6.0 * np.ones((N, 12)) # replay["P"] + replay_D = 0.3 * np.ones((N, 12)) # replay["D"] # 0.09547498, 1.25215899, -2.01927128, -0.09552912, 1.25175677, # -2.01855657, 0.52255345, 1.34166507, 0.11203987, -0.52311626, # 1.34141582, 0.11178296] - # replay_q[0, :] = np.array([0.0, 0.3, 0.0] * 4) - # Enable or disable PyBullet GUI if not params.SIMULATION: params.enable_pyb_GUI = False @@ -95,12 +117,6 @@ def control_loop(name_interface_clone=None, des_vel_analysis=None): q_init = (replay_q[0, :]).copy() params.q_init = q_init.tolist() - """from IPython import embed - from matplotlib import pyplot as plt - embed()""" - - #### - if params.SIMULATION: device = PyBulletSimulator() qc = None @@ -111,9 +127,6 @@ def control_loop(name_interface_clone=None, des_vel_analysis=None): if params.LOGGING or params.PLOTTING: loggerSensors = LoggerSensors(device, qualisys=qc, logSize=params.N_SIMULATION-3) - # Number of motors - nb_motors = 12 - # Initiate communication with the device and calibrate encoders if params.SIMULATION: device.Init(calibrateEncoders=True, q_init=q_init, envID=params.envID, @@ -157,19 +170,14 @@ def control_loop(name_interface_clone=None, des_vel_analysis=None): device.joints.set_desired_velocities(replay_v[k_log_whole, :]) device.joints.set_torques(1.0 * replay_tau[k_log_whole, :]) - """print("--- ", k_log_whole) - print(replay_q[k_log_whole, :]) - print(replay_v[k_log_whole, :])""" - # Call logger if params.LOGGING or params.PLOTTING: loggerSensors.sample(device, qc) # Send command to the robot - for i in range(1): - device.send_command_and_wait_end_of_cycle(params.dt_wbc) + device.send_command_and_wait_end_of_cycle(params.dt_wbc) - t += params.dt_wbc # Increment loop time + t += params.dt_wbc dT_whole = T_whole T_whole = time.time() @@ -178,75 +186,29 @@ def control_loop(name_interface_clone=None, des_vel_analysis=None): # **************************************************************** - if (t >= t_max): - finished = True - else: - finished = False - - # DAMPING TO GET ON THE GROUND PROGRESSIVELY ********************* - t = 0.0 - t_max = 2.5 - while ((not device.is_timeout) and (t < t_max)): - - device.parse_sensor_data() # Retrieve data from IMU and Motion capture - - # Set desired quantities for the actuators - device.joints.set_position_gains(np.zeros(nb_motors)) - device.joints.set_velocity_gains(0.1 * np.ones(nb_motors)) - device.joints.set_desired_positions(np.zeros(nb_motors)) - device.joints.set_desired_velocities(np.zeros(nb_motors)) - device.joints.set_torques(np.zeros(nb_motors)) - - # Send command to the robot - device.send_command_and_wait_end_of_cycle(params.dt_wbc) - if (t % 1) < 5e-5: - print('IMU attitude:', device.imu.attitude_euler) - print('joint pos :', device.joints.positions) - print('joint vel :', device.joints.velocities) - device.robot_interface.PrintStats() - - t += params.dt_wbc - - # FINAL SHUTDOWN ************************************************* - - # Whatever happened we send 0 torques to the motors. - device.joints.set_torques(np.zeros(nb_motors)) + finished = (t >= t_max) + damp_control(device, 12) + + device.joints.set_torques(np.zeros(12)) device.send_command_and_wait_end_of_cycle(params.dt_wbc) if device.is_timeout: print("Masterboard timeout detected.") print("Either the masterboard has been shut down or there has been a connection issue with the cable/wifi.") - # Save the logs of the Logger object if params.LOGGING: loggerSensors.saveAll() print("Log saved") if params.SIMULATION and params.enable_pyb_GUI: - # Disconnect the PyBullet server (also close the GUI) device.Stop() - print("End of script") - return finished, des_vel_analysis -def main(): - """Main function - """ - - parser = argparse.ArgumentParser(description='Playback trajectory to show the extent of solo12 workspace.') - parser.add_argument('-c', - '--clone', - required=False, - help='Name of the clone interface that will reproduce the movement of the first one \ - (use ifconfig in a terminal), for instance "enp1s0"') - +if __name__ == "__main__": os.nice(-20) #  Set the process to highest priority (from -20 highest to +20 lowest) - f, v = control_loop(parser.parse_args().clone) # , np.array([1.5, 0.0, 0.0, 0.0, 0.0, 0.0])) + f, v = control_loop() # , np.array([1.5, 0.0, 0.0, 0.0, 0.0, 0.0])) + print("End of script") print(f, v) quit() - - -if __name__ == "__main__": - main() diff --git a/scripts/plot_IMU_mocap_result.py b/scripts/plot_IMU_mocap_result.py deleted file mode 100644 index 32739a81..00000000 --- a/scripts/plot_IMU_mocap_result.py +++ /dev/null @@ -1,788 +0,0 @@ -import glob -import numpy as np -from matplotlib import pyplot as plt -import pinocchio as pin -import tsid as tsid -from example_robot_data.path import EXAMPLE_ROBOT_DATA_MODEL_DIR as modelPath -from IPython import embed - -import plot_utils -"""import matplotlib as matplotlib -matplotlib.rcParams['pdf.fonttype'] = 42 -matplotlib.rcParams['ps.fonttype'] = 42""" - -# Transform between the base frame and the IMU frame -_1Mi = pin.SE3(pin.Quaternion(np.array([[0.0, 0.0, 0.0, 1.0]]).transpose()), np.array([0.1163, 0.0, 0.02])) - - -def EulerToQuaternion(roll_pitch_yaw): - roll, pitch, yaw = roll_pitch_yaw - sr = np.sin(roll / 2.) - cr = np.cos(roll / 2.) - sp = np.sin(pitch / 2.) - cp = np.cos(pitch / 2.) - sy = np.sin(yaw / 2.) - cy = np.cos(yaw / 2.) - qx = sr * cp * cy - cr * sp * sy - qy = cr * sp * cy + sr * cp * sy - qz = cr * cp * sy - sr * sp * cy - qw = cr * cp * cy + sr * sp * sy - return [qx, qy, qz, qw] - - -def quaternionToRPY(quat): - qx = quat[0] - qy = quat[1] - qz = quat[2] - qw = quat[3] - - rotateXa0 = 2.0 * (qy * qz + qw * qx) - rotateXa1 = qw * qw - qx * qx - qy * qy + qz * qz - rotateX = 0.0 - - if (rotateXa0 != 0.0) and (rotateXa1 != 0.0): - rotateX = np.arctan2(rotateXa0, rotateXa1) - - rotateYa0 = -2.0 * (qx * qz - qw * qy) - rotateY = 0.0 - if (rotateYa0 >= 1.0): - rotateY = np.pi / 2.0 - elif (rotateYa0 <= -1.0): - rotateY = -np.pi / 2.0 - else: - rotateY = np.arcsin(rotateYa0) - - rotateZa0 = 2.0 * (qx * qy + qw * qz) - rotateZa1 = qw * qw + qx * qx - qy * qy - qz * qz - rotateZ = 0.0 - if (rotateZa0 != 0.0) and (rotateZa1 != 0.0): - rotateZ = np.arctan2(rotateZa0, rotateZa1) - - return np.array([[rotateX], [rotateY], [rotateZ]]) - - -def linearly_interpolate_nans(y): - # Fit a linear regression to the non-nan y values - - # Create X matrix for linreg with an intercept and an index - X = np.vstack((np.ones(len(y)), np.arange(len(y)))) - - # Get the non-NaN values of X and y - X_fit = X[:, ~np.isnan(y)] - y_fit = y[~np.isnan(y)].reshape(-1, 1) - - # Estimate the coefficients of the linear regression - beta = np.linalg.lstsq(X_fit.T, y_fit)[0] - - # Fill in all the nan values using the predicted coefficients - y.flat[np.isnan(y)] = np.dot(X[:, np.isnan(y)].T, beta) - return y - - -def cross3(left, right): - """Numpy is inefficient for this - - Args: - left (3x0 array): left term of the cross product - right (3x0 array): right term of the cross product - """ - return np.array([[left[1] * right[2] - left[2] * right[1]], [left[2] * right[0] - left[0] * right[2]], - [left[0] * right[1] - left[1] * right[0]]]) - - -def BaseVelocityFromKinAndIMU(contactFrameId, model, data, IMU_ang_vel): - """Estimate the velocity of the base with forward kinematics using a contact point - that is supposed immobile in world frame - - Args: - contactFrameId (int): ID of the contact point frame (foot frame) - """ - - frameVelocity = pin.getFrameVelocity(model, data, contactFrameId, pin.ReferenceFrame.LOCAL) - framePlacement = pin.updateFramePlacement(model, data, contactFrameId) - - # Angular velocity of the base wrt the world in the base frame (Gyroscope) - _1w01 = IMU_ang_vel.reshape((3, 1)) - # Linear velocity of the foot wrt the base in the base frame - _Fv1F = frameVelocity.linear - # Level arm between the base and the foot - _1F = np.array(framePlacement.translation) - # Orientation of the foot wrt the base - _1RF = framePlacement.rotation - # Linear velocity of the base from wrt world in the base frame - _1v01 = cross3(_1F.ravel(), _1w01.ravel()) - (_1RF @ _Fv1F.reshape((3, 1))) - - # IMU and base frames have the same orientation - _iv0i = _1v01 + cross3(_1Mi.translation.ravel(), _1w01.ravel()) - - return _1v01, np.array(_iv0i) - - -######### -# START # -######### - -on_solo8 = False -"""for name in np.sort(glob.glob('./*.npz')): - print(name)""" -last_date = np.sort(glob.glob('./*.npz'))[-1][-20:] -print(last_date) -last_date = "2020_11_02_13_25.npz" -# last_date = "2020_11_02_13_25.npz" -# Load data file -data = np.load("data_" + last_date) - -# Store content of data in variables - -# From Mocap -mocapPosition = data['mocapPosition'] # Position -mocapOrientationQuat = data['mocapOrientationQuat'] # Orientation as quat -mocapOrientationMat9 = data['mocapOrientationMat9'] # as 3 by 3 matrix -mocapVelocity = data['mocapVelocity'] # Linear velocity -mocapAngularVelocity = data['mocapAngularVelocity'] # Angular velocity - -cheatLinearVelocity = data["baseLinearVelocity"] -cheatForce = data["appliedForce"] -cheatPos = data["dummyPos"] - -# Fill NaN mocap values with linear interpolation -for i in range(3): - mocapPosition[:, i] = linearly_interpolate_nans(mocapPosition[:, i]) - mocapVelocity[:, i] = linearly_interpolate_nans(mocapVelocity[:, i]) - mocapAngularVelocity[:, i] = linearly_interpolate_nans(mocapAngularVelocity[:, i]) - -# From IMU -baseOrientation = data['baseOrientation'] # Orientation as quat -baseLinearAcceleration = data['baseLinearAcceleration'] # Linear acceleration -baseAngularVelocity = data['baseAngularVelocity'] # Angular Vel -# Acceleration with gravity vector -baseAccelerometer = data['baseAccelerometer'] -print(baseAngularVelocity) -# From actuators -torquesFromCurrentMeasurment = data['torquesFromCurrentMeasurment'] # Torques -q_mes = data['q_mes'] # Angular positions -v_mes = data['v_mes'] # Angular velocities - -data_control = np.load("data_control_" + last_date) - -log_tau_ff = data_control['log_tau_ff'] # Position -log_qdes = data_control['log_qdes'] # Orientation as quat -log_vdes = data_control['log_vdes'] # as 3 by 3 matrix -log_q = data_control['log_q'] -log_dq = data_control['log_dq'] - -# From estimator -if data['estimatorVelocity'] is not None: - estimatorHeight = data['estimatorHeight'] - estimatorVelocity = data['estimatorVelocity'] - contactStatus = data['contactStatus'] - referenceVelocity = np.round(data['referenceVelocity'], 3) - log_xfmpc = data['logXFMPC'] - -# Creating time vector -Nlist = np.where(mocapPosition[:, 0] == 0.0)[0] -if len(Nlist) > 0: - N = Nlist[0] -else: - N = mocapPosition.shape[0] -if N == 0: - N = baseOrientation.shape[0] -N = baseOrientation.shape[0] -Tend = N * 0.002 -t = np.linspace(0, Tend, N + 1, endpoint=True) -t = t[:-1] - -# Parameters -dt = 0.0020 -lwdth = 2 - -####### -####### - -imuRPY = np.zeros((N, 3)) -vx_ref = np.zeros((N, 1)) -vy_ref = np.zeros((N, 1)) -vx_est = np.zeros((N, 1)) -vy_est = np.zeros((N, 1)) -for i in range(N): - imuRPY[i, :] = pin.rpy.matrixToRpy(pin.Quaternion(baseOrientation[i:(i + 1), :].transpose()).toRotationMatrix()) - - c = np.cos(imuRPY[i, 2]) - s = np.sin(imuRPY[i, 2]) - R = np.array([[c, -s, 0.0], [s, c, 0.0], [0.0, 0.0, 1.0]]) - v = R.transpose() @ log_xfmpc[i:(i + 1), 6:9].transpose() - # v = pin.Quaternion(baseOrientation[i:(i+1), :].transpose()).toRotationMatrix().transpose() @ log_xfmpc[i:(i+1), 6:9].transpose() - vx_ref[i] = v[0] - vy_ref[i] = v[1] - - v_est = log_dq[0:3, i:(i + 1)] - vx_est[i] = v_est[0] - vy_est[i] = v_est[1] - -plot_forces = True - -c = ["royalblue", "forestgreen"] -lwdth = 1 -velID = 4 -# embed() -# HEIGHT / ROLL / PITCH FIGURE -fig1 = plt.figure(figsize=(7, 4)) -offset_h = cheatPos[0, 2] - log_xfmpc[0, 2] -# Height subplot -ax0 = plt.subplot(3, 1, 1) -plt.plot(t[:-1], cheatPos[:-1, 2] - offset_h, color=c[0], linewidth=lwdth) -plt.plot(t[:-1], log_q[2, :-1], color="darkgreen", linewidth=lwdth) -plt.plot(t[:-1], log_xfmpc[:-1, 2], "darkorange", linewidth=lwdth, linestyle="--") -plt.ylabel("Height [m]", fontsize=14) -plt.legend(["Ground truth", "Estimated", "Command"], prop={'size': 10}, loc=2) - -# Roll subplot -ax1 = plt.subplot(3, 1, 2, sharex=ax0) -plt.plot(t[:-1], imuRPY[:-1, 0], color=c[0], linewidth=lwdth) -plt.plot(t[:-1], log_q[3, :-1], color="darkgreen", linewidth=lwdth) -plt.plot(t[:-1], log_xfmpc[:-1, 3], "darkorange", linewidth=lwdth, linestyle="--") -plt.ylabel("Roll [rad]", fontsize=14) - -if plot_forces: - ax1bis = ax1.twinx() - ax1bis.set_ylabel("$F_y$ [N]", color='k', fontsize=14) - ax1bis.plot(t[:-1], cheatForce[:-1, 1], color="darkviolet", linewidth=lwdth, linestyle="--") - ax1bis.tick_params(axis='y', labelcolor='k') - ax1bis.legend(["Force"], prop={'size': 10}, loc=1) - -# Pitch subplot -ax2 = plt.subplot(3, 1, 3, sharex=ax0) -plt.plot(t[:-1], imuRPY[:-1, 1], color=c[0], linewidth=lwdth) -plt.plot(t[:-1], log_q[4, :-1], color="darkgreen", linewidth=lwdth) -plt.plot(t[:-1], log_xfmpc[:-1, 4], "darkorange", linewidth=lwdth, linestyle="--") -plt.xlabel("Time [s]", fontsize=16) -plt.ylabel("Pitch [rad]", fontsize=14) - -if plot_forces: - ax2bis = ax2.twinx() - ax2bis.set_ylabel("$F_x$ [N]", color='k', fontsize=14) - ax2bis.plot(t[:-1], cheatForce[:-1, 0], color="darkviolet", linewidth=lwdth, linestyle="--") - ax2bis.tick_params(axis='y', labelcolor='k') - ax2bis.legend(["Force"], prop={'size': 10}, loc=1) - -for ax in [ax0, ax1, ax2]: - ax.tick_params(axis='both', which='major', labelsize=10) - ax.tick_params(axis='both', which='minor', labelsize=10) - -plt.savefig("/home/palex/Documents/Travail/Article_10_2020/solopython_02_11_2020ter/Figures/H_R_P_vele" + str(velID) + - last_date[:-4] + ".eps", - dpi="figure", - bbox_inches="tight") -plt.savefig("/home/palex/Documents/Travail/Article_10_2020/solopython_02_11_2020ter/Figures/H_R_P_vele" + str(velID) + - last_date[:-4] + ".png", - dpi=800, - bbox_inches="tight") - -# VX / VY / WYAW FIGURE -fig2 = plt.figure(figsize=(7, 4)) -# Forward velocity subplot -ax0 = plt.subplot(3, 1, 1) -plt.plot(t[:-1], cheatLinearVelocity[:-1, 0], color=c[0], linewidth=lwdth) -plt.plot(t[:-1], vx_est[:-1], color="darkgreen", linewidth=lwdth) -plt.plot(t[:-1], vx_ref[:-1], "darkorange", linewidth=lwdth, linestyle="--") -plt.ylabel("$\dot x$ [m/s]", fontsize=14) -ax0.legend(["Ground truth", "Estimated", "Command"], prop={'size': 10}, loc=2) - -if plot_forces: - ax0bis = ax0.twinx() - ax0bis.set_ylabel("$F_x$ [N]", color='k', fontsize=14) - ax0bis.plot(t[:-1], cheatForce[:-1, 0], color="darkviolet", linewidth=lwdth, linestyle="--") - ax0bis.tick_params(axis='y', labelcolor='k') - ax0bis.legend(["Force"], prop={'size': 10}, loc=1) - -# Lateral velocity subplot -ax1 = plt.subplot(3, 1, 2, sharex=ax0) -plt.plot(t[:-1], cheatLinearVelocity[:-1, 1], color=c[0], linewidth=lwdth) -plt.plot(t[:-1], vy_est[:-1], color="darkgreen", linewidth=lwdth) -plt.plot(t[:-1], vy_ref[:-1], "darkorange", linewidth=lwdth, linestyle="--") -plt.ylabel("$\dot y$ [m/s]", fontsize=14) -#ax1.legend(["Ground truth", "Estimated", "Command"], prop={'size': 10}, loc=2) - -if plot_forces: - ax1bis = ax1.twinx() - ax1bis.set_ylabel("$F_y$ [N]", color='k', fontsize=14) - ax1bis.plot(t[:-1], cheatForce[:-1, 1], color="darkviolet", linewidth=lwdth, linestyle="--") - ax1bis.tick_params(axis='y', labelcolor='k') - ax1bis.legend(["Force"], prop={'size': 10}, loc=1) - -# Angular velocity yaw subplot -ax2 = plt.subplot(3, 1, 3, sharex=ax0) -plt.plot(t[:-1], baseAngularVelocity[:-1, 2], color=c[0], linewidth=lwdth) -plt.plot(t[:-1], log_dq[5, :-1], color="darkgreen", linewidth=lwdth) -plt.plot(t[:-1], log_xfmpc[:-1, 11], "darkorange", linewidth=lwdth, linestyle="--") -plt.ylabel("$\dot \omega_z$ [rad/s]", fontsize=16) -plt.xlabel("Time [s]", fontsize=14) -#ax2.legend(["Ground truth", "Estimated", "Command"], prop={'size': 10}, loc=2) - -for ax in [ax0, ax1, ax2]: - ax.tick_params(axis='both', which='major', labelsize=10) - ax.tick_params(axis='both', which='minor', labelsize=10) - -plt.savefig("/home/palex/Documents/Travail/Article_10_2020/solopython_02_11_2020ter/Figures/Vx_Vy_Wyaw_vele" + - str(velID) + last_date[:-4] + ".eps", - dpi="figure", - bbox_inches="tight") -plt.savefig("/home/palex/Documents/Travail/Article_10_2020/solopython_02_11_2020ter/Figures/Vx_Vy_Wyaw_vele" + - str(velID) + last_date[:-4] + ".png", - dpi=800, - bbox_inches="tight") - -plt.show(block=True) - -######## -######## - -# embed() -# X_F_MPC -index = [1, 5, 9, 2, 6, 10, 3, 7, 11, 4, 8, 12] -lgd1 = ["Ctct force X", "Ctct force Y", "Ctct force Z"] -lgd2 = ["FL", "FR", "HL", "HR"] -plt.figure() -for i in range(12): - if i == 0: - ax0 = plt.subplot(3, 4, index[i]) - else: - plt.subplot(3, 4, index[i], sharex=ax0) - plt.plot(log_xfmpc[:, i], "b", linewidth=2) - # plt.ylabel(lgd[i]) -plt.suptitle("b_xfmpc") - -plt.figure() -for i in range(12): - if i == 0: - ax0 = plt.subplot(3, 4, index[i]) - else: - plt.subplot(3, 4, index[i], sharex=ax0) - - h1, = plt.plot(log_xfmpc[:, 12 + i], "b", linewidth=5) - - plt.xlabel("Time [s]") - plt.ylabel(lgd1[i % 3] + " " + lgd2[int(i / 3)]) - - if (i % 3) == 2: - plt.ylim([-1.0, 15.0]) - else: - plt.ylim([-1.5, 1.5]) - -plt.suptitle("b_xfmpc forces") - -# plt.show(block=True) - -############### -# ORIENTATION # -############### - -mocapRPY = np.zeros((N, 3)) -imuRPY = np.zeros((N, 3)) -for i in range(N): - mocapRPY[i, :] = pin.rpy.matrixToRpy(mocapOrientationMat9[i, :, :]) - imuRPY[i, :] = pin.rpy.matrixToRpy(pin.Quaternion(baseOrientation[i:(i + 1), :].transpose()).toRotationMatrix()) - -fig = plt.figure() -# Roll orientation -ax0 = plt.subplot(2, 1, 1) -plt.plot(t, mocapRPY[:N, 0], "darkorange", linewidth=lwdth) -plt.plot(t, imuRPY[:N, 0], "royalblue", linewidth=lwdth) -plt.ylabel("Roll") -plt.legend(["Mocap", "IMU"], prop={'size': 8}) -# Pitch orientation -ax1 = plt.subplot(2, 1, 2, sharex=ax0) -plt.plot(t, mocapRPY[:N, 1], "darkorange", linewidth=lwdth) -plt.plot(t, imuRPY[:N, 1], "royalblue", linewidth=lwdth) -plt.ylabel("Pitch") -plt.xlabel("Time [s]") - -# embed() - -################### -# LINEAR VELOCITY # -################### -mocapBaseLinearVelocity = np.zeros((N, 3)) -imuBaseLinearVelocity = np.zeros((N, 3)) -for i in range(N): - mocapBaseLinearVelocity[i, :] = ( - (mocapOrientationMat9[i, :, :]) @ (mocapVelocity[i:(i + 1), :]).transpose()).ravel() - if i == 0: - imuBaseLinearVelocity[i, :] = mocapBaseLinearVelocity[0, :] - else: - imuBaseLinearVelocity[i, :] = imuBaseLinearVelocity[i - 1, :] + dt * baseLinearAcceleration[i - 1, :] - -fig = plt.figure() -# X linear velocity -ax0 = plt.subplot(3, 1, 1) -plt.plot(t, mocapBaseLinearVelocity[:N, 0], "darkorange", linewidth=lwdth) -plt.plot(t, imuBaseLinearVelocity[:N, 0], "royalblue", linewidth=lwdth) -if data['estimatorVelocity'] is not None: - plt.plot(t, estimatorVelocity[:N, 0], "darkgreen", linewidth=lwdth) -plt.plot(t, referenceVelocity[:N, 0], color="darkviolet", linewidth=lwdth) -plt.ylabel("$\dot x$ [m/s]") -plt.legend(["Mocap", "IMU", "Estimator", "Reference"], prop={'size': 8}) -# Y linear velocity -ax1 = plt.subplot(3, 1, 2, sharex=ax0) -plt.plot(t, mocapBaseLinearVelocity[:N, 1], "darkorange", linewidth=lwdth) -plt.plot(t, imuBaseLinearVelocity[:N, 1], "royalblue", linewidth=lwdth) -if data['estimatorVelocity'] is not None: - plt.plot(t, estimatorVelocity[:N, 1], "darkgreen", linewidth=lwdth) -plt.plot(t, referenceVelocity[:N, 1], color="darkviolet", linewidth=lwdth) -plt.ylabel("$\dot y$ [m/s]") -# Z linear velocity -ax1 = plt.subplot(3, 1, 3, sharex=ax0) -plt.plot(t, mocapBaseLinearVelocity[:N, 2], "darkorange", linewidth=lwdth) -plt.plot(t, imuBaseLinearVelocity[:N, 2], "royalblue", linewidth=lwdth) -if data['estimatorVelocity'] is not None: - plt.plot(t, estimatorVelocity[:N, 2], "darkgreen", linewidth=lwdth) -plt.plot(t, referenceVelocity[:N, 2], color="darkviolet", linewidth=lwdth) -plt.ylabel("$\dot z$ [m/s]") -plt.xlabel("Time [s]") - -###################### -# ANGULAR VELOCITIES # -###################### -mocapBaseAngularVelocity = np.zeros(mocapAngularVelocity.shape) -for i in range(N): - #mocapBaseAngularVelocity[i, :] = ((mocapOrientationMat9[i, :, :]) @ (mocapAngularVelocity[i:(i+1), :]).transpose()).ravel() - mocapBaseAngularVelocity[i, :] = (mocapAngularVelocity[i:(i + 1), :]).transpose().ravel() - -fig = plt.figure() -# Angular velocity X subplot -ax0 = plt.subplot(3, 1, 1) -plt.plot(t, mocapBaseAngularVelocity[:N, 0], "darkorange", linewidth=lwdth) -plt.plot(t, baseAngularVelocity[:N, 0], "royalblue", linewidth=lwdth * 2) -plt.plot(t, referenceVelocity[:N, 3], color="darkviolet", linewidth=lwdth) -plt.ylabel("$\dot \phi$ [rad/s]") -plt.legend(["Mocap", "IMU", "Reference"], prop={'size': 8}) -# Angular velocity Y subplot -ax1 = plt.subplot(3, 1, 2, sharex=ax0) -plt.plot(t, mocapBaseAngularVelocity[:N, 1], "darkorange", linewidth=lwdth) -plt.plot(t, baseAngularVelocity[:N, 1], "royalblue", linewidth=lwdth) -plt.plot(t, referenceVelocity[:N, 4], color="darkviolet", linewidth=lwdth) -plt.ylabel("$\dot \\theta$ [rad/s]") -# Angular velocity Z subplot -ax2 = plt.subplot(3, 1, 3, sharex=ax0) -plt.plot(t, mocapBaseAngularVelocity[:N, 2], "darkorange", linewidth=lwdth) -plt.plot(t, baseAngularVelocity[:N, 2], "royalblue", linewidth=lwdth) -plt.plot(t, referenceVelocity[:N, 5], color="darkviolet", linewidth=lwdth) -plt.ylabel("$\dot \psi$ [rad/s]") -plt.xlabel("Time [s]") - -####################### -# LINEAR ACCELERATION # -####################### - -fig = plt.figure() -# X linear acc -ax0 = plt.subplot(3, 1, 1) -plt.plot(t, baseLinearAcceleration[:N, 0], "royalblue", linewidth=lwdth) -plt.ylabel("$\ddot x$ [m/s^2]") -plt.legend(["IMU"], prop={'size': 8}) -# Y linear acc -ax1 = plt.subplot(3, 1, 2, sharex=ax0) -plt.plot(t, baseLinearAcceleration[:N, 1], "royalblue", linewidth=lwdth) -plt.ylabel("$\ddot y$ [m/s^2]") -# Z linear acc -ax1 = plt.subplot(3, 1, 3, sharex=ax0) -plt.plot(t, baseLinearAcceleration[:N, 2], "royalblue", linewidth=lwdth) -plt.ylabel("$\ddot z$ [m/s^2]") -plt.xlabel("Time [s]") - -#################### -# JOYSTICK CONTROL # -#################### - -fig = plt.figure() -# X linear velocity -ax0 = plt.subplot(3, 1, 1) -plt.plot(t, mocapBaseLinearVelocity[:N, 0], "darkorange", linewidth=lwdth) -if data['estimatorVelocity'] is not None: - plt.plot(t, estimatorVelocity[:N, 0], "darkgreen", linewidth=lwdth) -plt.plot(t, referenceVelocity[:N, 0], color="darkviolet", linewidth=lwdth) -plt.ylabel("$\dot x$ [m/s]") -plt.legend(["Mocap", "Estimator", "Reference"], prop={'size': 8}) -# Y linear velocity -ax1 = plt.subplot(3, 1, 2, sharex=ax0) -plt.plot(t, mocapBaseLinearVelocity[:N, 1], "darkorange", linewidth=lwdth) -if data['estimatorVelocity'] is not None: - plt.plot(t, estimatorVelocity[:N, 1], "darkgreen", linewidth=lwdth) -plt.plot(t, referenceVelocity[:N, 1], color="darkviolet", linewidth=lwdth) -plt.ylabel("$\dot y$ [m/s]") -# Z linear velocity -ax1 = plt.subplot(3, 1, 3, sharex=ax0) -plt.plot(t, mocapBaseAngularVelocity[:N, 2], "darkorange", linewidth=lwdth) -plt.plot(t, baseAngularVelocity[:N, 2], "royalblue", linewidth=lwdth) -plt.plot(t, referenceVelocity[:N, 5], color="darkviolet", linewidth=lwdth) -plt.ylabel("$\dot \psi$ [rad/s]") -plt.xlabel("Time [s]") -plt.suptitle("Tracking of the velocity command sent to the robot") - -############# -# ACTUATORS # -############# - -index = [1, 5, 2, 6, 3, 7, 4, 8] -plt.figure() -for i in range(8): - if i == 0: - ax0 = plt.subplot(2, 4, index[i]) - else: - plt.subplot(2, 4, index[i], sharex=ax0) - plt.plot(t, torquesFromCurrentMeasurment[:N, i], "forestgreen", linewidth=lwdth) - - if (i % 2 == 1): - plt.xlabel("Time [s]") - if i <= 1: - plt.ylabel("Torques [N.m]") - -contact_state = np.zeros((N, 4)) -margin = 25 -treshold = 0.4 -for i in range(4): - state = 0 - front_up = 0 - front_down = 0 - for j in range(N): - if (state == 0) and (np.abs(torquesFromCurrentMeasurment[j, 2 * i + 1]) >= treshold): - state = 1 - front_up = j - if (state == 1) and (np.abs(torquesFromCurrentMeasurment[j, 2 * i + 1]) < treshold): - state = 0 - front_down = j - l = np.min((front_up + margin, N)) - u = np.max((front_down - margin, 0)) - contact_state[l:u, i] = 1 - -plt.figure() -for i in range(4): - if i == 0: - ax0 = plt.subplot(1, 4, i + 1) - else: - plt.subplot(1, 4, i + 1, sharex=ax0) - plt.plot(t, torquesFromCurrentMeasurment[:N, 2 * i + 1]) - plt.plot(t, contact_state[:N, i]) - plt.legend(["Torque", "Estimated contact state"], prop={'size': 8}) -"""fig = plt.figure() -# Angular velocity X subplot -ax0 = plt.subplot(3, 1, 1) -plt.plot(t, torquesFromCurrentMeasurment[:N, - 0], "forestgreen", linewidth=lwdth) -plt.ylabel("Torques [N.m]") -# Angular velocity Y subplot -ax1 = plt.subplot(3, 1, 2, sharex=ax0) -plt.plot(t, q_mes[:N, 0], "forestgreen", linewidth=lwdth) -plt.ylabel("Angular position [rad]") -# Angular velocity Z subplot -ax2 = plt.subplot(3, 1, 3, sharex=ax0) -plt.plot(t, v_mes[:N, 2], "forestgreen", linewidth=lwdth) -plt.ylabel("Angular velocity [rad/s]") -plt.xlabel("Time [s]")""" - -# Set the paths where the urdf and srdf file of the robot are registered -if on_solo8: - urdf = modelPath + "/solo_description/robots/solo.urdf" -else: - urdf = modelPath + "/solo_description/robots/solo12.urdf" -srdf = modelPath + "/solo_description/srdf/solo.srdf" -vector = pin.StdVec_StdString() -vector.extend(item for item in modelPath) - -# Create the robot wrapper from the urdf model (which has no free flyer) and add a free flyer -robot = tsid.RobotWrapper(urdf, vector, pin.JointModelFreeFlyer(), False) -model = robot.model() - -# Creation of the Invverse Dynamics HQP problem using the robot -# accelerations (base + joints) and the contact forces -invdyn = tsid.InverseDynamicsFormulationAccForce("tsid", robot, False) - -# Compute the problem data with a solver based on EiQuadProg -t0 = 0.0 -if on_solo8: - q_FK = np.zeros((15, 1)) -else: - q_FK = np.zeros((19, 1)) -q_FK[:7, 0] = np.array([0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 1.0]) -RPY = quaternionToRPY(baseOrientation.ravel()) -IMU_ang_pos = np.zeros(4) -IMU_ang_pos[:] = EulerToQuaternion([RPY[0], RPY[1], 0.0]) -q_FK[3:7, 0] = IMU_ang_pos - -v_FK = np.zeros((q_FK.shape[0] - 1, 1)) -invdyn.computeProblemData(t0, q_FK, v_FK) -data = invdyn.data() - -# Feet indexes -if on_solo8: - indexes = [8, 14, 20, 26] # solo8 -else: - indexes = [10, 18, 26, 34] # solo12 -alpha = 0.98 -filteredLinearVelocity = np.zeros((N, 3)) -"""for a in range(len(model.frames)): - print(a) - print(model.frames[a])""" -FK_lin_vel_log = np.nan * np.zeros((N, 3)) -iFK_lin_vel_log = np.nan * np.zeros((N, 3)) -rms_x = [] -rms_y = [] -rms_z = [] -irms_x = [] -irms_y = [] -irms_z = [] -alphas = [0.97] # [0.01*i for i in range(100)] -i_not_nan = np.where(np.logical_not(np.isnan(mocapBaseLinearVelocity[:, 0]))) -i_not_nan = (i_not_nan[0])[(i_not_nan[0] < 9600)] -for alpha in alphas: - print(alpha) - filteredLinearVelocity = np.zeros((N, 3)) - ifilteredLinearVelocity = np.zeros((N, 3)) - for i in range(N): - # Update estimator FK model - q_FK[7:, 0] = q_mes[i, :] # Position of actuators - v_FK[6:, 0] = v_mes[i, :] # Velocity of actuators - - pin.forwardKinematics(model, data, q_FK, v_FK) - - # Get estimated velocity from updated model - cpt = 0 - vel_est = np.zeros((3, )) - ivel_est = np.zeros((3, )) - for j in (np.where(contactStatus[i, :] == 1))[0]: - vel_estimated_baseframe, _iv0i = BaseVelocityFromKinAndIMU(indexes[j], model, data, - baseAngularVelocity[i, :]) - - cpt += 1 - vel_est += vel_estimated_baseframe[:, 0] - ivel_est = ivel_est + _iv0i.ravel() - if cpt > 0: - FK_lin_vel = vel_est / cpt # average of all feet in contact - iFK_lin_vel = ivel_est / cpt - - filteredLinearVelocity[i, :] = alpha * (filteredLinearVelocity[i - 1, :] + - baseLinearAcceleration[i, :] * dt) + (1 - alpha) * FK_lin_vel - FK_lin_vel_log[i, :] = FK_lin_vel - - # Get previous base vel wrt world in base frame into IMU frame - i_filt_lin_vel = ifilteredLinearVelocity[i-1, :] + \ - cross3(_1Mi.translation.ravel(), - baseAngularVelocity[i, :]).ravel() - - # Merge IMU base vel wrt world in IMU frame with FK base vel wrt world in IMU frame - i_merged_lin_vel = alpha * \ - (i_filt_lin_vel + - baseLinearAcceleration[i, :] * dt) + (1 - alpha) * iFK_lin_vel.ravel() - """print("##") - print(filteredLinearVelocity[i, :]) - print(i_merged_lin_vel)""" - # Get merged base vel wrt world in IMU frame into base frame - ifilteredLinearVelocity[i, :] = np.array( - i_merged_lin_vel + cross3(-_1Mi.translation.ravel(), baseAngularVelocity[i, :]).ravel()) - #print(ifilteredLinearVelocity[i, :]) - """if np.array_equal(filteredLinearVelocity[i, :], ifilteredLinearVelocity[i, :]): - print("Same values") - - else: - print("Different") - print(filteredLinearVelocity[i, :]) - print(ifilteredLinearVelocity[i, :])""" - - else: - filteredLinearVelocity[i, :] = filteredLinearVelocity[i - 1, :] + baseLinearAcceleration[i, :] * dt - - # Get previous base vel wrt world in base frame into IMU frame - i_filt_lin_vel = ifilteredLinearVelocity[i-1, :] + \ - cross3(_1Mi.translation.ravel(), - baseAngularVelocity[i, :]).ravel() - # Merge IMU base vel wrt world in IMU frame with FK base vel wrt world in IMU frame - i_merged_lin_vel = i_filt_lin_vel + \ - baseLinearAcceleration[i, :] * dt - # Get merged base vel wrt world in IMU frame into base frame - ifilteredLinearVelocity[i, :] = i_merged_lin_vel + \ - cross3(-_1Mi.translation.ravel(), - baseAngularVelocity[i, :]).ravel() - - rms_x.append( - np.sqrt(np.mean(np.square(filteredLinearVelocity[i_not_nan, 0] - mocapBaseLinearVelocity[i_not_nan, 0])))) - rms_y.append( - np.sqrt(np.mean(np.square(filteredLinearVelocity[i_not_nan, 1] - mocapBaseLinearVelocity[i_not_nan, 1])))) - rms_z.append( - np.sqrt(np.mean(np.square(filteredLinearVelocity[i_not_nan, 2] - mocapBaseLinearVelocity[i_not_nan, 2])))) - irms_x.append( - np.sqrt(np.mean(np.square(ifilteredLinearVelocity[i_not_nan, 0] - mocapBaseLinearVelocity[i_not_nan, 0])))) - irms_y.append( - np.sqrt(np.mean(np.square(ifilteredLinearVelocity[i_not_nan, 1] - mocapBaseLinearVelocity[i_not_nan, 1])))) - irms_z.append( - np.sqrt(np.mean(np.square(ifilteredLinearVelocity[i_not_nan, 2] - mocapBaseLinearVelocity[i_not_nan, 2])))) - -plt.figure() -plt.plot(alphas, rms_x) -plt.plot(alphas, rms_y) -plt.plot(alphas, rms_z) -plt.plot(alphas, irms_x) -plt.plot(alphas, irms_y) -plt.plot(alphas, irms_z) -plt.legend(["RMS X", "RMS Y", "RMS Z", "New RMS X", "New RMS Y", "New RMS Z"], prop={'size': 8}) -plt.xlabel("Alpha") -plt.ylabel("RMS erreur en vitesse") - -fc = 10 -y = 1 - np.cos(2 * np.pi * fc * dt) -alpha_v = -y + np.sqrt(y * y + 2 * y) -lowpass_ifilteredLinearVelocity = np.zeros(ifilteredLinearVelocity.shape) -lowpass_ifilteredLinearVelocity[0, :] = ifilteredLinearVelocity[0, :] -for k in range(1, N): - lowpass_ifilteredLinearVelocity[ - k, :] = (1 - alpha_v) * lowpass_ifilteredLinearVelocity[k - 1, :] + alpha_v * ifilteredLinearVelocity[k, :] - -plt.figure() -plt.plot(t, filteredLinearVelocity[:N, 0], linewidth=3) -plt.plot(t, ifilteredLinearVelocity[:N, 0], linewidth=3, linestyle="--") -plt.plot(t, mocapBaseLinearVelocity[:N, 0], linewidth=3) -plt.plot(t, lowpass_ifilteredLinearVelocity[:N, 0], color="darkviolet", linewidth=3) -# plt.plot(t, FK_lin_vel_log[:N, 0], color="darkviolet", linestyle="--") -"""plt.plot(t, baseLinearAcceleration[:N, 0], linestyle="--")""" -plt.legend(["Filtered", "New Filtered", "Mocap"], prop={'size': 8}) -# plt.show() - -data_control = np.load("data_control_" + last_date) - -log_tau_ff = data_control['log_tau_ff'] # Position -log_qdes = data_control['log_qdes'] # Orientation as quat -log_vdes = data_control['log_vdes'] # as 3 by 3 matrix -log_q = data_control['log_q'] - -index12 = [1, 5, 9, 2, 6, 10, 3, 7, 11, 4, 8, 12] -plt.figure() -for i in range(12): - if i == 0: - ax0 = plt.subplot(3, 4, index12[i]) - else: - plt.subplot(3, 4, index12[i], sharex=ax0) - plt.plot(t, log_qdes[i, :], color='r', linewidth=lwdth) - plt.plot(t, q_mes[:, i], color='b', linewidth=lwdth) - plt.legend(["Qdes", "Qmes"], prop={'size': 8}) - -plt.figure() -for i in range(12): - if i == 0: - ax0 = plt.subplot(3, 4, index12[i]) - else: - plt.subplot(3, 4, index12[i], sharex=ax0) - plt.plot(t, log_vdes[i, :], color='r', linewidth=lwdth) - plt.plot(t, v_mes[:, i], color='b', linewidth=lwdth) - plt.legend(["Vdes", "Vmes"], prop={'size': 8}) - -# Z linear velocity -plt.figure() -for i in range(12): - if i == 0: - ax0 = plt.subplot(3, 4, index12[i]) - else: - plt.subplot(3, 4, index12[i], sharex=ax0) - plt.plot(t, log_tau_ff[i, :], color='r', linewidth=lwdth) - plt.plot(t, torquesFromCurrentMeasurment[:, i], color='b', linewidth=lwdth) - plt.legend(["Tau_FF", "TAU"], prop={'size': 8}) - -plt.show(block=True) diff --git a/scripts/plot_IMU_mocap_result_bis.py b/scripts/plot_IMU_mocap_result_bis.py deleted file mode 100644 index 985c69d0..00000000 --- a/scripts/plot_IMU_mocap_result_bis.py +++ /dev/null @@ -1,802 +0,0 @@ -import glob -import numpy as np -from matplotlib import pyplot as plt -import pinocchio as pin -import tsid as tsid -from example_robot_data.path import EXAMPLE_ROBOT_DATA_MODEL_DIR as modelPath -from IPython import embed - -import plot_utils -"""import matplotlib as matplotlib -matplotlib.rcParams['pdf.fonttype'] = 42 -matplotlib.rcParams['ps.fonttype'] = 42 -matplotlib.rcParams['text.usetex'] = True""" - -# Transform between the base frame and the IMU frame -_1Mi = pin.SE3(pin.Quaternion(np.array([[0.0, 0.0, 0.0, 1.0]]).transpose()), np.array([0.1163, 0.0, 0.02])) - - -def EulerToQuaternion(roll_pitch_yaw): - roll, pitch, yaw = roll_pitch_yaw - sr = np.sin(roll / 2.) - cr = np.cos(roll / 2.) - sp = np.sin(pitch / 2.) - cp = np.cos(pitch / 2.) - sy = np.sin(yaw / 2.) - cy = np.cos(yaw / 2.) - qx = sr * cp * cy - cr * sp * sy - qy = cr * sp * cy + sr * cp * sy - qz = cr * cp * sy - sr * sp * cy - qw = cr * cp * cy + sr * sp * sy - return [qx, qy, qz, qw] - - -def quaternionToRPY(quat): - qx = quat[0] - qy = quat[1] - qz = quat[2] - qw = quat[3] - - rotateXa0 = 2.0 * (qy * qz + qw * qx) - rotateXa1 = qw * qw - qx * qx - qy * qy + qz * qz - rotateX = 0.0 - - if (rotateXa0 != 0.0) and (rotateXa1 != 0.0): - rotateX = np.arctan2(rotateXa0, rotateXa1) - - rotateYa0 = -2.0 * (qx * qz - qw * qy) - rotateY = 0.0 - if (rotateYa0 >= 1.0): - rotateY = np.pi / 2.0 - elif (rotateYa0 <= -1.0): - rotateY = -np.pi / 2.0 - else: - rotateY = np.arcsin(rotateYa0) - - rotateZa0 = 2.0 * (qx * qy + qw * qz) - rotateZa1 = qw * qw + qx * qx - qy * qy - qz * qz - rotateZ = 0.0 - if (rotateZa0 != 0.0) and (rotateZa1 != 0.0): - rotateZ = np.arctan2(rotateZa0, rotateZa1) - - return np.array([[rotateX], [rotateY], [rotateZ]]) - - -def linearly_interpolate_nans(y): - # Fit a linear regression to the non-nan y values - - # Create X matrix for linreg with an intercept and an index - X = np.vstack((np.ones(len(y)), np.arange(len(y)))) - - # Get the non-NaN values of X and y - X_fit = X[:, ~np.isnan(y)] - y_fit = y[~np.isnan(y)].reshape(-1, 1) - - # Estimate the coefficients of the linear regression - beta = np.linalg.lstsq(X_fit.T, y_fit)[0] - - # Fill in all the nan values using the predicted coefficients - y.flat[np.isnan(y)] = np.dot(X[:, np.isnan(y)].T, beta) - return y - - -def cross3(left, right): - """Numpy is inefficient for this - - Args: - left (3x0 array): left term of the cross product - right (3x0 array): right term of the cross product - """ - return np.array([[left[1] * right[2] - left[2] * right[1]], [left[2] * right[0] - left[0] * right[2]], - [left[0] * right[1] - left[1] * right[0]]]) - - -def BaseVelocityFromKinAndIMU(contactFrameId, model, data, IMU_ang_vel): - """Estimate the velocity of the base with forward kinematics using a contact point - that is supposed immobile in world frame - - Args: - contactFrameId (int): ID of the contact point frame (foot frame) - """ - - frameVelocity = pin.getFrameVelocity(model, data, contactFrameId, pin.ReferenceFrame.LOCAL) - framePlacement = pin.updateFramePlacement(model, data, contactFrameId) - - # Angular velocity of the base wrt the world in the base frame (Gyroscope) - _1w01 = IMU_ang_vel.reshape((3, 1)) - # Linear velocity of the foot wrt the base in the base frame - _Fv1F = frameVelocity.linear - # Level arm between the base and the foot - _1F = np.array(framePlacement.translation) - # Orientation of the foot wrt the base - _1RF = framePlacement.rotation - # Linear velocity of the base from wrt world in the base frame - _1v01 = cross3(_1F.ravel(), _1w01.ravel()) - (_1RF @ _Fv1F.reshape((3, 1))) - - # IMU and base frames have the same orientation - _iv0i = _1v01 + cross3(_1Mi.translation.ravel(), _1w01.ravel()) - - return _1v01, np.array(_iv0i) - - -######### -# START # -######### - -on_solo8 = False -"""for name in np.sort(glob.glob('./*.npz')): - print(name)""" -last_date = np.sort(glob.glob('./*.npz'))[-1][-20:] -print(last_date) -# last_date = "2020_11_02_13_25.npz" -# Load data file -data = np.load("data_" + last_date) - -# Store content of data in variables - -# From Mocap -mocapPosition = data['mocapPosition'] # Position -mocapOrientationQuat = data['mocapOrientationQuat'] # Orientation as quat -mocapOrientationMat9 = data['mocapOrientationMat9'] # as 3 by 3 matrix -mocapVelocity = data['mocapVelocity'] # Linear velocity -mocapAngularVelocity = data['mocapAngularVelocity'] # Angular velocity - -cheatLinearVelocity = data["baseLinearVelocity"] -cheatForce = data["appliedForce"] -cheatPos = data["dummyPos"] - -# Fill NaN mocap values with linear interpolation -for i in range(3): - mocapPosition[:, i] = linearly_interpolate_nans(mocapPosition[:, i]) - mocapVelocity[:, i] = linearly_interpolate_nans(mocapVelocity[:, i]) - mocapAngularVelocity[:, i] = linearly_interpolate_nans(mocapAngularVelocity[:, i]) - -# From IMU -baseOrientation = data['baseOrientation'] # Orientation as quat -baseLinearAcceleration = data['baseLinearAcceleration'] # Linear acceleration -baseAngularVelocity = data['baseAngularVelocity'] # Angular Vel -# Acceleration with gravity vector -baseAccelerometer = data['baseAccelerometer'] -print(baseAngularVelocity) -# From actuators -torquesFromCurrentMeasurment = data['torquesFromCurrentMeasurment'] # Torques -q_mes = data['q_mes'] # Angular positions -v_mes = data['v_mes'] # Angular velocities - -data_control = np.load("data_control_" + last_date) - -log_tau_ff = data_control['log_tau_ff'] # Position -log_qdes = data_control['log_qdes'] # Orientation as quat -log_vdes = data_control['log_vdes'] # as 3 by 3 matrix -log_q = data_control['log_q'] -log_dq = data_control['log_dq'] - -# From estimator -if data['estimatorVelocity'] is not None: - estimatorHeight = data['estimatorHeight'] - estimatorVelocity = data['estimatorVelocity'] - contactStatus = data['contactStatus'] - referenceVelocity = np.round(data['referenceVelocity'], 3) - log_xfmpc = data['logXFMPC'] - -# Cut before end -S = 3000 -E = -16000 - -# Creating time vector -Nlist = np.where(mocapPosition[:, 0] == 0.0)[0] -if len(Nlist) > 0: - N = Nlist[0] -else: - N = mocapPosition.shape[0] -if N == 0: - N = baseOrientation.shape[0] -N = baseOrientation.shape[0] -Tend = N * 0.002 -t = np.linspace(0, Tend, N + 1, endpoint=True) -t = t[:-1] - -# Parameters -dt = 0.0020 -lwdth = 2 - -####### -####### - -b_v_mocap = np.zeros((N, 3)) -imuRPY = np.zeros((N, 3)) -vx_ref = np.zeros((N, 1)) -vy_ref = np.zeros((N, 1)) -vx_est = np.zeros((N, 1)) -vy_est = np.zeros((N, 1)) -for i in range(N): - imuRPY[i, :] = log_q[3:6, i] - - c = np.cos(imuRPY[i, 2]) - s = np.sin(imuRPY[i, 2]) - R = np.array([[c, -s, 0.0], [s, c, 0.0], [0.0, 0.0, 1.0]]) - v = R.transpose() @ log_xfmpc[i:(i + 1), 6:9].transpose() - # v = pin.Quaternion(baseOrientation[i:(i+1), :].transpose()).toRotationMatrix().transpose() @ log_xfmpc[i:(i+1), 6:9].transpose() - vx_ref[i] = v[0] - vy_ref[i] = v[1] - - v_est = log_dq[0:3, i:(i + 1)] - vx_est[i] = v_est[0] - vy_est[i] = v_est[1] - - b_v_mocap[i, :] = (mocapOrientationMat9[i, :, :].transpose() @ mocapVelocity[i:(i + 1), :].transpose()).ravel() - -mocapRPY = np.zeros((N, 3)) -for i in range(N): - mocapRPY[i, :] = pin.rpy.matrixToRpy(mocapOrientationMat9[i, :, :]) - -plot_forces = False - -c = ["royalblue", "forestgreen"] -lwdth = 1 -velID = 4 - -# HEIGHT / ROLL / PITCH FIGURE -fig1 = plt.figure(figsize=(6, 4)) - -offset_h = np.mean(mocapPosition[S:E, 2]) - np.mean(log_q[2, S:E]) - -mocapPosition[int(23.43 * 500):int(23.84 * 500), :] = np.nan -mocapRPY[int(23.43 * 500):int(23.84 * 500), :] = np.nan -b_v_mocap[int(23.43 * 500):int(23.84 * 500), :] = np.nan -mocapAngularVelocity[int(23.43 * 500):int(23.84 * 500), :] = np.nan - -# Height subplot -ax0 = plt.subplot(3, 1, 1) -plt.plot(t[S:E], mocapPosition[S:E, 2] - offset_h, color=c[0], linewidth=lwdth) -plt.plot(t[S:E], log_q[2, S:E], color="darkgreen", linewidth=lwdth) -plt.plot(t[S:E], log_xfmpc[S:E, 2], "darkorange", linewidth=lwdth, linestyle="--") -plt.ylabel("Height [m]", fontsize=14) - -# Roll subplot -ax1 = plt.subplot(3, 1, 2, sharex=ax0) -plt.plot(t[S:E], mocapRPY[S:E, 0], color=c[0], linewidth=lwdth) -plt.plot(t[S:E], log_q[3, S:E], color="darkgreen", linewidth=lwdth) -plt.plot(t[S:E], log_xfmpc[S:E, 3], "darkorange", linewidth=lwdth, linestyle="--") -plt.ylabel("Roll [rad]", fontsize=14) -plt.legend(["Ground truth", "Estimated", "Command"], prop={'size': 10}, loc=8) - -if plot_forces: - ax1bis = ax1.twinx() - ax1bis.set_ylabel("$F_y$ [N]", color='k') - ax1bis.plot(t[S:E], cheatForce[S:E, 1], color="darkviolet", linewidth=lwdth, linestyle="--") - ax1bis.tick_params(axis='y', labelcolor='k') - ax1bis.legend(["Force"], prop={'size': 16}, loc=1) - -# Pitch subplot -ax2 = plt.subplot(3, 1, 3, sharex=ax0) -plt.plot(t[S:E], mocapRPY[S:E, 1], color=c[0], linewidth=lwdth) -plt.plot(t[S:E], log_q[4, S:E], color="darkgreen", linewidth=lwdth) -plt.plot(t[S:E], log_xfmpc[S:E, 4], "darkorange", linewidth=lwdth, linestyle="--") -plt.xlabel("Time [s]", fontsize=16) -plt.ylabel("Pitch [rad]", fontsize=14) - -if plot_forces: - ax2bis = ax2.twinx() - ax2bis.set_ylabel("$F_x$ [N]", color='k') - ax2bis.plot(t[S:E], cheatForce[S:E, 0], color="darkviolet", linewidth=lwdth, linestyle="--") - ax2bis.tick_params(axis='y', labelcolor='k') - ax2bis.legend(["Force"], prop={'size': 6}, loc=1) - -for ax in [ax0, ax1, ax2]: - ax.tick_params(axis='both', which='major', labelsize=10) - ax.tick_params(axis='both', which='minor', labelsize=10) - -plt.savefig("/home/palex/Documents/Travail/Article_10_2020/solopython_02_11_2020ter/Figures/H_R_P_expe.eps", - dpi=150, - bbox_inches="tight") -plt.savefig("/home/palex/Documents/Travail/Article_10_2020/solopython_02_11_2020ter/Figures/H_R_P_expe.png", - dpi=800, - bbox_inches="tight") - -# VX / VY / WYAW FIGURE -fig2 = plt.figure(figsize=(15, 4)) -# Forward velocity subplot -ax0 = plt.subplot(3, 1, 1) -plt.plot(t[S:E], b_v_mocap[S:E, 0], color=c[0], linewidth=lwdth) -plt.plot(t[S:E], vx_est[S:E], color="darkgreen", linewidth=lwdth) -plt.plot(t[S:E], vx_ref[S:E], "darkorange", linewidth=lwdth, linestyle="--") -plt.ylabel("$\dot x$ [m/s]", fontsize=14) -ax0.legend(["Ground truth", "Estimated", "Command"], prop={'size': 12}, loc=2) - -if plot_forces: - ax0bis = ax0.twinx() - ax0bis.set_ylabel("$F_x$ [N]", color='k') - ax0bis.plot(t[S:E], cheatForce[S:E, 0], color="darkviolet", linewidth=lwdth, linestyle="--") - ax0bis.tick_params(axis='y', labelcolor='k') - ax0bis.legend(["Force"], prop={'size': 16}, loc=1) - -# Lateral velocity subplot -ax1 = plt.subplot(3, 1, 2, sharex=ax0) -plt.plot(t[S:E], b_v_mocap[S:E, 1], color=c[0], linewidth=lwdth) -plt.plot(t[S:E], vy_est[S:E], color="darkgreen", linewidth=lwdth) -plt.plot(t[S:E], vy_ref[S:E], "darkorange", linewidth=lwdth, linestyle="--") -plt.ylabel("$\dot y$ [m/s]", fontsize=14) -#ax1.legend(["Ground truth", "Estimated", "Command"], prop={'size': 10}, loc=2) - -if plot_forces: - ax1bis = ax1.twinx() - ax1bis.set_ylabel("$F_y$ [N]", color='k') - ax1bis.plot(t[S:E], cheatForce[S:E, 1], color="darkviolet", linewidth=lwdth, linestyle="--") - ax1bis.tick_params(axis='y', labelcolor='k') - ax1bis.legend(["Force"], prop={'size': 16}, loc=1) - -# Angular velocity yaw subplot -ax2 = plt.subplot(3, 1, 3, sharex=ax0) -plt.plot(t[S:E], mocapAngularVelocity[S:E, 2], color=c[0], linewidth=lwdth) -plt.plot(t[S:E], log_dq[5, S:E], color="darkgreen", linewidth=lwdth) -plt.plot(t[S:E], log_xfmpc[S:E, 11], "darkorange", linewidth=lwdth, linestyle="--") -plt.ylabel("$\dot \omega_z$ [rad/s]", fontsize=14) -plt.xlabel("Time [s]", fontsize=16) -#ax2.legend(["Ground truth", "Estimated", "Command"], prop={'size': 10}, loc=2) - -for ax in [ax0, ax1, ax2]: - ax.tick_params(axis='both', which='major', labelsize=10) - ax.tick_params(axis='both', which='minor', labelsize=10) - -plt.savefig("/home/palex/Documents/Travail/Article_10_2020/solopython_02_11_2020ter/Figures/Vx_Vy_Wyaw_expe.eps", - dpi=150, - bbox_inches="tight") -plt.savefig("/home/palex/Documents/Travail/Article_10_2020/solopython_02_11_2020ter/Figures/Vx_Vy_Wyaw_expe.png", - dpi=800, - bbox_inches="tight") - -plt.show(block=True) - -######## -######## - -# embed() -# X_F_MPC -index = [1, 5, 9, 2, 6, 10, 3, 7, 11, 4, 8, 12] -lgd1 = ["Ctct force X", "Ctct force Y", "Ctct force Z"] -lgd2 = ["FL", "FR", "HL", "HR"] -plt.figure() -for i in range(12): - if i == 0: - ax0 = plt.subplot(3, 4, index[i]) - else: - plt.subplot(3, 4, index[i], sharex=ax0) - plt.plot(log_xfmpc[:, i], "b", linewidth=2) - # plt.ylabel(lgd[i]) -plt.suptitle("b_xfmpc") - -plt.figure() -for i in range(12): - if i == 0: - ax0 = plt.subplot(3, 4, index[i]) - else: - plt.subplot(3, 4, index[i], sharex=ax0) - - h1, = plt.plot(log_xfmpc[:, 12 + i], "b", linewidth=5) - - plt.xlabel("Time [s]") - plt.ylabel(lgd1[i % 3] + " " + lgd2[int(i / 3)]) - - if (i % 3) == 2: - plt.ylim([-1.0, 15.0]) - else: - plt.ylim([-1.5, 1.5]) - -plt.suptitle("b_xfmpc forces") - -# plt.show(block=True) - -############### -# ORIENTATION # -############### - -mocapRPY = np.zeros((N, 3)) -imuRPY = np.zeros((N, 3)) -for i in range(N): - mocapRPY[i, :] = pin.rpy.matrixToRpy(mocapOrientationMat9[i, :, :]) - imuRPY[i, :] = pin.rpy.matrixToRpy(pin.Quaternion(baseOrientation[i:(i + 1), :].transpose()).toRotationMatrix()) - -fig = plt.figure() -# Roll orientation -ax0 = plt.subplot(2, 1, 1) -plt.plot(t, mocapRPY[:N, 0], "darkorange", linewidth=lwdth) -plt.plot(t, imuRPY[:N, 0], "royalblue", linewidth=lwdth) -plt.ylabel("Roll") -plt.legend(["Mocap", "IMU"], prop={'size': 8}) -# Pitch orientation -ax1 = plt.subplot(2, 1, 2, sharex=ax0) -plt.plot(t, mocapRPY[:N, 1], "darkorange", linewidth=lwdth) -plt.plot(t, imuRPY[:N, 1], "royalblue", linewidth=lwdth) -plt.ylabel("Pitch") -plt.xlabel("Time [s]") - -# embed() - -################### -# LINEAR VELOCITY # -################### -mocapBaseLinearVelocity = np.zeros((N, 3)) -imuBaseLinearVelocity = np.zeros((N, 3)) -for i in range(N): - mocapBaseLinearVelocity[i, :] = ( - (mocapOrientationMat9[i, :, :]) @ (mocapVelocity[i:(i + 1), :]).transpose()).ravel() - if i == 0: - imuBaseLinearVelocity[i, :] = mocapBaseLinearVelocity[0, :] - else: - imuBaseLinearVelocity[i, :] = imuBaseLinearVelocity[i - 1, :] + dt * baseLinearAcceleration[i - 1, :] - -fig = plt.figure() -# X linear velocity -ax0 = plt.subplot(3, 1, 1) -plt.plot(t, mocapBaseLinearVelocity[:N, 0], "darkorange", linewidth=lwdth) -plt.plot(t, imuBaseLinearVelocity[:N, 0], "royalblue", linewidth=lwdth) -if data['estimatorVelocity'] is not None: - plt.plot(t, estimatorVelocity[:N, 0], "darkgreen", linewidth=lwdth) -plt.plot(t, referenceVelocity[:N, 0], color="darkviolet", linewidth=lwdth) -plt.ylabel("$\dot x$ [m/s]") -plt.legend(["Mocap", "IMU", "Estimator", "Reference"], prop={'size': 8}) -# Y linear velocity -ax1 = plt.subplot(3, 1, 2, sharex=ax0) -plt.plot(t, mocapBaseLinearVelocity[:N, 1], "darkorange", linewidth=lwdth) -plt.plot(t, imuBaseLinearVelocity[:N, 1], "royalblue", linewidth=lwdth) -if data['estimatorVelocity'] is not None: - plt.plot(t, estimatorVelocity[:N, 1], "darkgreen", linewidth=lwdth) -plt.plot(t, referenceVelocity[:N, 1], color="darkviolet", linewidth=lwdth) -plt.ylabel("$\dot y$ [m/s]") -# Z linear velocity -ax1 = plt.subplot(3, 1, 3, sharex=ax0) -plt.plot(t, mocapBaseLinearVelocity[:N, 2], "darkorange", linewidth=lwdth) -plt.plot(t, imuBaseLinearVelocity[:N, 2], "royalblue", linewidth=lwdth) -if data['estimatorVelocity'] is not None: - plt.plot(t, estimatorVelocity[:N, 2], "darkgreen", linewidth=lwdth) -plt.plot(t, referenceVelocity[:N, 2], color="darkviolet", linewidth=lwdth) -plt.ylabel("$\dot z$ [m/s]") -plt.xlabel("Time [s]") - -###################### -# ANGULAR VELOCITIES # -###################### -mocapBaseAngularVelocity = np.zeros(mocapAngularVelocity.shape) -for i in range(N): - #mocapBaseAngularVelocity[i, :] = ((mocapOrientationMat9[i, :, :]) @ (mocapAngularVelocity[i:(i+1), :]).transpose()).ravel() - mocapBaseAngularVelocity[i, :] = (mocapAngularVelocity[i:(i + 1), :]).transpose().ravel() - -fig = plt.figure() -# Angular velocity X subplot -ax0 = plt.subplot(3, 1, 1) -plt.plot(t, mocapBaseAngularVelocity[:N, 0], "darkorange", linewidth=lwdth) -plt.plot(t, baseAngularVelocity[:N, 0], "royalblue", linewidth=lwdth * 2) -plt.plot(t, referenceVelocity[:N, 3], color="darkviolet", linewidth=lwdth) -plt.ylabel("$\dot \phi$ [rad/s]") -plt.legend(["Mocap", "IMU", "Reference"], prop={'size': 8}) -# Angular velocity Y subplot -ax1 = plt.subplot(3, 1, 2, sharex=ax0) -plt.plot(t, mocapBaseAngularVelocity[:N, 1], "darkorange", linewidth=lwdth) -plt.plot(t, baseAngularVelocity[:N, 1], "royalblue", linewidth=lwdth) -plt.plot(t, referenceVelocity[:N, 4], color="darkviolet", linewidth=lwdth) -plt.ylabel("$\dot \\theta$ [rad/s]") -# Angular velocity Z subplot -ax2 = plt.subplot(3, 1, 3, sharex=ax0) -plt.plot(t, mocapBaseAngularVelocity[:N, 2], "darkorange", linewidth=lwdth) -plt.plot(t, baseAngularVelocity[:N, 2], "royalblue", linewidth=lwdth) -plt.plot(t, referenceVelocity[:N, 5], color="darkviolet", linewidth=lwdth) -plt.ylabel("$\dot \psi$ [rad/s]") -plt.xlabel("Time [s]") - -####################### -# LINEAR ACCELERATION # -####################### - -fig = plt.figure() -# X linear acc -ax0 = plt.subplot(3, 1, 1) -plt.plot(t, baseLinearAcceleration[:N, 0], "royalblue", linewidth=lwdth) -plt.ylabel("$\ddot x$ [m/s^2]") -plt.legend(["IMU"], prop={'size': 8}) -# Y linear acc -ax1 = plt.subplot(3, 1, 2, sharex=ax0) -plt.plot(t, baseLinearAcceleration[:N, 1], "royalblue", linewidth=lwdth) -plt.ylabel("$\ddot y$ [m/s^2]") -# Z linear acc -ax1 = plt.subplot(3, 1, 3, sharex=ax0) -plt.plot(t, baseLinearAcceleration[:N, 2], "royalblue", linewidth=lwdth) -plt.ylabel("$\ddot z$ [m/s^2]") -plt.xlabel("Time [s]") - -#################### -# JOYSTICK CONTROL # -#################### - -fig = plt.figure() -# X linear velocity -ax0 = plt.subplot(3, 1, 1) -plt.plot(t, mocapBaseLinearVelocity[:N, 0], "darkorange", linewidth=lwdth) -if data['estimatorVelocity'] is not None: - plt.plot(t, estimatorVelocity[:N, 0], "darkgreen", linewidth=lwdth) -plt.plot(t, referenceVelocity[:N, 0], color="darkviolet", linewidth=lwdth) -plt.ylabel("$\dot x$ [m/s]") -plt.legend(["Mocap", "Estimator", "Reference"], prop={'size': 8}) -# Y linear velocity -ax1 = plt.subplot(3, 1, 2, sharex=ax0) -plt.plot(t, mocapBaseLinearVelocity[:N, 1], "darkorange", linewidth=lwdth) -if data['estimatorVelocity'] is not None: - plt.plot(t, estimatorVelocity[:N, 1], "darkgreen", linewidth=lwdth) -plt.plot(t, referenceVelocity[:N, 1], color="darkviolet", linewidth=lwdth) -plt.ylabel("$\dot y$ [m/s]") -# Z linear velocity -ax1 = plt.subplot(3, 1, 3, sharex=ax0) -plt.plot(t, mocapBaseAngularVelocity[:N, 2], "darkorange", linewidth=lwdth) -plt.plot(t, baseAngularVelocity[:N, 2], "royalblue", linewidth=lwdth) -plt.plot(t, referenceVelocity[:N, 5], color="darkviolet", linewidth=lwdth) -plt.ylabel("$\dot \psi$ [rad/s]") -plt.xlabel("Time [s]") -plt.suptitle("Tracking of the velocity command sent to the robot") - -############# -# ACTUATORS # -############# - -index = [1, 5, 2, 6, 3, 7, 4, 8] -plt.figure() -for i in range(8): - if i == 0: - ax0 = plt.subplot(2, 4, index[i]) - else: - plt.subplot(2, 4, index[i], sharex=ax0) - plt.plot(t, torquesFromCurrentMeasurment[:N, i], "forestgreen", linewidth=lwdth) - - if (i % 2 == 1): - plt.xlabel("Time [s]") - if i <= 1: - plt.ylabel("Torques [N.m]") - -contact_state = np.zeros((N, 4)) -margin = 25 -treshold = 0.4 -for i in range(4): - state = 0 - front_up = 0 - front_down = 0 - for j in range(N): - if (state == 0) and (np.abs(torquesFromCurrentMeasurment[j, 2 * i + 1]) >= treshold): - state = 1 - front_up = j - if (state == 1) and (np.abs(torquesFromCurrentMeasurment[j, 2 * i + 1]) < treshold): - state = 0 - front_down = j - l = np.min((front_up + margin, N)) - u = np.max((front_down - margin, 0)) - contact_state[l:u, i] = 1 - -plt.figure() -for i in range(4): - if i == 0: - ax0 = plt.subplot(1, 4, i + 1) - else: - plt.subplot(1, 4, i + 1, sharex=ax0) - plt.plot(t, torquesFromCurrentMeasurment[:N, 2 * i + 1]) - plt.plot(t, contact_state[:N, i]) - plt.legend(["Torque", "Estimated contact state"], prop={'size': 8}) -"""fig = plt.figure() -# Angular velocity X subplot -ax0 = plt.subplot(3, 1, 1) -plt.plot(t, torquesFromCurrentMeasurment[:N, - 0], "forestgreen", linewidth=lwdth) -plt.ylabel("Torques [N.m]") -# Angular velocity Y subplot -ax1 = plt.subplot(3, 1, 2, sharex=ax0) -plt.plot(t, q_mes[:N, 0], "forestgreen", linewidth=lwdth) -plt.ylabel("Angular position [rad]") -# Angular velocity Z subplot -ax2 = plt.subplot(3, 1, 3, sharex=ax0) -plt.plot(t, v_mes[:N, 2], "forestgreen", linewidth=lwdth) -plt.ylabel("Angular velocity [rad/s]") -plt.xlabel("Time [s]")""" - -# Set the paths where the urdf and srdf file of the robot are registered -if on_solo8: - urdf = modelPath + "/solo_description/robots/solo.urdf" -else: - urdf = modelPath + "/solo_description/robots/solo12.urdf" -srdf = modelPath + "/solo_description/srdf/solo.srdf" -vector = pin.StdVec_StdString() -vector.extend(item for item in modelPath) - -# Create the robot wrapper from the urdf model (which has no free flyer) and add a free flyer -robot = tsid.RobotWrapper(urdf, vector, pin.JointModelFreeFlyer(), False) -model = robot.model() - -# Creation of the Invverse Dynamics HQP problem using the robot -# accelerations (base + joints) and the contact forces -invdyn = tsid.InverseDynamicsFormulationAccForce("tsid", robot, False) - -# Compute the problem data with a solver based on EiQuadProg -t0 = 0.0 -if on_solo8: - q_FK = np.zeros((15, 1)) -else: - q_FK = np.zeros((19, 1)) -q_FK[:7, 0] = np.array([0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 1.0]) -RPY = quaternionToRPY(baseOrientation.ravel()) -IMU_ang_pos = np.zeros(4) -IMU_ang_pos[:] = EulerToQuaternion([RPY[0], RPY[1], 0.0]) -q_FK[3:7, 0] = IMU_ang_pos - -v_FK = np.zeros((q_FK.shape[0] - 1, 1)) -invdyn.computeProblemData(t0, q_FK, v_FK) -data = invdyn.data() - -# Feet indexes -if on_solo8: - indexes = [8, 14, 20, 26] # solo8 -else: - indexes = [10, 18, 26, 34] # solo12 -alpha = 0.98 -filteredLinearVelocity = np.zeros((N, 3)) -"""for a in range(len(model.frames)): - print(a) - print(model.frames[a])""" -FK_lin_vel_log = np.nan * np.zeros((N, 3)) -iFK_lin_vel_log = np.nan * np.zeros((N, 3)) -rms_x = [] -rms_y = [] -rms_z = [] -irms_x = [] -irms_y = [] -irms_z = [] -alphas = [0.97] # [0.01*i for i in range(100)] -i_not_nan = np.where(np.logical_not(np.isnan(mocapBaseLinearVelocity[:, 0]))) -i_not_nan = (i_not_nan[0])[(i_not_nan[0] < 9600)] -for alpha in alphas: - print(alpha) - filteredLinearVelocity = np.zeros((N, 3)) - ifilteredLinearVelocity = np.zeros((N, 3)) - for i in range(N): - # Update estimator FK model - q_FK[7:, 0] = q_mes[i, :] # Position of actuators - v_FK[6:, 0] = v_mes[i, :] # Velocity of actuators - - pin.forwardKinematics(model, data, q_FK, v_FK) - - # Get estimated velocity from updated model - cpt = 0 - vel_est = np.zeros((3, )) - ivel_est = np.zeros((3, )) - for j in (np.where(contactStatus[i, :] == 1))[0]: - vel_estimated_baseframe, _iv0i = BaseVelocityFromKinAndIMU(indexes[j], model, data, - baseAngularVelocity[i, :]) - - cpt += 1 - vel_est += vel_estimated_baseframe[:, 0] - ivel_est = ivel_est + _iv0i.ravel() - if cpt > 0: - FK_lin_vel = vel_est / cpt # average of all feet in contact - iFK_lin_vel = ivel_est / cpt - - filteredLinearVelocity[i, :] = alpha * (filteredLinearVelocity[i - 1, :] + - baseLinearAcceleration[i, :] * dt) + (1 - alpha) * FK_lin_vel - FK_lin_vel_log[i, :] = FK_lin_vel - - # Get previous base vel wrt world in base frame into IMU frame - i_filt_lin_vel = ifilteredLinearVelocity[i-1, :] + \ - cross3(_1Mi.translation.ravel(), - baseAngularVelocity[i, :]).ravel() - - # Merge IMU base vel wrt world in IMU frame with FK base vel wrt world in IMU frame - i_merged_lin_vel = alpha * \ - (i_filt_lin_vel + - baseLinearAcceleration[i, :] * dt) + (1 - alpha) * iFK_lin_vel.ravel() - """print("##") - print(filteredLinearVelocity[i, :]) - print(i_merged_lin_vel)""" - # Get merged base vel wrt world in IMU frame into base frame - ifilteredLinearVelocity[i, :] = np.array( - i_merged_lin_vel + cross3(-_1Mi.translation.ravel(), baseAngularVelocity[i, :]).ravel()) - #print(ifilteredLinearVelocity[i, :]) - """if np.array_equal(filteredLinearVelocity[i, :], ifilteredLinearVelocity[i, :]): - print("Same values") - - else: - print("Different") - print(filteredLinearVelocity[i, :]) - print(ifilteredLinearVelocity[i, :])""" - - else: - filteredLinearVelocity[i, :] = filteredLinearVelocity[i - 1, :] + baseLinearAcceleration[i, :] * dt - - # Get previous base vel wrt world in base frame into IMU frame - i_filt_lin_vel = ifilteredLinearVelocity[i-1, :] + \ - cross3(_1Mi.translation.ravel(), - baseAngularVelocity[i, :]).ravel() - # Merge IMU base vel wrt world in IMU frame with FK base vel wrt world in IMU frame - i_merged_lin_vel = i_filt_lin_vel + \ - baseLinearAcceleration[i, :] * dt - # Get merged base vel wrt world in IMU frame into base frame - ifilteredLinearVelocity[i, :] = i_merged_lin_vel + \ - cross3(-_1Mi.translation.ravel(), - baseAngularVelocity[i, :]).ravel() - - rms_x.append( - np.sqrt(np.mean(np.square(filteredLinearVelocity[i_not_nan, 0] - mocapBaseLinearVelocity[i_not_nan, 0])))) - rms_y.append( - np.sqrt(np.mean(np.square(filteredLinearVelocity[i_not_nan, 1] - mocapBaseLinearVelocity[i_not_nan, 1])))) - rms_z.append( - np.sqrt(np.mean(np.square(filteredLinearVelocity[i_not_nan, 2] - mocapBaseLinearVelocity[i_not_nan, 2])))) - irms_x.append( - np.sqrt(np.mean(np.square(ifilteredLinearVelocity[i_not_nan, 0] - mocapBaseLinearVelocity[i_not_nan, 0])))) - irms_y.append( - np.sqrt(np.mean(np.square(ifilteredLinearVelocity[i_not_nan, 1] - mocapBaseLinearVelocity[i_not_nan, 1])))) - irms_z.append( - np.sqrt(np.mean(np.square(ifilteredLinearVelocity[i_not_nan, 2] - mocapBaseLinearVelocity[i_not_nan, 2])))) - -plt.figure() -plt.plot(alphas, rms_x) -plt.plot(alphas, rms_y) -plt.plot(alphas, rms_z) -plt.plot(alphas, irms_x) -plt.plot(alphas, irms_y) -plt.plot(alphas, irms_z) -plt.legend(["RMS X", "RMS Y", "RMS Z", "New RMS X", "New RMS Y", "New RMS Z"], prop={'size': 8}) -plt.xlabel("Alpha") -plt.ylabel("RMS erreur en vitesse") - -fc = 10 -y = 1 - np.cos(2 * np.pi * fc * dt) -alpha_v = -y + np.sqrt(y * y + 2 * y) -lowpass_ifilteredLinearVelocity = np.zeros(ifilteredLinearVelocity.shape) -lowpass_ifilteredLinearVelocity[0, :] = ifilteredLinearVelocity[0, :] -for k in range(1, N): - lowpass_ifilteredLinearVelocity[ - k, :] = (1 - alpha_v) * lowpass_ifilteredLinearVelocity[k - 1, :] + alpha_v * ifilteredLinearVelocity[k, :] - -plt.figure() -plt.plot(t, filteredLinearVelocity[:N, 0], linewidth=3) -plt.plot(t, ifilteredLinearVelocity[:N, 0], linewidth=3, linestyle="--") -plt.plot(t, mocapBaseLinearVelocity[:N, 0], linewidth=3) -plt.plot(t, lowpass_ifilteredLinearVelocity[:N, 0], color="darkviolet", linewidth=3) -# plt.plot(t, FK_lin_vel_log[:N, 0], color="darkviolet", linestyle="--") -"""plt.plot(t, baseLinearAcceleration[:N, 0], linestyle="--")""" -plt.legend(["Filtered", "New Filtered", "Mocap"], prop={'size': 8}) -# plt.show() - -data_control = np.load("data_control_" + last_date) - -log_tau_ff = data_control['log_tau_ff'] # Position -log_qdes = data_control['log_qdes'] # Orientation as quat -log_vdes = data_control['log_vdes'] # as 3 by 3 matrix -log_q = data_control['log_q'] - -index12 = [1, 5, 9, 2, 6, 10, 3, 7, 11, 4, 8, 12] -plt.figure() -for i in range(12): - if i == 0: - ax0 = plt.subplot(3, 4, index12[i]) - else: - plt.subplot(3, 4, index12[i], sharex=ax0) - plt.plot(t, log_qdes[i, :], color='r', linewidth=lwdth) - plt.plot(t, q_mes[:, i], color='b', linewidth=lwdth) - plt.legend(["Qdes", "Qmes"], prop={'size': 8}) - -plt.figure() -for i in range(12): - if i == 0: - ax0 = plt.subplot(3, 4, index12[i]) - else: - plt.subplot(3, 4, index12[i], sharex=ax0) - plt.plot(t, log_vdes[i, :], color='r', linewidth=lwdth) - plt.plot(t, v_mes[:, i], color='b', linewidth=lwdth) - plt.legend(["Vdes", "Vmes"], prop={'size': 8}) - -# Z linear velocity -plt.figure() -for i in range(12): - if i == 0: - ax0 = plt.subplot(3, 4, index12[i]) - else: - plt.subplot(3, 4, index12[i], sharex=ax0) - plt.plot(t, log_tau_ff[i, :], color='r', linewidth=lwdth) - plt.plot(t, torquesFromCurrentMeasurment[:, i], color='b', linewidth=lwdth) - plt.legend(["Tau_FF", "TAU"], prop={'size': 8}) - -plt.show(block=True) diff --git a/scripts/plot_comparison_fb.py b/scripts/plot_comparison_fb.py deleted file mode 100644 index 5bf77894..00000000 --- a/scripts/plot_comparison_fb.py +++ /dev/null @@ -1,171 +0,0 @@ - -import numpy as np -from matplotlib import pyplot as plt -import pinocchio as pin -import tsid as tsid -from IPython import embed - -# For storage -log_feet_pos = [] -log_feet_pos_target = [] -log_feet_vel_target = [] -log_feet_acc_target = [] -log_x_cmd = [] -log_x = [] -log_q = [] -log_dq = [] -log_x_ref_invkin = [] -log_x_invkin = [] -log_dx_ref_invkin = [] -log_dx_invkin = [] -log_tau_ff = [] -log_qdes = [] -log_vdes = [] -log_q_pyb = [] -log_v_pyb = [] - -files = ["push_no_ff.npz", "push_with_ff.npz", "push_pyb_no_ff.npz", "push_pyb_with_ff.npz"] -for file in files: - # Load data file - data = np.load(file) - # Store content of data in variables - log_feet_pos.append(data["log_feet_pos"]) - log_feet_pos_target.append(data["log_feet_pos_target"]) - log_feet_vel_target.append(data["log_feet_vel_target"]) - log_feet_acc_target.append(data["log_feet_acc_target"]) - log_x_cmd.append(data["log_x_cmd"]) - log_x.append(data["log_x"]) - log_q.append(data["log_q"]) - log_dq.append(data["log_dq"]) - log_x_ref_invkin.append(data["log_x_ref_invkin"]) - log_x_invkin.append(data["log_x_invkin"]) - log_dx_ref_invkin.append(data["log_dx_ref_invkin"]) - log_dx_invkin.append(data["log_dx_invkin"]) - log_tau_ff.append(data["log_tau_ff"]) - log_qdes.append(data["log_qdes"]) - log_vdes.append(data["log_vdes"]) - log_q_pyb.append(data["log_q_pyb"]) - log_v_pyb.append(data["log_v_pyb"]) - -# Creating time vector -N = log_tau_ff[0].shape[1] -Tend = N * 0.001 -t = np.linspace(0, Tend, N+1, endpoint=True) -t_range = t[:-1] - -# Parameters -dt = 0.0020 -lwdth = 2 - -########## -# GRAPHS # -########## - -k_lgd = ["No FF"] -index6 = [1, 3, 5, 2, 4, 6] -index12 = [1, 5, 9, 2, 6, 10, 3, 7, 11, 4, 8, 12] - -lgd_X = ["FL", "FR", "HL", "HR"] -lgd_Y = ["Pos X", "Pos Y", "Pos Z"] -plt.figure() -for i in range(12): - if i == 0: - ax0 = plt.subplot(3, 4, index12[i]) - else: - plt.subplot(3, 4, index12[i], sharex=ax0) - for k in range(len(log_tau_ff)): - plt.plot(t_range, log_feet_pos[k][i % 3, np.int(i/3), :], color='b', linewidth=3, marker='') - plt.plot(t_range, log_feet_pos_target[k][i % 3, np.int(i/3), :], color='r', linewidth=3, marker='') - plt.legend([lgd_Y[i % 3] + " " + lgd_X[np.int(i/3)]+"", lgd_Y[i % - 3] + " " + lgd_X[np.int(i/3)]+" Ref"]) -plt.suptitle("Reference positions of feet (world frame)") - -lgd_X = ["FL", "FR", "HL", "HR"] -lgd_Y = ["Vel X", "Vel Y", "Vel Z"] -plt.figure() -for i in range(12): - if i == 0: - ax0 = plt.subplot(3, 4, index12[i]) - else: - plt.subplot(3, 4, index12[i], sharex=ax0) - for k in range(len(log_tau_ff)): - plt.plot(t_range, log_feet_vel[k][i % 3, np.int(i/3), :], color='b', linewidth=3, marker='') - plt.plot(t_range, log_feet_vel_target[k][i % 3, np.int(i/3), :], color='r', linewidth=3, marker='') - plt.legend([lgd_Y[i % 3] + " " + lgd_X[np.int(i/3)]+" Ref"]) -plt.suptitle("Current and reference velocities of feet (world frame)") - -lgd_X = ["FL", "FR", "HL", "HR"] -lgd_Y = ["Acc X", "Acc Y", "Acc Z"] -plt.figure() -for i in range(12): - if i == 0: - ax0 = plt.subplot(3, 4, index12[i]) - else: - plt.subplot(3, 4, index12[i], sharex=ax0) - for k in range(len(log_tau_ff)): - plt.plot(t_range, log_feet_acc_target[k][i % 3, np.int(i/3), :], color='r', linewidth=3, marker='') - plt.legend([lgd_Y[i % 3] + " " + lgd_X[np.int(i/3)]+" Ref"]) -plt.suptitle("Current and reference accelerations of feet (world frame)") - -# LOG_Q -lgd = ["Position X", "Position Y", "Position Z", "Position Roll", "Position Pitch", "Position Yaw"] -plt.figure() -for i in range(6): - if i == 0: - ax0 = plt.subplot(3, 2, index6[i]) - else: - plt.subplot(3, 2, index6[i], sharex=ax0) - for k in range(len(log_tau_ff)): - plt.plot(t_range[:-2], log_x[k][i, :-2], "b", linewidth=2) - plt.plot(t_range[:-2], log_x_cmd[k][i, :-2], "r", linewidth=3) - # plt.plot(t_range, log_q[i, :], "g", linewidth=2) - plt.plot(t_range[:-2], log_x_invkin[k][i, :-2], "g", linewidth=2) - plt.plot(t_range[:-2], log_x_ref_invkin[k][i, :-2], "violet", linewidth=2, linestyle="--") - plt.legend(["WBC integrated output state", "Robot reference state", - "Task current state", "Task reference state"]) - plt.ylabel(lgd[i]) - -# LOG_V -lgd = ["Linear vel X", "Linear vel Y", "Linear vel Z", - "Angular vel Roll", "Angular vel Pitch", "Angular vel Yaw"] -plt.figure() -for i in range(6): - if i == 0: - ax0 = plt.subplot(3, 2, index6[i]) - else: - plt.subplot(3, 2, index6[i], sharex=ax0) - for k in range(len(log_tau_ff)): - plt.plot(t_range[:-2], log_x[k][i+6, :-2], "b", linewidth=2) - plt.plot(t_range[:-2], log_x_cmd[k][i+6, :-2], "r", linewidth=3) - # plt.plot(t_range, log_dq[i, :], "g", linewidth=2) - plt.plot(t_range[:-2], log_dx_invkin[k][i, :-2], "g", linewidth=2) - plt.plot(t_range[:-2], log_dx_ref_invkin[k][i, :-2], "violet", linewidth=2, linestyle="--") - plt.legend(["WBC integrated output state", "Robot reference state", - "Task current state", "Task reference state"]) - plt.ylabel(lgd[i]) - -plt.figure() -for k in range(len(log_tau_ff)): - plt.plot(t_range[:-2], log_x[k][6, :-2], "b", linewidth=2) - plt.plot(t_range[:-2], log_x_cmd[k][6, :-2], "r", linewidth=2) - plt.plot(t_range[:-2], log_dx_invkin[k][0, :-2], "g", linewidth=2) - plt.plot(t_range[:-2], log_dx_ref_invkin[k][0, :-2], "violet", linewidth=2) -plt.legend(["WBC integrated output state", "Robot reference state", - "Task current state", "Task reference state"]) - -k_c = ["r", "g", "b", "violet"] -plt.figure() -plt.plot(t_range[:-2], log_x_cmd[0][6, :-2], "k", linewidth=2) -for k in range(len(log_tau_ff)): - plt.plot(t_range[:-2], log_v_pyb[k][1, :-2], color=k_c[k], linewidth=2) # (1+len(log_tau_ff))-k) -plt.legend(["Reference", "Inv Kin FB no FF", "Inv Kin FB with FF", "PyB FB no FF", "PyB FB with FF"]) - -k_c = ["r", "g", "b", "violet"] -plt.figure() -plt.plot(t_range[:-2], log_x_cmd[0][1, :-2], "k", linewidth=2) -for k in range(len(log_tau_ff)): - plt.plot(t_range[:-2], log_q_pyb[k][1, :-2], color=k_c[k], linewidth=2) # (1+len(log_tau_ff))-k) -plt.xlabel("Time [s]") -plt.ylabel("Position [m]") -plt.legend(["Reference", "Inv Kin FB no FF", "Inv Kin FB with FF", "PyB FB no FF", "PyB FB with FF"]) -plt.show(block=True) diff --git a/scripts/solo3D/SurfacePlanner.py b/scripts/solo3D/SurfacePlanner.py index bdb87adf..9e7d8bf3 100644 --- a/scripts/solo3D/SurfacePlanner.py +++ b/scripts/solo3D/SurfacePlanner.py @@ -10,7 +10,7 @@ from solo_rbprm.solo_abstract import Robot as SoloAbstract from hpp.corbaserver.affordance.affordance import AffordanceTool from hpp.corbaserver.rbprm.tools.surfaces_from_path import getAllSurfacesDict -from solo3D.tools.utils import getAllSurfacesDict_inner +from solo3D.utils import getAllSurfacesDict_inner from hpp.corbaserver.problem_solver import ProblemSolver from hpp.gepetto import ViewerFactory diff --git a/scripts/solo3D/SurfacePlannerWrapper.py b/scripts/solo3D/SurfacePlannerWrapper.py index a0d3c5cb..14dd62ba 100644 --- a/scripts/solo3D/SurfacePlannerWrapper.py +++ b/scripts/solo3D/SurfacePlannerWrapper.py @@ -15,7 +15,6 @@ N_SURFACE_MAX = 10 N_POTENTIAL_SURFACE = 7 N_FEET = 4 - class SurfaceDataCtype(ctypes.Structure): ''' ctype data structure for the shared memory between processes, for surfaces Ax <= b diff --git a/scripts/heightmap_generator.py b/scripts/solo3D/heightmap_generator.py similarity index 97% rename from scripts/heightmap_generator.py rename to scripts/solo3D/heightmap_generator.py index 3931128d..3e49a4f4 100644 --- a/scripts/heightmap_generator.py +++ b/scripts/solo3D/heightmap_generator.py @@ -2,8 +2,8 @@ import matplotlib.pyplot as plt import os import numpy as np -from solo3D.tools.heightmap_tools import Heightmap -from solo3D.tools.utils import getAllSurfacesDict_inner +from solo3D.heightmap_tools import Heightmap +from solo3D.utils import getAllSurfacesDict_inner from solo_rbprm.solo_abstract import Robot diff --git a/scripts/solo3D/tools/heightmap_tools.py b/scripts/solo3D/heightmap_tools.py similarity index 99% rename from scripts/solo3D/tools/heightmap_tools.py rename to scripts/solo3D/heightmap_tools.py index bb1f3593..3f715206 100644 --- a/scripts/solo3D/tools/heightmap_tools.py +++ b/scripts/solo3D/heightmap_tools.py @@ -2,8 +2,6 @@ import numpy as np import hppfcl import pickle import ctypes -import quadruped_reactive_walking as qrw - COLORS = ['#1f77b4', '#ff7f0e', '#2ca02c', '#d62728', '#e377c2', '#7f7f7f', '#bcbd22', '#17becf'] diff --git a/scripts/solo3D/tools/pyb_environment_3D.py b/scripts/solo3D/pyb_environment_3D.py similarity index 100% rename from scripts/solo3D/tools/pyb_environment_3D.py rename to scripts/solo3D/pyb_environment_3D.py diff --git a/scripts/solo3D/tools/utils.py b/scripts/solo3D/utils.py similarity index 100% rename from scripts/solo3D/tools/utils.py rename to scripts/solo3D/utils.py diff --git a/scripts/test_convergence_mpc.py b/scripts/test_convergence_mpc.py deleted file mode 100644 index a4c8d515..00000000 --- a/scripts/test_convergence_mpc.py +++ /dev/null @@ -1,563 +0,0 @@ -import numpy as np -from matplotlib import pyplot as plt -import quadruped_reactive_walking as qrw -import MPC_Wrapper -import utils_mpc - -"""dt_mpc = 0.02 -T_mpc = 0.32 - -k_mpc = 20 -N_gait = 100""" -h_ref = 0.2447495 - -def test_1(): - # Position of base in world frame - q = np.zeros((18, 1)) - q[0:6, 0] = np.array([0.0, 0.0, h_ref, 0.0, 0.0, 0.0]) - q[6:, 0] = np.array([0.0, 0.7, -1.4, -0.0, 0.7, -1.4, 0.0, -0.7, +1.4, -0.0, -0.7, +1.4]) - - # Velocity of base in horizontal frame - h_v = np.zeros((18, 1)) - h_v[0, 0] = 0.1 - h_v[1, 0] = 0.1 - #h_v[1, 0] = 0.1 - - # Velocity reference of base in horizontal frame - v_ref = np.zeros((18, 1)) - v_ref[0, 0] = 0.1 - - # Params - params = qrw.Params() # Object that holds all controller parameters - - """params.dt_mpc = dt_mpc - params.T_mpc = T_mpc - params.h_ref = h_ref - params.enable_multiprocessing = False""" - - # Initialisation of the solo model/data and of the Gepetto viewer - utils_mpc.init_robot(q[6:, 0], params) - - # State planner - statePlanner = qrw.StatePlanner() - statePlanner.initialize(params) - - gait = qrw.Gait() - gait.initialize(params) - - footstepPlanner = qrw.FootstepPlanner() - footstepPlanner.initialize(params, gait) - - # MPC wrapper - params.type_MPC = 0 - mpc_wrapper_classic = MPC_Wrapper.MPC_Wrapper(params, q) - params.type_MPC = 1 - mpc_wrapper_croco = MPC_Wrapper.MPC_Wrapper(params, q) - - # Update gait - for i in range(5): - gait.updateGait(i*20, 20, 0) - cgait = gait.getCurrentGait() - - # Compute target footstep based on current and reference velocities - footstepPlanner.updateFootsteps(False, 20, q[:, 0:1], h_v[0:6, 0:1].copy(), v_ref[0:6, 0]) - fsteps = footstepPlanner.getFootsteps() - - fsteps[:12, 0] += h_v[0, 0] * params.T_gait * 0.25 - fsteps[:12, 1] += h_v[1, 0] * params.T_gait * 0.25 - fsteps[:12, 9] += h_v[0, 0] * params.T_gait * 0.25 - fsteps[:12, 10] += h_v[1, 0] * params.T_gait * 0.25 - - """from IPython import embed - embed()""" - - - # Run state planner (outputs the reference trajectory of the base) - statePlanner.computeReferenceStates(q[0:6, 0:1].copy(), h_v[0:6, 0:1].copy(), v_ref[0:6, 0:1].copy()) - xref = statePlanner.getReferenceStates() - - # Create fsteps matrix - shoulders = np.zeros((3, 4)) - shoulders[0, :] = [0.1946, 0.1946, -0.1946, -0.1946] - shoulders[1, :] = [0.14695, -0.14695, 0.14695, -0.14695] - shoulders[2, :] = np.zeros(4) - - # Solve MPC problem once every k_mpc iterations of the main loop - mpc_wrapper_classic.solve(0, xref.copy(), fsteps.copy(), cgait.copy(), np.zeros((3,4))) - mpc_wrapper_croco.solve(0, xref.copy(), fsteps.copy(), cgait.copy(), shoulders.copy()) - - # Retrieve reference contact forces in horizontal frame - x_f_mpc_classic = mpc_wrapper_classic.get_latest_result() - x_f_mpc_croco = mpc_wrapper_croco.get_latest_result() - - # Solve MPC problem once every k_mpc iterations of the main loop - mpc_wrapper_classic.solve(1, xref, fsteps, cgait, np.zeros((3,4))) - mpc_wrapper_croco.solve(1, xref, fsteps, cgait, shoulders) - - # Retrieve reference contact forces in horizontal frame - x_f_mpc_classic = mpc_wrapper_classic.get_latest_result() - x_f_mpc_croco_32 = mpc_wrapper_croco.get_latest_result() - - x_f_mpc_classic = np.hstack((np.vstack((xref[:, 0:1], np.zeros((12, 1)))), x_f_mpc_classic)) - x_f_mpc_croco = np.hstack((np.vstack((xref[:, 0:1], np.zeros((12, 1)))), x_f_mpc_croco_32[:24, :])) - - # print(xref) - - index6 = [1, 3, 5, 2, 4, 6] - index12 = [1, 5, 9, 2, 6, 10, 3, 7, 11, 4, 8, 12] - titles = ["X", "Y", "Z", "Roll", "Pitch", "Yaw"] - N = x_f_mpc_classic.shape[1] - plt.figure() - for i in range(6): - plt.subplot(3, 2, index6[i]) - h1, = plt.plot(x_f_mpc_classic[i, :N], "b", linewidth=2) - h2, = plt.plot(x_f_mpc_croco[i, :N], "r", linewidth=2) - h3, = plt.plot(xref[i, :N], "b", linestyle="--", marker='x', color="g", linewidth=2) - plt.xlabel("Time [s]") - # plt.legend([h1, h2, h3], ["Output trajectory of classic MPC", "Output trajectory of croco MPC", "Input trajectory of planner"]) - plt.legend([h1, h2, h3], ["OSQP", "Croco", "Ref"]) - if i in [0, 1]: - m1 = np.min(x_f_mpc_classic[0:2, :N]) - M1 = np.max(x_f_mpc_classic[0:2, :N]) - m2 = np.min(x_f_mpc_croco[0:2, :N]) - M2 = np.max(x_f_mpc_croco[0:2, :N]) - plt.ylim([np.min([m1, m2]) - 0.01, np.max([M1, M2]) + 0.01]) - elif i in [3, 4]: - m1 = np.min(x_f_mpc_classic[3:5, :N]) - M1 = np.max(x_f_mpc_classic[3:5, :N]) - m2 = np.min(x_f_mpc_croco[3:5, :N]) - M2 = np.max(x_f_mpc_croco[3:5, :N]) - plt.ylim([np.min([m1, m2]) - 0.01, np.max([M1, M2]) + 0.01]) - plt.title("Predicted trajectory for " + titles[i]) - plt.suptitle("Analysis of trajectories in position and orientation computed by the MPC") - - plt.figure() - for i in range(6): - plt.subplot(3, 2, index6[i]) - h1, = plt.plot(x_f_mpc_classic[i+6, :N], "b", linewidth=2) - h2, = plt.plot(x_f_mpc_croco[i+6, :N], "r", linewidth=2) - h3, = plt.plot(xref[i+6, :N], "b", linestyle="--", marker='x', color="g", linewidth=2) - plt.xlabel("Time [s]") - if i in [0, 1]: - m1 = np.min(x_f_mpc_classic[6:8, :N]) - M1 = np.max(x_f_mpc_classic[6:8, :N]) - m2 = np.min(x_f_mpc_croco[6:8, :N]) - M2 = np.max(x_f_mpc_croco[6:8, :N]) - plt.ylim([np.min([m1, m2]) - 0.01, np.max([M1, M2]) + 0.01]) - elif i in [3, 4]: - m1 = np.min(x_f_mpc_classic[9:11, :N]) - M1 = np.max(x_f_mpc_classic[9:11, :N]) - m2 = np.min(x_f_mpc_croco[9:11, :N]) - M2 = np.max(x_f_mpc_croco[9:11, :N]) - plt.ylim([np.min([m1, m2]) - 0.01, np.max([M1, M2]) + 0.01]) - # plt.legend([h1, h2, h3], ["Output trajectory of classic MPC", "Output trajectory of croco MPC", "Input trajectory of planner"]) - plt.title("Predicted trajectory for velocity in " + titles[i]) - plt.suptitle("Analysis of trajectories of linear and angular velocities computed by the MPC") - - lgd1 = ["Ctct force X", "Ctct force Y", "Ctct force Z"] - lgd2 = ["FL", "FR", "HL", "HR"] - plt.figure() - for i in range(12): - if i == 0: - ax0 = plt.subplot(3, 4, index12[i]) - else: - plt.subplot(3, 4, index12[i], sharex=ax0) - h1, = plt.plot(x_f_mpc_classic[i+12, 1:(N+1)], "b", linewidth=3) - h2, = plt.plot(x_f_mpc_croco[i+12, 1:(N+1)], "r", linewidth=3) - plt.xlabel("Time [s]") - plt.ylabel(lgd1[i % 3]+" "+lgd2[int(i/3)]+" [N]") - """if (i % 3) == 2: - plt.ylim([-0.0, 26.0]) - else: - plt.ylim([-26.0, 26.0])""" - - if i % 3 != 2: - row = int(int(i/3)*3+14) - plt.plot(0.9 * np.abs(x_f_mpc_croco[row, 1:(N+1)]), "b--", linewidth=3) - plt.plot(-0.9 * np.abs(x_f_mpc_croco[row, 1:(N+1)]), "b--", linewidth=3) - plt.plot(0.9 * np.abs(x_f_mpc_croco[row, 1:(N+1)]), "r--", linewidth=3) - plt.plot(-0.9 * np.abs(x_f_mpc_croco[row, 1:(N+1)]), "r--", linewidth=3) - - if i % 3 != 2: - idx = np.array([0, 1, 3, 4, 6, 7, 9, 10]) + 12 - else: - idx = np.array([2, 5, 8, 11]) + 12 - m1 = np.min(x_f_mpc_classic[idx, :N]) - M1 = np.max(x_f_mpc_classic[idx, :N]) - m2 = np.min(x_f_mpc_croco[idx, :N]) - M2 = np.max(x_f_mpc_croco[idx, :N]) - plt.ylim([np.min([m1, m2]) - 0.2, np.max([M1, M2]) + 0.2]) - - plt.legend([h1, h2], ["Classic", "Croco"]) - plt.suptitle("Contact forces (MPC command)") - - """index8 = [1, 5, 2, 6, 3, 7, 4, 8] - lgd_x = ["FL", "FR", "HL", "HR"] - lgd_y = [" x", " y"] - plt.figure() - for i in range(8): - plt.subplot(2, 4, index8[i]) - plt.plot(shoulders[int(i % 2), int(i/2)] * np.ones(x_f_mpc_croco_32.shape[1]), "b", linewidth=3) - plt.plot(x_f_mpc_croco_32[24+i, :], "r", linewidth=3) - plt.legend([lgd_x[int(i/2)] + lgd_y[i % 2] + " classic", lgd_x[int(i/2)] + lgd_y[i % 2] + " croco"]) - plt.suptitle("Footsteps positions")""" - - plt.show(block=True) - - -def test_2(): - # Position of base in world frame - q = np.zeros((19, 1)) - q[0:7, 0] = np.array([0.0, 0.0, h_ref, 0.0, 0.0, 0.0, 1.0]) - q[7:, 0] = np.array([0.0, 0.7, -1.4, -0.0, 0.7, -1.4, 0.0, -0.7, +1.4, -0.0, -0.7, +1.4]) - - # Velocity of base in horizontal frame - h_v_1 = np.zeros((18, 1)) - h_v_2 = np.zeros((18, 1)) - h_v_1[0, 0] = 0.1 - h_v_1[1, 0] = 0.0 - h_v_2[0, 0] = - h_v_1[0, 0] - h_v_2[1, 0] = - h_v_1[1, 0] - - # Velocity reference of base in horizontal frame - v_ref_1 = np.zeros((18, 1)) - v_ref_2 = np.zeros((18, 1)) - v_ref_1[0, 0] = 0.1 - v_ref_2[0, 0] = - v_ref_1[0, 0] - - # Params - params = qrw.Params() # Object that holds all controller parameters - - # Initialisation of the solo model/data and of the Gepetto viewer - utils_mpc.init_robot(q[7:, 0], params) - - # State planner - statePlanner_1 = qrw.StatePlanner() - statePlanner_1.initialize(params) - statePlanner_2 = qrw.StatePlanner() - statePlanner_2.initialize(params) - - gait = qrw.Gait() - gait.initialize(params) - - footstepPlanner_1 = qrw.FootstepPlanner() - footstepPlanner_1.initialize(params, gait) - footstepPlanner_2 = qrw.FootstepPlanner() - footstepPlanner_2.initialize(params, gait) - - # MPC wrapper - enable_multiprocessing = False - mpc_wrapper_1 = MPC_Wrapper.MPC_Wrapper(params, q) - mpc_wrapper_2 = MPC_Wrapper.MPC_Wrapper(params, q) - - # Update gait - gait.updateGait(0, 20, q[0:7, 0:1], 0) - - # Compute target footstep based on current and reference velocities - footstepPlanner_1.updateFootsteps(False, 20, q[:, 0:1], h_v_1[0:6, 0:1].copy(), v_ref_1[0:6, 0]) - footstepPlanner_2.updateFootsteps(False, 20, q[:, 0:1], h_v_2[0:6, 0:1].copy(), v_ref_2[0:6, 0]) - - # Run state planner (outputs the reference trajectory of the base) - statePlanner_1.computeReferenceStates(q[0:7, 0:1].copy(), h_v_1[0:6, 0:1].copy(), v_ref_1[0:6, 0:1].copy()) - xref_1 = statePlanner_1.getReferenceStates() - statePlanner_2.computeReferenceStates(q[0:7, 0:1].copy(), h_v_2[0:6, 0:1].copy(), v_ref_2[0:6, 0:1].copy()) - xref_2 = statePlanner_2.getReferenceStates() - - fsteps_1 = footstepPlanner_1.getFootsteps() - fsteps_2 = footstepPlanner_2.getFootsteps() - cgait = gait.getCurrentGait() - - xref_test = xref_2.copy() - xref_test[0, :] *= -1.0 - xref_test[1, :] *= -1.0 - xref_test[5, :] *= -1.0 - xref_test[6, :] *= -1.0 - xref_test[7, :] *= -1.0 - xref_test[11, :] *= -1.0 - print(np.allclose(xref_1, xref_test)) - # print(xref_1 - xref_test) - - # Create gait matrix - """cgait = np.zeros((params.N_gait, 4)) - for i in range(7): - cgait[i, :] = np.array([1.0, 0.0, 0.0, 1.0]) - for i in range(8): - cgait[7+i, :] = np.array([0.0, 1.0, 1.0, 0.0]) - cgait[15, :] = np.array([1.0, 0.0, 0.0, 1.0]) - for j in range(1, 10): - for i in range(7): - cgait[16*j+i, :] = np.array([1.0, 0.0, 0.0, 1.0]) - for i in range(8): - cgait[16*j+7+i, :] = np.array([0.0, 1.0, 1.0, 0.0]) - cgait[16*j+15, :] = np.array([1.0, 0.0, 0.0, 1.0])""" - - # Create fsteps matrix - """shoulders = np.zeros((3, 4)) - shoulders[0, :] = [0.1946, 0.1946, -0.1946, -0.1946] - shoulders[1, :] = [0.14695, -0.14695, 0.14695, -0.14695] - shoulders[2, :] = np.zeros(4) # np.ones(4) * h_ref - fsteps = np.zeros((params.N_gait, 12)) - for i in range(params.N_gait): - for j in range(4): - if cgait[i, j] == 1: - fsteps[i, (3*j):(3*(j+1))] = shoulders[:, j]""" - - from IPython import embed - embed() - - # Solve MPC problem once every k_mpc iterations of the main loop - try: - mpc_wrapper_1.solve(0, xref_1.copy(), fsteps_1.copy(), cgait.copy(), np.zeros((3, 4))) - mpc_wrapper_2.solve(0, xref_2.copy(), fsteps_2.copy(), cgait.copy(), np.zeros((3, 4))) - except ValueError: - print("MPC Problem") - - # Retrieve reference contact forces in horizontal frame - x_f_mpc_1 = mpc_wrapper_1.get_latest_result() - x_f_mpc_2 = mpc_wrapper_2.get_latest_result() - - """from IPython import embed - embed()""" - - # Solve MPC problem once every k_mpc iterations of the main loop - try: - mpc_wrapper_1.solve(1, xref_1.copy(), fsteps_1.copy(), cgait.copy(), np.zeros((3, 4))) - mpc_wrapper_2.solve(1, xref_2.copy(), fsteps_2.copy(), cgait.copy(), np.zeros((3, 4))) - except ValueError: - print("MPC Problem") - - # Retrieve reference contact forces in horizontal frame - x_f_mpc_1 = mpc_wrapper_1.get_latest_result() - x_f_mpc_2 = mpc_wrapper_2.get_latest_result() - - """from IPython import embed - embed()""" - - x_f_mpc_1 = np.hstack((np.vstack((xref_1[:, 0:1].copy(), np.zeros((12, 1)))), x_f_mpc_1.copy())) - x_f_mpc_2 = np.hstack((np.vstack((xref_2[:, 0:1].copy(), np.zeros((12, 1)))), x_f_mpc_2.copy())) - - index6 = [1, 3, 5, 2, 4, 6] - index12 = [1, 5, 9, 2, 6, 10, 3, 7, 11, 4, 8, 12] - coeff = [-1.0, -1.0, 1.0, -1.0, -1.0, -1.0] - titles = ["X", "Y", "Z", "Roll", "Pitch", "Yaw"] - N = x_f_mpc_1.shape[1] - plt.figure() - for i in range(6): - plt.subplot(3, 2, index6[i]) - h1, = plt.plot(x_f_mpc_1[i, :N], "b", linewidth=2) - h2, = plt.plot(coeff[i] * x_f_mpc_2[i, :N], "r", linewidth=2) - h3, = plt.plot(xref_1[i, :N], "forestgreen", linestyle="--", marker='x', color="g", linewidth=2) - plt.xlabel("Time [s]") - # plt.legend([h1, h2, h3], ["Output trajectory of classic MPC", "Output trajectory of croco MPC", "Input trajectory of planner"]) - plt.title("Predicted trajectory for " + titles[i]) - plt.suptitle("Analysis of trajectories in position and orientation computed by the MPC") - - plt.figure() - for i in range(6): - plt.subplot(3, 2, index6[i]) - h1, = plt.plot(x_f_mpc_1[i+6, :N], "b", linewidth=2) - h2, = plt.plot(coeff[i] * x_f_mpc_2[i+6, :N], "r", linewidth=2) - h3, = plt.plot(xref_1[i+6, :N], "forestgreen", linestyle="--", marker='x', color="g", linewidth=2) - plt.xlabel("Time [s]") - #plt.legend([h1, h2, h3], ["Output trajectory of classic MPC", "Output trajectory of croco MPC", "Input trajectory of planner"]) - plt.title("Predicted trajectory for velocity in " + titles[i]) - plt.suptitle("Analysis of trajectories of linear and angular velocities computed by the MPC") - - lgd1 = ["Ctct force X", "Ctct force Y", "Ctct force Z"] - lgd2 = ["FL", "FR", "HL", "HR"] - reorder = [9, 10, 11, 6, 7, 8, 3, 4, 5, 0, 1, 2] - plt.figure() - for i in range(12): - if i == 0: - ax0 = plt.subplot(3, 4, index12[i]) - else: - plt.subplot(3, 4, index12[i], sharex=ax0) - h1, = plt.plot(x_f_mpc_1[i+12, 1:(N+1)], "b", linewidth=3) - h2, = plt.plot(coeff[i % 3] * x_f_mpc_2[reorder[i]+12, 1:(N+1)], "r", linewidth=3) - # h3, = plt.plot(x_f_mpc_1[i+12, 1:(N+1)] - coeff[i % 3] * x_f_mpc_2[reorder[i]+12, 1:(N+1)], "g", linewidth=3) - plt.xlabel("Time [s]") - plt.ylabel(lgd1[i % 3]+" "+lgd2[int(i/3)]+" [N]") - """if (i % 3) == 2: - plt.ylim([-0.0, 26.0]) - else: - plt.ylim([-26.0, 26.0])""" - #plt.legend([h1, h2], ["Classic", "Croco"]) - plt.suptitle("Contact forces (MPC command)") - - plt.figure() - for i in range(6): - plt.subplot(3, 2, index6[i]) - h1, = plt.plot(x_f_mpc_1[i, :N] - coeff[i] * x_f_mpc_2[i, :N], "g", linewidth=2) - plt.xlabel("Time [s]") - plt.suptitle("Analysis of trajectories in position and orientation computed by the MPC") - - plt.figure() - for i in range(6): - plt.subplot(3, 2, index6[i]) - h1, = plt.plot(x_f_mpc_1[i+6, :N] - coeff[i] * x_f_mpc_2[i+6, :N], "g", linewidth=2) - plt.xlabel("Time [s]") - plt.suptitle("Analysis of trajectories of linear and angular velocities computed by the MPC") - - plt.figure() - for i in range(12): - if i == 0: - ax0 = plt.subplot(3, 4, index12[i]) - else: - plt.subplot(3, 4, index12[i], sharex=ax0) - h3, = plt.plot(x_f_mpc_1[i+12, 1:(N+1)] - coeff[i % 3] * x_f_mpc_2[reorder[i]+12, 1:(N+1)], "g", linewidth=3) - plt.xlabel("Time [s]") - plt.ylabel(lgd1[i % 3]+" "+lgd2[int(i/3)]+" [N]") - plt.suptitle("Contact forces (MPC command)") - - plt.figure() - off = [9, 9, 9, 3, 3, 3] - for i in range(6): - if i == 0: - ax0 = plt.subplot(3, 2, index6[i]) - else: - plt.subplot(3, 2, index6[i], sharex=ax0) - plt.plot(x_f_mpc_1[i+12, 1:(N+1)] - coeff[i % 3] * x_f_mpc_2[reorder[i]+12, 1:(N+1)] + (x_f_mpc_1[i+off[i]+12, 1:(N+1)] - coeff[i % 3] * x_f_mpc_2[reorder[i+off[i]]+12, 1:(N+1)]), "g", linewidth=3) - plt.xlabel("Time [s]") - plt.ylabel(lgd1[i % 3]+" "+lgd2[int(i/3)]+" [N]") - plt.suptitle("Contact forces (MPC command)") - - plt.show(block=True) - -def test_3(typeMPC=True): - # Position of base in world frame - q = np.zeros((19, 1)) - q[0:7, 0] = np.array([0.0, 0.0, h_ref, 0.0, 0.0, 0.0, 1.0]) - q[7:, 0] = np.array([0.0, 0.7, -1.4, -0.0, 0.7, -1.4, 0.0, -0.7, +1.4, -0.0, -0.7, +1.4]) - - # Velocity of base in horizontal frame - h_v_1 = np.zeros((18, 1)) - h_v_2 = np.zeros((18, 1)) - h_v_1[0, 0] = 0.1 - h_v_2[0, 0] = - h_v_1[0, 0] - - # Velocity reference of base in horizontal frame - v_ref_1 = np.zeros((18, 1)) - v_ref_2 = np.zeros((18, 1)) - v_ref_1[0, 0] = 0.1 - v_ref_2[0, 0] = - v_ref_1[0, 0] - - # Params - params = qrw.Params() # Object that holds all controller parameters - params.dt_mpc = dt_mpc - params.T_mpc = T_mpc - params.h_ref = h_ref - params.enable_multiprocessing = False - - # State planner - statePlanner_1 = qrw.StatePlanner() - statePlanner_1.initialize(params) - statePlanner_2 = qrw.StatePlanner() - statePlanner_2.initialize(params) - - # MPC wrapper - mpc_wrapper_1 = MPC_Wrapper.MPC_Wrapper(params, q) - mpc_wrapper_2 = MPC_Wrapper.MPC_Wrapper(params, q) - - # Run state planner (outputs the reference trajectory of the base) - statePlanner_1.computeReferenceStates(q[0:7, 0:1].copy(), h_v_1[0:6, 0:1].copy(), v_ref_1[0:6, 0:1].copy()) - xref_1 = statePlanner_1.getReferenceStates() - statePlanner_2.computeReferenceStates(q[0:7, 0:1].copy(), h_v_2[0:6, 0:1].copy(), v_ref_2[0:6, 0:1].copy()) - xref_2 = statePlanner_2.getReferenceStates() - - # Create gait matrix - cgait = np.zeros((N_gait, 4)) - for i in range(7): - cgait[i, :] = np.array([1.0, 0.0, 0.0, 1.0]) - for i in range(8): - cgait[7+i, :] = np.array([0.0, 1.0, 1.0, 0.0]) - cgait[15, :] = np.array([1.0, 0.0, 0.0, 1.0]) - - # Create fsteps matrix - shoulders = np.zeros((3, 4)) - shoulders[0, :] = [0.1946, 0.1946, -0.1946, -0.1946] - shoulders[1, :] = [0.14695, -0.14695, 0.14695, -0.14695] - shoulders[2, :] = np.zeros(4) # np.ones(4) * h_ref - fsteps = np.zeros((N_gait, 12)) - for i in range(N_gait): - for j in range(4): - if cgait[i, j] == 1: - fsteps[i, (3*j):(3*(j+1))] = shoulders[:, j] - - - # Solve MPC problem once every k_mpc iterations of the main loop - try: - mpc_wrapper_1.solve(0, xref_1.copy(), fsteps.copy(), cgait.copy(), np.zeros((3,4))) - mpc_wrapper_2.solve(0, xref_2.copy(), fsteps.copy(), cgait.copy(), np.zeros((3,4))) - except ValueError: - print("MPC Problem") - - # Retrieve reference contact forces in horizontal frame - x_f_mpc_1 = mpc_wrapper_1.get_latest_result() - x_f_mpc_2 = mpc_wrapper_2.get_latest_result() - - # Solve MPC problem once every k_mpc iterations of the main loop - try: - mpc_wrapper_1.solve(0, xref_1.copy(), fsteps.copy(), cgait.copy(), np.zeros((3,4))) - mpc_wrapper_2.solve(0, xref_2.copy(), fsteps.copy(), cgait.copy(), np.zeros((3,4))) - except ValueError: - print("MPC Problem") - - # Retrieve reference contact forces in horizontal frame - x_f_mpc_1 = mpc_wrapper_1.get_latest_result() - x_f_mpc_2 = mpc_wrapper_2.get_latest_result() - x_f_mpc_1 = np.hstack((np.vstack((xref_1[:, 0:1].copy(), np.zeros((12, 1)))), x_f_mpc_1.copy())) - x_f_mpc_2 = np.hstack((np.vstack((xref_2[:, 0:1].copy(), np.zeros((12, 1)))), x_f_mpc_2.copy())) - - index6 = [1, 3, 5, 2, 4, 6] - index12 = [1, 5, 9, 2, 6, 10, 3, 7, 11, 4, 8, 12] - coeff = [-1.0, -1.0, 1.0, -1.0, -1.0, -1.0] - titles = ["X", "Y", "Z", "Roll", "Pitch", "Yaw"] - N = -1 - plt.figure() - for i in range(6): - plt.subplot(3, 2, index6[i]) - h1, = plt.plot(x_f_mpc_1[i, :N], "b", linewidth=2) - h2, = plt.plot(coeff[i] * x_f_mpc_2[i, :N], "r", linewidth=2) - h3, = plt.plot(xref_1[i, :N], "b", linestyle="--", marker='x', color="g", linewidth=2) - plt.xlabel("Time [s]") - # plt.legend([h1, h2, h3], ["Output trajectory of classic MPC", "Output trajectory of croco MPC", "Input trajectory of planner"]) - plt.title("Predicted trajectory for " + titles[i]) - plt.suptitle("Analysis of trajectories in position and orientation computed by the MPC") - - plt.figure() - for i in range(6): - plt.subplot(3, 2, index6[i]) - h1, = plt.plot(x_f_mpc_1[i+6, :N], "b", linewidth=2) - h2, = plt.plot(coeff[i] * x_f_mpc_2[i+6, :N], "r", linewidth=2) - h3, = plt.plot(xref_1[i+6, :N], "b", linestyle="--", marker='x', color="g", linewidth=2) - plt.xlabel("Time [s]") - #plt.legend([h1, h2, h3], ["Output trajectory of classic MPC", "Output trajectory of croco MPC", "Input trajectory of planner"]) - plt.title("Predicted trajectory for velocity in " + titles[i]) - plt.suptitle("Analysis of trajectories of linear and angular velocities computed by the MPC") - - lgd1 = ["Ctct force X", "Ctct force Y", "Ctct force Z"] - lgd2 = ["FL", "FR", "HL", "HR"] - reorder = [9, 10, 11, 6, 7, 8, 3, 4, 5, 0, 1, 2] - plt.figure() - for i in range(12): - if i == 0: - ax0 = plt.subplot(3, 4, index12[i]) - else: - plt.subplot(3, 4, index12[i], sharex=ax0) - h1, = plt.plot(x_f_mpc_1[i+12, 1:(N+1)], "b", linewidth=3) - h2, = plt.plot(coeff[i % 3] * x_f_mpc_2[reorder[i]+12, 1:(N+1)], "r", linewidth=3) - # h3, = plt.plot(x_f_mpc_1[i+12, 1:(N+1)] - coeff[i % 3] * x_f_mpc_2[reorder[i]+12, 1:(N+1)], "g", linewidth=3) - plt.xlabel("Time [s]") - plt.ylabel(lgd1[i % 3]+" "+lgd2[int(i/3)]+" [N]") - """if (i % 3) == 2: - plt.ylim([-0.0, 26.0]) - else: - plt.ylim([-26.0, 26.0])""" - #plt.legend([h1, h2], ["Classic", "Croco"]) - plt.suptitle("Contact forces (MPC command)") - - plt.show() - -test_1() -# test_2() -#test_3() \ No newline at end of file diff --git a/scripts/test_mpc.py b/scripts/test_mpc.py deleted file mode 100644 index b53d3092..00000000 --- a/scripts/test_mpc.py +++ /dev/null @@ -1,199 +0,0 @@ -import unittest -import numpy as np -import time - -# Import classes to test -import MPC_Wrapper -np.set_printoptions(precision=3, linewidth=300) - - -class TestStringMethods(unittest.TestCase): - - def test_upper(self): - self.assertEqual('foo'.upper(), 'FOO') - - def test_isupper(self): - self.assertTrue('FOO'.isupper()) - self.assertFalse('Foo'.isupper()) - - def test_split(self): - s = 'hello world' - self.assertEqual(s.split(), ['hello', 'world']) - # check that s.split fails when the separator is not a string - with self.assertRaises(TypeError): - s.split(2) - - -class TestMPC(unittest.TestCase): - - def setUp(self): - - self.mass = 2.50000279 - type_MPC = 0 - dt_wbc = 0.002 - dt_mpc = 0.02 - k_mpc = int(dt_mpc / dt_wbc) - T_mpc = 0.32 - T_gait = 0.32 - q_init = np.zeros((19, 1)) - q_init[0:7, 0] = np.array([0.0, 0.0, 0.24474949993103629, 0.0, 0.0, 0.0, 1.0]) - q_init[7:, 0] = np.array([0.0, 0.7, -1.4, -0.0, 0.7, -1.4, 0.0, -0.7, +1.4, -0.0, -0.7, +1.4]) - enable_multiprocessing = True - self.mpc_wrapper = MPC_Wrapper.MPC_Wrapper(type_MPC, dt_mpc, np.int(T_mpc/dt_mpc), - k_mpc, T_mpc, q_init, enable_multiprocessing) - - self.planner = MPC_Wrapper.Dummy() - n_steps = np.int(T_gait/dt_mpc) - self.planner.xref = np.zeros((12, 1 + n_steps)) - self.planner.gait = np.zeros((20, 5)) - self.planner.fsteps = np.zeros((20, 13)) - - def tearDown(self): - self.mpc_wrapper.stop_parallel_loop() # Stop MPC running in parallel process - - def test_fourstance_immobile(self): - - self.planner.xref[2, :] = 0.24474949993103629 - self.planner.gait[0, :] = np.array([16, 1, 1, 1, 1]) - self.planner.fsteps[0, :] = np.array([16, 0.195, 0.147, 0., 0.195, -0.147, 0., -0.195, 0.147, 0., -0.195, -0.147, 0.]) - """planner.fsteps[0, :] = np.array([7, 0.195, 0.147, 0., 0., 0., 0., 0., 0., 0., -0.195, -0.147, 0.]) - planner.fsteps[1, :] = np.array([8, 0., 0., 0., 0.195, -0.147, 0., -0.195, 0.147, 0., 0., 0., 0.]) - planner.fsteps[2, :] = np.array([1, 0.195, 0.147, 0., 0., 0., 0., 0., 0., 0., -0.195, -0.147, 0.])""" - - # First iteration returns [0.0, 0.0, 8.0] for all feet in contact - self.mpc_wrapper.solve(0, self.planner) - while not self.mpc_wrapper.newResult.value: - time.sleep(0.002) - x_f_mpc = self.mpc_wrapper.get_latest_result() - - # Second iteration should return [0.0, 0.0, mass/4] for all feet - for i in range(1, 100): - self.mpc_wrapper.solve(i, self.planner) - while not self.mpc_wrapper.newResult.value: - time.sleep(0.002) - x_f_mpc = self.mpc_wrapper.get_latest_result() # Retrieve last result of MPC - # print("X: ", x_f_mpc[:12, 0:6]) - # print("F: ", x_f_mpc[12:, 0:6]) - - self.planner.xref[:, 0] = x_f_mpc[:12, 0].copy() # Update current state of the robot - - # print(9.81*self.mass/4) - # print(x_f_mpc[12:, 0]) - # print(x_f_mpc[:12, 0] - self.planner.xref[:, 1]) - self.assertTrue(np.allclose(x_f_mpc[12:, 0], np.array([x_f_mpc[12, 0], x_f_mpc[13, 0], x_f_mpc[14, 0]] * 4)), "All feet forces are equal.") - self.assertTrue(np.allclose(x_f_mpc[:12, 0], self.planner.xref[:, 1], atol=1e-3), "Close to reference state") - # self.assertTrue(np.allclose(x_f_mpc[12:, 0], np.array([0.0, 0.0, 9.81*self.mass/4] * 4)), "Feet forces are equal to theorical value.") - - def test_fourstance_not_centered(self): - self.planner.xref[2, :] = 0.24474949993103629 - self.planner.gait[0, :] = np.array([16, 1, 1, 1, 1]) - self.planner.fsteps[0, :] = np.array([16, 0.195, 0.147, 0., 0.195, -0.147, 0., -0.195, 0.147, 0., -0.195, -0.147, 0.]) - - # Non centered state - self.planner.xref[:, 0] = np.array([0.05, 0.05, 0.2, 0.1, 0.1, 0.1, 0.01, 0.01, 0.04, 0.4, 0.4, 0.4]) - - # First iteration - self.mpc_wrapper.solve(0, self.planner) - while not self.mpc_wrapper.newResult.value: - time.sleep(0.002) - x_f_mpc = self.mpc_wrapper.get_latest_result() - - # Run the mpc during 500 iterations - for i in range(1,500): - self.mpc_wrapper.solve(i, self.planner) - while not self.mpc_wrapper.newResult.value: - time.sleep(0.002) - x_f_mpc = self.mpc_wrapper.get_latest_result() # Retrieve last result of MPC - self.planner.xref[:, 0] = x_f_mpc[:12, 0].copy() # Update current state of the robot - - self.assertTrue(np.allclose(x_f_mpc[12:, 0], np.array([x_f_mpc[12, 0], x_f_mpc[13, 0], x_f_mpc[14, 0]] * 4)), "All feet forces are equal.") - self.assertTrue(np.allclose(x_f_mpc[:12, 0], self.planner.xref[:, 1], atol=1e-3), "Close to reference state") - - def roll(self, gait, fsteps): - if(gait[0, 0]==1): - gait[2, 0] += 1 - fsteps[2, 0] += 1 - gait[0, :] = gait[1, :].copy() - gait[1, :] = gait[2, :].copy() - fsteps[0, :] = fsteps[1, :].copy() - fsteps[1, :] = fsteps[2, :].copy() - gait[2, :] *= 0.0 - fsteps[2, :] *= 0.0 - elif(gait[0, 0]==8): - gait[0, 0] -= 1 - fsteps[0, 0] -= 1 - gait[2, 0] = 1 - fsteps[2, 0] = 1 - gait[2, 1:] = gait[0, 1:].copy() - fsteps[2, 1:] = fsteps[0, 1:].copy() - else: - gait[0, 0] -= 1 - fsteps[0, 0] -= 1 - gait[2, 0] += 1 - fsteps[2, 0] += 1 - - # Two feet in stance phase at a given time (FL-HR and FR-HL) with a 0.32s gait period. Check if robot stays centered. - def test_twostance_centered(self): - pair_1 = np.array([0.195, 0.147, 0., 0., 0., 0., 0., 0., 0., -0.195, -0.147, 0.]) - pair_2 = np.array([0., 0., 0., 0.195, -0.147, 0., -0.195, 0.147, 0., 0., 0., 0.]) - - self.planner.xref[2, :] = 0.24474949993103629 - self.planner.gait[0, :] = np.array([7, 1, 0, 0, 1]) - self.planner.gait[1, :] = np.array([8, 0, 1, 1, 0]) - self.planner.gait[2, :] = np.array([1, 1, 0, 0, 1]) - self.planner.fsteps[0:3, 0] = np.array([7, 8, 1]) - self.planner.fsteps[0, 1:] = pair_1 - self.planner.fsteps[1, 1:] = pair_2 - self.planner.fsteps[2, 1:] = pair_1 - - # Run the mpc during 500 iterations - for i in range(0, 500): - self.mpc_wrapper.solve(i, self.planner) - while not self.mpc_wrapper.newResult.value: - time.sleep(0.002) - x_f_mpc = self.mpc_wrapper.get_latest_result() # Retrieve last result of MPC - self.roll(self.planner.gait, self.planner.fsteps) - if(i > 0): - self.planner.xref[:, 0] = x_f_mpc[:12, 0].copy() # Update current state of the robot - - print(x_f_mpc[:12, 0]) - self.assertTrue(np.allclose(x_f_mpc[:12, 0], self.planner.xref[:, 1], atol=1e-2), "Close to reference state") - - # Two feet in stance phase at a given time (FL-HR and FR-HL) with a 0.32s gait period. Check if robot stays centered. - def test_twostance_not_centered(self): - pair_1 = np.array([0.195, 0.147, 0., 0., 0., 0., 0., 0., 0., -0.195, -0.147, 0.]) - pair_2 = np.array([0., 0., 0., 0.195, -0.147, 0., -0.195, 0.147, 0., 0., 0., 0.]) - - self.planner.xref[2, :] = 0.24474949993103629 - self.planner.gait[0, :] = np.array([7, 1, 0, 0, 1]) - self.planner.gait[1, :] = np.array([8, 0, 1, 1, 0]) - self.planner.gait[2, :] = np.array([1, 1, 0, 0, 1]) - self.planner.fsteps[0:3, 0] = np.array([7, 8, 1]) - self.planner.fsteps[0, 1:] = pair_1 - self.planner.fsteps[1, 1:] = pair_2 - self.planner.fsteps[2, 1:] = pair_1 - - # Non centered state - self.planner.xref[:, 0] = np.array([0.05, 0.05, 0.2, 0.1, 0.1, 0.1, 0.01, 0.01, 0.04, 0.4, 0.4, 0.4]) - - # Run the mpc during 500 iterations - for i in range(0, 2000): - self.mpc_wrapper.solve(i, self.planner) - while not self.mpc_wrapper.newResult.value: - time.sleep(0.002) - x_f_mpc = self.mpc_wrapper.get_latest_result() # Retrieve last result of MPC - self.roll(self.planner.gait, self.planner.fsteps) - if(i > 0): - self.planner.xref[:, 0] = x_f_mpc[:12, 0].copy() # Update current state of the robot - - print(x_f_mpc[:12, 0]) - self.assertTrue(np.allclose(x_f_mpc[:12, 0], self.planner.xref[:, 1], atol=1e-2), "Close to reference state") - - - def test_upper(self): - self.assertEqual('foo'.upper(), 'FOO') - - - -if __name__ == '__main__': - unittest.main() diff --git a/scripts/test_new_InvKin.py b/scripts/test_new_InvKin.py deleted file mode 100644 index 00c1bfe1..00000000 --- a/scripts/test_new_InvKin.py +++ /dev/null @@ -1,214 +0,0 @@ -import numpy as np -import utils_mpc -from example_robot_data.robots_loader import Solo12Loader -import pinocchio as pin - -class Test: - - def __init__(self, params): - - self.k = 0 - self.k_mpc = 20 - self.dt_wbc = params.dt_wbc - q_init = np.array(params.q_init.tolist()) - - # Initialisation of the solo model/data and of the Gepetto viewer - self.solo = utils_mpc.init_robot(q_init, params) - - self.h_ref = params.h_ref - - self.wbcWrapper = qrw.WbcWrapper() - self.wbcWrapper.initialize(params) - - self.gait = qrw.Gait() - self.gait.initialize(params) - - self.footstepPlanner = qrw.FootstepPlanner() - self.footstepPlanner.initialize(params, self.gait) - - self.footTrajectoryGenerator = qrw.FootTrajectoryGenerator() - self.footTrajectoryGenerator.initialize(params, self.gait) - - self.q = np.zeros((19, 1)) # Orientation part is in roll pitch yaw - self.q[0:7, 0] = np.array([0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 1.0]) - self.q[7:, 0] = q_init - self.h_v = np.zeros((18, 1)) - self.h_v_ref = np.zeros((18, 1)) - - self.q_wbc = np.zeros((18, 1)) - self.dq_wbc = np.zeros((18, 1)) - self.xgoals = np.zeros((12, 1)) - self.xgoals[2, 0] = self.h_ref - - self.ddq_cmd = np.zeros((18, 1)) - - # Load robot model and data - """Solo12Loader.free_flyer = True - self.solo = Solo12Loader().robot""" - - def run(self): - - # Update gait - self.gait.updateGait(self.k, self.k_mpc, 0) - cgait = self.gait.getCurrentGait() - - # Compute target footstep based on current and reference velocities - qftps = np.zeros((18, 1)) - qftps[:3, 0] = self.q[:3, 0] - RPY = pin.rpy.matrixToRpy(pin.Quaternion(self.q[3:7, 0:1]).toRotationMatrix()) - qftps[3:6, 0] = RPY - qftps[6:, 0] = self.q[7:, 0] - o_targetFootstep = self.footstepPlanner.updateFootsteps(self.k % self.k_mpc == 0 and self.k != 0, - int(self.k_mpc - self.k % self.k_mpc), - qftps[:, 0], - self.h_v[0:6, 0:1].copy(), - self.h_v_ref[0:6, 0:1]) - - # Update pos, vel and acc references for feet - self.footTrajectoryGenerator.update(self.k, o_targetFootstep) - - # Update configuration vector for wbc - self.q_wbc[3, 0] = RPY[0] # Roll - self.q_wbc[4, 0] = RPY[1] # Pitch - self.q_wbc[6:, 0] = self.q[7:, 0] # Joints - - # Update velocity vector for wbc - self.dq_wbc[:, 0] = self.h_v[:, 0].copy() - - # Feet command position, velocity and acceleration in base frame - oRh = pin.Quaternion(self.q[3:7, 0:1]).toRotationMatrix() - oTh = self.q[:3, 0:1] - - self.feet_a_cmd = self.footTrajectoryGenerator.getFootAccelerationBaseFrame( - oRh.transpose(), np.zeros((3, 1)), np.zeros((3, 1))) - self.feet_v_cmd = self.footTrajectoryGenerator.getFootVelocityBaseFrame( - oRh.transpose(), np.zeros((3, 1)), np.zeros((3, 1))) - self.feet_p_cmd = self.footTrajectoryGenerator.getFootPositionBaseFrame( - oRh.transpose(), oTh + np.array([[0.0], [0.0], [self.h_ref]])) - - # Desired position, orientation and velocities of the base - self.xgoals[[0, 1, 5], 0] = np.zeros((3,)) - self.xgoals[2:5, 0] = [0.0, 0.0, 0.0] - - self.xgoals[6:, 0] = self.h_v_ref[:6, 0] # Velocities (in horizontal frame!) - - cgait = self.gait.getCurrentGait() - - """if self.k == 50: - from IPython import embed - embed()""" - - # Run InvKin + WBC QP - self.wbcWrapper.compute(self.q_wbc, self.dq_wbc, - np.zeros((12, 1)), np.array([cgait[0, :]]), - self.feet_p_cmd, - self.feet_v_cmd, - self.feet_a_cmd, - self.xgoals) - - # Quantities sent to the control board - self.h_v[:, 0] += self.dt_wbc * self.wbcWrapper.ddq_cmd[:] - self.q[:, 0] = pin.integrate(self.solo.model, self.q, self.dt_wbc * self.h_v) - - self.k += 1 - - -if __name__ == "__main__": - - import quadruped_reactive_walking as qrw - import pinocchio as pin - - params = qrw.Params() # Object that holds all controller parameters - params.enable_corba_viewer = True - test = Test(params) - q_display = np.zeros((19, 1)) - - test.h_v[0, 0] = 0.6 - test.h_v_ref[0, 0] = 0.7 - - N = 10000 - log_q = np.zeros((N, 19)) - log_q_wbc = np.zeros((N, 18)) - log_dq = np.zeros((N, 18)) - log_ddq_cmd = np.zeros((N, 18)) - log_ddq_with_delta = np.zeros((N, 18)) - for i in range(N): - test.run() - - log_ddq_cmd[i] = test.wbcWrapper.ddq_cmd - log_dq[i] = test.h_v[:, 0] - log_q[i] = test.q[:, 0] - log_q_wbc[i] = test.q_wbc[:, 0] - - print("#####-> ", test.h_v[0, 0]) - - """test.q[2, 0] = test.b_des[2] - test.q[3:6, 0] = pin.rpy.matrixToRpy(pin.Quaternion(test.b_des[3:7].reshape((-1, 1))).toRotationMatrix()) - test.q[6:, 0] = test.q_des[:]""" - - # Display robot in Gepetto corba viewer - if (i % 10 == 0 and i > 0): - q_display[:3, 0] = test.q[0:3, 0] - q_display[3:7, 0] = test.q[3:7, 0] - q_display[7:, 0] = test.q[7:, 0] - test.solo.display(q_display) - - """from IPython import embed - embed()""" - """test.q[0, 0] += params.dt_wbc * test.h_v[0, 0] - test.q[1, 0] = 0.0 - test.q[5, 0] = 0.0""" - - index6 = [1, 3, 5, 2, 4, 6] - - from matplotlib import pyplot as plt - t_range = np.array([k*0.001 for k in range(N)]) - - lgd = ["Acc X", "Acc Y", "Acc Z", "Acc Roll", "Acc Pitch", "Acc Yaw"] - plt.figure() - for i in range(6): - if i == 0: - ax0 = plt.subplot(3, 2, index6[i]) - else: - plt.subplot(3, 2, index6[i], sharex=ax0) - - plt.plot(t_range, log_ddq_cmd[:, i], "b", linewidth=3) - - plt.legend(["ddq_cmd"], prop={'size': 8}) - plt.ylabel(lgd[i]) - - plt.show(block=True) - - lgd = ["Pos X", "Pos Y", "Pos Z", "Roll", "Pitch", "Yaw"] - plt.figure() - for i in range(6): - if i == 0: - ax0 = plt.subplot(3, 2, index6[i]) - else: - plt.subplot(3, 2, index6[i], sharex=ax0) - - if i < 3: - plt.plot(t_range, log_q[:, i], "b", linewidth=3) - else: - plt.plot(t_range, log_q_wbc[:, i], "b", linewidth=3) - - plt.legend(["Robot state"], prop={'size': 8}) - plt.ylabel(lgd[i]) - - lgd = ["Vel X", "Vel Y", "Vel Z", "Vel Roll", "Vel Pitch", "Vel Yaw"] - plt.figure() - for i in range(6): - if i == 0: - ax0 = plt.subplot(3, 2, index6[i]) - else: - plt.subplot(3, 2, index6[i], sharex=ax0) - - plt.plot(t_range, log_dq[:, i], "b", linewidth=3) - - plt.legend(["Robot state"], prop={'size': 8}) - plt.ylabel(lgd[i]) - - plt.show(block=True) - from IPython import embed - embed() - diff --git a/scripts/test_tasks_InvKin.py b/scripts/test_tasks_InvKin.py deleted file mode 100644 index 0f2136f7..00000000 --- a/scripts/test_tasks_InvKin.py +++ /dev/null @@ -1,277 +0,0 @@ -import numpy as np -import utils_mpc -from example_robot_data.robots_loader import Solo12Loader -import pinocchio as pin -import quadruped_reactive_walking as qrw -from IPython import embed - -def check_task_tracking(): - - params = qrw.Params() # Object that holds all controller parameters - params.w_tasks = [1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0] # Keep only contact task - dt = params.dt_wbc - h_ref = 0.244749 - - # Load robot model and data - # Initialisation of the Gepetto viewer - Solo12Loader.free_flyer = True - solo = Solo12Loader().robot - q = solo.q0.reshape((-1, 1)) - q[2, 0] = h_ref - q[7:, 0] = params.q_init - dq = np.zeros((18, 1)) - - solo.initViewer(loadModel=True) - if ('viewer' in solo.viz.__dict__): - solo.viewer.gui.addFloor('world/floor') - solo.viewer.gui.setRefreshIsSynchronous(False) - solo.display(q) - - wbcWrapper = qrw.WbcWrapper() - wbcWrapper.initialize(params) - - feet_p_cmd0 = np.array([[0.1946, 0.1946, -0.1946, -0.1946], - [0.16891, -0.16891, 0.16891, -0.16891], - [0.0191028, 0.0191028, 0.0191028, 0.0191028]]) - feet_p_cmd0[2, :] = - h_ref - feet_p_cmd = np.zeros((3, 4)) - feet_v_cmd = np.zeros((3, 4)) - feet_a_cmd = np.zeros((3, 4)) - xgoals = np.zeros((12, 1)) - q_wbc = np.zeros((18, 1)) - - k = 0 - N = 50000 - while k < N: - - # Rotation from world to base frame - oRb = pin.Quaternion(q[3:7, 0:1]).toRotationMatrix() - - # Roll pitch yaw vector - RPY = pin.rpy.matrixToRpy(oRb) - - # Rotation from horizontal to base frame - hRb = pin.rpy.rpyToMatrix(RPY[0], RPY[1], 0.0) - - # Target positions of feet - feet_p_cmd = feet_p_cmd0.copy() - feet_v_cmd = np.zeros((3, 4)) - feet_a_cmd = np.zeros((3, 4)) - feet_p_cmd[0, 0] = 0.1946 + 0.04 * np.sin(2 * np.pi * 0.25 * k * dt) - feet_p_cmd[1, 1] = -0.16891 + 0.04 * np.sin(2 * np.pi * 0.25 * k * dt) - feet_p_cmd[2, 2] = - h_ref + 0.04 * np.sin(2 * np.pi * 0.25 * k * dt) - feet_v_cmd[0, 0] = 0.04 * 2 * np.pi * 0.25 * np.cos(2 * np.pi * 0.25 * k * dt) - feet_v_cmd[1, 1] = 0.04 * 2 * np.pi * 0.25 * np.cos(2 * np.pi * 0.25 * k * dt) - feet_v_cmd[2, 2] = 0.04 * 2 * np.pi * 0.25 * np.cos(2 * np.pi * 0.25 * k * dt) - feet_a_cmd[0, 0] = -0.04 * (2 * np.pi * 0.25)**2 * np.sin(2 * np.pi * 0.25 * k * dt) - feet_a_cmd[1, 1] = -0.04 * (2 * np.pi * 0.25)**2 * np.sin(2 * np.pi * 0.25 * k * dt) - feet_a_cmd[2, 2] = -0.04 * (2 * np.pi * 0.25)**2 * np.sin(2 * np.pi * 0.25 * k * dt) - - # Express feet so that they follow base orientation - feet_p_cmd = hRb @ feet_p_cmd - feet_v_cmd = hRb @ feet_v_cmd - feet_a_cmd = hRb @ feet_a_cmd - - # Goal is 20 degrees in pitch - xgoals[4, 0] = - 20.0 / 57 - - # Make q_wbc vector - q_wbc[:3, 0] = np.zeros(3) # Position - q_wbc[3, 0] = RPY[0] # Roll - q_wbc[4, 0] = RPY[1] # Pitch - q_wbc[5, 0] = 0.0 # Yaw - q_wbc[6:, 0] = q[7:, 0] # Actuators - - # Run InvKin + WBC QP - wbcWrapper.compute(q_wbc, dq, np.zeros(12), np.array([[0.0, 0.0, 0.0, 1.0]]), - feet_p_cmd, feet_v_cmd, feet_a_cmd, xgoals) - - # Velocity integration - dq[0:3, 0:1] += dt * oRb.transpose() @ wbcWrapper.ddq_cmd[0:3].reshape((-1, 1)) - dq[3:6, 0:1] += dt * oRb.transpose() @ wbcWrapper.ddq_cmd[3:6].reshape((-1, 1)) - dq[6:, 0] += dt * wbcWrapper.ddq_cmd[6:] - - # Position integration - q[:, 0] = pin.integrate(solo.model, q, dt * dq) - - k += 1 - - if (k % 10 == 0): - solo.display(q) - - -def check_task_contact(): - - params = qrw.Params() # Object that holds all controller parameters - params.w_tasks = [1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0] # Keep only contact task - dt = params.dt_wbc - h_ref = 0.244749 - - # Load robot model and data - # Initialisation of the Gepetto viewer - Solo12Loader.free_flyer = True - solo = Solo12Loader().robot - q = solo.q0.reshape((-1, 1)) - q[2, 0] = h_ref - q[7:, 0] = params.q_init - dq = np.zeros((18, 1)) - - solo.initViewer(loadModel=True) - if ('viewer' in solo.viz.__dict__): - solo.viewer.gui.addFloor('world/floor') - solo.viewer.gui.setRefreshIsSynchronous(False) - solo.display(q) - - wbcWrapper = qrw.WbcWrapper() - wbcWrapper.initialize(params) - - feet_p_cmd0 = np.array([[0.1946, 0.1946, -0.1946, -0.1946], - [0.16891, -0.16891, 0.16891, -0.16891], - [0.0191028, 0.0191028, 0.0191028, 0.0191028]]) - feet_p_cmd0[2, :] = - h_ref - feet_p_cmd = np.zeros((3, 4)) - feet_v_cmd = np.zeros((3, 4)) - feet_a_cmd = np.zeros((3, 4)) - xgoals = np.zeros((12, 1)) - q_wbc = np.zeros((18, 1)) - - k = 0 - N = 10000 - freq = 0.2 - log_f = np.zeros((N, 3, 4)) - log_fcmd = np.zeros((N, 3, 4)) - dx = 0.0 - dy = 0.0 - dw = 0.0 - while k < N: - - # Displacement - sig = np.sign(np.sin(2 * np.pi * freq * k * dt)) - V = 0.02 - W = 10.0 / 57 - dx += dt * V * sig - dy += dt * V * sig - dw += dt * W * sig - q[0, 0] = dx # 0.04 * np.cos(2 * np.pi * freq * k * dt) - q[1, 0] = dy # 0.04 * np.sin(2 * np.pi * freq * k * dt) - RPY = pin.rpy.matrixToRpy(pin.Quaternion(q[3:7, 0:1]).toRotationMatrix()) - RPY[2] = dw - q[3:7, 0] = pin.Quaternion(pin.rpy.rpyToMatrix(RPY[0], RPY[1], RPY[2])).coeffs() - - # Rotation from world to base frame - oRb = pin.Quaternion(q[3:7, 0:1]).toRotationMatrix() - - # Roll pitch yaw vector - RPY = pin.rpy.matrixToRpy(oRb) - - # Rotation from horizontal to base frame - oRh = pin.rpy.rpyToMatrix(0.0, 0.0, RPY[2]) - hRb = pin.rpy.rpyToMatrix(RPY[0], RPY[1], 0.0) - - # Target positions of feet - feet_p_cmd = feet_p_cmd0.copy() - feet_v_cmd = np.zeros((3, 4)) - feet_a_cmd = np.zeros((3, 4)) - - # Feet in the air move with the base - """feet_p_cmd[0, 1] += 0.04 * np.cos(2 * np.pi * freq * k * dt) - feet_p_cmd[1, 1] += 0.04 * np.sin(2 * np.pi * freq * k * dt) - feet_p_cmd[0, 2] += 0.04 * np.cos(2 * np.pi * freq * k * dt) - feet_p_cmd[1, 2] += 0.04 * np.sin(2 * np.pi * freq * k * dt)""" - - """feet_v_cmd[0, 1] = -0.04 * 2 * np.pi * freq * np.sin(2 * np.pi * freq * k * dt) - feet_v_cmd[1, 1] = 0.04 * 2 * np.pi * freq * np.cos(2 * np.pi * freq * k * dt) - feet_v_cmd[0, 2] = -0.04 * 2 * np.pi * freq * np.sin(2 * np.pi * freq * k * dt) - feet_v_cmd[1, 2] = 0.04 * 2 * np.pi * freq * np.cos(2 * np.pi * freq * k * dt) - - feet_a_cmd[0, 1] = -0.04 * (2 * np.pi * freq)**2 * np.cos(2 * np.pi * freq * k * dt) - feet_a_cmd[1, 1] = -0.04 * (2 * np.pi * freq)**2 * np.sin(2 * np.pi * freq * k * dt) - feet_a_cmd[0, 2] = -0.04 * (2 * np.pi * freq)**2 * np.cos(2 * np.pi * freq * k * dt) - feet_a_cmd[1, 2] = -0.04 * (2 * np.pi * freq)**2 * np.sin(2 * np.pi * freq * k * dt) - - # Feet in contact do not move with the base - feet_p_cmd[0, 0] -= 0.04 * np.cos(2 * np.pi * freq * k * dt) - feet_p_cmd[1, 0] -= 0.04 * np.sin(2 * np.pi * freq * k * dt) - feet_p_cmd[0, 3] -= 0.04 * np.cos(2 * np.pi * freq * k * dt) - feet_p_cmd[1, 3] -= 0.04 * np.sin(2 * np.pi * freq * k * dt)""" - - feet_v_cmd[0, 1] = V * sig - feet_v_cmd[1, 1] = V * sig - feet_v_cmd[0, 2] = V * sig - feet_v_cmd[1, 2] = V * sig - - for i in [0, 3]: - feet_p_cmd[0, i] -= dx - feet_p_cmd[1, i] -= dy - feet_p_cmd[:, i:(i+1)] = oRh.transpose() @ feet_p_cmd[:, i:(i+1)] - feet_v_cmd[:, i:(i+1)] = oRh.transpose() @ feet_v_cmd[:, i:(i+1)] - feet_a_cmd[:, i:(i+1)] = oRh.transpose() @ feet_a_cmd[:, i:(i+1)] - - # Express feet so that they follow base orientation - feet_p_cmd = hRb @ feet_p_cmd - feet_v_cmd = hRb @ feet_v_cmd - feet_a_cmd = hRb @ feet_a_cmd - - # Make q_wbc vector - q_wbc[:3, 0] = np.zeros(3) # Position - q_wbc[3, 0] = RPY[0] # Roll - q_wbc[4, 0] = RPY[1] # Pitch - q_wbc[5, 0] = 0.0 # Yaw - q_wbc[6:, 0] = q[7:, 0] # Actuators - - xgoals[6, 0] = V * sig - xgoals[7, 0] = V * sig - xgoals[11, 0] = W * sig - - # Run InvKin + WBC QP - wbcWrapper.compute(q_wbc, dq, np.zeros(12), np.array([[1.0, 0.0, 0.0, 1.0]]), - feet_p_cmd, feet_v_cmd, feet_a_cmd, xgoals) - - # Logging - """log_f_cmd = feet_p_cmd0.copy() - log_f_cmd[0, 1] += 0.04 * np.cos(2 * np.pi * freq * k * dt) - log_f_cmd[1, 1] += 0.04 * np.sin(2 * np.pi * freq * k * dt) - log_f_cmd[0, 2] += 0.04 * np.cos(2 * np.pi * freq * k * dt) - log_f_cmd[1, 2] += 0.04 * np.sin(2 * np.pi * freq * k * dt)""" - log_fcmd[k] = wbcWrapper.feet_pos_target - log_fcmd[k, 0, :] += q[0, 0] - log_fcmd[k, 1, :] += q[1, 0] - log_fcmd[k, :, :] = oRh @ log_fcmd[k, :, :] - log_f[k] = wbcWrapper.feet_pos - log_f[k, 0, :] += q[0, 0] - log_f[k, 1, :] += q[1, 0] - log_f[k, :, :] = oRh @ log_f[k, :, :] - - # Velocity integration - dq[0:3, 0:1] += dt * oRb.transpose() @ wbcWrapper.ddq_cmd[0:3].reshape((-1, 1)) - dq[3:6, 0:1] += dt * oRb.transpose() @ wbcWrapper.ddq_cmd[3:6].reshape((-1, 1)) - dq[6:, 0] += dt * wbcWrapper.ddq_cmd[6:] - - # Position integration - q[:, 0] = pin.integrate(solo.model, q, dt * dq) - - k += 1 - - if (k % 10 == 0): - solo.display(q) - - from matplotlib import pyplot as plt - for j in range(3): - plt.figure() - for i in range(4): - if i == 0: - ax0 = plt.subplot(2, 2, i+1) - else: - plt.subplot(2, 2, i+1, sharex=ax0) - - plt.plot(log_f[:, j, i], "b", linewidth=3) - plt.plot(log_fcmd[:, j, i], "r", linewidth=3, linestyle="--") - - plt.legend(["Mes", "Ref"], prop={'size': 8}) - - plt.show(block=True) - -if __name__ == "__main__": - - # check_task_tracking() - check_task_contact() diff --git a/scripts/ForceMonitor.py b/scripts/tools/ForceMonitor.py similarity index 99% rename from scripts/ForceMonitor.py rename to scripts/tools/ForceMonitor.py index bb573625..36a4eb8d 100644 --- a/scripts/ForceMonitor.py +++ b/scripts/tools/ForceMonitor.py @@ -1,9 +1,5 @@ -# coding: utf8 - -import numpy as np import pybullet as pyb - class ForceMonitor: def __init__(self, robotId, planeId): diff --git a/scripts/LoggerControl.py b/scripts/tools/LoggerControl.py similarity index 100% rename from scripts/LoggerControl.py rename to scripts/tools/LoggerControl.py diff --git a/scripts/LoggerSensors.py b/scripts/tools/LoggerSensors.py similarity index 100% rename from scripts/LoggerSensors.py rename to scripts/tools/LoggerSensors.py diff --git a/scripts/PyBulletSimulator.py b/scripts/tools/PyBulletSimulator.py similarity index 100% rename from scripts/PyBulletSimulator.py rename to scripts/tools/PyBulletSimulator.py diff --git a/scripts/gamepadClient.py b/scripts/tools/gamepadClient.py similarity index 100% rename from scripts/gamepadClient.py rename to scripts/tools/gamepadClient.py diff --git a/scripts/place_com_with_invkin.py b/scripts/tools/place_com_with_invkin.py similarity index 99% rename from scripts/place_com_with_invkin.py rename to scripts/tools/place_com_with_invkin.py index ec936ced..a34d50e6 100644 --- a/scripts/place_com_with_invkin.py +++ b/scripts/tools/place_com_with_invkin.py @@ -1,7 +1,6 @@ -from IPython import embed import numpy as np -from example_robot_data.robots_loader import Solo12Loader import pinocchio as pin +from example_robot_data.robots_loader import Solo12Loader # Parameters of the Invkin l = 0.1946 * 2 diff --git a/scripts/tools/qualisysClient.py b/scripts/tools/qualisysClient.py new file mode 100644 index 00000000..614da788 --- /dev/null +++ b/scripts/tools/qualisysClient.py @@ -0,0 +1,161 @@ +""" +This client connects to a Qualisys (motion capture) server with an asyncronous subprocess and expose 6d position and velocity of a given body +Thomas FLAYOLS - LAAS CNRS +""" + +import asyncio +from multiprocessing import Process, Lock +from multiprocessing.sharedctypes import Value, Array +from ctypes import c_double +import qtm +import numpy as np + +import pinocchio +from pinocchio.utils import se3ToXYZQUAT +from pinocchio.explog import log + + +class QualisysClient(): + def __init__(self, ip="127.0.0.1", body_id=0): + # shared c_double array + self.shared_bodyPosition = Array(c_double, 3, lock=False) + self.shared_bodyVelocity = Array(c_double, 3, lock=False) + self.shared_bodyOrientationQuat = Array(c_double, 4, lock=False) + self.shared_bodyOrientationMat9 = Array(c_double, 9, lock=False) + self.shared_bodyAngularVelocity = Array(c_double, 3, lock=False) + self.shared_timestamp = Value(c_double, lock=False) + #self.shared_timestamp = -1 + args = (ip, body_id, self.shared_bodyPosition, self.shared_bodyVelocity, + self.shared_bodyOrientationQuat, self.shared_bodyOrientationMat9, + self.shared_bodyAngularVelocity, self.shared_timestamp) + self.p = Process(target=self.qualisys_process, args=args) + self.p.start() + + def stop(self): + self.p.terminate() + self.p.join() + + def getPosition(self): + return np.array([self.shared_bodyPosition[0], + self.shared_bodyPosition[1], + self.shared_bodyPosition[2]]) + + def getVelocity(self): + return np.array([self.shared_bodyVelocity[0], + self.shared_bodyVelocity[1], + self.shared_bodyVelocity[2]]) + + def getAngularVelocity(self): + return np.array([self.shared_bodyAngularVelocity[0], + self.shared_bodyAngularVelocity[1], + self.shared_bodyAngularVelocity[2]]) + + def getOrientationMat9(self): + return np.array([[self.shared_bodyOrientationMat9[0], self.shared_bodyOrientationMat9[1], self.shared_bodyOrientationMat9[2]], + [self.shared_bodyOrientationMat9[3], self.shared_bodyOrientationMat9[4], + self.shared_bodyOrientationMat9[5]], + [self.shared_bodyOrientationMat9[6], self.shared_bodyOrientationMat9[7], self.shared_bodyOrientationMat9[8]]]) + + def getOrientationQuat(self): + return np.array([self.shared_bodyOrientationQuat[0], + self.shared_bodyOrientationQuat[1], + self.shared_bodyOrientationQuat[2], + self.shared_bodyOrientationQuat[3]]) + + def qualisys_process(self, ip, body_id, shared_bodyPosition, shared_bodyVelocity, + shared_bodyOrientationQuat, shared_bodyOrientationMat9, + shared_bodyAngularVelocity, shared_timestamp): + print("Qualisys process!") + ''' This will run on a different process''' + shared_timestamp.value = -1 + + def on_packet(packet): + """ Callback function that is called everytime a data packet arrives from QTM """ + position = packet.get_6d()[1][body_id][0] + orientation = packet.get_6d()[1][body_id][1] + timestamp = packet.timestamp * 1e-6 + + # Get the last position and Rotation matrix from the shared memory. + last_position = np.array( + [shared_bodyPosition[0], shared_bodyPosition[1], shared_bodyPosition[2]]) + last_rotation = np.array([[shared_bodyOrientationMat9[0], shared_bodyOrientationMat9[1], shared_bodyOrientationMat9[2]], + [shared_bodyOrientationMat9[3], shared_bodyOrientationMat9[4], shared_bodyOrientationMat9[5]], + [shared_bodyOrientationMat9[6], shared_bodyOrientationMat9[7], shared_bodyOrientationMat9[8]]]) + last_se3 = pinocchio.SE3(last_rotation, last_position) + + # Get the new position and Rotation matrix from the motion capture. + position = np.array([position.x, position.y, position.z]) * 1e-3 + rotation = np.array(orientation.matrix).reshape(3, 3).transpose() + se3 = pinocchio.SE3(rotation, position) + xyzquat = se3ToXYZQUAT(se3) + + # Get the position, Rotation matrix and Quaternion + shared_bodyPosition[0] = xyzquat[0] + shared_bodyPosition[1] = xyzquat[1] + shared_bodyPosition[2] = xyzquat[2] + shared_bodyOrientationQuat[0] = xyzquat[3] + shared_bodyOrientationQuat[1] = xyzquat[4] + shared_bodyOrientationQuat[2] = xyzquat[5] + shared_bodyOrientationQuat[3] = xyzquat[6] + + shared_bodyOrientationMat9[0] = orientation.matrix[0] + shared_bodyOrientationMat9[1] = orientation.matrix[3] + shared_bodyOrientationMat9[2] = orientation.matrix[6] + shared_bodyOrientationMat9[3] = orientation.matrix[1] + shared_bodyOrientationMat9[4] = orientation.matrix[4] + shared_bodyOrientationMat9[5] = orientation.matrix[7] + shared_bodyOrientationMat9[6] = orientation.matrix[2] + shared_bodyOrientationMat9[7] = orientation.matrix[5] + shared_bodyOrientationMat9[8] = orientation.matrix[8] + + # Compute world velocity. + if (shared_timestamp.value == -1): + shared_bodyVelocity[0] = 0 + shared_bodyVelocity[1] = 0 + shared_bodyVelocity[2] = 0 + shared_bodyAngularVelocity[0] = 0.0 + shared_bodyAngularVelocity[1] = 0.0 + shared_bodyAngularVelocity[2] = 0.0 + else: + dt = timestamp - shared_timestamp.value + shared_bodyVelocity[0] = (position[0] - last_position[0])/dt + shared_bodyVelocity[1] = (position[1] - last_position[1])/dt + shared_bodyVelocity[2] = (position[2] - last_position[2])/dt + bodyAngularVelocity = log(last_se3.rotation.T.dot(se3.rotation))/dt + shared_bodyAngularVelocity[0] = bodyAngularVelocity[0] + shared_bodyAngularVelocity[1] = bodyAngularVelocity[1] + shared_bodyAngularVelocity[2] = bodyAngularVelocity[2] + + shared_timestamp.value = timestamp + + async def setup(): + """ Main function """ + connection = await qtm.connect(ip) + if connection is None: + print("no connection with qualisys!") + return + print("Connected") + try: + await connection.stream_frames(components=["6d"], on_packet=on_packet) + except: + print("connection with qualisys lost") + + asyncio.ensure_future(setup()) + asyncio.get_event_loop().run_forever() + + +def exampleOfUse(): + import time + qc = QualisysClient(ip="140.93.16.160", body_id=0) + for i in range(300): + print(chr(27) + "[2J") + print("position: ", qc.getPosition()) + print("quaternion: ", qc.getOrientationQuat()) + print("linear velocity: ", qc.getVelocity()) + print("angular velocity: ", qc.getAngularVelocity()) + time.sleep(0.3) + print("killme!") + + +if __name__ == "__main__": + exampleOfUse() diff --git a/scripts/utils_mpc.py b/scripts/tools/utils_mpc.py similarity index 69% rename from scripts/utils_mpc.py rename to scripts/tools/utils_mpc.py index 7651307f..b0b82fd9 100644 --- a/scripts/utils_mpc.py +++ b/scripts/tools/utils_mpc.py @@ -3,11 +3,6 @@ from example_robot_data.robots_loader import Solo12Loader import pinocchio as pin -################## -# Initialisation # -################## - - def init_robot(q_init, params): """Load the solo model and initialize the Gepetto viewer if it is enabled @@ -15,7 +10,6 @@ def init_robot(q_init, params): q_init (array): the default position of the robot actuators params (object): store parameters """ - # Load robot model and data # Initialisation of the Gepetto viewer Solo12Loader.free_flyer = True @@ -81,35 +75,6 @@ def init_robot(q_init, params): for j in range(3): params.shoulders[3*i+j] = shoulders_init[j, i] params.footsteps_init[3*i+j] = fsteps_init[j, i] - params.footsteps_under_shoulders[3*i+j] = fsteps_init[j, i] # Use initial feet pos as reference + params.footsteps_under_shoulders[3*i+j] = fsteps_init[j, i] #  Use initial feet pos as reference return solo - - -def display_all(solo, k, sequencer, fstep_planner, ftraj_gen, mpc): - """Update various objects in the Gepetto viewer: the Solo robot as well as debug spheres - - Args: - k (int): current iteration of the simulation - sequencer (object): ContactSequencer object - fstep_planner (object): FootstepPlanner object - ftraj_gen (object): FootTrajectoryGenerator object - mpc (object): MpcSolver object - """ - - # Display non-locked target footholds with green spheres (gepetto gui) - fstep_planner.update_viewer(solo.viewer, (k == 0)) - - # Display locked target footholds with red spheres (gepetto gui) - # Display desired 3D position of feet with magenta spheres (gepetto gui) - ftraj_gen.update_viewer(solo.viewer, (k == 0)) - - # Display reference trajectory, predicted trajectory, desired contact forces, current velocity - # mpc.update_viewer(solo.viewer, (k == 0), sequencer) - # mpc.plot_graphs(sequencer) - - qu_pinocchio = np.array(solo.q0).flatten() - qu_pinocchio[0:3] = mpc.q_w[0:3, 0] - qu_pinocchio[3:7] = pin.rpy.matrixToRpy(pin.Quaternion(mpc.q_w[3:6, 0]).toRotationMatrix()).ravel() - # Refresh the gepetto viewer display - solo.display(qu_pinocchio) diff --git a/src/Controller.cpp b/src/Controller.cpp index e9b787c4..6404dd5f 100644 --- a/src/Controller.cpp +++ b/src/Controller.cpp @@ -2,6 +2,10 @@ #include "pinocchio/algorithm/crba.hpp" #include "pinocchio/math/rpy.hpp" +#include "pinocchio/math/rpy.hpp" +#include "pinocchio/parsers/urdf.hpp" +#include "pinocchio/algorithm/compute-all-terms.hpp" +#include "pinocchio/algorithm/frames.hpp" Controller::Controller() : P(Vector12::Zero()), diff --git a/src/FootstepPlanner.cpp b/src/FootstepPlanner.cpp index e0fb9d45..fda686c3 100644 --- a/src/FootstepPlanner.cpp +++ b/src/FootstepPlanner.cpp @@ -1,5 +1,10 @@ #include <example-robot-data/path.hpp> +#include "pinocchio/math/rpy.hpp" +#include "pinocchio/parsers/urdf.hpp" +#include "pinocchio/algorithm/compute-all-terms.hpp" +#include "pinocchio/algorithm/frames.hpp" + #include "qrw/FootstepPlanner.hpp" FootstepPlanner::FootstepPlanner() diff --git a/src/Joystick.cpp b/src/Joystick.cpp index d29885eb..c4c02f4a 100644 --- a/src/Joystick.cpp +++ b/src/Joystick.cpp @@ -1,5 +1,9 @@ #include "qrw/Joystick.hpp" +#include <fcntl.h> +#include <stdio.h> +#include <unistd.h> + Joystick::Joystick() : A3_(Vector6::Zero()), A2_(Vector6::Zero()), @@ -9,6 +13,12 @@ Joystick::Joystick() v_gp_(Vector6::Zero()), v_ref_heavy_filter_(Vector6::Zero()) {} +Joystick::~Joystick() { + if (js != -1) { + close(js); + } +} + void Joystick::initialize(Params& params) { params_ = ¶ms; dt_wbc = params.dt_wbc; diff --git a/src/MpcWrapper.cpp b/src/MpcWrapper.cpp index b781d5a8..1aa24e55 100644 --- a/src/MpcWrapper.cpp +++ b/src/MpcWrapper.cpp @@ -1,4 +1,7 @@ #include "qrw/MpcWrapper.hpp" +#include <chrono> +#include <thread> +#include <mutex> // Shared global variables Params* shared_params = nullptr; // Shared pointer to object that stores parameters diff --git a/src/FootTrajectoryGeneratorBezier.cpp b/src/Solo3D/FootTrajectoryGeneratorBezier.cpp similarity index 99% rename from src/FootTrajectoryGeneratorBezier.cpp rename to src/Solo3D/FootTrajectoryGeneratorBezier.cpp index 47f7aa87..381b39bf 100644 --- a/src/FootTrajectoryGeneratorBezier.cpp +++ b/src/Solo3D/FootTrajectoryGeneratorBezier.cpp @@ -1,6 +1,10 @@ #include <example-robot-data/path.hpp> -#include "qrw/FootTrajectoryGeneratorBezier.hpp" +#include "pinocchio/math/rpy.hpp" +#include "pinocchio/parsers/urdf.hpp" +#include "pinocchio/algorithm/compute-all-terms.hpp" +#include "pinocchio/algorithm/frames.hpp" +#include "qrw/Solo3D/FootTrajectoryGeneratorBezier.hpp" #include <chrono> diff --git a/src/FootstepPlannerQP.cpp b/src/Solo3D/FootstepPlannerQP.cpp similarity index 98% rename from src/FootstepPlannerQP.cpp rename to src/Solo3D/FootstepPlannerQP.cpp index c290c31a..c4195bf0 100644 --- a/src/FootstepPlannerQP.cpp +++ b/src/Solo3D/FootstepPlannerQP.cpp @@ -1,6 +1,11 @@ #include <example-robot-data/path.hpp> -#include "qrw/FootstepPlannerQP.hpp" +#include "pinocchio/math/rpy.hpp" +#include "pinocchio/parsers/urdf.hpp" +#include "pinocchio/algorithm/compute-all-terms.hpp" +#include "pinocchio/algorithm/frames.hpp" + +#include "qrw/Solo3D/FootstepPlannerQP.hpp" FootstepPlannerQP::FootstepPlannerQP() : gait_(NULL), diff --git a/src/Heightmap.cpp b/src/Solo3D/Heightmap.cpp similarity index 98% rename from src/Heightmap.cpp rename to src/Solo3D/Heightmap.cpp index 2ebb340a..b460258b 100644 --- a/src/Heightmap.cpp +++ b/src/Solo3D/Heightmap.cpp @@ -1,4 +1,4 @@ -#include "qrw/Heightmap.hpp" +#include "qrw/Solo3D/Heightmap.hpp" Heightmap::Heightmap() : z_(), diff --git a/src/StatePlanner3D.cpp b/src/Solo3D/StatePlanner3D.cpp similarity index 96% rename from src/StatePlanner3D.cpp rename to src/Solo3D/StatePlanner3D.cpp index ef1cc62f..1eb8977c 100644 --- a/src/StatePlanner3D.cpp +++ b/src/Solo3D/StatePlanner3D.cpp @@ -1,4 +1,9 @@ -#include "qrw/StatePlanner3D.hpp" +#include "qrw/Solo3D/StatePlanner3D.hpp" + +#include "pinocchio/math/rpy.hpp" +#include "pinocchio/parsers/urdf.hpp" +#include "pinocchio/algorithm/compute-all-terms.hpp" +#include "pinocchio/algorithm/frames.hpp" StatePlanner3D::StatePlanner3D() : nStates_(0), diff --git a/src/Surface.cpp b/src/Solo3D/Surface.cpp similarity index 96% rename from src/Surface.cpp rename to src/Solo3D/Surface.cpp index 24ab1746..13e05999 100644 --- a/src/Surface.cpp +++ b/src/Solo3D/Surface.cpp @@ -1,4 +1,4 @@ -#include "qrw/Surface.hpp" +#include "qrw/Solo3D/Surface.hpp" Surface::Surface() { // Empty diff --git a/src/st_to_cc.cpp b/src/st_to_cc.cpp index 7e3869b5..67254e00 100644 --- a/src/st_to_cc.cpp +++ b/src/st_to_cc.cpp @@ -1,8 +1,7 @@ #include <stdlib.h> #include <stdio.h> -#include <math.h> #include <time.h> -#include <string.h> +#include <math.h> #include "other/st_to_cc.hpp" diff --git a/scripts/crocoddyl_eval/README.md b/tests/python/crocoddyl/README.md similarity index 100% rename from scripts/crocoddyl_eval/README.md rename to tests/python/crocoddyl/README.md diff --git a/scripts/crocoddyl_eval/test_1/analyse_control_cycle.py b/tests/python/crocoddyl/analyse_control_cycle.py similarity index 100% rename from scripts/crocoddyl_eval/test_1/analyse_control_cycle.py rename to tests/python/crocoddyl/analyse_control_cycle.py diff --git a/scripts/crocoddyl_eval/test_3/analyse_control_cycle.py b/tests/python/crocoddyl/analyse_control_cycle_2.py similarity index 100% rename from scripts/crocoddyl_eval/test_3/analyse_control_cycle.py rename to tests/python/crocoddyl/analyse_control_cycle_2.py diff --git a/scripts/crocoddyl_eval/test_4/analyse_simu.py b/tests/python/crocoddyl/analyse_simu.py similarity index 100% rename from scripts/crocoddyl_eval/test_4/analyse_simu.py rename to tests/python/crocoddyl/analyse_simu.py diff --git a/scripts/crocoddyl_eval/test_5/analyse_simu.py b/tests/python/crocoddyl/analyse_simu_2.py similarity index 100% rename from scripts/crocoddyl_eval/test_5/analyse_simu.py rename to tests/python/crocoddyl/analyse_simu_2.py diff --git a/scripts/crocoddyl_eval/test_6/compare_mpcs.py b/tests/python/crocoddyl/compare_mpcs.py similarity index 100% rename from scripts/crocoddyl_eval/test_6/compare_mpcs.py rename to tests/python/crocoddyl/compare_mpcs.py diff --git a/scripts/crocoddyl_eval/test_4/main.py b/tests/python/crocoddyl/main.py similarity index 100% rename from scripts/crocoddyl_eval/test_4/main.py rename to tests/python/crocoddyl/main.py diff --git a/scripts/crocoddyl_eval/test_5/main.py b/tests/python/crocoddyl/main_2.py similarity index 100% rename from scripts/crocoddyl_eval/test_5/main.py rename to tests/python/crocoddyl/main_2.py diff --git a/scripts/crocoddyl_eval/test_4/run_scenarios.py b/tests/python/crocoddyl/run_scenarios.py similarity index 100% rename from scripts/crocoddyl_eval/test_4/run_scenarios.py rename to tests/python/crocoddyl/run_scenarios.py diff --git a/scripts/crocoddyl_eval/test_5/run_scenarios.py b/tests/python/crocoddyl/run_scenarios_2.py similarity index 100% rename from scripts/crocoddyl_eval/test_5/run_scenarios.py rename to tests/python/crocoddyl/run_scenarios_2.py diff --git a/scripts/crocoddyl_eval/test_2/unittest_augmented.py b/tests/python/crocoddyl/unittest_augmented.py similarity index 100% rename from scripts/crocoddyl_eval/test_2/unittest_augmented.py rename to tests/python/crocoddyl/unittest_augmented.py diff --git a/scripts/crocoddyl_eval/test_2/unittest_linear.py b/tests/python/crocoddyl/unittest_linear.py similarity index 100% rename from scripts/crocoddyl_eval/test_2/unittest_linear.py rename to tests/python/crocoddyl/unittest_linear.py diff --git a/scripts/crocoddyl_eval/test_2/unittest_nonlinear.py b/tests/python/crocoddyl/unittest_nonlinear.py similarity index 100% rename from scripts/crocoddyl_eval/test_2/unittest_nonlinear.py rename to tests/python/crocoddyl/unittest_nonlinear.py diff --git a/scripts/crocoddyl_eval/test_2/unittest_step.py b/tests/python/crocoddyl/unittest_step.py similarity index 100% rename from scripts/crocoddyl_eval/test_2/unittest_step.py rename to tests/python/crocoddyl/unittest_step.py -- GitLab