From 52a3b065228c0d6de0090d70a163a572b75c1cb3 Mon Sep 17 00:00:00 2001 From: Nathan Kau Date: Sat, 11 Apr 2020 01:47:54 -0700 Subject: [PATCH 01/49] Add pybullet sim code --- RunPyBulletSim.py | 96 +++++++++++++++++++ {src => common}/Command.py | 0 {src => common}/Controller.py | 13 +-- {src => common}/Gaits.py | 0 {src => common}/IMU.py | 0 {src => common}/JoystickInterface.py | 6 +- {src => common}/StanceController.py | 0 {src => common}/State.py | 4 +- {src => common}/SwingLegController.py | 0 {src => common}/Tests.py | 0 {src => common}/Utilities.py | 0 {src => common}/__init__.py | 0 run_robot.py | 12 +-- sim/HardwareInterface.py | 41 ++++++++ sim/IMU.py | 13 +++ sim/Sim.py | 29 ++++++ sim/__init__.py | 0 sim/pupper_pybullet_out.xml | 129 ++++++++++++++++++++++++++ sim/test.py | 1 + 19 files changed, 327 insertions(+), 17 deletions(-) create mode 100644 RunPyBulletSim.py rename {src => common}/Command.py (100%) rename {src => common}/Controller.py (93%) rename {src => common}/Gaits.py (100%) rename {src => common}/IMU.py (100%) rename {src => common}/JoystickInterface.py (95%) rename {src => common}/StanceController.py (100%) rename {src => common}/State.py (81%) rename {src => common}/SwingLegController.py (100%) rename {src => common}/Tests.py (100%) rename {src => common}/Utilities.py (100%) rename {src => common}/__init__.py (100%) create mode 100644 sim/HardwareInterface.py create mode 100644 sim/IMU.py create mode 100644 sim/Sim.py create mode 100644 sim/__init__.py create mode 100644 sim/pupper_pybullet_out.xml create mode 100644 sim/test.py diff --git a/RunPyBulletSim.py b/RunPyBulletSim.py new file mode 100644 index 00000000..2c908557 --- /dev/null +++ b/RunPyBulletSim.py @@ -0,0 +1,96 @@ +import pybullet as p +import pybullet_data +import time +import numpy as np + +from sim.IMU import IMU +from sim.Sim import Sim +from common.Controller import Controller +from common.Command import Command +from common.JoystickInterface import JoystickInterface +from common.State import State +from sim.HardwareInterface import HardwareInterface +from pupper.Config import Configuration +from pupper.Kinematics import four_legs_inverse_kinematics + + +def main(use_imu=False, default_velocity=np.zeros(2), default_yaw_rate=0.0): + # Create config + config = Configuration() + config.z_clearance = 0.02 + sim = Sim(xml_path="sim/pupper_pybullet_out.xml") + hardware_interface = HardwareInterface(sim.model, sim.joint_indices) + + # Create imu handle + if use_imu: + imu = IMU() + + # Create controller and user input handles + controller = Controller(config, four_legs_inverse_kinematics,) + state = State() + command = Command() + + # Emulate the joystick inputs required to activate the robot + command.activate_event = 1 + controller.run(state, command) + command.activate_event = 0 + command.trot_event = 1 + controller.run(state, command) + command = Command() # zero it out + + # Apply a constant command. # TODO Add support for user input or an external commander + command.horizontal_velocity = default_velocity + command.yaw_rate = default_yaw_rate + + # The joystick service is linux-only, so commenting out for mac + # print("Creating joystick listener...") + # joystick_interface = JoystickInterface(config) + # print("Done.") + + print("Summary of gait parameters:") + print("overlap time: ", config.overlap_time) + print("swing time: ", config.swing_time) + print("z clearance: ", config.z_clearance) + print("x shift: ", config.x_shift) + + # Run the simulation + timesteps = 240 * 60 * 10 # simulate for a max of 10 minutes + + # Sim seconds per sim step + sim_steps_per_sim_second = 240 + sim_dt = 1.0 / sim_steps_per_sim_second + last_control_update = 0 + start = time.time() + + for steps in range(timesteps): + sim_time_elapsed = sim_dt * steps + if sim_time_elapsed - last_control_update > config.dt: + last_control_update = sim_time_elapsed + + # Get IMU measurement if enabled + state.quat_orientation = ( + imu.read_orientation() if use_imu else np.array([1, 0, 0, 0]) + ) + + # Step the controller forward by dt + controller.run(state, command) + + # Update the pwm widths going to the servos + hardware_interface.set_actuator_postions(state.joint_angles) + + # Simulate physics for 1/240 seconds (the default timestep) + sim.step() + + # Performance testing + elapsed = time.time() - start + if (steps % 60) == 0: + print( + "Sim seconds elapsed: {}, Real seconds elapsed: {}".format( + round(sim_time_elapsed, 3), round(elapsed, 3) + ) + ) + # print("Average steps per second: {0}, elapsed: {1}, i:{2}".format(steps / elapsed, elapsed, i)) + + +if __name__ == "__main__": + main(default_velocity=np.array([0.15, 0])) diff --git a/src/Command.py b/common/Command.py similarity index 100% rename from src/Command.py rename to common/Command.py diff --git a/src/Controller.py b/common/Controller.py similarity index 93% rename from src/Controller.py rename to common/Controller.py index d7a5fba5..28351ba5 100644 --- a/src/Controller.py +++ b/common/Controller.py @@ -1,10 +1,11 @@ -from src.Gaits import GaitController -from src.StanceController import StanceController -from src.SwingLegController import SwingController -from src.Utilities import clipped_first_order_filter -from src.State import BehaviorState, State +from common.Gaits import GaitController +from common.StanceController import StanceController +from common.SwingLegController import SwingController +from common.Utilities import clipped_first_order_filter +from common.State import BehaviorState, State import numpy as np +from collections import defaultdict from transforms3d.euler import euler2mat, quat2euler from transforms3d.quaternions import qconjugate, quat2axangle from transforms3d.axangles import axangle2mat @@ -31,7 +32,7 @@ def __init__( self.hop_transition_mapping = {BehaviorState.REST: BehaviorState.HOP, BehaviorState.HOP: BehaviorState.FINISHHOP, BehaviorState.FINISHHOP: BehaviorState.REST, BehaviorState.TROT: BehaviorState.HOP} self.trot_transition_mapping = {BehaviorState.REST: BehaviorState.TROT, BehaviorState.TROT: BehaviorState.REST, BehaviorState.HOP: BehaviorState.TROT, BehaviorState.FINISHHOP: BehaviorState.TROT} - self.activate_transition_mapping = {BehaviorState.DEACTIVATED: BehaviorState.REST, BehaviorState.REST: BehaviorState.DEACTIVATED} + self.activate_transition_mapping = defaultdict(lambda: BehaviorState.DEACTIVATED, {BehaviorState.DEACTIVATED: BehaviorState.REST}) def step_gait(self, state, command): diff --git a/src/Gaits.py b/common/Gaits.py similarity index 100% rename from src/Gaits.py rename to common/Gaits.py diff --git a/src/IMU.py b/common/IMU.py similarity index 100% rename from src/IMU.py rename to common/IMU.py diff --git a/src/JoystickInterface.py b/common/JoystickInterface.py similarity index 95% rename from src/JoystickInterface.py rename to common/JoystickInterface.py index e3ade947..4922dc4a 100644 --- a/src/JoystickInterface.py +++ b/common/JoystickInterface.py @@ -1,9 +1,9 @@ import UDPComms import numpy as np import time -from src.State import BehaviorState, State -from src.Command import Command -from src.Utilities import deadband, clipped_first_order_filter +from common.State import BehaviorState, State +from common.Command import Command +from common.Utilities import deadband, clipped_first_order_filter class JoystickInterface: diff --git a/src/StanceController.py b/common/StanceController.py similarity index 100% rename from src/StanceController.py rename to common/StanceController.py diff --git a/src/State.py b/common/State.py similarity index 81% rename from src/State.py rename to common/State.py index abb7c98b..3af64bfe 100644 --- a/src/State.py +++ b/common/State.py @@ -10,13 +10,13 @@ def __init__(self): self.pitch = 0.0 self.roll = 0.0 self.activation = 0 - self.behavior_state = BehaviorState.REST + self.behavior_state = BehaviorState.DEACTIVATED self.ticks = 0 self.foot_locations = np.zeros((3, 4)) self.joint_angles = np.zeros((3, 4)) - self.behavior_state = BehaviorState.REST + self.quat_orientation = np.array([1, 0, 0, 0]) class BehaviorState(Enum): diff --git a/src/SwingLegController.py b/common/SwingLegController.py similarity index 100% rename from src/SwingLegController.py rename to common/SwingLegController.py diff --git a/src/Tests.py b/common/Tests.py similarity index 100% rename from src/Tests.py rename to common/Tests.py diff --git a/src/Utilities.py b/common/Utilities.py similarity index 100% rename from src/Utilities.py rename to common/Utilities.py diff --git a/src/__init__.py b/common/__init__.py similarity index 100% rename from src/__init__.py rename to common/__init__.py diff --git a/run_robot.py b/run_robot.py index 30b472ea..591b4ee8 100644 --- a/run_robot.py +++ b/run_robot.py @@ -1,9 +1,9 @@ import numpy as np import time -from src.IMU import IMU -from src.Controller import Controller -from src.JoystickInterface import JoystickInterface -from src.State import State +from common.IMU import IMU +from common.Controller import Controller +from common.JoystickInterface import JoystickInterface +from common.State import State from pupper.HardwareInterface import HardwareInterface from pupper.Config import Configuration from pupper.Kinematics import four_legs_inverse_kinematics @@ -75,5 +75,5 @@ def main(use_imu=False): # Update the pwm widths going to the servos hardware_interface.set_actuator_postions(state.joint_angles) - -main() +if __name__ == "__main__": + main() diff --git a/sim/HardwareInterface.py b/sim/HardwareInterface.py new file mode 100644 index 00000000..fe27a3ba --- /dev/null +++ b/sim/HardwareInterface.py @@ -0,0 +1,41 @@ +import pybullet +import pybullet_data + + +class HardwareInterface: + def __init__(self, model, joint_indices, kp=0.25, kv=0.5, max_torque=10): + self.model = model + self.joint_indices = joint_indices + self.kp = kp + self.kv = kv + self.max_torque = max_torque + + def set_actuator_postions(self, joint_angles): + serial_joint_angles = self.parallel_to_serial_joint_angles(joint_angles) + pybullet.setJointMotorControlArray( + bodyUniqueId=self.model[1], + jointIndices=self.joint_indices, + controlMode=pybullet.POSITION_CONTROL, + targetPositions=list(serial_joint_angles.T.reshape(12)), + positionGains=[self.kp] * 12, + velocityGains=[self.kv] * 12, + forces=[self.max_torque] * 12, + ) + + def parallel_to_serial_joint_angles(self, joint_matrix): + """Convert from joint angles meant for the parallel linkage in + Pupper to the joint angles in the serial linkage approximation implemented in the simulation + + Parameters + ---------- + joint_matrix : Numpy array (3, 4) + Joint angles for parallel linkage + + Returns + ------- + Numpy array (3, 4) + Joint angles for equivalent serial linkage + """ + temp = joint_matrix + temp[2, :] -= joint_matrix[1, :] + return temp diff --git a/sim/IMU.py b/sim/IMU.py new file mode 100644 index 00000000..397179ee --- /dev/null +++ b/sim/IMU.py @@ -0,0 +1,13 @@ +import numpy as np +import pybullet + +class IMU: + def __init__(self): + pass + + def read_orientation(self): + (_, q_scalar_last) = pybullet.getBasePositionAndOrientation(1) + return np.array( + [q_scalar_last[3], q_scalar_last[0], q_scalar_last[1], q_scalar_last[2]] + ) + diff --git a/sim/Sim.py b/sim/Sim.py new file mode 100644 index 00000000..3fdebf37 --- /dev/null +++ b/sim/Sim.py @@ -0,0 +1,29 @@ +import pybullet +import pybullet_data + + +class Sim: + def __init__( + self, + xml_path, + kp=0.25, + kv=0.5, + max_torque=10, + g=-9.81, + ): + # Set up PyBullet Simulator + pybullet.connect(pybullet.GUI) # or p.DIRECT for non-graphical version + pybullet.setAdditionalSearchPath(pybullet_data.getDataPath()) # optionally + pybullet.setGravity(0, 0, g) + self.model = pybullet.loadMJCF(xml_path) + print("") + print("Pupper body IDs:", self.model) + numjoints = pybullet.getNumJoints(self.model[1]) + print("Number of joints in converted MJCF: ", numjoints) + print("Joint Info: ") + for i in range(numjoints): + print(pybullet.getJointInfo(self.model[1], i)) + self.joint_indices = list(range(0, 24, 2)) + + def step(self): + pybullet.stepSimulation() diff --git a/sim/__init__.py b/sim/__init__.py new file mode 100644 index 00000000..e69de29b diff --git a/sim/pupper_pybullet_out.xml b/sim/pupper_pybullet_out.xml new file mode 100644 index 00000000..b5754f96 --- /dev/null +++ b/sim/pupper_pybullet_out.xml @@ -0,0 +1,129 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/sim/test.py b/sim/test.py new file mode 100644 index 00000000..384c4794 --- /dev/null +++ b/sim/test.py @@ -0,0 +1 @@ +from ..pupper import Config \ No newline at end of file From 4b2bf5bab4695f36700e1f76a4223a3c8fc70043 Mon Sep 17 00:00:00 2001 From: Nathan Kau Date: Sat, 11 Apr 2020 13:32:32 -0700 Subject: [PATCH 02/49] update readme with diagrams --- README.md | 24 ++++++++++++++++++++++-- imgs/diagram1.jpg | Bin 0 -> 480722 bytes imgs/diagram2.jpg | Bin 0 -> 329019 bytes 3 files changed, 22 insertions(+), 2 deletions(-) create mode 100644 imgs/diagram1.jpg create mode 100644 imgs/diagram2.jpg diff --git a/README.md b/README.md index 8f2791d4..64b8168f 100644 --- a/README.md +++ b/README.md @@ -1,12 +1,32 @@ # Stanford Quadruped ## Overview -This repository hosts the code for Stanford Pupper and Stanford Woofer, both quadruped robots that can trot, walk, and jump. +This repository hosts the code for Stanford Pupper and Stanford Woofer, Raspberry Pi-based quadruped robots that can trot, walk, and jump. -Video of pupper: https://youtu.be/NIjodHA78UE +![Pupper CC Max Morse](https://live.staticflickr.com/65535/49614690753_78edca83bc_4k.jpg) + +Video of pupper in action: https://youtu.be/NIjodHA78UE Link to project page: https://stanfordstudentrobotics.org/pupper +## How it works +![Overview diagram](imgs/diagram1.jpg) +The main program is ```run_robot.py``` which is located in this directory. The robot code is run as a loop, with a joystick interface, a controller, and a hardware interface orchestrating the behavior. + +The joystick interface is responsible for reading joystick inputs from a UDP socket and converting them into a generic robot ```command``` type. A separate program, ```joystick.py```, publishes these UDP messages, and is responsible for reading inputs from the PS4 controller over bluetooth. The controller does the bulk of the work, switching between states (trot, walk, rest, etc) and generating servo position targets. A detailed model of the controller is shown below. The third component of the code, the hardware interface, converts the position targets from the controller into PWM duty cycles, which it then passes to a Python binding to ```pigpiod```, which then generates PWM signals in software and sends these signals to the motors attached to the Raspberry Pi. +![Controller diagram](imgs/diagram2.jpg) +This diagram shows a breakdown of the robot controller. Inside, you can see four primary components: a gait scheduler (also called gait controller), a stance controller, a swing controller, and an inverse kinematics model. + +The gait scheduler is responsible for planning which feet should be on the ground (stance) and which should be moving forward to the next step (swing) at any given time. In a trot for example, the diagonal pairs of legs move in sync and take turns between stance and swing. As shown in the diagram, the gait scheduler can be thought of as a conductor for each leg, switching it between stance and swing as time progresses. + +The stance controller controls the feet on the ground, and is actually quite simple. It looks at the desired robot velocity, and then generates a body-relative target velocity for these stance feet that is in the opposite direction as the desired velocity. It also incorporates turning, in which case it rotates the feet relative to the body in the opposite direction as the desired body rotation. + +The swing controller picks up the feet that just finished their stance phase, and brings them to their next touchdown location. The touchdown locations are selected so that the foot moves the same distance forward in swing as it does backwards in stance. For example, if in stance phase the feet move backwards at -0.4m/s (to achieve a body velocity of +0.4m/s) and the stance phase is 0.5 seconds long, then we know the feet will have moved backwards -0.20m. The swing controller will then move the feet forwards 0.20m to put the foot back in its starting place. You can imagine that if the swing controller only put the leg forward 0.15m, then every step the foot would lag more and more behind the body by -0.05m. + +Both the stance and swing controllers generate target positions for the feet in cartesian coordinates relative the body center of mass. It's convenient to work in cartesian coordinates for the stance and swing planning, but we now need to convert them to motor angles. This is done by using an inverse kinematics model, which maps between cartesian body coordinates and motor angles. These motor angles, also called joint angles, are then populated into the ```state``` variable and returned by the model. + + + ## Installation ### Materials - Raspberry Pi 4 diff --git a/imgs/diagram1.jpg b/imgs/diagram1.jpg new file mode 100644 index 0000000000000000000000000000000000000000..430556436ae7ad9cb722065a22201bf6f5999b66 GIT binary patch literal 480722 zcmeFa2V7LmmM^-YNfJdQhXw%w$w*KMEh)Nk&a~v9 zWCQ`p1|)VPHVt%m+waVob7$uM-poCB?mOpum-z&v}u^V|QCCa3wGw*E_+=XcuM&j0swfvaxr z0iKTb4&MB7GBPs!>b7pycKo*kyu9sPy!droZQMNF-8`+l?QFrkf2rT^y8!0DWc=M@ zqOun+UJ(1^>VM4a!e`Mt60pLIT|8Hfy-~a&q zA^@Pk|LvN55&*oE005@+zg;^k3jimj0igW_=^emKLo>+q5<+$cAZI3nFq4tG0Vvqj zlw^N|zgCNk96~`!MNM;pmJZBNcM>2cgFwhBAe5B9Cn{M8_&Y$sOnFK`R-KB)z>4~e z$7#9n)K@fuSE@Q#4ad+z=dC>>PSCQkb8vDApA``mJ14K8sC41trK{I8G_|yKuHU|6 zWNZRf(Z<&9fxUyHlb5%Tub+QF;G@W>=$P2J__QZa(=#%kJx~8_S zzM-+HxwEUgr?;rv>{nr{6@prZCUmNzfcFh4-0rEcrgd7|t2m~A{3NTPoQ~nOr zG}M0tntutje+0VUf#F{R2`q#RECalm3jAX@L4D$1fBP>dNb?|JJ0#5l^bj&|GC`OD z7(l@1$BP2T@wg9;=fMB3=KzE>`e$D2Wg#Ip#im20>n6-*W^=F79KZV{i;e|IYztMBo7a9`o8X=__jTw?sn&kN>yrC0(_mc;81L6M zClj|-5g|&?%+-ozEvt%&0|?6UJCeiMex=NK6Qvq4*#6giXb~6LmR#sO38?Ahkt!+G zRyEPjhL)Zl!MQ|MX1|)!C^+**ldex8wbOfh=CjsbTCoqdpc8j)kUULGoC*KE?`;@sndr z=@@4_h7FIQ)MI%07%e|W%a76WW3>DjEk8!fkJ0jDwEP$?KSs-s(eh)o{1`1iM$3=U z@?*687%l%_MawN3wkD1)-R!WNLb`Mi#pE~As0rv~#PvO1I&2XkPvzQR79v@`Kf(LR zOEqT0JCzKspnr5en5oeMxg0yapj=i6!)RLQg<8vXQ zP{9q&u+SHdS?%c+vlZB+AUDKA65#7>YUnUB_V_X4(kQZ5895`pBJxOTxC&j?>&7td ziBg$$>7~{<^=_Dh;7hwOj&Op{1}!CZ`@-02Z?7;&-WACS;7GorD%jq@z#_YG)RWrg zp%F$1&2N8*Q$I4o3*)-2CTd%L7CNWhN7y-;Tjk7+vkxS@;%MeD0|s!N@jt7|J%lv& zXH_FU2*PF(isWHoL@3)-gyhwpz^Ar9rszGZkb+z69AB;#1{d)6cR9SHA0(T`yAoci zP@|=tfy!^Z^U0&0Wcn>;d9>}+xXhJ>dJ@3ie&O>yOA_GF*cdUsl%BSU zfb>(Tw7AO%#$6s<&A+d-Fa-u*%&ckmV|7}Z)p!M(*mxP%JNE%MM~B{7 zF7y~F`joI`0L+&zgi9Q?+4RqyBmwS_F`d1O_f?BE2N2XayV7+_ zU#{~T_fz7YoW!G_hK^*e@uDxu|B>-!Q+<7FgsypGn!lZ4wbq#!t=p4wFCv&;yO^1x}F~~eArI(1D3@(s7G2%}&APoPCL3d%_;7ZWk_Y#)B_q8au z-PXP#q*M)+!!AfH>F~_V`O$3CvGYPas@p$RD)p(6p;6ryjCznBV`ndjUH;?X8uha> zLUD&>O#R6;f@gA$!ha#6Rc`Pghi#PR$6r2epaJ}uB7!vjXM}^UT#5MLPA!xL z?81^3+4rO)Ldn`N8C7v5(8h_)eHZ7JK5AQ=F-FJ8Bn$ z%^#qmSH8S=rs&%D^AdQc%tSs*PjQXsRO8W`t5B9;txq<51y?l`$vhvR2j+=qtb?%kX4Jig+nBSD$;c`;^b=4yCNe zrm*Jk;w-M{qcX_Co zuA205al2;wmEH|h4ZLrMEA*%@ROW8Mlbx%oTRp4N4H+-5P*=B$?_CC7o=YTq2dR?` zx>Ic?i=bz< zBuE166tF|Alhq&Oj$qF-r=0fHL`gvO8MFz3{!$46!$bm@weYg+5vVn*kFcFs1TOx_ zG9EG0==O!F{Nr{os9{F0v4lM2@X9IwXzk+>bxkYjp%yvrQ#jmLb*G52)Lss3BW|9Eda-W!ki#{Xe&)R5l1x_qjn zA9FT8rpiCx>Hw%4vLtqAB^3}#y4q#wi^xdp33M z&3dS>Qdi3C_vOW%VC72P3iF=+WbQHFS6WsKYw&^7dDokYLZ{kc=#bqt62PV+y1ukr zn5hEKnwfNLIb3hLT(XW^>u7ZTT8+T|?7PH6zWl~A+oub) z^GUCgGH113_*1XCb*02E3!t~(Bm{R6RisFOhc}ZUxor2dZ5s*diol*=XAB)y8QuE^ zeh25{f5>o{^TYYPe0^e9YF$%?VD3^Q?^Ba!YcOs#nPA$F`RI}!g4*{x6X)y2zTV&G zySwVmesShfa?!mE9`g6&tv7CxS1`pne%>sxWcftk$ZwLS@?Y&F!p5Fhpo{kW>W9LX z{nOZceXqxS)8vcvnzX$?ZGKO)L*w)pb_Hcn7977pX0`EvxqGbdiR} zB)jOlpX7A7!v+VtBFbs_lWEFW58fY92R~??^nSk+PLxcYxPwNgS;*+83e;)MDKw2J zSA517RQB=%r%;-u4j>p__>bznzvsEsq=`Qt2#ZW30S|ZLQ_vGjLtDk!vI!;_W!|%+ zue%Bj#gycdNr1%VQo(e;+i)|JFG^d^rMehD>`U}cXON$yO@2jN`Fe@6>XdI?L~$gPu8a^C4Ek8HKm%}q%6ONc&|CK z!x1vJ`)j_gaIPA_%^hhuop-WdMs{rNH`jINJ;=LN$7drE^N6*S^D`mqW&&OX|Goij zk2RYJRvE+9tT^b|SfsZ8s(pM=Kehe&+Z9idOqDdxuswSBkMnp+99oI zWxkJ?>am|OV_q(k`wqeV%ZoTn8NvxS$o%RNVI(dY`FqyPpZ1=+YQkt#4Bo0x@0EX6FYlFJkDnTH->GZFpmH*sgX+9VZU#DqAD@Z1 z7#uXL=0%c#lQ4T#kM=XclC8NLS8iv=ehNsUHyub`mkpOtO9N>4XD{3QTI^U%;^W1& z6mV{0?8|0Lk6d%NG81!^di@ufRk=B-qdR&-vb4wVI27GlTPhQ$k6@xW8TbgE3*~BO z+CWg@)!BQQBFnKEin|Ay#$)seie3>{NC0c?^Vxp?8>`!?4c~rBAX6{Z`mU$wGR1$} zw{JS+)d2CE4kO+bU2AuyrO9+#P(R&rg-5dchL%QCc&zGxlr#3c`c&=CDTgdXY;D}N zsY^NKN*Uu!tI^(!F&IPfrMy|`j`ypu$maPsXOAirVOz?Ua@R7#YRI<7+zg1neBp25 zDbOASMPH2Tmqnjt^O=X5H}B349pQAalnV;j>mk6A)1Pirn*0-PO1;uypeN_fE<$0j z8-~m4TW>Y|^IU^P@$RZEKU5vCqhN7+o?EJH6bl^HIT!~k9rR|F!Cv| zx3afBiHjrI;)j5wgCJSksBFj?x0SGwv~ zqN`Fb+aGG{|0yBcW6y0t6uOmlKtDmf>ExxgY>$kt7~xhO+qXMyU}-S^k5ZY?k}w!y z>5z*_);Kp9KwmDSjy=fa3($mrzgZEXXhHpN`Uh{L@i-$Z)7km40NXlFxcO&&OE2 zq%d;G?NhoIp8xR3?@}rB=?S93p+4pbQHLoRwrT#61ni}m;b#bOh%cJcBw$klws+0@ zkPMrC+Ccm7*PTM=*kJPrIl-_u77ooL-6{05i>B8{@4Y*G!M&2s$jL)>!AFq3Q-ir>;=Z1Xu>%Db$O8Er+iNScg!353%moIB1g+@kr7bN-y$PG92x1lI#HO|9BZo(l?&EJ0iuRadoNi=Xa;&eqa-ZqM5dU2MK8 zZQR%}vRbryU^35&Zp*~yeM=z$a77Yu_^>#P5Sbq@1{i3Z{PGL3 zoxXIl!IAaX(-CNlwS9ygeWJluml*#ZKeM^tV?@V&`Dc3ja{{Ql2M$*H49d*Jou`SR z@m}x(RJA@n8`?<%j#&3b2&d}yRDn>1U~v)pwAp;Ctg{;X_>Mx7;B9`1`th0W33)qA-dVdVX<~!B+}!Ef zyD*&a_vAVxN9d4V;f7o**jMoznSrV=l69d~2Qv41vs2)bC3XgQ(bJ4FqL4k;c=2#t z3`T!>y3>Wz2jmL*1m2>5B_OxRm%bUd_@3l2cmlF)Rvc&qpZ)JA$vW(I;dF zD+`+A9xw#;++<`kS5~NNxbVxlN#JQv=-Md#!ZQg6lY(L z^}*ea6!#N&2gtA7_+4Zqid&5%*aN+f7edk3&4pOcs^)(aI;&i!<*uz83q5tMkD5E0 zo8q~rWWQad-IvpnJv_Le8dnJgp^=EDVBzML zyRD#(-$}<&*^Z1UUFXjBubfM((-e7^!O9lL*i)Y}Jgg9kf3vNqBvF`OBmGGpFo3h+bqOe#JyVpW{3IT-;$m{^iOJa4 zU1`G+{S1edY_fPa<*RZL=NtI>&OdgZ2&E@ZLTN%T;esqM`Vl^2))OjomrzJF zFec;oY?B@*UuBM83043{?IG@bsYQ?53gQGVMk`*6);?@*p^pRBy`;mk|<)$lq=2c{pjl-(nQ$*U^j`p+N&EtvkG1L-_--`$E<%A*< za9@9B^$N}fBe*i0V)J@-!#L2mtfGSpE?cKtm#h;lXeaW31T4=_g!lMC(YkI23cn8= z5^fW3O;6<2+2gaddZ0(Ae<29MY3(<`;c(c*x=sCBfR}G zES8V24g-(yan^IwZZjOUG`%hySJlA@^?8aObRYER=Mygm_4LKR<|V`H_20o~h+k{- zxSU-ADn;qNU4$vW?vg7pDfkJwe>r(MtJ}ANb7PWKL5GPnXjNcCQBnp*U|Gn8$Uh1FWCXI#})r!s;&*%m1Q*5 zvO>2JqNG=qIOOH$cdmm%7HJ&76J^9#IQ`u%8L{*lUgH<#V=`XL;j_pZo9(>dn33A! z;O;(Ww(cP0sm#nbwfX5=7)-|jnWaV+I+aHW+S#ua$Gqcu@zx33Z`U~Hb75-kRx!Cy*mh zW<-ZE%3f9Qu8XqvI9{*PtoO)_I5kXTty5M`aze4i23KMJ!f@vaS6AWt z+Q}SuTB-n+s9X9Fd9uKG{2l@)_IyuP?WyY9xJ1p`0H=bM66Hh@p6s$u)A;2{l75WDu zvH%H@@oz$8{0AX=2HXf59{tet-Sx7HJ^v{6thY%w9|T;8QN$q_vx-fjKlhc7KB9H1 zp4;Nw(se&}dssdXcbrLVl&o!e{4zB$HBEf$5D?9e|JNw~^F7uRj?;rVz}aytZVOsK zdoJ5XU1iCMlZP~ZWbmMk{Sv*=I$n*N3>AexA!{~Q7RTEK2{95z5ApEVsTpbJG-P`; zXKfC)S=a2`zjgO;SX;cV*>MuhZy&`({3Fd{{%?Kun}wN%wO?pwEUvqfEa4DtNEN*Vo4G{S0IUpR519$l3qSeQ>%N!~oHO1pN95`lBcw zJj!opuO3B9MI(6>+jX)HkgYo0`4r0M_bB?{JqIdHcHjV_*;w2*+e z+s{Em3)Rp#lkaYLRwkmJYMppX0<1Z5zItuG z(F=v+nL+Yt7tDvtM#q2$YbWdSSo||)kGjoNiwis$$}=K3zBDE(pQEn#ojtKCq2K03 z0(cNhPffC*G1>QU%*c6Xzl_wHk%A3NLw&CX5dxQg+J&ywaGrPwVnqENKj`Sh2|kyx zkBw?T%uHh~$Lo0E#8dW1l;4W^9g5q-V*>zQZ36PQ>n$zbUK>eM0Of0pv`Z zTWBq9G{a_sV%7P9*Bf%0ewsdXFWapJwo}gtsiP7eY@ZKDE8$tZRuP?TXTHJ1L;2Ck zc}vJx_nkWS6{`5}X3n0${Zf1nhj=ILbY$6>s~D^y@QP7PaKI5hhYrMckyEAqie|;0A2Qbk5UW7 z;t}eSLGF?a>mn|D31kHGI33g07DUm}aj#8>pijp}tRPlFE-u-RlV853;8UkU@$IF| z#t><>Fzxff>ga-wRL5q8E@<_LW07Y4u84I5S7CD6YD+Qu#U<~`CKU~E3I&Xvv{-b= zn0@M`^lZ>S^oo{6i^~HoSd7|JvhVDnG;W{Dh_uv8ZII=*q3%#t%;sz`^nRMAkFKQk zR(bBsOq?TS>$-4U_BViEIM#ZxH68!izh(v2hlqpLLpy>-W~n>hFIxoZO}AdOb0h!s z`7T|yL0MT`{fJQhjh5=2#LWYDDs|)!zA#$65jd@iaF5Kush1K3di1cH%+^6~m(*j| z1DFn#W~C~lUS=7jwro~KyXuo)-GJ8_?dorN9EtjSVGGed#W||qu}X3BT4@%7cXsiU z`pRzE6l*k+^eyZc1X9DSQk(8V5X;cb1T^*1w>YZoWz>lu`_pAyCw{pYQna@>rfNyq zK2^$W{8`N(t1KC4A0NsPER3noQ_Nf$p>_x?YW?x`ZR6XhXN+_3``&^zVibIlCSP)+ zmQ!%&^f!N5F-5m3zV)Bzn)QrzF&V0vT)F$$${42la*~{K*(Bwu5LWa1aZwf=@a3j(@}ev3f&6(<|-Q6+i(e)&}y`#N_Tsz(q;a8d+zXg z6(moPQO-NcXOsZTlQ1fOR{V76NGLO|27@xzpBZ^~>Cw#E!kM-Nqp4_F*TNCq(2VXDnytBPUFLo;0`nEMgXQ)*?$uZ%?T)x%`etWW;PQ33F|1(Yq$Wf z(_X(gGQ3t)ExSwa_mXKeB?482e5W6ANwuyrVYy7w=I%9kt#e>2^8#E?O6EhfhF!S+ z{ux@?#O;eBA5~n?%1is*E>e2X-UWuSI`e?jm3B2r4^jj<<86&H&h}|0rN>kR7M&); zQDYjGsgqGlIeBb*@T5Gd9am&9!y5}ima}pkH^kRsZ?5w~#zjH;(d+7V;%Q1R?Fpl3 zXyTq*Y&-2J-fwwEWk?DBwqa5-u6HSuhDY3{pxF2A=DYZV5$x8O_mCS_9~Z+|8lEw& zACF~IHC&lp5j(?=6^@=*Kf#N+CxT}&H*B4R+2+xAcyqf%VJlo9vcqfbGZL*qRH;ux zL?QDqr;!82lz13cY#qe-bcGS152~8HaH4eRq)R?=sF|;L)-A%@ye!G@PWs6MnSigX z-=F(2sku`4V$uMiyr%&v@X@|4Qxb4?45LNtQH7HL9b04qV(Ez*>xB1CIEXEHJCxj- z3f2-XAE$RcQjKa=yUs@f#D~NY?@A$?h)6_r<~u~htO}Q3q>7l8!e<9I3loC~Sw{GVjH2skD8iGw(985~*vnyiS!rqRuHd zJ#jSH6~8|y3OOK*NwuFrbjTwd=JXjhE=3-qKv;?GdgZRn8S#WOgDIY8DBi$LZ3Ds) zQ)j7Z*G=}Z3;t3slh(h#sy9Zd|R!b28s*VuJ z*7NXAVK8$EA}<~`QHv@3LF63UdT8WJ=kQQ+HB$Oz(k&^~DmY8%_##^0EfU7A0tfB%afy*?|9?W52xWHOkv=Atg~0NwnmmvN&Db?pnVXudZkWNY|SO9 zC65JVvZ+ioz2Je*ibN@2}J z@CZ$?=vZZ#@V-Lfg)f{kCR+_(Z(bok#UJ?6W#q5`osE?t+X0@{!Kw9{E8Sq2X2I*5#DRG5mA)iM*6WBs9KQt>r`y4re+s@{Sp z>!#1XK7W?+K=@gjPGv@z+NlZHef_9hHc*^KBooQno6+5Ywn!h5m`y>W>a^vt#|L_k z??-jAHDCuf6u%9z&(aZTuddqRQZP3U5%j_GRXJ0=qUtAOyR2SKB20% z0gC{M;LQ7XY9KN?)(XkDFxP=*dZ?AyvlaMwr4D2SrKb+-E34Bm&EL8JQm5h{&Av$` zbB>oZ$`y?jJ%re>Q<(BwU8nD#J98%N%^Ltb$2+$L+8v|au$(vqT6#6P2!nVR*!#-a zD!^W~oR5#6JIKS+=mlp2dz$b$dXKk*FHUWR!(H^~O_){NIwh*E7xD5?85?u(KkA@x zSAQ+~lBrW4CyLx0T82NG&5R^o43z55C+F6eG|GeEvM46{ zf~bRAK7j-fFK$&rpFxoQfSo4N;%;lB38(~lTuGWa-QCqj2+_=3_e@gXz;jbhuZF-U z@p~x=Fos%b(9<6SUL8H%?VQaUIH+scXzr%xD{)_Z)s-=&vi|;lNPc&deEO3si zI~>G*ICJ*qVRCkmpI>3`m!*4iybW(P^%r!QjaMY-Sx><*x2QMkLLCqtSG`lhP)uqp z&I_=Qc-EH-xSu@_<&)&F&e}tB_ulhOH$Q-QDb&)M-uwQY`SnsfK^ob)6aPf-$SZU{ z(5;i8I=lJ~&Xju>X(@L@-_8C^j^-_`t6uJ>K60F*jr3RuQ_BDeL{R7e@g&->GlXsh znT&_o2d(mYT2(ksvp<%2;#mLir5TMMq-q`((r6X)tRSN9(9hs1z2az}n;Tcp>FdnQ zfRT|w7{CL1nWWA5H=ZLeLZMY~GF)nmK_MJENR3Q~S+hdXasH_-IhxD|AhSA+eACWP z0{Wv?;71hTF1HqgOh;Km4^FFSfj%)sQG41*6A=;+06(A2jz1gHq;cA0I`{H_?^#*! z36K~GO%p}@{je@s`^zu(r=s;N$9Y}9-?Z0R9?!b?J`IEa!F^Lehl6>yeqy((yvzve zJ+Fzhe#Pe~ninz#?|IlfRVAM!F+DA(%u^#jtfTfN*BSehc!Dy(&nF*$%l!G5r@~XQ zceKBTNn}3n)#rRSGT!>(tjpH=n|m3kJUrx0B} zrNTUxcJ^SmsZbug!q}e4c&n^?M&@~^$3rU9ndjms0GnI^9;Ximmnq{cdYWc0VlKS# z796@Yo+G9=E3zfY`VC6iE^LOk!rfj*#MNi?4h3H=(eTCgG#s$-lvhQsy6dn$RV3rL z4Id2*ap4pb7OoK}QwA$@F7mI3UVqoO$;$MW?(ZJP<)B+uLu=6Amn&29+tZg5B5Rwn z??gL(Yi+t?{0zc_p;~`o$yVjJIK&B(CPZT#2o`!P2SFTO=&Uk-OqK{>eS|pd6^_NlL z-uDqoweLa&4@N7jK~PmRq5)tbB3 z&PQA~i;&hox^l0JZ1}L^UlY5{GV)14om-c8(CZmL1?O-!WGW1#PU2K0q|Um4Oe8N*AKuM?pY!^k&xf9#tmngyaV z+@!4Iaz!CtwS!A%gX|S>3P)FiZ3%VY=~N0Zf?n)iB(KXke>3fnZsbx|SJuD_g(~Z^ z=F4m9BSO-uRhOa2|9JQx3ToF9Kn~nBB|4M>z2DU)y~I}HXSKYg#-O<1oWkhrEFVYy zP%}02L@wDwQRvOZ8Whv7ypy2%*en%lWnQ?J*UezU#np#FHru17IYYtGN(9;8ogBc+ zbnzwAhee#|$Yz&XNwLV50=inH3S%F2!^Etk`h(|ZGxL)Jfkp12V-N0}n!j;Xh`6PG zxQJCH#~4oIq)NI{cR#2Tr-$nD~&be%5Zg zz*_Qw=MOh=Gjf~U;mbcbAIyJ!tbOK+C}ckwMFoPPaPl>1?evxoMq~x_^PKHpXI^pY z=h2n98_nI13B|hshNs441XgR~PsUbs=0tucN5P4p8O;i`8y1zNm7peuv%vGND0f|G z8qcv!?5!Fc;6CsqVqvm?OUh6BLuU9>6bF%-I0~=Y?{l%o#u0M7zfT8?mFuVu5%cKv zJnJ#@sBG1WkL5S2>zW6S`ioKsw*Xm-CU>T}k473aVdqLgV;O)KIK7U4kU*r}v2k>` zKdr`Qss82~`2g+udQ~PQO?Q_1Ms8S{&Ezy)Md&EJL2D~HrV~ZoD&Vn{N4NO(!K6#; zoR0%{w5g9{x6>WQ>vLzcy9DVOMaki_bA1a;7}RgP>0@5xFKq=a^mf(qkhG!mgGC

-TpvFKtWlLH7Egbb8J-fZRyD#f)GhIz6qL1Y}wpZMCS zXQ+1xJiwsyOb!?9`N=GW9_sXzebNh_^3t}8pi{P@Tvp(-tKF~~-rmRz_aE-pCF*Yb zG@F;TIN0Rg{XhvAiH@@hd|FXS{TZD1(B$U<<~(dKa}Vr!AYwBTls%K}H}OKgq#r_1K?(dc`*tWLiXVTj-?QU9ejF z&VjF!6(qoO`lW9E(0OT0t)aSv92?KKGqHiCJr3(AvBkY1?JPF{DCW^FmkZnqxa~!=k=v%&o>48 z*5l(-o#WixqG@zN4&xlwi7wi!msyQ2FM)Phfww62oQan~ebrxEO2jbdgH*yJgrgn| z>w|0DSt)VAi>y4enW%F-&2}VSkkQa`?xJ1P^YnKEyYsP>Vbq7NQ>ZTt2ohj9fmowL zQG&wp%-r(gmH-+K%DJrpu0Mq9ktIVVPQES1yPdufx6IDoe^&-jq`p13M4!}QdKnfh zKcs(is&>N#uGJiU*t;u~JNs<`gpl$dQ<-QP8l{K#^FP+GM0OFBux6nA5*a$gF82ck z0!j&IFwmGRE&mGZ=6dZgp$ID#?lGyP)6r{o6cFge%T=p z-i6HKL_WqJ67-qR1WPZg^Oiy?!6Ki8jt7P|6m=a*;$wJ^muZg;zVQyTyU23|% z4|%&A;R)(KoH}%*0fXD`Wq-Yb;&nMIUc+gwdZC}@$!7nTn*JI7VVrgAxngs_H3h(* z`aghx?@>5m>OM)RPF^>ZtZw6JeV$Phac&gf3+P{nvu+9Z!iU~7=#Re?^%(p86^?ME zMVwubti?=snj^xw;@7we1CwJLGG?VJg2d{cs+@7y2K{(xJ+9^*94u1HZ-p&4;8{S& zUa&+W@MH00>v_jF{^Be3QRSAG?ye7b6ul2}VamX6F+bCs`dQ$*Ti98!_uw8C03A(d z#lkDcv0a7j!CC@CmIg5|> zl~}$`nOC2ntF6Aqc=h~a8-mtLrd~KsEH6q$7k#wi)&-xK8w%TxQtyMDI^t8+`&-pPU16~MbMCM)elph`tM zAyUP>)IS>=>YT^p&$tU$bQTUr`iWQtSuvYlE2UDKa0$C(7Y}(0gl-tX6Pv+9#6fNv zv%X#wUFDX-UAZU1^~J1y$xX@5cK!#Oy3Fg&+_(Oi^`m*LAF`x356~IvUi_b=f?INY z9e(1i1fppQ1gG@Yl|dC5r>`w_5e_cJSr@)GN(dyq5bwWZ7ZKt4iRXnkt2K%*6bS8u z*V?D3$vU8FwYF}rh{sCr={EXsGe~@vm`;(P7m8QB%QRCV`RIPFfo;RN{^vr(u3KdA zL=@V1W=+61ZfWb-z8e3*%Geale^8}hlq!EPS<{HJ`6xijN$ z4LbraILIjU9K2zN!2NZR$YKVXEA1lf z;^On*vM-@}I@{C^lJ=yt!cEFuF<;sQIn(?TnE+?-mQI8+;IICM!HAELraBL8XE|SH zMo0TlC!q(+&K!X%7*9dg)opg;GJ1M5fvFckF;6k6;%3F08S_|1t|P=hv4$mOwTe#6 zCaL|QmHq-NNKiWDLn)xqaLSQx7vIk%v1Z41JzRQ`>EZ3{HRX zdzbPkR|PkK>AOOB-l~U?oQ_dpu5iladU5joH?x_!4!N`Wqy24_w$T?-!v%w)AsHfv z33YY#)%DSX!$J`Y3kva~1-D9L!zhg)VE_l)Ni-PO74AT;P)o`#n>dje3 z*s>!|i3CvB!|;JENXlRXoHIsb>(TN~e61S`!ae}*OdLQ(>~9i7Nr3c+T??$+r#Y|0 ztqW_;xP1&$WU$FH=Sn^1K|<+T&CQ~f6oa~qk6&)Nn;IJ#zT=Zqo-W2q5MHT?1hb+0 z5>yn>bB0{9nAj>^!WGJ%J&(HyVXxh!5I(3ahNj7YM-HFf4+r11Py1GR%mh+;$E4881_vCh79H1FWTh7aMeh&x-~R-hrg@M`5bpPurK zTvOV6>$4V7A6uF^@1@8tC}b@P5r00I5~^Xr#jGsGw5y`&f4HpXF*+?kGqln!Oy91~ zn)u*Q)hd#e(Bi7;@xnH6+EQFTM}hMSmx9;1yGCax0t*heK|?d9C@8br_i;Sgsw8!H zX2vKX-#J9wprJM6f*<9=0DYp7pA4rUC%=iuYo|chBrCPDa*GZdJEv%!ZCBg7R&nfQ z%1yLyl+!LF-{s+i-0&GA93uRtV4P|LR7fjwTM&y{8cWPkc`dUYP zRc!iY#K)fJe8~XEHya)#_koSjsyjt#2u*#KMp@yZKE?l6Z20u)=yU0)}=o2uvix|T8Mm2Hhs>cqq4ON zs-k?asyXDw+dWp@`Mhb%Cm7@sw(Zrr<=HV6kL5XnpynK*0O9t=T-U|1^;ElenSk~_ z;L(`48jt2RC(_a#@vlu+Sb1TnP84d+4mp-MDH$+%NGKw?nS5;E@6*=VH|`&ref}U( zm~J0rB}ijtYi#tm*f-PY0a?}K6TCwqWXmHnP;3UqGCo&ew4G<8=F{~E?V_}~&2M*9 zqLa>wZWnsezNYXzZ;8MT1^l?qg`XMwbwN5VZz81&Ix7Mi!s{?Jbip}(WPSW}TcAdV zp8XYjSxA;oa!5hT!*@srZfQDST`h@Gxea0ik1Q3@4G|AyoM$Ve5RN6ysHb|}qt*Fwa*FIC4iA%> zhW(KsdGCQy5M^-u3wdlf5%{>x#I9>`^Mvaunx{Oj=TGlq17)mBs*vYp`tEeq4RC+{ z@#>0#v@gPF7QV%O1al6|DNZN|)+9T7sj}*(HjUVE+I%v>%q=0WxM{mEjD>K(}=X@1V{y=Bdl)Sp?NL7q%2qi zQ#U#mfyk3i0eNrtvFK`&$8Jk4#|unymwY1yCmYe*aSxyDaPJQ6D>WAxxVai^-J@^0^D(@Kzlq|~ zMRR-Z%d*5yaxb(-u!Cn}-@F_*{-$hoyqTx}&dsq*Wwz&Equ*SWjb(a!Th)#>ux82D ze3xhFC=|UmEBtFqMR#GUr|PPNNln7e&y7nnoWCArCykuadu`e@Q*+TgaOYxQ^EAs9 zb~nbUldp7taKxA1YKa2_i&eJ)MKcIXuXv)`3%g*Lh zuWYNiC!Gbey3EIN&eElgLoKWi_B3g`?P;fUD9RQS3YvqPeAKyw)0!|nyRQ}3ZlgxJ zqXGQ%4`@Q74T7{SB0l(9n@L4^CO5ljjO0(aSrO)hBpq8dUnW(69RLrQUvB}y5x8`2 z%e;1xe?a|1vzl(_KQ$*@-7?U4l0kM>O;MxI-rl^asgY^`waytPGTFMw`zA`p zZzDlz#9IEj&J!MF@a;e)f_1@FC{{39W{%FX`hhFLGqEzyhk;jl$=#k}yc1Oe+0MgM zWFg(>F`%ldIi$~5@X=1|t-*T`IezHTJK9H)0gza1jK@+z&GmaBfh2YhCR@Mz8 zDtcJ4XD_LHY&JHq5U?;`{Et@)hMJ&-dz_G4^0M)40SY2LlL;*SUb+tuj{s>!>wT~t z0o|1~M{g^R0P04aY|7#OYx!VKY;!2V506^V>MZsb59T1Cb@7zR(xPU5SB5+8+P}t{ zP?kG@j?gRD<^Zk87jf^_VlCW&4L!^3HEjy7Mf7Qu!w1zV>1~_qvY7Z_4)~{=9hQX= zM2)=ffW9HOK zE@szKplU}@p=%1d_tDETH~a&5oKHN@u?p_blH1O7n^1Zq+sl;=RY}=dv))emF%J~% zy`QpKXtz?FzZy6Oi_O&9%I6Rm(52SV@Di*e@dkHdc$zQ4b&sCnu15tL<0;$OHH#e_ zUZ%@ICY$n`Iz-34zS40f7Yhliv0Vte8U&~VuBx8_$318aFu8OuFoZ*dkflM}Zgd72 zMT^dcYgv!Ha62bCW9eKY-Fm~w=|my-IK%-T`~v{W9RnJys{9XQ zam*%iHukzyl($Zho9%7E3OFcI=4iB$4!xemTW-{H1(?Ev@5Ym5**T9X*Omrtm&&TT=xU<1`+by}Xx#cHa*sJoZ z+Lr9E#psx}@Mmefia-c}IhxN0`Vj&a=@@JRHF0AVx2C2(e8_w`*(V$SE7|PU>b6TM z17k`<8V$8=hzbPt&Q35Y=4Jej_v4%|av#8j@gjc<)x&=M;Rl02vttBcWg~(KV?$$8 z78Pm!tM9|KIGw(w`T6pi-V;a(HB}WL4`I%c8J@@@JHQ;ymUiV>9gyCE50pky|T*)Hxrk^$U=jWoGN$qQ-@*1 zd^Wh8T;we}PY7q$|G{Fpsy9-)sJOeL>+(5w<_-D_QDl*a3cjh0gyPJqY|+l&l8gNc zrn`NpY)Ab%eq=}bQ!M$Rmw7tD-=N!q^G&z({5qhthf@KUjen%Ux5-20g1#v|cbG5K zJq7JPac`rGM=+{hgqP7>Cn}6C50~XSoN3hE+?L?ydR7<3>!3aWeQ$8vG=y*AVi1ypI0q6rro*}ZN`C6IG@zZn2qdvR=T$XDxx?wZ}h9kDK>^Y zTFuwW2u$_`2Sb2dhz}NFNI>q~yO{Z^gYHMaO@Dz)#`7xMOU1d?tq2FtFl}+ye2eT< zI!&$nrlE%vF=R1OQHd(6O;-us>a@MRJ(C*XOEb;6AT=z{BPZ)fbShSM>+5rV%Ugq~cPYpaSRgjlpR(w_hD`yG((Yvm*!hq49(cX5L|dB zYRECDa0D&@SV6ms_XEgRig2;m)%YqNNsVZNfEar0l@fVw>t+oIG+1YK#+n<2H+qs{WZJd{)1G=7{e?001!MGuH=bQZYGow!BtHBsKy zkLH77ACJ0OEKI}U}IU7c$T?{$GxTMd2>1ipR7C4jFgffNw4?k zKw{5C}ZK4__5Nlafymw5d(kO;E7!od)Ol*EL z5Kk&3ggMDPN8L2K6)Bjd0Ms{WFp+C5^UCspp{EhnwXbH!KDtVK8g5LcHl_5`bs0WSVv7t2fiYDv?CY!@mKCAaL4P`vcpJ-kGaIs(L9fz;tR&Wf;+Q%UI(|l|!ZlY$go?iR z|2`=^DjYjNFa{4I7-VPKP(5>C1e zT0t4osEkFuQDq&HwGt6|UH7edbX#nP_jyBR2z)8kLdWQG4<|kBqzUu2d1%*h*hkqP zhy=BFa;(W@7kZXN%f`ie$;?Pn4HRx2oPuk>KF1Wc7q8hcjQenKgglZr%W(aH(`HV+ zDWE-JMRQrl6ER(^Ty);9q^eKAKZ_@!G(~IGH`_$n_5>r*M9b$UT9;Zyd}~ z5f)p6Rfea`aH^OBcx0!Q-IH}l;%pn5G=yvT?EcIP+JpGll?-Eym`}%CRFx$tW3w6- zk<3m?HIYOq@hGvlaFd#}f$ec4J?b|8$ft2wS%|8W(e;~ZCvVV>)ETD5ruQEYe)M_y zEAGi#*yuK(Ko=cltIY-1G2LL*3Nu7<1F+{=LzxxUiuhy z^pwzxLoWz!Md7~hV+~@w2k1mkb>A87Ef_h6)PA_7py`lEyKJ)9KmA@odX}a&pJsg)B5TvAi~XpXXD(Z=WD}#{wHy`5CmdV;K7JK(^074&9Uc zkp1RLze7aCRLV5DD3A$H*Meg7MsDwdV5fd>UR!@?Q274-UTppV(PsC-{p zqJJOvfxRptBQ%qqUNG)fg?))88C!dX!VH?h#E_M?Zm{OL5M^bTv)6(<6C;;Xfb zVam4HN2UjeOQm#F!BePjh4JqE!v_X$CZBlqwTb6dtUpbe3fg*n3;T*@2`Hm$T6ii7 zyA5LG_)Tzhp@*5zS`$VaVMb4m1ZhmxrgJehOsL*zh!Pce8mC2)7kp@L0_$@U7&yLo? z!ANx=Ve;}4Lu=9Ii81LNzyn2NDiCi$nXgnz9?IWLv za8lAJAs#nh!6T!ZdEvS`c+Bgav}5hDZNA2eOig)>+dVXesSal)g{e=~me>z*=7eWv z8M42YO4Wv6ZFwIUYWT5U{7Vu%-(>%ZT-cTia)dTl4||`P&fT3^>ZM?iIL^|!@&)Os z;S5=sBQlRK_;mtDMJb~|=2$P5B&au6j;q3#Dxm!UP)JNTK`N^fb5V7j+=WQA-!MsHs8c*Jiz^Q4G7 zl~|(76B9^@)!BA9^9@BiGxfROS<%()vly1@iI4xL*`8|Kx^eXdoN@u6#bYx1*1)tx z@Mn0`W9=V9?Y7j9?2tFylcK)ICSO_s1g;+kNi`N_rWgD7iQyZM^|#j$5GXaq*&r0b zE{-xFI4*L5Et=z1h8@oOVBa!-TTSN~eM95v^CSZ8A+_W9Xi-%uf-`oXxi@HGj*$?I z!VUYzeK}3y^h`HLxJ<9PI}4Tfia? z-NZL6&DDVACW$IIWV-~wQ_4d3 zQ@w*-HG=d>mgB0DT$a;wRIk)e*TudbIsUR`vpxK8DRf8d?rQ|gL7#HGx)Bcg##PLf z&%ZD$NO(gbCq~j@W+vy#moHS$v_Ui(dma<<4^6pbsdK+1aNj}7%M~6pEuiRwTP9U8 zwx0<~y9;6oHOw2LZZdOQ=I)GsC)a!7w1F3Q`wx?j!GumK)4pA!-bY}|!@bHz}d)STN} z^2G`({bSxzXZJ8l)D$R z1i&3${#V?=X~K$--Z>eG`m{a>g+V%j#E5SZ_Vpj!R%~e)#8Re4Z93f4~Z=d zFMq=B>p&vX`-7js6=Zj$&lqxQp^-M=L4ZzE1w5r4)*vNwcw`<5bx--o|A)H_)SA z?z@~qj{>&g%PI3PMC*dtAfTas^v{?AN_jwM)24c()~YE$eb`56^uB0KTH?=Ir<_RoOx0Qn^&K}+<+H5Eo3OzGXBQW2y;vV3Hi%2jM?|^OjktLXe%;G~b<_35^ z5w&NadIKN{UHSk^<0J;U8CXFY;~6(rF~9>N>%gEhyWr6b`K{J@=B7$*S)S{gRttkN z6VbOH+Wn~eC`5B3mOn(zk5}!2mxQ%tc_F1@6T{nQOIyf-Myo~WWjM7~N(Z;xScwdm zoJ5n)=V>k1YlwPw&Bx|PhRFd}PTc=WT*88Tlw2n#2Jly?xDw>8)+ggT?52BJif@70 z$u7+T0RJ6@|InENc%Es|K4mWBdQ~)0OVQ?dX8JNl0m>Y{(5wkXwBawH-bGJ_cUW3( zvOBiB!YAu@)jizAtlu7paBg$H=Kd71$(Qom6gtxGttmWC-DiMSlh5-9baLgk+ zd;1I9(QNBVqm%JnKZS@5O|?H4+;8i|BrM&!7$AmVQ@xEtBm}c>w(H=7kwpX;q=wHV z@^scpIimH%UT?uX4w*V0{(F4$c#G#O7#?MWr~QC4UM$Fy$Z4K(&W4ArV}>+(dF`qi z6H&8N!CRg+1DGqz;paarNc$+BDSiJDQ>!cPq>QQoVso>2{u7|=CIo%uu~$~N=#8b5 zXF-LFb1^)$&DWj7A%tkGo_zaQX%Yu?I!{c9>w&iZ3CF}a+5Hz7++*Z#vIxGgrh`=% zwP-DGH;R_07LK3f2Y&&WvPn# zn701SdjZ!T)43c>lBI6d;L+{w%oMe;COFKS%J-&iJr(BA$?t!Gck`)Q6?W1hDGcmZ zs+9ONaA8o=g_mqP!HwLm?B9-jSl*|; z5Q$ky_)L<)YsEG4&Ic)<*>%;geE4L3oguc=Xoo|AIw`T){zvRb+V}nbeneTiEkNh5 zVbF>p+y#27#nBTKFd%gaV)zf;!D6_=comKumtcO}SZ1D%gIMzi>Y1k0^;*AVvoOh@ z*PJGA&N3rsY~L(`qwCY&e_k6OUVqh8awK2<(+-eM%0)VT^nqxddyBj;ZLuhA`PN0@ zwv&>A`A_*e(i`hQTY{m({O@4i8A7*uZ2NT}jkk5=#u-gNQ>9zE9>zY7i|t{N;7fis zY_m@@FoGh;-IGBJ-#%a|JeA7L;4)1Q;gQNGNt1UZkBu}C630qq6-AT3ogsdH^1i2@ zD%Y+JY42&dCHD+{yZ<^dblKOFnWlo#Uv~FYekwqI2vrMEuDO1YLx-?ZgvSs}l0`^ME^ zKylFu2B@4SyY9)%!j`$XV+?F;3Hdy<<9=cFIfxkfk*aK6RA^6yjN@62z?S zIg&46=pA-O|B4|zg5p;J1G)4}K28GQt3}>@{U>St|K{Vr+D-t&+rNa+IMMxncsnQY zA6?MD$ff?j`a7OKga6wbQT_?w{qxZ@t?Rq<&;|^im!Zn2sUe;_@ur6;Jo@kZ0bLM? zQB3R>7Rh~S8mV>~ZtChiqtub&0J~auH}LbQH0t{Q;dG0SwGN z*^}!4ZXEsxlq86iCq;Pgl91A|XT78;%L2SgOU>!%;pDqU+Wei>82FY;nA z#LS@T{xF-o+q5nNsv$H)^&vs;ObmF1mg*%-7df6Q1?9g!jpoI`I&}NR=O5xCO~C6^ zLQgL7FLwnTFrPcy)(8$F_r0RqUN0b!S5}Xb#%0dtu5eHpy8Z$EVxOPAW+0R!_c;5U z=JwQ-Gv!W77+CG!hUj_4XEE?ewn6*&F19C^jP71mVRvn+YRbD$ZJx|Jo}-y<5(L5) z{Cl>M@RRkU>-l=imC|n&p>nc8g;O`MKnUbT!w?0KZ~nhO@83jz{}#ggIW4p%G9B~kAL@YVnf6seb8$8Zf!CskZN4T%25(&je%}uQhDtMHLshC zhWPFA(@Aalo|}fW`2{lrQ*+(jksnz%zY1G_wRL5%>w-_R|CWS43h@}vz=LC<-+)9B zyTu&ma-wO*fQ{abA7k3br>^x6hPU=7}4PKaB1=tjZeh;xPDAWsry5N z^S^aCEhFBuTd3Qyzu3#RQn+UN62!2Os&+xpO^u`vl|7XuQ^h6w|?kkof+8n3e8fpajFa6)=AD-89ILPh^ zmntXXw*&%FfTGY9Zs{*&%ZfR>6cKX^# z6FdNIxmZ;b3Q3gBgC|pK-BIH%wY$2}vC4M)me!;`NTExMlCMEYWIa{k^WM$ul{)3= z{6gn?U!<*jzO&rd2@6ZjuTxW2n&s*=PLhC_RrpH+VCfLq1DyRNK&c9CN1k1Afu7!C zC&i$o_=CdRM-0X0;d-ubIQ6saMmqAmc< zMS}!6wHMkvN&u`37k&SLk}KvBXV)G6fQITs27iKQpgrwW#0S7#M)8fn0yI;AUO`0< zFVf|!ZrX$k90O!ZHRo)G6n9?#aO1v1d&0jLm5xf)5esX5NG6Rhf{6^rWR1D#xx=$u z#9Bi=>D`y_wk(mcx`=&2=Bdv+!F0e)Vsj9rG}n!wll}elK~wWk6*VmSe#np(Oh%91 zZe&|pReD%<6w%6!b_?8%$?yoAiumP7wYD@T#J?eh`c#4>h+ZegA!rbredfS@npWjS zzI^xx#A^_PI&23(lV9lKAC}Ki<9nGBr18_8;Q2ufmV>B||D4EK_MzLrh`CjVS0;B( z4UjH1zeNLc>_GI~k@zfPO*W06V07RxOc*5Q!M)l~F|mQ_`2uQsNG_tvgu`5`-Em1{%N&i21TPhC`M{9Jo!_+1I>M8XmbP>7QoQ z4|`$o?IMahzo~fDfFLNb)xPitlz^d^1+&4AM%^1F<_F!n+SJ~m52?etSeLoDS;yr3 znF!GuibgG`7$VD58>D)UsgZ6GeUse%dCkaK)$L9gjQYLcq``9$zoe{BoZbouB4h3% zpag6WBzc#R)sOzl{M`HhN3Z;`J`s%=HcdR@bRweQYyZuvsLcSZa*XitW_B;(nl`U zie$YvQVNGkhb|}F{Q{-MjL*I@-B}Y98$e;^(L8%5DwM#)ON}H6x!{0HShF>g6a0(k z+RiS~k#dqKHowN(+*}3r+*|Q;sH#aJzn4nT@*wJR&&GM|B5)AoiSXZ~(61M}$#1KG zfYDaLW?=%N4a(SPjGKB=uWLbcggM@NXWwE`b}+0c8M(E~y!D;#>etX-P{$(GbF(6# zs=1#t**+_{+n=9b8c`xAC)w@p3Z!7rNZr<6j0XX@9mo`j24g*6hvbG+w}F`gg%I;7 z&hNx6KsgaGGpep0&nsDS!De-TZ|ISTg8^|Ez#nPf@R$GTDqAlf|C!_%}BGskx* z;}c3!PB8s6k&4idMMUiXIF?+$es5x0pV1`oWC zA%vfa5*!XK*aHUWbiF?Hid16s4#9p2DZL+ziF zJLNnkFLLad&~Ce9bzSb-Y@9sW*+iW{>XhHsYt|#H=r9IbN z?%wl!tIg807{EvX7y@DK;7iTd)&MlxCxEp~#RJ=L8NK6v>)w$0r1j@y5p5kdBtxpS zU0PzIj_G4?CeNE-rY0N@GEif_R8uf)Ree-^i%Wpj_Q>Dj+%W}6ZB4BQi}^hF`wSR; zWJMw)j$D*G-60#q-ZlPcZ0p>4E2}jt=(>yg(skw+-`?(H5HcZPijmhQ z3*P#w761X}uz?9gJ5Oa)yVa&ddF%B!?>_%qIC5dli}If+$(p3@TU0&2zk4!g&bt{x zEyt6IZiL_m*cJ?0t=r@6kRYIYz7|$@}_5J_&*3{t!i3 zQX&BN6PuZEl#ziV;M0B%t*^s#iNP>)M*g0~FXIu3HU4E8T(wJ;j<(QV$L;VxAVGCt zx#-f}CDCF^mB_l_7d$6QJiu~s2Z~tpsSY6CK1~TFyeH8Fx1#o({(xw~n{5CWsp}@P zS${%(bj3U6NR!~%(;8CV@C0evR7(*|@vONC4WTBozLMx!F2-XX=X^axGZA3zy3}x_ zS@}>z-^t4lQ}4Dr(4>)lHa~8y3mH=sk~D=k_Aak!xcZd8t2ES*{71=r^5LitSpF>t zKsWJ>G;n|}fUUSsNs#p%vF@bUWAIRU2jYrNTs?vv{C1AkNeLPAcQv!qR=Y_?`@7q^ zyq=diz9VWFc2DJ+?IflYHL*W081@I`h>SAhzJ$xHggTk$rkIZSo>R>YsPs?Kp01X+ z*L=?>(}qMW6}GGLju82=dV-y=1j59$G@7eNT)86ePh0kU>+0}3H^K=ygq+EdM^Q8g zXC9i#S-98Z$bpWesp5?+o~(N{Y2OkAZkLA3aMW2C^HW@!oG{!!;m9i#caP1Ui#PgK z-921I&;ja{2Y_Qqc7AnO^)8(IyO@&L^RqK$o64GdNwQm?_u73wOS0r&-jut<7FIL+ zT<}jxmzxuhcqg3LP-nWK)HaqgYPuFCTRZJWOj zgE(}X*%OM3)%%+|r?v5&R{`*$PkWJ3StVR}yT+DRM>XrkI?1|dcX(u_ttdd_`%9n+ zc(}{$!p%j>DN|uhMty}>Xx7J=>(UosTY?JMq-K(?nR5Sx9j7dU+h*t%4cdUgOuU1? ze17Ul1>ERaLwwWsh51aaw|!zTOY$r z-Q2q;vXOV+59Zr$#X|>E9aFkLQ1{&}BV)_mM%|E$f*r3YV}RXXXa9iO>%a6Cz{qSP zHnYYYEO56{ffo4mQ`~npRv%VA%oofAWHA-BO^Gv5!xOyOKO?u;M}$I`Hhfz|=Wd@B z-w*+~CBB3@bRU!;JkY|kRT}V+^oe-aHP#i{H{|mNBnG$YNhGB$l>Y(UeP+zW6hh;q z)C5Nmne2`t!xwlu*8?wN14gTG-3csWlRDD^a`hh-<%W{GuLxYsc6%@S`r}Q1f{qHe z*kC$vI`aBA(5^aqZpdK?f{+%?yPMrIuXS}KI)9;@dcK%cXJKoD z+N9#lMz;dG;_msM`S|@so~UN_-@Cf7%}}}gm*M2Qm20X2@4bG>wN^>DCcX75t2k;R zY=gI{@ZC@Fd5jHCzNMu1*_spQWH!y7BEx&6>zvZHjb>?Scp3r8d!hUqTw$L<0au0q|62HuD<`>~K%F9maQx%I=-qgIx3jl1N91I-O&-)gSo{B4^_YUC#7-jzvkIc?pd4x#CY#7qCRj4 z$!CCf6uoA51W;coT7Nq=o9p0HD-Y-Z_+O^EZ1>+nLk1HZ3w`{T&UbBl-ZeX#XCN@d zocutOb_#(#>Np{|oS*;=mZ(xVs@;a&+^XYMRl-|wXy5DE>29~1h@HZBeYJZEoa2LX zX(jvd-^p5kKro3DMKlooD7%3*o9rX&!>~wF{3|s1?Opi$ zU0m*l-_zh*!7D&9qDZC)RK{tw0P4Sj%%|cirr1rb+QyMGkblmbhilbGt336wm#NR~ zD|>c?WFsDIF7y0$C+jIM)R4jer1;@YbaC-Wo0?{v3FLw2m}~zu`4QrUE1e#0bz2S3 z|8U4wH^6lKRwiHkeLjvU|ICuDb=$ke<6!~EV|I7q2J(iqL50NU8QW_ae{ zDpJ-)+!(#APG z!!Xg?!u2`RMR&cvmk&?3RZ~yUIKhPrL@z=(47V}fVF`)ct-AbiLa(?o`eJ_@%amI@ zJ9yVxmznZh%r=kIWB5L;U%c<^M%Regmf`6*01RF9!XMM;!_xfIX335KJ$YI ztfr>d<}ZSto@-%&8UtlfHT;6raG7_IcC#r~?FxfEafnZs!k;@yCBf>w&B zG5B4AH?#|S%B3Q8VuQfPfENZ4Y=|{)T=%j+kjyAjG5I_QLt)n!xqE`jfHL|ZE^d+) zM-S0a89-Vj?r^&s<&Z!9gu1X2^4Lb|w&`@tS+zYQ6DV0t@R*WJC5UG-8gFKWV-`Az zXi-(>k7<=?K;1aqR*D%f>=mC@!_8N!XuSN0bOnH**O4-Sn)x5m z`9O0IGdNMi#PA%+x}Z+)Zk}EN&P@O* zcd-(rU<<_h#j1ah3xI%q>6Z!@Air1YCVzBuUdHT>sv_P!1BU`*C5Q+AVbQPMAe5Ui zrE`u+*5qr2=b+Wp=Y2P{!v$5-M*fwgH=BbdoDIVJ(8Ok7V1?Dgvv=~U2nO@kN?qTj ztJx0M?dwuU{3I~(K&7c`$I6*nuv=6IT=Va=i=Zq^6Iy6;P5l#ROks)s*$ zmT%jHE_c7@-LOVJ1)W+Q!GL#l4OAzLFZ6@E$ugr@93s+3TciKYp59ol--WomV%jC` zoJ7xr9gC@WKA1&XeACkd2&`6+Cf1XmKxReDe&^ z$`{PQaW8ri!4Uh=i#Op{mjOC``2rFcneoB;K#6r;Me$5IP~RYm%z+P7l{DBQ?20=k z++IljzOa%Z?R=+OrsZKYdym&wtlC~^n7`E9@}$DEWB6&tVCr=V50~IlL@VzEvTcAX zThIwlK|wnqSBzQ`IsA#?1J=hxfX~(?0)x}`4A|YplH`rf?gP&}efbO#)7BVp6a@fD z=kU_xj%~yrkhUP&7R~*)Nm>dCd<3jI%1{7aqS`D&w~%PE@%$&!1jj$1oBVC4BhF#W zL4gvv4@MaJZ-3X`1Eet}O#7|@qw4tQg%e3qIbvyzEQt8s2^>f^WZRv{s6WDdI{ojd4{W^1 zTO`BLa5C>f6p@jMth3s|b9NONh{}*nQt&9z(QWcCDt8+Xn0hi_d zy}X#T0m5y{jvy_p;IyL8Xl_&HeEulUN2bcCQeI%*`lA6 z)+n6|X9PeLd{7)@mUo=nE}Qx_ZN1N1@j?H=Vp_q>(Ko@x*JkqE0?D<&rZq$+zrW2a zU*P4TU{0|gkKw3R`l{5KSo&|ejw@0%b@8t%1I#s-f+m<(&!vEKOlQ)>OT*j)$&O`T;NOMu(7r9eP#H1eR`(>2h>&($k$>YhJiKCjI}j3CJD_jPqsI7TUAcfui)}+){BA?gCEFxn3P-#7N?C^N|B!Mp_hfOVSTq)_8Lgb0P5{U)gSfvrITrJu1~SxO z%c%bhNI_RrJl&?rkjr8K<1~HpaZYZv7h1Ktg;_vOsxOotrvILg?NV}ROo1ber>f0Y z4c=MxET&K_y>L*xqK}imjb5H=;}#lgyolZA@3N$coHP05zP-C`zPg+>sm2${Y0p?| zJ8jQSu2Yo{w8urYAfuGf9R{q^d5|@(Ry@h^}4&QKkmuj=)!MIf_5B8qMliW1?@)MZ$-rbp(Hx&092CurdjLNLU;SQuY20)UO0k5UYwXcQ1y_x2E!9P;Y&gVFnUC!yyL zfOoHp{m*>F|FY*2Z2HIs`#`IQ{(vCK{r_Z3&!PV#hxlKx1M)x1mjBG7Cl5Vh={{b9 z6ea=mJ?i7%=gR4bG2Hw>rScYfDgYS;|BwG(3`~ZN==c4xWG2;Vpheppxbe>xO$3KH z+9Uyn0Vlc(fv?6@uLr7*O|?zRN99(;alqh~Sp1IbvpQ!R3%jI{9}R|&KTqEAG~j7u zng0V~`2%_m4guJm-Rw~yMoV?T0#l>LXj76hF~d5pY*<*8#%9f&Qf2XmP2qekzS3p1 zudTu6nOF`qy+MJNfEm)0|B}Gl$d_`$hr)EKso-|H z1n4zY8ZK>sLAp5}g{f9S)&#xP1Q@6a|17gzDGtEfA7{7APL2mJ%z(==B&J2N!NGj}ueJNpR70F-CDiG>;m{cK=d`0qchuh4@ z3pPFA`Aleets+1-2Mv>RExUoz8Zrc?Au|NZ66CWnkz_V_@bJB_X$DI6)ieV#@48ML zlCmsVY0vpSqr4Ea(>h;nvQadWIS#8id1qGo(6G|3XzlO>=sPb;5oED+G0^ij#)%>? zj_aes&_9c1EA70Kowu2^JRkdr@$~XuATZPlvYbk2yh>gBQaPjOqnItvCd5xz26DN) zx=|E?FxcX5lx5VBZ|Mspm1wM}w3@g|k3)PbBp!E1DeQs}%{d+jp^tn8a%Mtk&~p`^ zvK%HVB^T-394s*t`ppm?{oHw0nmppb>MMJChKG@<2G8UI&Bq+^Y{R=mk)oNNq3OPb z^~IVPe~#pScNycByexyX=-Q=^$$I`ZKu-j)`W3;ceElUZ!MDfWym(jG6n5F1_IKE% z;-vuc{(8*G+H&orUxcFbhF_xw8|-EgaSz7+6OHB4U$h+GE%On(zx^Zqx?hUQ{*TpS zmE>#B-92^61{M&Vs5ej``x0;nAlvUg(_@0j?YfLJbTUtUN=luS(@B2dAR40&sY2)j zz*ITqR#6e$a=dk%hxTA;_{FN#Te-dIDeJ~BaUp$vG`&8OSGt#z&7OQ*RFLhr0D6?W zV7oq!*Y!~gOONo0_db}8-cm=JB;%8!$|+1r(&_X2*+hsyEIr~$!Dxoc;uBIanRha{ zMGjRNRE?qt7Hg_V7%7h>adV_&TvcZM^^z*L_YG+wUbhu(=;rA* zv*~NKn!d}QK-XDWvCSrRK!*+|cSF2-y(HR4AW5+d*Gj*1gk%Mq=#H9lw}3<%xI#M2 z3=OlQVZo#yx5o>qtC6c#3)i==;$!C@rN`sY9iD5^pLJ_%Kq;o|NL%~_#oLT;s7vz~9L#QBnjg?e4%6mQk)$&;xL z&v@45%b}A*<~mX`XS{@PqYq{nf{!!vF^$F8_p`@eLzqZCVs1GR zl;1uv*Yj*qo$0YRUk_aAG*+u75`3@$NDe@j-yOHJ9o(*p$#p)>t1blB2K0Hq&s{|&HqZKF8-!i> zy0Ymnnu0)=Ko>rp&xC5HWn{sCqU7CQjS>%i@EnS}(f>@9$W)CNY)6Y8w z74CWTDl5hB;$i9!_}tb0ifFzh&&%JH!tPw|K^I^a>cB9bQz0cZ2@j~Fx{8mz$Xvr` z9Dt@p^$+O#SUFJPjUd|V5q5}E!MPL5G4P2}Bf){S)|o1QAF|kcN_b4RsTkGwUoAGZ>tf{!_!zhn504$hk0q_CD zS}ObkavA&#@K=+sN!{GyoxNro_UpTpfT-5RT!$BaCFLhCJh+M0d8RbFg}J}UuFaf? z*83P2iO5rp>QER~!DmLb-&gHg-HV!U!n84NchYGn)#}wlTUuDljIqbt6=#}(u)$^A zcx>Y%*Gh}t{mN}&it%7if~%J<2B-1rt#}*X6gNQ+HA}^j;8@$y8ovl7weR9NX5iyG-vA7B3YC7rXsXa(J;&{p=i> zv4cB`uW@dR7+}*sU|?K0^@~u7&L&vnE&!RqNoN}HE}*63YlD^xl*b!DlIVU{uCWpa zL~zvGz1pF3ysQ`4_>XmuvhZewXIF!Jl_;Z{DK)?9xg%UZS{O5i=*;rMH!Yu+U6)!nu80m{GA%u&uXg_OA>pzrN8dFLB#n(XR?T$0B|br}HljBJ3bA2t}{fu5acbKPFbv{Pf&h)p$#W&nxmDDd<^GOeCW zPdw@LcNA$=q5Y;I`p9tb*RqBA(?|+?h8|gxI+(~*aioycSJVEBnlrQhXIU=pJmDMx zVwg(?WQb`I*)CZeUkUzCkCa-Y%Oa+a{ZcN4C}>6oL@#H|gd}~l^%hiFy})hP>%o}1 ze3JmoKf{OLoh|rrt1SReYeYAh+p1(;op5@HdgHon+!tTfAY1qG^Ln$lQ$ZqfSGj_F zY5XeQ{b-()OO|#TBEUMiZ^>E8oG|@%rZ0VMT>R4L|6=bwz?y2;bm1T%RY2(|MCnRX zqzEDrl_DrjdW%R0>C#Im(wl&Qq7V>}PDFYQ9RU#)B=k_ENKGgqkmA3-@662Ed(S>| zX8!B!{mq`Om$`@`S<9^TzE8jJ+bHGmy*jzO>Gli{$sbEYJd=)d|7Pn{8=}>7d{Kn| zn$*Kw7Ust~u7WYshwvOHycU_xhHwS%yCo%CjAf3Cn12{KsXDqzV@uZWl}CnO!YD%8wnV*=}xo zujRjll|!iT*Kgv37I?uOWX=YTX6+b(^iUn zl?6DJBhHL3!+8J454i7z# z-&rt@%g5@3)g_EDZ^%71&~aXo>ww632ylQUHL$Md zN?|HEriQyY(~Z8qn6PTeMF^N?eTEX2zvvCGd$T$0xY%SYj)SmX0DL{1{4Lcf zy7PdS!)b)r-k!zP2#$E){S)-89KhQ^x!Q$;ov;*GNY8BOhDAH5!pf75x|t7v$wkGp zUmKt;PahaqL3$Sg2ht23NeUKD>B+sUW%ZW1&Lndr&)cTsI3i?Y4ITw~7qdBnNnV!# z^o^P~0t+Si#7ICmT`QFId|6X%!S&1YUEW8G%%K^ByPK|1--`W%rm`Nrv=(}@18lwkc~a>%AZryh9_%Dho3yZV_JizohK|C1Tw1(jo_!xx zoTwyct6OodC+Ui@)DrkNPsS1Mx!``z5f`|U?t4X|XkSdmHgO@$dbfG?(oi%|jT!gf z~(d)Kb9ia5qDA|yy zr`nR>cjhKlS_pG57^9D#YU#NvObU{NN)M?nZ+Z`h=HSc8 zbcO`kjr6*{D8EGrlU*FkBwF1QU{aOL&(^*ky0?)HNOog1p_2_7jaoT2dRXO_h8-2} z5Goe=1y@(L0!&(~|GX#GA~iF&*ao3O7WkS9e3JCwq9Q!bSG` z?%b^A$4~?P<=5X|UrNbiCuxy;=Xe0lZRW{>PGvrPK5q}tR%OLeLyO?dv{_pZ!iBME z+3XsOSv=;$@QT}P&ZXWo zxG-|~);YCsEg;))Kl>iUP7tu7AlwWchA_aKbePT7Ag3!OshXdp2*XPzG|#u!I$ah# z-69@q*p>8QZQX-O9;9w1_k3N?#_|G-cM=u`fb<9*oFzdp~1M#f$0DXDZyhtaU+Z2zZt4lev zK4tqR1VVV^Xf`!&r*Jn@^!!tq(r@>oGRzsvxK1b&s)B1y86}=`uDN$#L;G%z*q@IT zwZBBXL_S6y$-?81IH?(+%f9*hpiv*ZFJ<{^_tZ(mVr9^M3^Hab`_SOq_WZl|^|vVR zdwVTjE1-_mwVa?xqfyFks&eF$z;Lt)r!VqCbTQ-_TeK3V-d!gjR>s6FkE$Cff&0kG zS7dF-f-xz%oeyY)U0f-2q%97UCb~9ezN?!iU;x zXoSRM0yD6D!$mgut#KuvC3lvoqLf&r+hyy%UqGd&mN!wSOL#%1ykV3R#)x2AQYQII z=;x^(xlrmacK5|Xr*pipJiOAAD&4GCxKjIxdx=Uhquc_=Zlg$h_$2yn3+I$yw-jxs zM`fF!<(Uz$%iB+TeBp>r(|U_vD|sHpb7N9B$wN+Gj`W2n3_bufN{y z`{7v71#^&^+~`EsxObPsPT(KN8=rwp`P|nwpu0g@0`aJUa$@sblP_zi@@jF|1L~59 zP?kjg0`@o8?1X10SD_qa9!Cflz|a=CfQaLiQ#?qY<_3UlLJRph6idO#tHfX4? zPg=<~<+`NKbK>L2{xE<{GdBX62AN7(+(Pz4lIO(msn+zJ#pqda4$yh^ATb$pf5G&` zmx9Tcw_ZQf{_H{RudsPxh&u%FdAp;*xA}DFM>Mq$a|*y^PlR9=Cln_whH*J&3yRY} z>hVD_BlcpkpL3P^_2!V3ZBq9}_buf{)xNrZ9q;R+-Kxxsbxjtv)=hnrJXi*z{A|1e zbbTo2If-H;PxpxCsLFbm-0SqXS19I_DRjyj+}}fr_OA3Z=IU)hOW0A*twS>S99ofu zb_wOf*Cn0-owN1V#R`CU8Ri2-;2v_Lm1A-(6RWnK%AX9GvhbhwW35{IPQbeeN9x{u` zbd6UOZ07bG@l;$0wQ(oYm17(F(OjWS&f{nn#M^H>!B@%{7(z6^XEo+dX&BuxEmRs3 zw0$?Hy;$UDy9-kj8*D!n%!#4taHlc{jQF<%GpElVMu!APR%T``K7ayN(4X)vFr@amo)4wmWx=~D9&JlLN_#1?|26jkE79S?i*!L)Y8g@({Fl^gP%^Ko z<6NckO$!7a7%7=EPzpvC(z$@LvvRN@(0wQ)WgiSoE!}DXbStELVju4mG=@=5bLtL@ z@FD{ahJ(oh;*~sARXpazl|+B%fX7M+NGQEi)|V5-W- z`@6)$2ivsP6RX+y1}Ii4NtxfJTOTV|TJ-&B=w%-ZFC#;@IK2;bW~lfeoB`nLFE7LJAjP+J=O=lvszp^cswi` zOiT2`0|RWhY*H4)-aQh@$PqwPSd=j8*K2KUZ;lgbZ+IX5BPu6Z#FRrWnNGJ+Y(=d_ z;K-wcY=BSi2}CCxkkosXg<670#zswP+q>&GDTkFln$AXqN%yRVQNw^{J1d!qcm+TF zrXT1C#gTbyu+-0)Y{M*0nm+UeUA-;yIIYJ7M5k^MJ{%0Zf$0Y+2~Zb=!v3?mKgT>JZDs^Kp|18k;iZ+-c4$_uX0&kCKGES z4hDFY)Dva;f-?m!v21<+9wLHS#VL}q+gbginc4BI9pk==ZTS-Jex9CwFhNFuZU*xSKc4f*Sd`-VjU8c)Rz#a*ZCx|KE&qS>au$dtu3$4EH=DRS5EYQk|ZoTT>o$eOYza8RXW|xEu7!XjZSTpSZ zq^4p~N@|8+v=I|CuK`d~`@iP$-=_T;aN?vF%H00(sNP&A3~y0=rOo;5@s;)UJ>AQi ztre-2-}lNCQ!^gQU;NJE5}o`Y{^`-!*CXVvT&`q#QpFQ6z#GHMihG9FDIqG2Eo)uh z8VV?MW_(5NhtVpVr;Zhr%Xm=?s9!sJr@q^X1r}yX=qdlfjm})=Z)qNK&L~z82fzO_Z46ZvPikEws&R0EcoU_rvaV1N!7DKEcNC9l81ez zg70D0rQFt6e3cIantsY+BI%6FYJh-NCM)T^m|yTRh$TzcxBOgqrt@)4C*+;fX2E-Jz8ui@L`yMaxMU{Q)ob_)*nou}E1F$o7c2Q~*NLE|!wBQ~1 zP1Zv%j7{|($VZ9DrK&S%+;KYZNStJn%QT`ee0MbhanmTR-L{9?xEr9gtH#q11PCS_je>xT?1w7`z8^=TsR?DoHz1|oxM$G$; z^*(qW@ECRtUVli;@#{el7{Me~-Vh1`W#~5uCs72e4kY(f)PT%9JVN$5YBWnTjdq}x zU^8$rmpg;1{JpXCHGA7j=3yS{n+|}1vj!%IgBBqPvQp>#M>=6sigVTSQ&MioI-hGw zlb1RDvQEu-B0wHx)K7kb7?8F*ldJQ6^?;VmQm1dWRYfeeKS&%Uk2)RODE^j+wP%Q3x4wi{ebeQ$se0vnhmssfGBAt}=NdW1eH3gV1N zAXDRW=G`NWvd~k?^y9Mr`~6>qA_Q=-t&7P=i_g!$yyvB1_t2vBY&b71sT2=z5{G_- zv$aA?@Q3|Yj69hwJw?n_U5(|x_j?TVd8x19j`%bk79M2=HW&iiDJ>I zIXDSC4Bt}62=x4>7S+4u(xup2k?_{SV%RT#E<@RH1ul>om+_9mzmx7#O7lGKJlqU# z48#jeq(Z=C8})Z)+vmUCFf+V76FSum6PLTV}-D1Wj(40Lpp^7sb+ zB?i8L>XTxEL@5ic88vTb54Q<4Qr%^I(TBIY^}Y+g^yG2zIS2NmLtr$hQyA$md+Pw0 zD24SZ8fZ@v6lbPJcv9|2o4uqV(oKvR3}V^J6c&mK_TDYUJuPsKCBDVy5CTF+k?i8a zU+UaB-ZJ*yc25;)~vYuwV_qZs&h?hTQ1-&4(#fvSTfBayI zD2bIh7OI==vb314xU9qYHIJU5@XH70!7C}6HhF?>3q0cd71Xp6oX9c z7ocrpj5^j%FIrQydmH!0OvSo*;#MZEzWz&vZYSeSAkr884Vne~L1;;K8t0*FGf+10 z(`Kwz>tkdOGK4$_6h46Tjw9Hx0Poi`>TiDc%R$hr;;8of`Ua!;>k7FncBxANRz?h2 zL$0%j225fdb;xNcTn<(^0Z;|;USulvD|XJTF|{&p?yPqSdJ3?T#fEnauy}Y6!_>g1 zkv1ul1&jT$!dPf>D}zHoxkV0&(-*~Q7M$L+zDr8>r>Y97iRd411%S_gSs(v4U@Xz6 zdA}?>u*Pvwv;t*Z-H6 zXOi*u>c4B20&Xwn3AqpGHtQgF>ndQoKGuu{oXinU!RRBl-)io7FpiE?3%Hk?_|>9d zQG7y$e7sDOFTUZHcdNp7_URPN~FhwgFH)#l9;62 zgb;7eRH4t9Bp~RG3gxfII)oD$oE*w0>j^I9 zuU@qrh7*)-?FMvR+Z?21>M_nyzu43DCOaD{PgcK!H7Gi3vH){;Pi|Kr!O173;@kNG zJT?^HR=XDT2MKCjtG=6`YyUzZS`9Yy*mB)~bASc}UUBJbm&L00K-rx6WU)nr_3XJ) z{vkg<{x>pJB_(tw-*l}Fm_S_Yqy&FtXFD6vWQ(aHUR<&i{;dxb#>wGVEe_D0a%+#D zlYYloaoI5JJRlw{^4Ch$`xJQkjgMZ(__$&^r^%Pr8(rBoX7Fc_cMV&H*vJkzYbyiB zZB$n=C893rk%Yv4z{9vGB<}fYFjkZ0-dhDh>34IwNgc^gVVW6xfFQ`f8S#{uT)LWn zHR4U}xxDk`T)DeWAMKuJ2wm1pyBeVy!fP22%2&w~oM8w1JlLl3$v7Tpo3$kV&LGgv z4A_MT@@EJO!~y-3$E_MOSy20}Zr1Y2$ks*cyS=YN@6?=$JMZ`ru^iU&?K!BQyA$kh zEVKlpz{@Y{#JDL5EzReN1akwE?S!knyhg{(FSbV;* ziI!X9+uY5_M^fZZI4PN^dUL!(Xd*YK1igmakF1Hm~GBKbXqS%q&a!ghTrtGZ#nN;|9Q{ez&iLA znqW3DtL_KxalNG$7fF@PU~2Q2FENGAh^CPr33&cLpQSKzh0N!|s%JC0EV?nfa!(Xa zSQ;C?WV)fR)u(pM;uvk17+>pb8i?GbiGOq8Nldv<%4ol|0Stx!v}o#!4)Lx9b>HfO zf}&bXbPIKaiayr&8R%<&%NpDReLA_xB(@B}i|T9!lo0(sZ?y{(6&kMM0a{VCeOj+( z={K1Jdzge4ixS>+vS8rs*n2Nun|(j^FST%HC!=hRNQaX-#U{Vm@yzN9T@^+fXFvPUp#r^boP)KejC9|xXP)Dw7zlUu`kK~IjTLSXD1O_tKKJ-BL8_VSQjhQ zSI&!&8+R^sx1;#cB(Y!+t8k9C{!!ag1OTah;=_05*)BF+*MKzS#CzB%pckH&fGOL$7pO9yE)+O=`Dmcp8RHqsb;{3{tl2!xwZmF95DjpgFGlbS#sSgDkWIlZXq{ZEl)H(1KDUq;Iz3_XdfR%ZEKuJgzb2mMxpN7x{u3Dv_9?mV;&p< z$U+KmzTYH=NdQ_COgro`+*Ig#X2iRC8z1Wi*|BfBkglnl_~R2wW89>ta7hp*Gts*R9pZDs`x*HF_ZZ6cs zE|FsOIQOe^TiylSxu})vwu8A`p71n>zrb1u6-GVFrxsauOJWLrkK{Q3xK` zJRckYbMb&k>TlXlV8BGS8k_~Ty?`Stpv*axJ=2%&?8f*bE(Y+gL_+=@i0>$$;UfW> zB+fY4=4lu(W6IZVM2dxd*TsTKPl1v2FZ}JL|CcwkS-?rl!Ji&OF)wk;0L7+Nz@IiC z{^RHD%g}SJ#*2^>#Ipdvrd0scI9_W>Pd@IY4+ztt5?=>~3oo1noCOQl&V!4h#lkXG zn}L<=#Q1f1o&46t3aD0zRj?k`Yv?McUH!P*)+6dcdQiSc%}aAj=N!V|Fv-_7cQ*&VTm~b)rnx7BCL1s?&$W>#l=|p($JIun*nq z(%Ueof$=T_KzJ)eP=$SYfJKnm6oHXYZ~>V|=g&_AsOdt!TOV-yK@eqPyOCtNaP0IV zP=Lvi?+fL_r%Sx37Xu1+vZeL1ylB&}d+6(Ijro3(4k2$1}822DRFvZ0|1=vTv54HBuwp`MdUY2QyovM`{L!?I`cX0?!@HMN2OX%LY(Gd zXTV%|v2L=Y+_1gRu;h@w+$XQkq$;+oArVR;`G*)qW4(LHGJr6_bN=)6Wd$IL4iHn= zgN+}CTcs=S5FN-VpkjGQ$|qjL_V)nj7v*#7Sbt+R%OVcZ(8>Sv-IxW zv=_`vJU^NE{W~13d6cz?256L(h;FEq`1bSu`qy)uzUiA2v|er&ztp>h$aej%`n;?} z*WxM&M03uVPcg~)`H|z`$El|a+*Z!3d!37jX+K;MwjugJiWZ;MpCuotjc^sp*=n9N z>0DJ2ox)~C&k9mJe>QDmdq$BJddYYnC~Py00)3w~6QGIF*#?+H-U2djF+l+Kxf+;; zi3~!MuUiT3CR)s{3X*`>N1*P}4~f)05h800t_fd*eb8@=rfKJ&Q7Jbub-W)`G<(~D z`gP`AJHgAe^i%z8_Gi+P3aggwCHE>wyR8ppo}7H@N6#9y%H{hkB=H+qeE z01$zPZ^5vB^AKQtV-6P#dlY4|le0*beq{qL>@yX70p~UN&7;zUrkAfOh<@~wq@Q2K z!28-|u<|`RZ0pLh*o+@zb(LmN<=r0z$pYf9ZmrsC#$MA^Havl>ge8J&cDk5T83;f>&^eHp1rr0irqdX_Woj$ks_tU{tXXan5V5}Z{Qnb6{)$?Er!e@V zBHW*2|MXESdp|y9VKq$2+M9hR0l-CX_^}jcoNG>c%IU>#n^X3+;8~O4{5ks;dQnQu z22LCU4nF`GMIcL6kyUuVyJJs=6*tVyuZy*CiPYDh-cUB9ee=XN@ltSsBbOBo`|;{e z5WW0-{yb3`(?F&Jv;&7jEke7{yTQm>W>Uxo`Zx$NnGM31FL7=%5EO!qKCjk{5@j9c zXHAwX>vWi>`|WL>B`Xa*VW29}mcOVwL8vHPX%{BNk}nX|NI6JH%Lh1Ve5se)lcS>7 zj@uv2#DeN#XZmoPGYKve6c2NX#JXyfVJ_vEy&f|EC|L$@E&4?1IZC_MT1>?=b1SRq zXI~V)T4x7k&CyXC&UEH(HgbRXK(o!uW;}wfMRo!+l|&D`ok%#5cj+vW3SGC!sdoHX zBN+e2*r*|EFim6^?QauJ_|QaUt4q`5oNe{8%BjIjuFmOXelhwM?$9VpPyDkEW0~Pn znmn~7?_I_U+Vk`AD@tGtYGI^%^hq$~f+cG=)NK-n*bGse>mJ!{c)X_+I~qDW+~Dh( zp8OUm3|W{&^8zCiO+Z@&EsrK<0SQ6`)LB^^8VBcSm0G;-OEBfRWM)=wX`v;}8L_g$ zzxMvB>ukeDJcyM2KRrs<7_2BVIYHY=^Gv1aO_*}XH>4eS5@C*fWiUqO@pm>akCqZo zDDLGuykYXxkXt0pGc78Kk01&Aas{(Wrl<@NQMKE=2)jgxU(NDf8Nu5iC%wsW zDF9mSl;clO^mSlvX6*&u`zHuA-k$y@rTi<|@Q`^*t7*@Hcm=%)K!Wb{cf;`~Ys(3I zQUDp5xcc>0s;f+L|`suV+9C+ z?`IsU{zYx*VjjdAaE>?sD>&9a`n|B9-~Q>n>TmY|CZBtfR3rtncb`HpsmF^4i-;tk zjZi)WN*DGe(^^eghpdk?^@l>y58ULE+k(JlfW}k*qP>1~@R?>Ne|?`O6Nd&$EpFlu z^t%QkTxyFFs7wbQl5;n3_F)kE*4qTt&^c&bA|T-$rA*s`af=I9Du1=1@wQ&s++*>+ z{>IQ93oj#54QH; zo(+>`hi2Rghk5`yYQL36L$AU*Wsu+7f&unsL><7av(Zd?iRg333uh6t5XtBR9P-%G z?`)3KPy4~b#895DOy^yJV7hg5SMvPoQ^Va zDIP?OBc&l7bt2)wNVkhrA|OEQu&D6_&Fr7KY7%nkXudJk&1lt-aOaMor&2<*)T7 zkZxrV<`aA#P2+@h3Y5#>Om%Q#(p2TsddMN(lPQ>X_qV?&t((-rTUcgX4bawQ^UsEz z1h9^M^=4Le&eg5B(EGhT&*F47avf6H!WjfkQp8?6zjU%a4)Ic1C={4zs&Vh#;h4d1 zEOJKLj2%pm#YswjC6kAXSn`q>iYh;fek{rNW1kJ9P@)H|Ko)?SpRLZZXgwTH2~_$& z)E$Kr7(zb-++M6iYkb2ZIMzxqL4CCKu7}{)ZNY}73^#VSZ9%~RJq2i*>NStT)rqD3 zVlwYH!a3Og!ZRcO1mqG1b6 zc$+u9`9DrBY){Q82)$_Cy;QETtG%nSX~^#NQJak^BJ2jw-#Ezp+e>%+9u)i$J=1@} zbN;Fg{;{<|)IYtG{G&3-UxEG~y7K>DhS|RY{eR&`|04o_nxCJ4*|5JuVdAgZ$zL|? zmks;7UxELT#fo17p?}T3{5@X#WyAjNJNW-)?DeO|`W1)$p>fzRR^Pvez4~kC_`BG! zXU`}E=b7GyaWo-W@yISR?Yt{rz6orE1>G(d{sqMRB=P&f7q14tYGb(`|Qf>6oL{lHi0l>r<=2XeW7B4CIu1 zdZF!}=Jq~d7Gr+If)bs5!JvM1I7T+OaKR!I@&1 zL)_LF%_~nIiE2of`;#?5oWmqs8=&hoCV0U<>+2A?fN9jE(6@S4HjAw=*a-1c%I4G! zB%<-RN%KE{6BttlXu<0o(*tm!$g==ibZqbAtEwts*nA&~=yD((4;lacJl(%O@#|XsS|z{s$1lt9%O(E7dz@o=$++|NkwCxX)A-y=S&O&lP;YGOxX!Ju|lqE@mIRz7B{eNq@Uy2WO0 zbrRBJmqLx5(BKUz|JI3Z=V$tsfkGes1ic(K7A+RqemTV%`$UTM$B#06AQ`P!lfFId z%KzczHl4mlccW7BK{b@xe*|ZaZ^5XMq1?pN{f*iZb9-oHNC6JX!(3POtcIq|Y zAl@8*?MQ#?*Vr*_Sw#3s3NY&pP{u zFSJs8Mr*OsOejQcDf;roZU&PPTW$H&!x;xbYRaWXIK)IVbPx^z+z~CvnZQY3nknUg z$9FLdI2R0}GfDBrt!4giN)KdUKNQm??_7_$Vt$hQ4ljep&e*)Q@egNF#0MAS9H-_C z-pK=&i1^xD@uC&K5u5!vOTn*y|JSa^5i2eRP#=e2t)`ZG=GZl!z&ZJ|_6#0J5W^28 zL2IjT22TdbEhHf=znCvz*+qv9-fj-OX3HoHg%YXpt5uFu3wQ;rzm`kclosy#_3}?b zXAmdmd_~gycMAt*I|c^R4~6_wwwwscs#vk^ktG=Y^ipr2j8J@!vg@sJ<$LPqUh3NR z1m-?y-dcj$LlWJwXS+`=kOE!F=RbcjGWOn^H4hnkm8*5}$o8-s+!jwth_0Dfa`Mty zgrbO7cAJtJCbhD!gLMJc@&kv=zuaBF{K+5bdnkXww*RO46ETJ!@`X{N$ikL-Pji85 z-Kc9}Qx>mA(%mV@luZZk0DBAcZ0ICeDnz8C+5KrH`f>BtWI)&r*9u${&4!qoI^pfR zo^hN((SzzDQSae9t4LdSYADeJ53eNpViQB31cr>Bm9>7Z__RQ*LE*^N`VyP3_|uRn zk{aSXo?%`F?}>TU-OhdG$WP0$!MN4SZ5tURs@%d|&x|uLMxf>cs-#U`-z$?Z*4Y^G z-tyRge*O($8Up$j{=nw)A2C??H#;XZ9m%J3!<(Q${>;A`E zX!G#TCm99rVYs7d2A~y&dyp;n`D;W^jE<@Q5;`c4qQb0R0c=O}iLdc8_qFYt`v`NP zzM)g`iRoW{kb*x28w%;ay0=+@aP<)r3sLJ+&7N8p%;x6I@c&Mc0WcTy)IqO?4$Mix zSc$@QqubDsPvJ`0-nPWP({UFdH&fohnxOYkJ2IEbo_|vv!!qjUIsh?$_i0$u%%E z-w<=v99+_FRT1RWQZ~!%$;$9mY=SslT zS~Y$6(_s8pApXY&;=h2zf4Um~p3ncrg&nbZB!FEWAOXaOmPLRRo|y4m1_l}f`%Yc} zw&Pa-`JPd}>R(Lif}Bp-+YFmOtgImY}0l_vkl-SeM4H|6fDg??hLLlSah z!wld(?P@0>!T=HCfffI0a(f+ubWUt%inJ61o3SB1QSVy;_gMpcbd4TSe}b9)6`209 zf$1+S>EF{f{^_~?QS4;1l{O+fr`~!T2?ZV^8ny$J8D6yyE6J+U9Hf#w5Ki-mD$o7z(bvu0G*=P@~8L8*KO%ajCTj=3m72o8l=%iq1R$htY zmz|yx*^&iu%CKsA;-$t$ShC&E-Zq%#$@c2{A?rcoQ%7`rU8drsVDO+l=X#KO||f z+=zBIi&z)Vo-%nrQK+Vu`%-|7;;4oo2TOh29C$sWpmLS zySKqv%LyhP=ASNF)w*~dEzBE4{`V0R2J zASV!GoCaM}d^ICfyW1&LQ)8})x%*<-&@=9Ij6iNdJn@Ls0I^M(Z0G{lxc8*QhH~Oz zg-%u%YN|PX59>>?G7s*0v)JD;-bG!A?XY0Ph>b$#vyi)XxpY9=q|*H-NZZeF-8etS z-`!n}Fm3MJG(tBr<)t|d&U*q>xEyZ&o-08U$;yBhhCBSU|Fk9Q33y6!7kwW&CMhXC z&$Civvur*fAmd5Oo#5i1D3qKa>m>uSBU4)QI$J2h)nFM|Jf9fAAyVnw9Be#3F6CZ~ zhg<9&T5QvIXzI~Y2OP!FU=T)`mYM~6Nrryw-h;K7RU-RwsxSzY0b&cACM-5|r<@{c zeuX$DX@BbPnR0C}c6aw)3<>&_ESABPApEgvp81-fL;eky4fn|goGR%(nJd`xOREd^ z!BXXFT&wIuN#)4`Lj!zB zPCwg0;oT5LlPbU9S;yECg%r)ioQt!0Z)hk_P$#(@Y zAa*P)2{NCLtlkNCU;SDKjm^wz$o$Gxn4($NGM44_T28n=T7!wX5PlEU0|f*S&W-W#P)vW(z>Y&-op7_R8J621ttx;P$B=EplN z-k0xbexiSLX5{UR;Nr!brK|4P`_1IT zexdLGuQtYFOId|<;b=C8{w^z5K3QS|6V zS%i8XKGO1Qt5n{)l`u+#quDLh>BhnLt;0tR^+|;ppA@>@q~neE`Z2{Fd{+Sj{)YUO zXQvk&2Qc;n+Gg}0&qoZ3hz>m79Cj@>Z@46sYCPQX!meq_Z4I{^+0|Dpt6B9q8DJob zF)BzZ;GNtyJ0!Ai^t6kjgujp}iRar<1qnhzZP}((Iaj0XYu?A}h{LAse}Z_jVMO+! zMX5+x^B{0Cn0mX`Ut}G(XJIk}QhcuxbW*Ut_yydIl#LPT9-$1rjM+jyZRcC_RR({R zxOsZYpq|O%0ZampFL3@f|wx zVd;X~dBKcNOep;?O*Ag`OgF}nIf$v4dG!Ryd=8AO6+*a6{ z{_ab`(JHzX^Xo6ZwZ461$*qh#NSZ!uSSao}MYD(iDk;pt>X_~tr%-{>tpkRKfaWpB z6Gj^kMJ3ngo|EAfo-a&pU8z)^J3|=V94ykSUy}H;3a^FtZ&BhL@y0>e2R+%A&*OeqJ0hyc35Vpfs^PC>gAZL6YM>0VHwZncoNsJ}$07?m|VIS7v^b zT+qz_5|gh_E3g3_fdT|=Oit)`Sz8AMM13AxW(;bPDs9Ba4YwiGDtDM%TG|zBkThQN zyd{YZ#MT#?h*C4xVK&sv(XcYBt3-TP4bYZL3k1K1*3fM6E{sg2EMyVIM;L!7Mkl#t zNAjrBx+XEvVeU-m0fWoI;?4(R1Bp9XTn5JH$Y?>=uU|I@|d$ zeTY1?VJ%!TdWLNn&H~5g(VNN>u zi^d%zlZPhl7^@uKk)&4h;&k>tcu}*ulZzteQB!NkU~+M^$ycM>-PGs9aXUS)NbZ_= zpT)`t-FmgnZMg|0Gfn_SILg!f!{_kC*Dpcr_y<7xl7e@_==2}M6N4R=K0I!{jitQT z61ORSV3{T1?r@&z@XKwO7)pg8Wt^4y4*1RVyXsb660>~%e#hJr)4#F4E$+>i6!OV)! z(x9dvrV>xrUwv8mQFo@NaqYCdn>yF`&=05~WF2I)4YP+!!+Tb&HP0p3lSR$xknif? z5&~^CZFlU$0_NQ>%e*+#r`@OTe=3?soi*~+a*mkfkCrzUmx_GEh%upq=sF!>%*=(E z#+fXI@qJn1L|5RP@^-|fl(u!0P@Ab>(6ilQ3Fi7_m=Pnuh}Jb;E+(ESpGWneBhmCq zHV#-wH!AmR%NX(2`)M_n5f0K$peRRQi`P ziwUlH8(mUM1;oX3p?v?#=A+Xv+W_p@hQ74pP``OKh(DovWblTz*m3GuD$TuE3)6T(8P1sQEQLQ4Y%&nU5fH=-m2}rCrN$%DHeVmgS}nQNX+5%98usYO$5e zx1mc5NA^v!dVYRrWd4ZN)n-)b93Z-}*3Jpk3l&g6iv64W2;l^7)UgO4s!2X+21un7 z&y(qYg7RTn0NJD{3?EMup~OKeaPw;?FY^RY>@r|{grpQ$Fz&ez z2yAwzFa_WHB2iUQp`=x;QZhX~mzTUKnBzz7L1&TNd)J8T{4yXf+1zOV3RM(Cy5eRnqJsxQ>%3zzZloA0hP7;rjoX2G@q5|ek=nyQP>Mo>zZK1 zc9DN!&s4H1lvgA5ZQTQ-|nd(v~<{RFIplD_`0f+^dgz0KQt+GKq&^-lh2HStFJJdkn*A;-*K#%Z*qE$zJ% zq&54@^EXEk0E;-K4KThUirI-ELSTysj&->ywUoEFP@Gu}UbK19LhB!gJN79{1u4>Q zB0eDEpcvy3+S`jX7-R>OV%NM<|QZ;_G-a>C4<562ai$6hp zq0{iX6*z&9sDuoXqV+dBNH@t*xpKBeM4Y4#89@K5wt$2HD zyOua+J=m37BGXqA)bOT#`Adj!38%NP3SpI!AFG4BIyp*bM06G>Q=E_8JKz{YKxS~L zH}vE(&EJh$o4Cp{DA*aKdDBzh$vs21X%26{ zOz3<_`}HZtB(BW6co1#SD{I8?@;bZ(;OAGC#rxr+@%QtI=9s$5;i%|(Nl;zu^lGO> z#jg2aqVD_Dc4>pi!Dk+H9XL(mPY|#q9;(PdsvW{VmV6Lw9M6$wbbC-b3sNunpoChZ z4rnZM&T;CxEJd&g^Yn&H~ z{t4Q3fU-e0S;6EC6)S3QbKX%YQgvorm#4cXhQwvVFc zuH|_o@|fxj3oj}gJ_wJ{_%PCs#2iaS0W`(hJ^(!_V?6?{EFSy_zYOT6E8^n-DGrx; zx3pua?)#UPg*}fg0E_mcbtCMMUx;*aj?P!Yp{zVG1`S2@j|DxD_7ZQkA z=PS^=j#+TrWhclnTLvl%*7o2)4fyuaBX5y5&?8x?r+@<1MJMR-1(zSrN5we6TBPga zb$)^#Wo7{KYaH#F6`qhjKnh?erYiyofjOh`qL8qkAUhpCli(XDqFBX7cGUJujxzf? z$A|SM_L(LbhRd#>7V=#uEDKUzybeF6wsOIGt9?0u##jkwJ*cj44GLk^zaoPvd@Job zv#dqgkoV(<8uzFnXI&DiGD_JcsN#rqA%@82J)e?9W !d6X=9Mv88=M;W0{v@=?6$jSBd`Haq3&9Ez6 zD2(Xif0srxy9X_P0HqJ@1Xm~L6AbWWuI9a2XQqM`F>Ql6T7&72Q4L;Y?`k7yu4Jh` zkjb;t6$M|>M~?YL61f*3F=W0P3_Rk=tNX0#?^Jl(GM;NOih}w)3Nmk)CYu6r_HZD6 z&|gVNotn>K>R1X0U=-^Ff+oTLAA9c|*JPWf4F^F{5D}yb5~K=VixsAlO!$) zf9eVwzPUSyK0aK)7XuF*2|IcqxlN_`+WuB5dCLF2+My_`a?9~C2jGrxuZ^>|ENlo>??(Oz( zx$4Iw`NF8_#SZoeZ_ZlS`?ClnIiefcpu@m9K zZ-i4XGG-G%r&? zm(0l3`{x)FSc>W@x4w-ipp3-8=|C%NO%hActj#7UL;QtxO-*+ctj4~YCR$cB+15(HRSTTIv+y%t@r=Gw+6 z?|gO7t45wi=XL0OW6oUTkj(Adz54vDXS=UF@eX_xa`G7TLYznO7!+b!hOnK^@VUg? zY`E~K4z%$4mWcs>7yq~T7^U!2;_YxI$_Ro@CTbi_p@S?ygTai_y|Tl5lZs;I3gemW z^{y{@cq*!xy&w41XT(+Cr;XNBgi%qsOBHX1|maefa4^ zcBr&v_&(p$I(5P%XZq`j#vf-5HpZGPKV=0Y>rTa1ZdUzR3Va!fHLZ)^Ld=$VM)_RJ z%7JlLr?eL9EGZ8s517EMb`r#%;WXM1R4=-JO|S3M;~mL)Dy;Bf_=S`<^f{*`o%|Eg zYstE61)ihKT4$g)SU;M|HIMU2@jnfJZ)kwe*E>bHt%vO=T{gVPljb1T?P?R|`yzWH-K z=Vgg<>Hq$H3dBJbI$LOTM!`AeoTQn(&(YMxjW6j%zmDMO8)#byLFAwn`4-H&k9t=d z6(F+-2oKb*3yusspDe$2aK2OF@Rr84?o#!`;3uiGtj&;InJ^&oYpt!HUojZmK)s+l zukGT@UBvSGl(}}NvRERc!h`s=&W~??4!+d&DeBx=!9nm7SX30k0ci3*G@8yeEbfLr zd)tzG;z`+^F)1#M)R-a_wYolz{?Bl~-)Az_;0f@p9{@@)n~$V(%lB0n6ccfDvl1*- z4WnN|N!5TRT>Vl*$pByQ4%`gglUPL%PBI>Ym@H-_D_L(PDk~Ce?Mr&^%1DUmpsaRK z%}}f{W8jPg?tRFd)GYY?M4G*R<TSTiE{JY*l zgyy{ZSZl+H-L^Lstrq4O3zN^2%Dt)OJ+aOa0xu3f4j6WkO7u6!}}mq?wH`weD2zzxFP8))?6{V_cyKw7cacN6S^z8 z=w#fpB7{~z%%)>X;2&}Hx{wOb%}Y)&qav@b%jUN=N=M#S2WM$%4`0i239hcfy9t z6Gm|wj3|8t*U?%CH4x}n7HsTSmrFz<&sH!poO&uyH)La%F6bmDllDzt<;R=&_(-Wh zfv1$wb{73RA5_D*UA{cNLuK&z6^QyRXw$+HXEU4IvK^_ymDqx2QBt%nGO1Ni7r;qO zIGU;j2$s)!f6!8tyslEiZ5YNH0N?mB?k(ryqmXYP(R2tf%vgO1Kgjt;MS}CJ=iA(x zF=*S7tHs2+M}|r(cgq7;V@q zU;`!}Pd)XMDtDk8q^iA_dU7zGC*tDWN|xLyt7^z!(t!uOvo7U4bd#QRk=}_}qS7rP2HT$G+&WT#kkDuo99B7M}bySp?sQ$%=6>+8+CWX~dQL!QT?3a@`T z-hb(`tOn4l@_+zMpX$HqhjvM>HR@2Qp9?WIT5$}@3iKsHsbDvOyzd*XitK9-J-TUx zsUUU&^2X}UqhC=G-yq>Fp;u6^=Ki?m6QZ;SJyf1VA8ooGgK~zT8LWrfnLx6?HGK>k zvqzF;lgX!1@7jNZWl+1y6VMZTz_V+@{`e*SVYdkuy%fD&fPY7&Ajq;t)4#7F&v^?B zOb-?LePWO&SoftkB@1*jT0uZ1ZZj}W121K>gvzB z0OL|8%&MxkEVav!de@DlW}!c~o02bTx-aO2)T?qVXi2yK;nBOK?{-vWm zRbke^tf71&FiU7au>^1@8bAioEsbb>Nf}1$-QPf9ALIc@macD#I{QD5{pWf3=X&^G zyDzfv7;<)@-p4N_r4pvd>LGWI>Z9@v$X%i&U{nsFw*Xrb#c}NP||QX zM)|4BOeqaLLd_j)dSiv>1)@#H*IPBwiBt~z@x%);Z>TPdQ{PZJX`-zXAC^x*sNrZ% zjadvi%5Z3PCVHN@U#;@}G%6M5OcWs9z)5PWyp8pGy9B_V7F(7Up3wfKVYLe^DCQz@B8l6alYgi0R?bC z{*ZEsw{QhJp_SIy6kXGCYKv9&t0%u*qO$H}ZcnEP>*T#|sAyZvv-wxLs8IJ&BoW=0 zah>F_H)u+X4m1T)B0&nCI0lgegDAm~Xzj+o`gr~)upJ=uAPQWrqczvk@n zEbZ@(*(dG}w`3>hv97`Q2h@$~>&k~Vh0*9_MSFYO8M~Z#e@$)||8HC0R1Ngc2&7W= zd3UVLt^BzlrwKaVYT-NqWNfkX;7ApYh$SrgJzqmQmp@}1zStOHWqMtJq44#0CsxLr z)15so#C?k#+Zywm%EJcVVT!e}yEa{rs_$98pW&TI7ALoz7Ndc{GKZTgx+87ZbqL<~ z$M-o=g1~Avw0&a{OXMQFJ_hL-m_^t>9+g0a?%Thsj~UVNIh4gQeqzN#JEDRNG3+WA zyz1uShYED&&3Sh3M;d;=oNW8^wn!(WF43OCO4tW5!dk+P3Y%9z8@gnyy_FnNWM*$9 z`77UJlB$s-bXRZc{*U%d<|bNZwhz=Xercy`lQ>(ra#Hpx{GCQ(eIF1%1F?Oa8<-Q( zd`sF~>IpfrQLy=|#wAC$pU#%ToH}7-_STD?Ti5RF)~cDxp4H>m4PS(v6|rQlWwOtI!cFznr|7keGW|o6s?nNx^H@*63r} zm`zMr4h&e=zF$kH((vgqvPhU(xxb%c&a|fsGb8%I`>FAvYcke%UuJu142H(I*enZ^n1}E|5VppXjPEJD zHIiPjbKPP0EiaQ7Cv*bvBJzueYNk^QpCZmI<*duyi3?q1CJ_;L~tUFU0Ivs{{i{0$b}i zRIg~snym7pP&!~a*^@eAx2K=%oAA9CPgI+ z>rtTqE-n|oNboM2`hMW}v`<>Lc&fLzA#Eh%!bCo^cDTS>w##%^=v3Ot)o=wu72X}V zV!)X^^?uOYNvxMk?2#{*4h`bvM}z4s!&_}an^_*z=e2mx`yj`i7jD6SfKMn1<1`G* zDFeeBEia45FDwBvg;>^amYg3KxQ0vfnQuv^7GI7`@_u&Z(NVixmIozTNWVPy$P z5@RG>)oi^(zC17#RAv7FT2Fhe(LHUMgC!wG&l%Sc0l^vIgcWHzr-9d#KRYi=K43t#~=|G zLjEzx!nBGKU=6JvSzShQLs~DKRp}oAD%dP6YX}B_;Yz9qYJ+k$DtR3ko~$U5DK}e` zk9ErR@mBt>SD!Gjb#MahZhyE=u$lh_dAd!w5)@7nUKpi($3miVQ@R^IMANXniCbRR zs}-N-jrA=r@VeL4xiz-O&r;HNQJ20Tx+^1k*uNnAIlw$J{TRzn$ypc8pNlahM#7{H zyx(N(TWk%EQbz5?epyvlRcnMATmME?UhnB?djIeyZ#a{oSQ^ebtp3I<hFju@kv=_!9-6u54C8qeCsnyx} zV*6Pw1yMfGSK6niL^olr#GCL@3?1U7iPB><{n+E3dSO?`liwyHzEtYGt7A^G4q#Sf zaTX+e5D4?DIi>EaY-E@^C(N0DLqj`1YoUJ<5c%9&pARDY1Iggv7qP>BtZ*}OVh9jO zoHuGQWIxJnMZF)Go-#HLSZsH3Roa&6DtiZVc1rB?u-cXUv@^VAtw9O@k7yps{M(gO z7=}Z2cis2oUk*LW?;-L4nKccXoTsf~k2$&bkRO6hP3CTs2VBVL4F zf6)OSICVNro0t7+sV{`cK$+szo^&d$OCd$mcQS%o%uwhzKmwE5La(%q7k4*dw@dUJ+H)9!ktu+MVr8!Ko%sqG1%&LiuS*e--Z*LMsO3IU9<)u~uO z7o`o&VLe0wI{;9u#@?wv29*S8AA^2m7fscX*N|T&Q6yPk8RA7CZ_a}W1CQ$51(Ioc zsE$z|qy$Au2C6EEEafQj`HH;?s}PDb&|2_`3JYr+3`pT)oafO*sx`=wuAs;M@9(i; z3}M)S1Brbz2aw!{61FKFalkdaVvkorb3X-B=YE_8+7Ckb}*gT5F1f|?TheGfyfM7zm9X|3BvBLnkk0NHoFCjE5ViqvMJAxzt z11Qb`zHp|KXfbBX9leS9W&jCe{77^G+)BnSQz%v!HQl>ha>zERp-r;YzXq!(}Xj(F|} zZ5m%#P`H?P#v|UXi8d>mv3(P0e`1H&v>E<1;7|Y~)v}g6XoF>MGr4vRb@Aj)A4l!D zwFlv^hRiHZ)-pxaHyU?Mxoj-%QUsWFD>8i@e=N021nw!*Q`p8xZ2XjWVo(y*5c*Iw zieLtCK~YEN3lUgaU~+3dMAV3imQ0GCt>4gxIuX_f1Q z-8KlD(j`dXo-@-bSF@y9m`9^odCbj)P|hb`j2Ba!ISdw*!YRW>RCAb6G=q})e41Ia z3LEZzbpHAg^ZViQb+NA8n(~vCNLlG;M)t5m@+hzDnG+!|nBzqr1xm-xbo*z<#if44 z45+g%rP0paUNwDz0v2;#eSkr^|IU?XRW%XU_)QFitFYzF>bz%9Gje@-?)0^Z$)5@} z{e~n5fI@L&FCqKO=%Y||XbtPy3&hSkiAf#{s4o9tm`#5CmfgTF!Uxbh3Fvp2{dE8z z{pA@?OoYBimOGO^qvqtuZ+@YVE-e9?_Piv-xhTTDE87zKK%q*n+zrz0`AZjC-mn6k zE=kAtT*_xVj~(-wnJ3j+PyJc1Zf(3dNi9QA$1zgq1c~=411idO1Xm)P*Ry4eUg&M^ zH*p>!-g$aF^O^H6stwDF{cxR0b%}W&E>ysKfF)6Ef3y`s^8Bh7D%xmlTXa@LuK(xXCCk9~69yODp$a%A79D`@+gJ7?#1TST|e zsZ$_@D^Z|x_M@#D@!XJ68=e=_F+Oj~lC$DgHik+L*R6=ch-L#4P{!yqrXnfp$4^=o zfj#hL|Ad;_lI`{4oq7d_Sn^^C=v9~aY_7KD7Q%<*fBp!8k5PuDS zozj^bH_+3+v~LI^?m}xTIQxl<6lly@32ZdsH*1$OjN-#Gwu)b(C&#QC4;NX3Na>E{ zOak6KbuVCW86x{^AN@TnI$%$N!S-u@?y7?0=ZH+y^m(&eB^|VtBOIvj{RB}=Gg)um zXk%2#=+k5cfRewhU>$vNr`sy0-kD*Xn(}cg@`ZAYtjs#NSZ-7J6Xgf;gtS&Njxh`- zV&j;-j(5N`?urlfhHld)M6RA!nY}JBgKRZ0ke?OlQBf`Xir;98S= z^S;4X;FhkGdZ5HLhm5#zUAG*qQJH2Mp#`yX4>(+*PtSQ53g2}JjZ27n_Bhs&|1g{| z_XXw@Mxk?^?}N@(#`07w^g;A7pG|dH9%Y1z^W8kyNQ;(Cz$nDDo~7dUgFZ&I0C<6a z8{$WxJ#YdP0Fy0f2qv+BTPat`AJO&*YWVmJW0`$~EXCfqLj0q;T%`+_UE$KJ(`r7s z@J&Wxk;|Rbka8p)MZ`;Z0pcf(4#qH6undx+NfPU|0i8ytuEeT^OL~f(p_}#6~)8|rhv#7+EzDu5Wp9mY(>|pgZ{)&7! z;;sw1J-D@BXzEr`QtYpj@^SH|Rz`?UUCEvSO)|;CC(RSzNm%fl7l(eY!g>VXYNrx7 zT@U~kWs0OZ5MYb;>*8!~`IPg4ezu>Au#5kUa|4h|@#&u0%dZo#ok^0;lUfBgi|`5=R2E})gjKa}31VrXw@m|`}aZi~Gw85bkZqM%URZ20Jd z+9frVKjj*XZmf}gZ58J;`)+r2$F9gJx2#g2+dk4%OH*-LssBnO(cXbnj4dvNr0_@>NPPZRnYPY1 zE9lAg$K5=99)jy2Oi9W)MBdE!q)E@`|#~?oT5X1%(0toVX8V$+8h(&!I z7$Aj#goUp$?{6H?@B~R-f_-;@Vn5=SSROzvy#Hj|K~EAqDSBJrqfH6QN7KeVls^d& z>Iok(l06cSLH7!witUgs=0nQ8z1RHd&Xx3{y(F|x{k!?|dp6T+D-G(s(1WRyz0o77(n0yMu1}6Z zq3#j{k*LjfCM@eg;B$igY~B0?{R`t$wuY};r>3+$o;TFoPJi}}V=|(`qA0u=$A6{_%L{mr+M;FaNPap%!jgnQrf z-fd^oQq>kr`)S^IHp>hz>s_(MZAXbPqhO}en#iYYH&n3s6FZHet{^U+#R z^X9cK8y;i|9{trppI!2n#`83%|J#Cs6D;J*nMLpUK64W9I(>WOA5$LH%s{))Phu6u zJNdybFCc^D&`ejaHb-(Dmaj)V(-XP*h@A1c%kzYMUzeTy3e8i!LijKg3#68j#d3jg zE|N$+_Lhan?L77DC*yZns}-FqY|Ly46al*R;p;a$x7ArO}HpK@k|u^G)Q(SeLij)Pw%L4QFQm~}5%17;JzD^DaQnq9eK1_3 zs%w#4$la3vqh}!YKpn;aq*h^s3y67VW_v_ACIYtJzX8zTb71U7mBXOo{maH%LWZ!) zNgv0Af!X+ptpKi5iWq{ZbGtcWo;{4jMC61?3#}WCZ5M32du2JCN}eM%s7&0Fs!$Vm zxi%O0;KCm3Q6JW5&d?95IR|~;$V#xKww_x*y$PGH(`{RkP;Ncfuk>w4u8!NqVzN+y zZD|C3oBc-eI)IWkVddl{_C>j3h|p2XYaBXtU}ygK(103|o%Qk6hg>l9@iyW1P!m z&cgFt%4A9|{`E8AXZ;S#w1lA4;~b2DJd7-iCl=7lxy7BKZNq68qv--cmliy(P{!o(?2Id;UQQ(xP9sq z(kijFGN$PmB*qouoUXHKCHiWh#l-wgM+^GXk(lwa^xXENEEdX+`59&Iw5ShgE95x1 z1zl>>x>_zq@0ahDVrH8=w(tA-WZQ@LI~jpz1bN>o($FqH`_>oHY_vXc1*K4EGMw^< z)&JPwgVD0)<^l2SI=b9?D*|UWcP-;wJdU=tSiD$!$=-H*Gb1`D;Q6mJ@0ZVThC8V; z)Sc~N)gsGfq8NkIIKRdn2)%mrq<{nla%u-KASiB8R#uY1an1IPg$a}hQGe~uz-V7B zKwrVQ=9HQA4!yr~@@VUst6m-XGh{X&!bxw(10t9R`#;oYb&3qepJS~>mfOc9L0I)Q zoxD-g6Jk}wTk(hS92hJyydk`D*=A90qlS2jBb744pFyyS668R^IsWfbe#>G4)go2=rA-x0ZXwkFO?wsHY_w6RwH#n}1m4;UBycm1+N>gGa~a18m@Ks(0ni zdHS3s-nTtXE0FjZ4k$qc@UMCtSf{YLaTNiAZ2LQp8)}Z%&@YOk4iDJ+c(R<{x2V%NnP=cg@T`Ob925R+Agivl(!{@Krbq8M#v4fSCS>X{{Y; z3hC!6?!PDmS~oa`5WCLJCE~O7gyjBBz4<&Pk-4O7<|3q2+YVpk`^kG{md@Po ztnbB^cF_tzZW9mGUzW)*&OUnJdw>X0X*mXQrzn}tYBqu2Bg+!~EPuUO9YV;Dxf4@4RGZi;{JXTU-+M=o{2F0SACNl`aF@)q_xy z0dPqxAuz=p3ok1(31{Voz|NrA_d4z$6b>Kiyso;N{e`!NF{bPA&q@#@uUu?;T;-*y`8Cx^VHOvVAmVs#d5NP zCkpv()1UI_99rn%9Z-;uD-LV2R`UDcyuHT;-@J$Jr@F5@B5rg9CLbVYSP%7xMu4`g z_c0-M{u1r%wfLNA(#?jl$cetpSPkv$NFQsR_@p%{fq6aYE-F=arzviL3vXxb4MJ^v z?(0E*t;wGIR_Fu%4sD9^17i)G$A`4h*p-$j`pH!Vr$Vp9#0O6-2u_>#=4gBlbX*1A zI_RH%6nT^LJK|G6ja(SGIho!I=NQ}8d9O^NXPkTTTBfC5c`yKaCpX2zCh-h6FeN{JHG75CRIJ#>zd6+*!6@h zafCYT_&H8iotGV3Mr<4qRRDkY5b|PgxV%3Q&Qv;BD6<~s?M#_Oe6rB!16gYb7R{(r znfRUQrpLYl%Vsss0uAO#L#ML~meCW$1h2gap!N%*F_zWr`CfR}I z)4i}sIU6VMPSZMd))g+~M{pHpL#l`}kXS3%?){Q-YgQwXEW7Dv2)|wW!byC>SZ9IV5`xlU&i)VXL&pl5+ zqpfOCtHA&Brr{cVpy=*Xl7ZT#n&pOA{1b8jT=5qY*jN*{@kxXL*}{2qvF|aH_p9oX zj~))S;T)=KV_ynrm4c^K3pr<<>FAJS$s+xdup*XEnMiBYjG&suj$@$LSf}$_psxc^ zS%V5XK%8q7Fp+5w-w>*-dG`(|15v&8#H>qgoNqBw&G4Z?fCw*9oOPw;^}D#tje#=l ze5pe~>`n%%m1Z+A#iRKi5S#S{9Cg#q-Cgqg8JXIUvKjMhMi<%@L2@!FvKtKjB$;u5 z1?9p6?6Y(yInC*QexxdPtDZ`wQDc+PPeeq(R~}fze#=s}fAr87Pu#HFxHu?j2li7) z3nH;b;R}LSFMci~$zZ3qtg0VXwU*GpIiH&kt`!Borkjh4JiUxog*?Oj)M-JKK4G8X zs~&;2!DU7rPo`~U^6!X0t+*Cb(NJ#kV&b{F1b>Omm2AA|5@Gq1Uv(xd~!pL zhl-t5;UAYheB5Brn<`&h@e3iBiw6iH|Lmx!hm^r$g2Idh&o_U$M)TXPIhQiK9d6(~ z>TMAV)3?YoXgSjZ^d^KL?o2)bOxWB;(;;w28Q2xgz{oabnUi;Qmj*!+-fOc!u2Dn7HwW)BQaWl+ zOn#2off8OzM>vKhHTyZWiAUWitI?Lnv+mLUc`#x=*!Ni=E>CR|2pU3L1d~`ZZwX<4F#L+jGtUa7hnnRst<<7+rL#b6n!g>`ZY~auD$M+U+1%8@ytq<&dWd zAVkkWP65sRAWwCO=rb_6AMEosez^%|DPE3Ob4DC`8|Ac$&FVczW6x7Pr)e{eQEE*< z{kj%9$q*5LrPfhIeed~jcJ{W96gGJmKMQ>9Xs>0d3@@(PCr9E_$DkUyzPafK-YCgs1#UTQ7hi#=D_xR6Se0qqq$em| z#Vkpi(D{lyoLS|a;{Wm;3v3i%+`&fZjxEGZpu+kEh9J_pF_K3}p|AwKdpfuYyDiPP z*!#un4OWLWOb_pfep%1ukBP&)Cr{NVf`NPp~6o(0D-(ysfbbPHi7NKpC;e;yWy=Lf95RIYq6J@%%#vt%_bpAlw7fV3r6+t4sY#w zc^U+Lx16ddQ?5@v2o_BrN&Nbo`q&=@9}t}ZW25|>;M}VRh}wj;OY(bi#{EV_i~P%J zE@SSEV;eQf2p`)b)Fz$%Oauq!=$FlgU|B3g2yGoj5E2T&V%icgY!F)pOC|RO;}!M+ z)AupvvZK2mIHeff5N8|1!vL)>p;H?#=vwy^LdC+ELh>x0>|g4$yno#=qz$Mzb)Ch8 zsnCtU!CuE8-6(?}6~Xu93h!GyiFc9BoxQkxIb12OKvGi4~0wSXXq*=!1+ zvTbKBRuk;9r)0acLw|a?WZmw7tsjE*Ikui2Hsl|ahW;`Mytz(yLvNe^XZN-c+zQ@- zz}_!Z#CzdPNl+k)U?kk7@Uo=d!V}vg!ltt{U#;!T+kec~w3e(^W&P>UJq^tTaunlm z^}D+(U$*)zPoA^|fEnZemf3gzs+NR5`m=HkEc>6;bkx7vCWa%5f(cWtgl_->e{k-6 z=Kr0EN4?vx4$$_0GT<-$NP?8Ui6MK`01d6}P(MNm_n^3ywPTRf^k=MuD!?Ws75~vo z{JjvlKYLwN;0Ai}7$l82I;;XdnYHf#lztr1O##&V`@7CS`ALs0AVf1bi(`j zqJNF4$3@|5P_?TKZ-M2Z`md|&ANlw7j4U=GWdTLE2EQvnz_#(cgKQOzn22by z+!9-H{wdLEihM`1nn%1%7xIk}D6=rp=zLdK!6)`*Ncm1Mn|dclL=?_w)Zmbedp1kr zCx2BE#EA|c%2o}HPn%yqRMW>;*Fg!ajb~H}Ty;ID@gAX9vi}61{TFJ6Hih&Y5T4v# zh$6D>Bgg^?Xj#NF=pj?ZF^EXdNM^bOkA?m91B_Hv1~WrNRsWdn`tP{CsKR>;>I$5P z5^11-;vfhWkA4O|WKq&Q23cM~?`fgF!vDqrM#6v_hDxQdlZ1S00N8FU{r|ML{g-hd zM$Pa`fbAd#QR;Mn-Diku_;aE2cbp#aT_Yk^nY)azezXP$8j7+K?DpsW1`$U4jxq>2 z2j?Rh5;XI@#O9#k!dSUr6wh?wzK>^u@Z(SeJ3h%KL)*4cx`gnp%`O3O&o;pmxj6?k zdA{Ux3<{WbCD|YFgl@Dhd>x3oD(-y8M&Uth9RviK8%9^ikpwZ=V#u6}9guU!Ibq0E z_=ZPB9nZwYl}$6)#vxS5liZ(}%X)NycnRKzD3@p|v}(JU*ntR>gDaN}Z$9(yzn{E@ z$BTJKA8@uM7MO4pJ$iZN>^bAqYbyB6a@5DM{Bzn9Gr>vv@63MyUw9?ue}bj?pZ*#C z$tpv45XlfSY!a9nQJPGRXa09g)L$}N{}b+`{VVeZsR7ZVz3V(A3Ugk`4Dx-aGUM7p zf1eLbKzKcnABXxuM>--$%Hz-xKljJkfu09<$tQCTfC%6pO4t5d<)={#rs`B`jBPsW zNXf36yQeeKE*cCzq-$J7g+m;pk3lSK?+|Me02CmYQ$-E*A!#zrUvE5#U9J+DI(i># z<<@o}r5dTXZf@VrM$TPO;Yk~c3O$Z!uF-M*DPb-&cmLQbKp1bu3}NGD9fkX2I&(gqcv|{-oExW z;1$qZ`f|<(aK>Y!mK&6QXeCdz%0Ql1+v*1SS*&S|Dr8pn%j)4{G`1I9VMAu&fM7lI zjzPFk*eBm1b(lENRIY?*h!{` zBWAY&5^sU!wcmj*E4GRx*|}+Q3{pP@G@x8Vke)>mtfMB%D4}P;1jS*XT%eu%pP%xd z=kkB-y1arZli0L>rnC;_5h#!!=c)N}!ex??IgfN-jBkgC|4z8iFjHlz(vW+5S5f-G z%LlBNbd*bow-`M{PjY{P`#pdP!lcQC^_=tFnS(GWBZ>b_*oRCLuy0(%5ZMmYrU&#U zCN7SRzU*1MblUpqY2L;2KA|a~wLhBZEYBDW*}3eMNNHvVI%Hm6UvmB#L{VpC0?6*W z5@cqvHRNA^e5CsrG-LE_8BjW&K{^4E(f-PZKemOezaO2neU~87irzs0W@pR}vDY)Q zTmOhMCxKk-*StzmpwuG20#Aou^!54&)!YA@hxlLqe*f&NF9ASr!iQPFy6ZzzQbayM zEdRTb<3HXY|C!r}zcS{N8s~$T17eFwpe$|+0D!WxQ9n$95G(=^^LyaX#Aw8?Rk1y` zlqn!|_={=s-#y-ha=<46TVo5wbAXTdOo=Lu*U6QL#alnn8`l9{S^4NJJc`5yWa{#> z5F(o!g3KSDu2P3dA(5{wcwFR$QlDqN2#^!O1w?L7hCW zaI0zy^Pq#rV}XG9cE2#LaPaew$E(A5i zszIgw84lIqPWd@nWVT7I^O5xPvWH^X>v4!}9I`$;j+S?OO=Y*LvZ~Bq(M&7m^fUeF z&WrEv7|fo0@D_9ll=tQ9pW$u)k1#&!WlT7xjJ*~3x*kKA&$YIVe7s5fipEX5;KAh^ z6)$M(xNmO!oCUhk?#}B03(&@y6VdXSP>&*qa~jSpg+x1My}qSOz3*e#DHfi4lPcgc z`8f&*9c|J6cnAlHUOAPCj}UOrsCv-p9M!IBuWH{hNNJhcZiCAnaqcwjBkt(Fi+%KB zSzoNJ`vPvK-tT293hdyF=c~y%|{! z;K{^lIbZF-pE^U6VjPrZxbti z(qUkhepD2vuJ?s*@tBDe=hB9+CrTeCER6t4;{ z&4_>hIAHHHs@+_Zaz<+29E7kV$r6gOFZKNg=p$5gBxV?E;RDWYTLH>#4w@Ek3?*8i z6KH$@IZj2`gv3rRYM;sYWFDs_f0wrCfW&7a$Old7x25q-d|_2Z7le9%Wq$1v5%+@@9%ZTvk_8e z=Uj$*6!zbfj;#8>`{v`Unt_o`wgAT~5sIq!T!=a^7o$5;7V`o0pbor$JvT`RClQtov~&xsDK(&-fRum}f0n51Q62f@ti5q6 zv1ZH4HgEQ|yFSg0AG|tnbKmIJ$oty3po?=bg`BYjfHl2)&}`+rA|Vn zMZ56x?lhWTR-o0q&x6*s=?ovbVSi zz`2;m#`keSn`M9;pDhp|EBpX-=nps>;?JVH_+`XN^kSqJBc(kJd<@c>N8QVK3;3zu zn5;jUWV(w8NA76BT!4n=GbjLtiy2$)-vC$(K3O#I4wk?>@S_Hu|K>4Yf6-1nexR=P zdn_G%0zP&G#4aI9R9z7+iUsGiJ{ab|&K*as% z?-io`_PW$NRr8lV5Y&iPKVK%??iwQLDzRVtWGVa7x^U&Yg5Rr)dQK29I)4s5*{vQF zL832c-}xrK!W9JF^UiW7g(VYXa(?3u|8Q!!gWAA{=j(y<`!o#b1$2IYr)uLiaI%Af z0oke`J0*m5U+-@nu?A4R+hWVE&w%!{{Z+vAJlgI0lcn}MWZ>X4jC~Gs2&qP_m!prY zUmnhg9D`mZ_V3taB_J*#%=JcqXQLTZ>VLm9{`vo(Zk7M+`5@&GfNdrGal!fMXcWEo z3Wc_xl?Vdwc&E$$HZl`f{F-z`JlbmxbHD*i$!5aU1mThZ>}QMn@*lB)v@7YrQW386 z1P&=e>`mD3@u8J}-&+!!gkI<$q1e>v%v$&Xgyap&KY9gVgZyKfY5rby0JOkiF9nED z(!eojeHjBtWa55+i{l=s^ZvIIt4rm31mNukF5QJS63tZG)3l!@Fhlf@k+)d+o>ntZh6PoIPg*zsv8}03}U8;BAT@+BCB8q zIH&D_soYyPoeUT01F?pu3~~0v73g$~zB~}U$XUrSGvnGx zm~WiJ+PvFCobb|A#~KAK+_0-<4XjLinY(@3G0S+kn{v-1p_Ej$#*A1g`747Jt0;O>0a40xFvG3?SGD@$}0^7QlH}LqP3w@>wxrTzw25%=^y+PuJl4ev zw6v8%oi(2rN1?$g=Y|?D6WH5$s7HW}+IG=;CPm6hkZnyU3J{Lj$vN@7qdQE&3z3sa z>ckr)=@HW9`G&i#kB8lLogB4#bG>s|-?g5-ktZd312LW8aE01K(j~SDcH_6Vr}RP3 zJ3H>Bz1Y^rI&QX}9$x<-I>GJ~u&J+9l6efOl1Rv^VLhUDbanQ2W}QyWQ@W7Z%~DeA z=H?P_{ZxxL;DaWOKF#ohCvt85!4}+v2eaa?^TJ_5J8lhh16w)GT#Nj{^Y^gN6K<7! z+WK}91b0C+--AP-wkjM$Xd4JseIkz_t~vbW4KwQ;T?K8W>dj#Z#qAed*Cp@0?9t#h z8bg;FHF1H*hi1RW&Spke*0@2+W!B@GcilOMo%N>|0&lgY1?&Fo<)*k$T9CkiJEAts z3n#Z3gu4%xr5C@Ymeq1-8=3i-hG}b^4S>e^yNF91m%2uX_Nw4;Agm=Jw>PPeK~NPT zK>4)iPE>~e#e4tILg@Fw$$$BOm?aU|c3puPh@Vdpze4PR8B4zp)rQRcjv!bwiq^_o zz_ptI7H}_8bgyR@;*Z(URH6mKt$$%XbM%`4$MR?DqQ5ii$>>+HeW=1fOKAj(Q4`RQ z?00$rm2>Ru55)RB07z-u@5`3|>1Q&EAR!1t8SsASnSFFvx?oA&a5?$>#MR15MU{ce z^);a*vWMXz{~vqr9njRbt&0XxkS@||kRl>Y0i{YnqzOn-L26V)niv&nQX(iIy$J{^ zMVg2Z=|~G5rAQSdw1g&|L@)$Wywh{uK5zei`@D1aId{Kz%iDhiafP+kTx-rb#`wPR zeeD;SJ}r8r}C4Jc??LRk;`1eSVsc(2^keQUo5b&jjH4SE|Bk#wuAcBU;$ z$lf_VVfJII^!9j^^Wcvki08shPEuLK-)8B!4;_vP6|Lk&_ zO-9faQZ;t#2~8MrgjBPDdU4UtPCw#f!*ka4C?*jl)zimpB&3tF$XCD0Jv39;w)-k| z#P*x6e1Avjuv)IwX7{%f$I&M!9JmcnVi#$k*uS^4Uq$rjP=-zotBu!3=LOp?LxaQv z+Zx;B{BkdTK6u}-cJ5?Tgqx*Ov>K)ib6{MN+$11MBeh) zhly(#1Mx6GzV8-P)On|Nph|XQ8FymXp=vH^@gm@b9}l^WY!{;VfIKRagLY^Z84kq* zXh8(IoC~H|sNXCOUii>@=F7RL2ADDo7e~_od7d6fj}L62+Y(65$awUQ1rG2i8n*DL z5seeX`|EtJORkjD=x+G_34s1#9d}8VfIWa9jMJipVI;m_8qdC~zUY^8Ve6DWKn+kO ztpQ}89ZF$o2E7)4J_XuzId7u-gJX6^_MfiH@Q>%PS$WMJs77R|+*YRX&(5Q$+-gX? z0-5rgeelOqP?g^#xQe#={yleYxjz3*VW4l|k2jk4hcn3Te2G5yD)7+6UdA8qllxC2 z8@p|cwKvIy=rbBh|$4AXTz8 z?F+^)c1IKajK*HgJ9A=qUR6~VGD*!nsONo`W$dBl^BdczgxEtIn+DcX2wC6f(Ctef z#tXL_b#Y_yV?PYk1D`oS#eIL?X72gka11erO8)ZT#gNlXLi<M#5SCH#N=)25C1*L>jS>;a(U z*#)X|NwOVCpl$I(gTevolTC0?pL9_IUbW@*Rw zsTuOKQ2a@9dTSN~9?{;!3}q$p>6Z^ae9I)`dEv$={%t|A?uxu(p#n z@Q77&wYr+|T-MOn#|N)3@+A!%cntGeRlgbSj}b_^71wHQ033l=4{IIq{M5`4bO#Ub z9*C^>OK24E5stbqDE~7H@A{zu!Fo0*gqHT6_C&`~>-J!-Qu-hqw^VJ8`4n@qZ!HAf{zc3vwz2lY=hAy^r#R2#*F~h6x#r%yOJk3J~cm# z<;L4HzKacMv($k;&1MFw78+Y^9FduP?MUVz=7t2b!P2AC{HvEEGcVcMW((fc`kXH> zL7eIqw#h}dk2ZpQ^@8@+FUW5(+aERP+ip1=OTe0D!+DM)99{+MfW>O~h29=VG`cGk zOJYts8gqT4qAl!e81!pWvwN;fsK+T?^4GH2amQD7rK34RL`cYPjkG8qTyLpIm*&TZ zB~yFEc&cU86-hrUOJgf03xDWy=)Y6Z`Dg9skBioSvUUT{g!3U?QInIMu%l--khpklzNmTdhBc6Xb88UF?u7D1=0RpcDa4od$}`OIjnwexQD!i3c4d;pSH; zx3akKBM$cyDqa>#k4(EHoHp3IwkZ%GGEglBgP(X)2an3;q)6anS~3SZkRnbjY+QP^ zs(e=S-lFI8@1ukkQYWm=(4?ld-k7x2zz$=RHVt*#;OPrOTzPb zUFfE13dBwzx8rhf%RAESeu3$MXo?iIsnL+^K^tgRHy61UboFB`o-wAnc%usE%>2f! z_%XqLN;B-3# zQw>b9_f=xl+t^Y93}qR0?dQlTOP=^ZZTY<<;WRI-XO zPl0*;B5P7uZdUm=GMrD}nM0jW0g&4V3UnWTi!}Yvle!{POR{%9c24zxLOr?K3s9+nEv3k;Bmv%b^l`(rQbR%kwJe^SHUQ*T~~A^_o`g@B4_ zbk3(-NAj$xVjArI$8JBJ`Lg|@aq%WjHKp3v@<%L(F1+|FWti46%K)@mMKKhebZlg& zCj3xqk>{I98{63YSvX{&kH>2P;@qsOzHm==6G3u8k!0Xh;j590uwRg4!}LFgqw!l4 zYprNL3KM>YgM)$~JatkfC^?!-c-(7Wcv~CX?4XW`IRC=A={Z+}NT~L_>49cWQVE%T z1;+IY;sIp|8By}DnZHzzAKlmQCZ7M6KQwhV1@lCuOW04+iJY_6GV|5pT@1h53Y?zKlQ^h6HUK}p4G<~u~do$bu}L%DCCm8XkXw} zhJcvB7-U82m^m?`g`6u9QZIcUxtTepxu$kk;$?qr?A(QqEt3OIx}A`ajiKKSlGj8} z5)4AI32Yu&rwCWqANeNa*_j0f`zZM89b|U=HZO@~ha604Irz$E-X*d#dr}ebK?&?{ zXCc*RNhbJg(~q9IrR8p@EdfLKHw>;X-C1vj=EaM(IvIEs#DtPv^h3@~BU{yw?(*{N zr8op8rIVvnY({(d42yq$;)C1*GppMyS?tasnm`<@wgZWYA<{^P<`tQNUt(=ZC)A4s5z$Oqqti-ol9o*jdicek7Lezs!qSK*SY=xLRRS4p$#>oa10$6zcCu~}d* zAXE|uNE2i;Aox_YK2Er7L9kB76m+CvQe!zMR(Lf6FZx!+4<>%l$v0eLoAFlMq_p+e zo@Lw#)DQ9^D+EbVi$jD~GZ)7_*>Ru12?Qe};tP_zfc?Or)J<#jHxDo_M5Yv!?xK8DolEbPhE8~n` zQl5Fwi9u_Q4S)(s0x{sT@O{?m6=Wrxl89nJemjHQIg6^rEf<6%`e~7=akOKbDj;7g z68oQ#ZT%z8>4P0#f~^BxP2lr;orG$sM{e$rw>D(`bA?ZKy;s1_f0b~|+2>k=7xC=9 z#+mOK9Rl1KUqJL5xltz9C4=*jp2!@eiNnm@-b7Qd#I}Dx0>{yV_!}lh^MSwNYwX5@ zM(+CwKZl?~FOUM^z)l3$_SYCsNWe1sM<8%az7<1R%B zs9wFK#S|3LxHAWSLBz(_zjD(N7}sCoU5WW5$M>G;*-)B9`@Ag6q}yD1Mf{H~i&J09 zm|pfbgz+XU_N-gzxk|>pX`Tf%K3Qz`Bp(qr26G?aqiBrD`IrdFE4KUbaeDghMz|yg zvP6mb@^*3G>8+7=P!`(@Wj#GGGit#&w;PAVzD5erIQ@Ho!F>fs+^zCM8RKU4^`4q_ ziLag={N|=G_X~0xE6qRMxcDxeI7{In4%6przmm$Rvq#Ie$FDMyJ!Z_QJ0DS))f4o1 zAks^H0`r)~2z8##I!-NVbh~rMt7o&?{>2u;S~+fLQtz&IyH_2%qlx!tL)1591ZW_j zh~U#(GZBv)8H);E=B?ackC0k?ouDWg9}sZsPG$K*ieoHAD z)LJd6xnT3IECJHX9Ctfn)yUbrVmnWb_ck`S=PXqUZTZYu7Z>R!rPCI+;gv8J6(~Q+ z88;hAfe{#O;YUdEZCz?-M9g##toi_{ms6}$*YAq)cFobLmC^pk_+fuWy=CV)CS7S4 z;=dqMXF}@67yQ6(0gRojN!x%Z(E%q%@K%@s*w0GNf|= zKaB}th&T2@g=f}{89n1olDoz9-Si!uWUHKo(ezV~b$>ha>o5a~G|r2$g(fgef#N*X z)>YyJhlPY>-6D8Th*>;q{!X79AT9aBGY6H0zKz5vw?eDX?eehh5blprhz`rnQuiCJ z*=Eg?@dSr@G?AssG709=?te?>lf=tdipNWp8F9owb(f&JcBE zt4^~t2gZBOFANM&!V~2(R1jv}FH5qiTHCAX`G=D3#fCy%-XyI`2jcm+jddVs@e>x}2ZEn7>-cYNNZ~IVQ*&r6q?fqcMHT8kCRY1Cy$PhB zqt~g6?9hmtOSl9^aidiUjGJd4=@ z`3?{59b#W!hzCD37h1#EU4oeC#VS5)K9>LNOhgP>^?VdQXxeIBsm(Ww|2+MrwP}eP zV~vV5CKR6cI}Y07Pw|?2HbrWfyAXx)uo_6wzm_9bJM$+8544ColtrNyXjfaY2%Fa*zt{Maf29P56&Zp zu7XyuWyty=hz1%Oq8u^+tCntoVl?5@BG|1G6Laosr1poI00`fV=2N<;_l4D5QeFjd za_{Znr%H)(#{wn$pPNfJyu9RFg`OG>#AjfXqe)yuCTax=?Xkr|iqdjtPbu)PJwM7s z8yGQp^SPk!-HlgZg8_!Og2#&R_is#?BJev#E4zKZns!G&WT*yfFJ+&;$Ir^%C~l8*>9y=C{`mzL6hk z>ElyBCK+48*_QlqRhG!`m{~S+RLdQ^Aq^j)$h=#tcS)-)VK^)3)wyum$?@sI+9Z0l zWXGJNzA`Ng^>z^1AHax<4lF{hzg4ln&1LU<56k{+LxX={bD%$bkrgm%JjlU{&WT4b zu7QwF2bvDU+d%nOorI|A@+$Hg)^S0WbDnG(+wKycaD7GV(k0qGJ9W{^Xp>9>u(U3hRRoIcrVCP1?LawYvM<}LJ1a}2xKIHQmgoB&q~8H88twr67u;D;UjS54LeC<5=| zthyY}&BrYq%uSoolY9`ebXnM?X5&syJM+GFvpY2p?FoGXm{|;=qQwLb3-@Z-a$0Ea z3iw?dDDQdRrJ?2)%g31j`+jQ&?hN>MTkZ%Oy3qb0O0K9nS*tvC=!kL^!x?sb_3eM4ft$Y zq&Wu?J2nnXPlj$Y<_;OXFUx%%cKDM-qHY0@fZ%C&qF9jJ3unxVR<-2^OYfHEyA_57 zU&N?8C$S4S3hMN<;B^HU9&2XG4#04CDbm0hbfkTjbOs<{^HqOyQum3_fA?ZM%Z93_ zxjL-%tnjp4&*F(nC6*ZV;W_c%QO4Mc1wVngL}Azet_IfMt&=6oVoflNc*rCX>G*a1 z;e?dcQ0a8vJ>|F9RQ8snthov#?pBZ%xRE?i>}m}MixS`E>zW#PH0DYwNn*~|N|zIp zXlN1gmF*D+MJ^#Sdq>3$O*&Qk3o^IXiF8X4A}L-41r{@y$@oq~Z*g7?XDcF*wc;b+ zsg!D-7-5JxJ#fE*9`=_dMw3w31O=gUH+~AKw2+S%vW@zSKyHg)q5oh*k7@phx7o_Q%;EHG~d<~vCdi5H|G=j~4pe;+Oii`-a_B6XBMu({E zDf^uDB|Ctl65?5iY9X^3S`3%XqlY(dSAKl9q+YtmNWZCn@ z^nD;j_upflDVuzpN3Ja7&kmp;UZnr&8@-1B2cg?JxB`4J^X9nTnig4Kt=bX&ea7*}40TnPDM!|4ITUqL6-j=A=QDRRWP-XApKS~*>jeQ&4^ z*b8R15rDT~_Iy#?9Vz@c0CgT~OTsywP^n%4Z}so{@RZaF^*36-g}Qw{v~Hqz4$0a^(4^%)z=?asvs_?(NdCw_2_D#_lr)m?D&tE6i0Y1f*T0l(=Oy{kR#I z!wuyu&AD1NP4^T-?S}MEF_T8hRqUk!;yT6geJZrj6c3qiAQz%!Z;dbeADaGA{Y9`1)mR`*seU;!l@g2 z!7`c2><4r%{~NRrP*9)~Yc%eymJ>mUGW!50Nm9hkudXw7$s(t(P{W{JpZe9eGVX+31S5jES8q`LpOO*Vp6Y=z{ zTv4fm^cl(b>pu4RV;I-txUX@1nt?&KI$YN+~qJf#DyjEU&}V zkgi*#FYbl7TZRgyl=4{)zRIkoOPD`KvrNBLX5M7oCGAf$taKZ}R?X1MwYAIW)a zxcn2e_AMf!k=Sfx6~{9zlXq)r$ZABKocz|7^v8%ny+>^`>JAkhtdBZQCq51ra@KFb zUAd<<3)ppGS1DHr+QkKHSyI#jif)OAop5tVdO&c&w8PZ3J^^T7O`4f|7T?sf$;9HG z;#CIN?Y9NjVG_W-YAUoZd~``TYNGX0g3)6$^^0cc<8#T;*AE^z6~KU&)mB2bDy#H@?u5@Eadjc2 z&bFbrwURH55wmW73#f1n2;G=bFXcUdX$O8*iJkY1u+8dgZo0igUSxUD6IRUvdU3We z&`Xsgr>h*UHFcy zo6aI@l&*Mm#txO4vvH^$OIM3fCwE0dz>;+uELk{G0UptjCDb$wb3=1xvo8xiSKY#` z2?@mr$>tkBt!M#NTaW$&`IIPS`Uuts?4Ca#{NF<3|N25p)0pW2;=e_Y9A^RGm%yRm zPB?JlXw@+i+zS1SJ*)^I8Z}u^eJ@EcNi5yxGvikOV7ot_u592sdnFaY zwcPR~j6D~Th}^0-|IP;D#?FV|k~vWVQ3f?}mS}A8Z9dUlM+s77+*VYzE$6 z5Q<}vVGb$1Jt<_$f)sCN{aGbR?&)lG$IWp@Ll7a3-<{Z{IiUmNtG8d7OUbc5ha*2{ zMc8G&e@Ux`*)5lG(0Gg5IrfEipcH{gB%x<^NXrtJ%_Y~5>v!tD%DZ@>t7}O!Ng!xr zda=^$3%l|-1N!L0rBsY|Lxxb5rM^yEboW@JUXK6WX$6XY@x;nKBbuE_;C+#L<-|*a z!%AV_4$ha+l_CCgmg-Ahj>ps`{hr$}0uzkOxJWA7J_n6;15H|l;;Xg!k%P0KM34Of z6m{b-6R*NjBb7G6!N&?Ix_I8oK;D=6{wYSyjjxh;nyM*W7Z-J%t2ujxA;vAs%8tRN zZ|3t8rGvwwPYS(!8K@a>cXQE5EL70gB`HkO?TK7pH{=98Xjv{6IKu-*vu%_F!Wg{} z5a2w~M9|a?De~qK&>huf7)iMXgutmq6~&bI4!s{|EFGYK`oHJMzxnp>gVoc$8{gzb zUn`1|4jltl6wAwcva+mUhp}NAg2|QqmiqTWu+FIsU9m}C!4ySRd1}5Dy7j^Qt$nAQ z*Yc+?0_NpBmNDsVPcind#gnmIdR?lX>uJ{<+@2cToAfh8>VsPy)B+S73Q~t_l*(#<&k0E^?dS+RAdxC3t zqtYPi+0WOoi>h?7;`^(z&SIu_Czq5qyA1A+h<`x;&1p)mEPWm3Q_}2_1w$ELjBlq! zP{Gq>@SUYRNFdo|v%;1UgGjt9Ky$lg$S1RV+B5uMqT0tPrUbB+0SdfoJ>ID)uz;&< zM%j?{Y3s3Vj@j_q3qa{x>da;q9Tlx*cw=#bVmO%lRh*wKurRyQfo?ie`nWX0$;r*X2H9oCv5Vdo+5Xee6^5X zYM*~p?iRH`fz9OXvl$0L=rggJ<`l@aRoJqhW&-|g;?qPhfzCeK)u6epVYKMT=Yt$c zUW@Ixfg@9Ap8FqY+o8T2ccbydJI-7Kbq^PgCVx_v(As&pG!2Pof8mUL4Q+mI^BwjW zhS(5a>#ZcE<`_F4Yw?^uu{ZerYffUMK6Je?64N|}H|#`4!Z~qV{)+I5(b>C8p-`6| z4x2EuinqHb5BaObqB-?QNh4^zGM-#mc(&I6P#wy){a@=)q(9W5M9&f0=Zo5BC%(5b z&T(`!l*BknZ`}KqTU{HN;WT%z?-{3ti)Fkq#JTJqN7pR=C$Ku>qancuh5L7U1%HF- zih4teXx(WFX&b*>kysq)`N?XI_v8a6V|tm^gIc zmOc+X-o;YFe>{2&wjqDR_k4V~v*X)5W=LD;H!J#|s@SbA4tk0&o-MKi73p``aXB-l zU)WrW199>*LPB4>>Mq?OTXWMVqg-$i&sqExh^c4T=- z-z-m%9$$pYt*?fWsLew^R)}+JUu09HGr2-2+YRaikFML1gvh?M0d$pO92)0D(QF>g zw(~Sb9hIGAk{_CTB81;_nWA@P6cCXupyr_OK*O>t&*tT?K)Df!+@`Ud zh~tO*`cCC7snM$wI|H&QTq*6Mf*+{K&7%Hc-NxlLUls2t>i6$h4;A#ylh1#TlDf)1 zAG#a0EDQX5+_PEzJ)KAb^K1Ry#^s}T0o>2DR)I0`^Ag@dh?PIzjCyTs(DNi!Y=Pq< zWKWMKiY5aPbASe(Sy=k-bk`M3u&{!V?)uJkUmH>J(W+dDLtJooRdF$MsPg%WRMGrc zc8U$yYYz615cus5c!gnPwIi}^U!f>ap`e6G0ii+;jCv(C6`h-P;kFutE~SMZRo!Sy zRsqaW)!~AnMsxgHyN&ONjFpXPZP={=|L@^Puf3$^`)Kb}(+@XF%qudH$U4;on=qe1 zd2hoe$3drWm(q`DYdl^ynktI8+>><}z$TPq<3Z=~1MhkIIB=T5GWQ33C zev)`w$k-YJ19$$M){ADNc$ShFJ2cYD_EC{rt|O@Mnhd!lss73ri~7E@4W4023?s2& z22Ar{ZC(2XsZgWZ1Jt9 zdt|M?=TgSgpVU^Io{*)3PLklo04`wh5ixAtKlF8a;OS0=YgVw*7}%aR5-S_3Trys~ zO1@;A&nS)K0KT8=0ds5Ls^;fq9-2fgT+0*e%J%W%l)J}rNy1+OZk?IDl zDQ#^r+UG|rIp)5X_KL;PViiNgjIS89^2~N*cQ&RQ>$*OBCmUbccs_0ab%&ErS;Fmz zHLE()M1dRTb?qvwv-{^7P)Z zZmFvY8Da;a@sbY-A4ThMxa;q!EkupZ(}s)hJ=$r9*+^COv+qK1!b@7==CV~J^5A}>wrp87vAF1M;t zo}9jzB;R52q=q5d+H8fNGgYdl*y`FS2L=#S{VUHCww~@Fgh)5Neeyktynrm(c~L;V zEYH^Y=6iaXlkF#U#P9~5`KT<|E&qiWq65h^x!3^Yf2tSMZajJ7$|(}8+aJs%8Ff^p z;==_U+l+V!eX{X6NFn_)Dw+b~(?hJ(ByG{v6t_%Ng4a)$W&Zr~W#YI-vaC$2XmF!B zgDy7oxV{gP8R?ZU5jk&A!WT(lnJ`zY*^1#UEz9|r>h^Y(krw5(BhKj-StcgWkLoK+)vHHIo)<7}P-V|RohMx;8&Qsu z#&KqPUD@o7HZI5lcSuc<pzG=liMJP>V&vk!ZrN8fzN9O#j>hhn1`;ihZ~ zZ+5HD?VjP8Lvz90P+>?$$}#78^fOU~k(~{pt8p$Px8wRpX7k?qcwQ^*NWN5XO=PIp z;;`gn-7-aN(MAGUgEpwqm?cbdo%^(P=53xky7KPE_wsuG5vfecy10X_I=zQuQiVSp zc&wfECVH{ac|L)GqBU4ZP>uiDz`?O{O4vA{*ul{2@J%LW!Sgu{*EcNF&V}Z%7e2r~b**%;3Gj532cl$M}&K0a6E^VyaUyE<)6Debd0s_W>vY!*k-fDtJrSLAq? z(VP0@RqTWbi)pL#w*02G%&4X?!)fgH03!r?ap$^g~e;~*eC|ug``hcEHsjJQ2j6w(0B#71?DUsHuomAszCL1VrTEJ3@SR7uKYxn<1rdV_QVmwl|qcG+2@ zQXhoZU4ECKRu*H)LZy3OB+ltb?D%1KTN1*N2eeLm0RTM&S~Z*#cE+|W?TqK-N1pQ; zckiBFGLdkWObH#*v4H3V#o$wD%#lD*$ZG65els_q*#9JLrNbhdQ&;$GvQY;F?Ga}C zCPBNBf4t_A>za8OOte`rWN?PRnGo4FecsH_bfj8+Cu1RvvG#`df$n2%pXg2u^#HA( zh;?21UbIKT1QeIPA&oV&>b^X*A>U{(^1d|B^TUOtnbwCnRmPGz^pYS0mrMF6;d!(H z&Z-Tv(J(y{(h}|nJ z&qg(J;lPqN``+FA-HNr%h@8%|F_RZo28a2}nOTGn78I^<66X zE57g=j%0#eDfEd~qi7aXHXPx(VrO71iHC@oK_1ET{OCZ}?5?M>0=WMQ9(U_ze(BiH zPxBF1#S-oromq#nH7f?4Cbbq$13Z~k%cO{uHr#as;Vt#F4Sw9JA*>EtEc@xx_u7k) zoku57skD={NoXZU>uYOA`fex9@&xNzuM~G8XMeFn+x)wWHAy|kZcrzfv->OYe0KEBupA|jJ;O)&kZ#Guv^zfel6qa1R45W_#Z115S;7!8vc2k7{?hu% zGB>X;FSnoUX%`DqKX^|cV(wtmfq16PN4ks+cAb-sQxF{2AN0yx{c$C(;NIhKI?D&P z8PBfL7oWk5FK%r#kgtS%X;z?ShDi8xwEcn{d3eqS-cWAh87O3uq>|h#(x;!w99H@` zf8nTF4#yA-;=k68!FFe!lXnv8q?OGjvf&RRRKVtdH0)<=r}{q2DU~!|jhJBzK7p=fTu)v<5_AQ>dF`?C z1D)@qsVx*Y`qj*nrEx#Aid+!I?jzkk?tVwj58^-gFGlOL#>akSeV>2C@SyP5cYn~S z{4-hdum3H(t=X3SBM}tN_BX)(P}mMHJo7h1a?^GyrYMgR2WmD)wTo6ZxGmu?MZf(6 z=Mkluz6)4eNRQc8m+yP_etRL_ zh18enzRGd!=ky;6-Yza&vkR_4c5<~nQCBP)()1U2 z{qOnwJ0SQ+?Vu9IJJl}I*&Ow@m;0TFh`f}G%Z~HC` z3tmWC8>jKNH=LkbLa`Qbf>Cswh`#!0i!v#-UV^3>^8mH%;WS5--iLid7 z`7ekLsDD#_w_-=3rdLmxaE=m5_) zv^#R|80`coqgkW(ud)fZglGW;2OVx3KO9Gd(>cOIsFutdN4UYI5jAs#Y4bc&vNPki z8qYQOp^#41?L9vy*x2v{JB#hglfD$u2zSU;iDu63CO&%X{=Nhb26mT(bieznS@hAr zAi5FfnVPb!D{6h#FV-qcli$vvjkNgiHn{A^K_7!)xsx$TpsWc@FO_a$FOLwC<6 zc>KJWE(TKtI^aAjv(?|j?@+wnww8Eu4!96wO8lRmZua^zb%I%q|KNth&lc49BTB_M zdV!<@-6wqjj$n3Fvv+?KtFzSq8!5KGZrk~<{2X!<1Ye-$yKowd+9!^}033rw{`nE0 z(6B%E$X$8)0s0h%kMYl@g@Q583gfBeYl#==9%E+)W^#v7vDy zxWH@>{Y}KDD*&Y|&)w+g9ps03P@M@K`1$=C1++#zwFgk+4kM^`wYVcmnJ^qL0Y;_U z0ySkpIPEyv|7{+b9X3E>9M5+CtW7^T;E8|IRqkDuy6QT<2L+%~nB zgv%}0?|q)G;n{O1+q&6J18|ER6Ccs2`^w31_InmQG8I8fk*b z`MJo9&o<0O3ZB_tV1GJH1=%Jtx3y2V3MVmv#f=L-)X6hJtLUW#(_na3+M9;#C|CtL zBFOj#VYki34|DZrBWJ&_ldV_&1qaL}2HWR!pF2Y)E%p5;;?K>ko{Y2W={6H|>bJu= zNOztn$i}6|t>?$7=U>0$8>EV$jQs#Yn8= zEX53pkMwV#J${rDTAxx9gQHtB9&v<%jOBWsit8xvem<15pyHu?+^>^@} zi!~*aCND0xd;H*6IJ|GO>BBRd?mTn!u7_%Ud7Ov#klpvc=h_3IYjWuCv!FT&SppY= zR0D7KA8&9C_?;Jd2*O)?d%Z4=c^Y48@|{zkcl%ZxHbox+nSatBoT7iD9+Fum<@@TJE99NVoc~QY1E|;M&y8;oQ;om;O$U4VjYy7~Kzv>H%HsW01V%)`v)1IAsw@TgA)630$FDg{!*)%nvE>$vuah>xQ-0Ka>R%e!7LXLK0otWVVm)xO9RCG* z@aStuoy~$Fg^Rc(3&o5RD~IkTqzBxen^4G${pogd^rvJ04wZu39R$r!kM^DrM?quh zB~l4!_~`^oT`1gqyl1wCy4aKeG^nfsiw?)(CST~nX0z`Y!T7Gj1o?$)DO_lp=>RU9 z8URPGw5>Lc5TAgHXClbbI@v&?WF(E^09olHeMwk3s$DYmVoK3;9U~bP{GbPUL>G0B zngh1Gu%L_Jdi8)h>@d?Z{Q{aKl}^d%jzF(VzeldzO5K-&zeeLt6!(-9*pT1M0Zupk zS$5~*Q^r;}{xXzh!atp;MtHw_G9vh>nd+4)Ux5iZn-3iwk9Z?&xg^Ll87MbuqEAdy zAgH+76vG=#H2p7|L`}!rHa_DOGu|{ZO&J~k0)VH4XOF-j-zp7kA6GuPs(rfg!|)yP zPct))9e&=;GX=c-0wxbx*Rt|pmudalN6>hV^uEX%8iz&DK9BeHTEJRm3ZLL=wR>;Z(Ja(R;2u2XKR>RRUth}#YdUcFO(L>Vyq;_` zYi(_9=k-d^_cem2w6w~T`-o1M+M75A9!~Bg5$>55>kt5$0TW#WwY>RQkOj36P`~WWzu9BU-s~HsBA6ZhC$A>>9yE;sghY$5 zF}%Ly^)7y{Bh1z^Hs~D>DwdYo&Cc$LMl=yQm8; z&r_Ac%hFMb+juX5e;4P_K4_#uw%nc5@>*#LI(4yBIQ{5xk=LVp*PrSf zzKuu*5Ucsb#j#1^+6c@wA#5Clr83TyrMtgf<+ZM8^tG_dn=z)vFkdHToe)|$ zx^eYet}ktz)}8&sW0nbsYg-P(c3#Wk24c`Z(veT##N!Ugm9yxJ7`m;Qv(!*9Qku|- zUl4mza2`qVQtij8q0L*><1^gB?uZ-VnVRWMliyEob1NGraSB+3hS<%avFRaVO$6|V z0}#3X@4*Gyx!V;M=NO87-q!oZ6K~1Fuo|r(c&g~};}cjqcuoii2!M1Nl*rNqR529c zAX>y5CG4HCpCt=bD^jH^0Tw!2W3wKEO{Z393jvX%V+9kW^OIeI!dwnK?zbXTRc&V7 z>ckCwrM$2>I*ZQpgjeIMapM%OdE$*ql5{Y>ti6@Uc5gqZ82YU2nBn-LWxa~EjfSAX zHdEEKe7#sy`iE51Yrv8NU9>F-GOrZqqU{fABKW#k@&S+KlH^luEWTz3u}t6yt@w9B3I2=_>j1iXdONBI(5U2pTix;kfHi zGjwI&vBW*C|32}WqH7lY=?jTC=fINKmRnHG!yRsVUfr9eK`63G$R{Wx%p*>F3EsAd%wag45Z<$Yc>kOwDjL^7A`Wwlo zMeptedQME(6z*+0r@6v5lvA?2Gbx{_&1mdvQ9*N748@R|p>@ogx32!_J&!Et(AUMV zK=*czDqTd{k4%{Z3`RBG$kA%8KW7e#yI5XtO3?MfjM$F6!2)(K9 zv%1iCo?)tGXq9mt8K$z<1Z{o9kn&bK-N&V1!v0dmmkIH3&MrenRyH4=Pb9`}QBhJl z_BGcWM^D)}ye|8QS<6lh6)7nz{7YGi5o`>#>FcOD6o#*D zMu_0rHc2R=oF@hQ??*g!vOM4rP|ETdnrXPXWD}+i>=Nl^tXm$eZKEQ8!|}hlRY&Y} zacB$~#}W14*n97&rrLK+I5g=XT{;MgG(oCT5^NL^P!wrGR8T;qs8k7rBE5saD=0`4 zloEQENCy$=AfYCJNKX($AmyFMGc(^h=ltf(eCK@Uk8ftpA6aBUfSsMapXa`>`zjjB zmLsx!?mAXA@$S74mF$ym3!;?_O`@c2u24(kDD-7Z*I;5g+U~PjP!#a<&Yb zB6v~3w)%$bg7u)>+O4V!-bLpe+NKN4IJ9~6gm}uUjoDhxbCj2qO5raSF?R#X<5D5K zM!Va-RAbXiS(!S?b@4U=%qov0BWhe~r9tTKB8r-p`=8LuMLl z^0K6Gz;ioN1z9Pe?>22F8S7a&b!7Do*CA~mAMYNME}Ic!%GMuaexrZ0&w%a-Sn^R^ z$B-_I5ss%x)n!-CBC9KmW|U24iDm0E_Zy;RQc#MOdvpppIbznU(_3X^Q8;aaj~mlP z>}+l(oLY?I#?+Y|Gm(v&dE(EwL{L$3v( z&9no)>E+crhQ0Cobv-x;hrS9G9w;!wFL$N~xVsQ9|IB{wMuX3hr5h8v8pS;J2+5Bj zzc`JECe*CoW+#4X!`Tp04Ut;hGDh`{uZ^yk<9pK;CAP%Q{YHI(C7@XmPGD~uCS?^P zLP*^HK}dX~eS2J2H&m?ob+OIm9YywPn2y>mS!4TGkJR@qEJ1Ep00G)OCc$*0WTGZ1 znOf(>Q(qDHSyp&x6y30=mDJkyRYHd&_jP{Q@3lyZNm0OHmz_m?8w`f=`Q+I4gltSg!?o_- zH9gq_016gfRfP^4P|R*=Wet#JC`uwR_f>#9oWT6_fKsny*O%GkC)QnybuxA+ia^9t z7(oJA3wnF;P&=gmHq-AgW=HMdl1D+y5)-P>Q0iOs(i=1#jX&Vgw_V)n2&d&;;kn-0 z$JtSh$J^_LxU_ZbXU$r8M9xX+78EYG9LTubi3@+@X7h{$P}iwa5p8bYPDImfDcT*K_zFLShy z;+k95o$el)GyRq|=VA$wzpSb|1gK0CA-5g9@~RO-t=dbTvu~F5pXN@Uk`1MdfYrGg zC?tyPMARe#!^GLanRr+g}~!- z+t*|Z(nBOkUYjcBkoCt>?xeN;eKJGH6bPdkzynOLq-QbS&M0>A^U+jZ>6LF;$Cm8v z=8c}qp2M+p{LAt*109n6Y1P~#a>FVE*;v2UZexPTBh;r0SN)TBS z7_4L^=+Qm==x*1ZmSx?Te%B#7+a-0cTWO>4I|L#|2R8x|kzL|>LoVov_1BgxLp@lr z7ZKhUDeiD0U}mRZCE0_%`~-Sm8&&RFL!X)R{<|y2w=%WZzR&HU6QkeM6u#6L8zsOJ z6L>!=VE7-rs8Hh~lyCSFN)bJ1zgs~=yk0eZ`aW&@)+o)e4jC(XYo8c* z1~ruYm;Y|H*?zcsiOFx%56n2G5=ByUWyrce>SLCUm2@+CJy4 zxv8z3eW1uWl~)>vm&$Ye&&u8pzo2>4a}^SD4j|)9j|lwd+Qt$5ElKAmYSrD-n5@Lo zOve7uBQCmuA3vQ^87-mUeltS0{39201%fKK zT})Q&^CzArW#tRQ+G^E}{)QmwPXJ}e2IMFtZWVEAIgg1%HWTR!`@O9VuU-;ORNGK& zn#c{yK7FrZ%iH}UF#HAvA{1aCBDh_yndpDLs@Z`3^7B9rHAt6KhCie8v-9t`GUI+| z?1~1c+q9Z;%D~5VJ&V5eE2E?{4L=Wb7G|Co%T+7^e`f#$!>}8~%1zgcnrU4SeXKvX zPG8IA&0Z589C;7bjf{TMVcnx652Q4u_GtiJYIsG5xoOODkL3b$%2j0uzjaQ)+OlLP zGRjK~b{qjOAiZ$2MtDCK8tKrBgTjv}q?K|S=Sc&87sc}9&N+SVxS+52 zER=0;I1$bNq@9hT0BE41WVwlaJoQ}@S@s!Aw!gnkq1h_@o{KM21K4M|uk9Z`jAL1F zd+U^>sr0Q|;bYPt<_szt=9w%`lDtWM6(aTBjdpUZvhq=F9avV0tg?P&4>a4ym2}{Y z6U;z{QXbTh4)O5@B$QJLG$k8z*Q+}1rtU@MitdInmA?eE6A8Q(_0L%Pnd69$DPZ6d z{vu$uBOA7rzEq)W4V1v5rA3nm9pIC(tlTzVkGeUh+Ao!m1bCMpfQUs7J5A-ZQ=xHq z0H|#h;#YTvD-{RW+2JPAAOni?n(-@*SeNJgTXE)e_eIY!=nr{;&_jW+vH(=)5#xtr zt>rduHT|urXLkz1UcYc=ekdC>!n`a;5j@Tpj4xq;wGfzTktNgX(_6)&J!B1piV1%q zH=El94%NU$^WIM?G(n3l)R9OXkR{E6i|@;(hv&9eMZu@)Y~A?4QRg_Dzx1BTa75j) zyvX>B<-7*ngMTt9lrR4h=g@C;1E{MYy6Fa71?@ou*!F$0RseL*3x^sF0WKq(A-QErY9_WE3`*ob-aF}gEjkkt^U@m^WF z>(O>?*Cp#7zcg3h<`U!?zMd~L)gE5(_B&4x|BWkEpX0?`=|4)bePlL(EYVs1w}4IP zv41rrM-3_m(JUgs5E~WGO+AI0z>NNf(;DtPY5A7yg~)b3m>OL$NzB|;Q>tivfBbEq zep7`4#S-}Zuu>cd+!X$JEV}zGL#Ie@KGt1ymu=9u+zw-+{EF4h|Ml0jQiWW*ga(}I zg`Z%Hn)+u(a{tzG(H*9Pjf(DXNXkJNdNUFfVhQ2xI8^jMTGOflVWon>pYm%3D)lF< z4+keR0*c1ZXjBIJf#e~-9@t6lpF!^%qdtcGFJ53R_ctUEuAU=AIUU>#tYxNi4gNWC z%(^244206j(X>{u%f7#Z`lPso2HepBY8P;DDF!~Kiq_u<7UY-h$aH1EZS%P&O;`3Oo_SS`Gs+jjvrT0Btq4-#zY=Q}K9vc|ucOFXk!kKS zyi_vP{u0j&z*#^I*xR85eQ*d!!g|{+h|Snixq8*1`d4D}b^su1U1oiu`wQC}hqP^) zi=KCt`R=XPcyxr`sihpA_asx}+A-y(xy+Pu`~IC(!!<8IS@N_QAh~`qH{W}aQ|xgZ zoRTPn7ug3n0N#7kP!=sh`Gw0Cm~_c1cH|K`;Z)ADuYW^4lMkgA4}`&JcjO`JIyD=N zm?8tzX&q%iQ&%6{2L@6tl$lj0WK7UM*{$~f;c5tw3duKJ(Z|8)3yt}Je3BfExsB-y z)4N;dh9k2hBI9i7WeaXa@x;#a20YXYey66z0QnnIKWRzp?7Ll)X9mooTI*U8^K%z` zY#(H5pK$iMXO$7w!Fc>C1QEQ1CY=%5N?*3%zKSa87T3M{=%uM!B+g>rvh`cue1Wu6q#&39QzaIDL7rAVwi2)KWKi{_kNac{4q<8g0dqpWiZM@*^T>qWkAH+`1zA<+Dn0y9mN@$Sv z$RZb%51~Q2Tqwy+QNvH=U|WTxi<3H;V&D6o;MB+qv1Um8_VxR&F?${-g1L}#mK2N~ zj)qFk0hpF^J+sA`Yl%74qww}GNinaK@a>K6=^7nn!vk6Ns#i}p~*ge!NlITj3A#452;|@6$@Xg(l#p zV##=Q_>O3dIGvtkIU1Y!hmL+E>&OU%r0xJ_T6uvP`7>+_r3rm91069ZMW$%Jw__|w zoUIpQ_3#3to_85N_vKu9y2G3Jc&v7B^6cR9qg1j<$Y{21fIk)$Rjd}^(s{tPy#2Ub zHUS_9X@b5+O-;V^%dUw+gE-i%&YAbjE7}x(ZDKn$7a%BMi+oVX&xJE&c#=$0?f9a( zDf{Pm-}@hCO`h^JtFj|{tJ*DICsfkO#Z6P+0C+SXSpyG+(j%aFqd3Y#&D`4jfahl8 zyW72~AFiEjZVcnS!Yy7Vb3aV@jucVzh^dk`41*wUmdyu5bT4x1NtSJ7jR||AQ2V0n zIj>jr?M$4*-hMx-J`F5a{_$KGxKaeD@1VT2krvL~SSZhCgnjk6XM2xdF9tV?d-EzS!~XV7&OH1>G_?>q-fEtJJDsaFfoyr_G^jpk+nx z>pcjj21(3jINjHnsTJgWmc53nv>fxoIfsvI|tUj!S>^^+|& z2E>^#_%#HSWQ$+K8m9QDM74{I>uEcaucxk0jedUga7m-G5K&1-{$~4W{W0@7G8Cah zfOR4x+C}g}i3lTK+)$8NW6Fj|{mPhy?12z(+fJEmQUB-_=RKUtufWI64DTp7Y8{jp zafif5_|`>S2et(Ew}S#KC57F1%3wKO{14>bF5k^;%$yfEt)P90P)?zI&8xb7t4flE zA`7bLq>w=v-#&{br)iJh0_P;6%5xueTzke*_}nkXru)RetP7Z%2VjPn%S=Z$Kz5k5 zGb8jy<;FseFZL1mdb6DR$15}@(@a^`(pMALnjlJXthn>+t*Lce-?00V$*>39Ge)>O zAGGRm!%;`qv!*#5-L^Q6?7wV18G4I?#tPSy2LWl>m_sq8V@?)NHh;k8m^UtrAl@@@j9Ey>dEl{tJxax zH^iUbMCOsLRfyI3Zx)bjswdv16Ba4Sb+%F^L?S??YeA@~HR0-0t@vWQ^*yr_y5X(% z-I1@3bFs>3GAD#^AS6h!A9^YP7hff+&7$-&{p?l$@^!(i16KN4o$i{uS9Xr8*D^6f zs?QH-gbp{5!myHY$YW<|QUTmI9By5lse!qo@98k}@3OkK9lB2wQn0>Lj#!be`#|Im#tHX8OU2n;5C!LwRDJ1&_a?A`80_cw&XJD?w5#T}+81AqT zbYGmIsS>Oce&m=`yW3}(MmE>hgiEg#nbE5cvX^pgJYy~$t^&UVKYPE1C(vHKb`nxVYqPxa5{l z+syc6V$`Tg+eLh`gUD*`Yj0&0)`q6KG~w6&rLH>)m7?DkV~Mi~J!brk=|(eHIlt_UJ65&elcJT; zaSwm}?$0rARQzZ*ysN^TMN3(h<2?OCqK*#t0>1r;e9B$q!NydcfZhc$j@C{Ghv2kj z3B0+?Uy=`A6H#F>53kuA>~PO6-6CLQ)z+y~3joJV;J><|TAT zx-LZp@0pIBsk|*at(CdFttR!eLU$)4t9|VI@cAK;uw;yg>N6+P@Ml+@YjF0os|3r44w$;IOYy7lKk0Lf(w?Iu2uUK z8?1i4eZqtHg2V-ll5vlvmR||?6P|8oNw_gN1(!chkeonA!SFYcGna9O@m{6F%Zf-g zxbZn?4o-4k{vF~OM~QDMs!+CMkvWWbl4R5wi!*6+&OZC5g*x=ED#uE&ntffF;n;Eg z-bKv<4muWl&%hqU;xha@oOq2CRyqhQudwe^iOt{ZYTSmP89#KzYE`Q<=hXQI9;jK| zy7oCBug`)cU$RBOFLpJ`<2P-R`xX@5N+|1eT{B7>xyuuS`LPmtQ4ptgQbopxO})t( z*`W<(q!{2~(FiBP;4)JyhSY~^cn8ujDrL^y?eO?vrgc~-1?DXpyVA+Rw^`q4S%rKg zJtvSW5fQ5g4Jq z;g`Vd$^yr%YQNc#dskc9U$bKFdd;l)F+;?MRGUh}RVI@T%|m^%7HwKWmYPt{O?n8Q zWw&S>+p5!c2Hj7rbew4^Q~ZVRTs<& zp;6|lhFHho#jUOW9mQXgIPGqg7)ktXSS+yi^?G^aON+p}cUcn_+_P6Ff<*jp7^L?7zSp=u6BZ`j{f+s_(SUy0De0@LGblwD9m#D#pNX_D%(C@u<|q`j6LgXEIa&b(GY<*6Dw4l*;E;`w1zmoL4FE<)3xTo zCV$r^Uc@I1KvVHuMj6ZZHhlS@rD|M8LN(vGM-nV2xRaqGv(#Lcw9G&%93g#o@JaXm>t=N!6$k-pJLtJkNiTLHm(XnP2Z9TV)9+LS z6NB#i@}~}oDQi@TCZEC778E|K$#{Y&N~1es?m;s`*-7L(I>1ecLWf22Y&_D8S=hj6 zzWqIr2;B&*?cS|_{`nizRjgMSj8TuX{3=d`389ZiMgO)Dm{QzUxl&WplIUz%DQI)w zi0)O2fnG#}F?Z@8OsA$XHbjSHeT9^W&o!ziW#DN}fkh{r_a3#qRQqx->2Bq~a;l)c zpB!D6is*q#cF1rZ{?=l&Nc)?17HV{#orH&reJIWD^h~6Xt!uzYuq`alKGLEfQJQZ6bf!6s#1?;8QpGS&kh3J=7Nj$Hl z&BJQ6qkR^)O?TsTI0zndyq(tQH*1aQkJG+zSHmk1_1HYpnY{QAUBqMjK^J-^9y>Yp z35(tq^&v=nD({nJ_bRCiwa{?q+iGN$u$AzCl!9f{jbZ+oC`n^oC5yQFy9YhQf9W(4 zIEZX(Lw`z!66WRxg(Z5PZo_Q?+&kNa@Q+dj!hRcMUn=&|B*ShR+h>3Bw;ZFiN=2bN2Hp=p8<2B+Pq#5 zv)|}g35K!X9_CkPPVJRv`ah!^|C&3A&FJ5_ znG6Vr)#)4vr64^IyxOLd=!%GKL91PrzyJ$C;OA?m*q zqyEjW@Yf6ce?wk{0t9i|eUYjqLOqB2y329)VBGdNxdaa{uL{mB!Q-7X(xRIhK@g_4>FTA%OLfa5P#e@F(v4q)o0G2!yaVrOCd;k{^sb}i(9FkzP( zFVaU#9faqh@g^#VQjYRKEYJxkT*gYS48Je6ds9mR<9e7YWJr>uQqTQkuZpi}qt=VF zIjzTbe!r@kGg9QZ=atdQapv&##Um)1=WmGnye17sTU_K0Vc1AJH{#QzH1=cuZsLGy z@TJ2nN#E6mM4A5edNasVVC@Kdh)T+9G%v~%MY|^RJFY{8KKTW!Eu5n6Pi;MI=$s#j z8kxRn_R}A4JwqC zpD0ULS4S#uR}>oGk2=LF_VgXw$B*Z&Za^U3Og8VhJJAX7YOv|eKyiOS_?pGI-}Zyb z;$}U+a|A>Z1gj}KV=SFr!Jg+{%ecOZTyqM&MvJ5M!RpP^$rcn?8g1iD9jK>%8lKl2 zf+`(eEaF_f+tHN1GE`s1s+3S(lp>I`iKAoWNePge#_o1)^Qz3CX>37HmyjHE?%3fI zMH>yJe!ZYy%WpHDe8CjAr(CKl1=1C<(>MzX|7D_5^|;S4U&t7Z9X+9yjvnd4zyk?Q9@l2PxkC(+!8_FyEuZ*>s7CZ(bIOVio=99{gYFisq9-a=z zay*j>QmZ}|3KNChhkf5%YE1IsW(*m9VI5mPF+=&HfF0^x^mlZVy?LN#O@>N2$8A&pt-14b*)8-SCnOhntF^5HK-)Kz1 zB0-BRw}P6pgOG-aAF0XhVze=95$iZTFC6DB122x5x!y;0X*^!UM<=b_1fA~{Yo)jG z>`}LtoPfcF6*a952J$Oy2#+#~H(tEW>e}TJ&ep%>{DA12dB^lbzw_Rdt<#-UnkB!y zxUuF@1{fcyk+%MZa6viy@Ph_#P%%&`^_iMpWT0S%1a#uN7>!i(nNCuz?XOk$1+)`) zm?CHq4dbynBt}Q6Nh4x=i}7L4_SlC#3u;g=@7bog@~&MG$PuhFM64R`A6e(cvYxEb z@Zxly`}^5XU5Du!TB%CL&IrzLRu>ee#&V=hC{jFvm`;W{@P4|jI!mYcJjb2-$WwbFEoAMUrGAq+PBr;A zM&g(j{_O9qh|)1gv2cvTPX+-?8wer{4?E z%($oG3L03W-&jmQ*3z;b;)jVzB;V5cxpkHX?+q?{^Y(!IqPJd{@?Cy*DS`Fo$a%=y z?o8Mz?hC18_i-89~& zfw=m#k|flv%?o$iV($RFONWHB%9qfOa-v_QVyE4ogKkXu;`}p_1LXacOtwvMrIw9tD-Ig zPpXtznLD3(`8qZf5A516Q$N90M%!hO(}^Xt%-Ip6oQ*p9CvWXDypEZ|H;XOVW+0sYh4X8~>HA-s@MTfPHib{VOIxH0YQ_o+ z+RUV%DfDIxpYdeXJlF=^29-7~iMQB|UaUoTw4!4j#R+F?KRVhk&S2PsCL51uG(Ri1 z$P#HV@^t?_O*8=0QaH&8jPvG`X`zZ8u%!|p=6I0@^!8|~i2K6d5NGZ~K-G?d5tYA# zku9)UN(R2q^u<(aW|q^_4;$*m^~FUNdcUr9IK`cLRoi-QNug9WeZ(4zOlUt%0b4_O z9K~uPL=YkVDW?n0UKa(@8CyLFMw->9?gT9rJG#92u&1mh#Gs^xI!Oh)6_XgD{vZPO z(1NGuegFNuZf&g>a(`9S#dta|>JTPOI4p!E=bh|;u)_khaYrs)@R{V!EJ6Io4GG22 zfan`<=vwZy)4gN--Dw~AnECn&V93AYR>1pHcn66dBXvKq1ikFVSd?F~7A~mEMHumX zwdYCcO_P;lfh;saB@C?FywOXv+TsDZPO85Z{#)g1*Q;9*H>#0WeHGHrS`cEn7Fz9# zL&`zhKG>3%MB}EGf`Q99()fqPxyO#o1oLFK_tcM0=aa^QNY2*b&$I_QBAD3uBI#6H z{gO9Mw%;Umk!4Ae%aXk?287Gx?oPQcjA_V2I(+{4`+V_?K1{`OM)KGEQ_5-0r)-kW z%WP~w6bU)Kd3#yh?4aH)f*(C>Ld|4TgsAUn@;?`uU`s_>i~PQ1_xM?H=If2Gx3~Qc zYuZ|FSM|o(M2Z%rUUWJzH0M$^fVs4*1Pp(MGLU>LHqm^V&ZBKmkJAm!O=|oZFMkfK zeik}AeqQ$EJ0**YJxH}h7T6<)=fq4>VW}&eaa)re#)P>WcDf$*#IL4qYnqe3$m_Wj zV-e4|I3`Um4ek%+tW)o^ ze%vd0oWd(jWurhzflI@YxqQ`lqfnnxjbKp=vugX#I@RPc<344OKIs3zCSH01PmQXza&Q<-(a-Swds-oCEp$|#>y5=`~|H0;dNTn64|=6%P1>FE5& z)fs|HfO+H{9grJh0le$Y?uX%Xr-)`{S0|qm_{!d`3z-8DqWa zHKjLsJ6A;4U75LO zB0Bzt)LC~W`eS|PJ0N%GSUn#kockOI63H+>&hN2&F*?h#{|$CWBN2X$a4gHM($zZU zv4}54{;9kFAKw~$zqU;8&ucYR7Z`b2P`Ln|bOPwipDlKn0bx9e&_{acSt?gd&sIQZ z?yD!TZa-AAlfS)0=%TCdl9!^0f}M1T07P6~k_h0**><_CuhNcm`bV%u*FmbWY;1Yt z=cwm`!ku06*{q`sh(wt+S-^0QMh)x=B0H@0q_O%gR%5#%{G=hkbbQp978HX6EOyIP zcC~6~(n}?=l*?Fg`D9FeW0Te< zy^7MftXAWVp0IBcOHZc-e)VnHllcRNiLda(FGFNN0sd*SuM5sKtB-m~(Mo?pzRRvI zEd0_Q5$~7f{YVm>CstFC@3m;g*X1aVpNjOtBDvi%vptjDxM!BC>cgZPlEj=Ibcaga z_3P6JCBVZL>-xI9Fx=S4K5%12d-*>9YKGjgQP091jdmNJeSQ_FHk?WVbZ_D%V-aR&^GnVasA%-xu>IIpb9I$fRJZt+ z#M+HxlMh$clDY9J6an21s0Jw>YY}~ma)F?g=!=_wFlbcY^vTsyBa`S8b~mE__01xt zh7}z8w)_7eYVi!i@6Nb0@9E&Vf9gnncPy-9QD6W+-C<`17$JEgJ@VlWDp#Z~GIg%0 znmiM+xHg)H^)9KuPy3u#GaMa4kB}Nen11};@pO4n0AuvQT_mTH9OKkNZ&SYPH*h6Z z_)3_??y0%%6rslqYoaL9nZ|AXcllFoR%GRX+`%h1f0(Fq8uIa9&U}<D)N~uy!R1D}J(Sa&78ee9zO_LCzuzwgJ(;kWHE1;zG8~a|UB3&0J#_W&Ig` zFSG|x^U;riLr|?s^n>Y;(~qBIX@{X}_j6A1ZD@bZ3;GgM6B<8Sl$xd~OFtte8S<&E zaeQkH-TG8aa8z%s`R9idN_}{GGy@<5ax!-y8?^g|MMA))Q0G@tVpg?p) z>*@!HP@Hy@OV>pgc0)f8d8IL-Cn+7F`X8rhY%YZH-cn3oXYx#KclJ)G8eviTQwwjm zPJ>6?L99iU|N6vq(H{fa@Is0P!6;sage25<9%XeVzOdyzjwyWo#L|ddriT(}YarLK zxJmPbKKsTjw||y92F+2CpM;t1KH|91{V}ySJF=$WWCGI-SqM<&`=EgM47~BY+LCS9 zlHxE|Ko%UoT8ZZ8q$Z+@=RdSnH3>V59_$49d7g@STV9kJ&Gv4rVeRIPVL%LymX9ALGoi~v`Q{lHM|I?p4R$9>Z+Fi6%NY}|A3FdB>b+VS|9h`RQMms{_t!`yj9+zRxpg#I|Ktp3Mj?>_I5jJ719NqGK|I2d|#-Khq=DWt@`$8tLijg zWyVIq0R<(sjKP!VUnOpw_|Sprk_z>gtTpc2TE(Mi-Fbkkz2447#86ZLhu0lgq@-6? zw9|)7EC@}Q=M-GY%=X>7S^BB2_GREx1^PRpvsc*|pUFg7oj7)#2|i*Bs@HeO8pU-O zX031Jz-fuO+ri5+)hUXb6SqY{Q@ z)vyQyOja1a>mpJ|Tx9mi^eMmk$%%63rZ)+10@G?$@4hXIWQN>eE}zC3ZC@-i!h;P# zcS$8dhbT4jJ1B@bcWXuVrrxu4|Lc8IEPok)MzTuOlfB?_A>U!Or(Xm3`J4`;W#2=b zhw#F$i|r|hSlzP{tj0_)g&>d>jxq(PsOK2n?-x48@v={ZZRpFnE;8pckG+LQEke+q z+~TysX;VA{@#Bc5X2iu=_lKnltSaT()6zT>Rrakn&aIk?rX9bJ=%`cqsR3(T+)C7X zqX{F~_{B=h_iER++x7|fWe}07dG9pnh~gpAu6Es$;^?K1GI#OS_HRWy7M_{<@_ea# zVU}*M7n;OYzn{+^5njaeW-4zRR1HkrQ#9qZrQxld!i~lkN$qCoo6yUrR$`^PloQxY zdyVymPxmG`N8XAB9tz)|6HP5kg&{R1I__+Wh1f2{3}Ok>pg z_pndIhSh;W({%pxWr{k1;I9=@LRM($BE2}xS106nY z-2Y8G`u;)L<`;-!&uGsW;=(O3UrBUsO@Mn&pNF3eK?4v+ai42 z5MjYjuC`74DSPh?xUGFn>Cu0)rWRVGQ&v=dct_5U?$*%Km1~C%9ig$ZTCwp&_e05RP6X((VB`fBo`~=T$=Ob5~By? zrluVe2I8@vq7EP$YX+MP-= zfVFJGuY<6-7VUV7{s)qEx7I*l@dh#7X2Bjk4^}7nlX)N0hi}3o&NcReh)Gya&RSfr z7e7LYAn=)O=URua$S>hv`~nRVCoOO9IMjrCvu&TDqe4dEoB@h7HWjiw32mOVbI_v} z@ND~)u##`k1ze_@k<8cF(_vM}R_XF&aZrx}zrKfgEVcuu<0}?Om3Vo1_oDA#-!Kb9uiw&fPu$aehN*3J-1BO#qD;3Rrr@Jizb1^cm2T#E&g_pM@hL%pFRU z4y<*Zw8u-yRfhSumoglkQS-n-^)c*NfbJ#yOYK{Wr=#Cv+{%2P&6d2eyHw38tG5dB zwV>}qb?hkWr1d39b_AH2gy;VZVJ1|R%S4KQn`=H|Vq@mQl9*V?buiG- ze%Y=M-tqM|QG#R#&q7bJL+=!!f?~o!-mZ&(h4`o!pO6Igd__luZRe0V+>m_x0Z?fQ zZ*7DDVKMq%jQy-lWNq}##@ZXwv3^f%D(_p-vmQGJNsOTr(OInK-mX^ZCc?v!B6rvG zc1J>X0?+0d;ofBqRtZp@=h@1IVs@q=?|h9@%U>>1^6a4)ba67rS+=wjOG2c@qcrRjfv zJS}l*oIp2Gm*e^_-Yx+aWi9Njia*ILe|;axI;?3=U)fdBkq%*{Lw<@BfsB6{)~0sIwExuXZ|#@ zmw=n_XVA#pY3)j|{Y>;N_q{b9#C@kyi}#OFo*1U}B%``?3!9skXC#^EVjC6Tb#OPw9M&N3 zA(t|81xc^57Bd;!?I-OWzuP;yH(I}7Dn4p^ZuEYDLsG2}nLcQg~)+Nr8 z_{f?eV@J@}%XtC;rdJ6L?X~y4{GG}Jm6_&<&wFKG#{ZRIEy|{qNo=ZngsvC&4*^?h6LB?kuVbf4r) z5p-;uw7{!dZaSHN30Llu-CkYuaB)p@jlX15lCGV8^0?s-gQnl^!z9J%m%q=vuLZ`E zUMJjNbjsg!Q;ieg^RreB{%D{+eGo`2ekTU&_~f$ewRM4fn`BLVKv;__CNy^CNhS2>)gD(lhgCTgS1z=%8Vqj(j zuE0B$J3*3pyAY4sw#WP1*G@h8-ltVo((NJBa(nr!jod|sbl?&samz)4|EV#z^FRDo zV90bp6eNk0HArKdeP}MO8cfB)+q0Q#H$K_o1b>M1 z)W20k`_liZuYed_gY}mdz4+= z%G|cy?k|MMU;ed{mmt0%DrU`z!Yd<{u^|sQflB)MH0Myk|4c zL)565z)8y}ad4b<({g5yKYW+?Rv9NNnR|!MI_iQReE=*GDF%pPD9rO^qfQtVm}tp9Qqtz2M(uP%#X=rKo~c?Kbec*AI?_M@iDb z9`9lbm%KW;IVf`RL>mGqU&ZR(Zz85zimUT{P-l0~xT$TCNxj5%xE+O;S_1}&v1mRG zFGf-y@d?2?LL=B@#lFIiydCTH;DhLSf3kUwhba9QAqiKnoK=nx%M{5%E2g3PPuq13 z{;9Gf=862(#`&qEy}~vUEK*Am6SwzoF@SbNySa(_3i$*XlUH-BUa=25%>MEthM0SSVQ#9bAdY-vs5mOj0%4ZzVxl_ zjNMB%Aer?50hH1+!cPO5Z?ObpqB}M>9c^QG?=3<2TK8s%-txmDpBrk+Y=%vYerJl6 zZKhtH2ETD<4>rCA|A1Go-4*tc7EW~)uX}|VxY@a6v$4phL@X#N3N;P&YSvi(rNok?eTb*O+TfRB< z4w70i`W)wU1MS6+MO~f5ewBnW6Fu=Ygu6s1JQDjB^8!_%9=h=mZ;*XVPasykPe}2- zLR(tLEAy*n#_B}(<*|JA&+i<3yvad)NZ_P+SMg;%z!wdff)S=P_dwso;QpS6@sU&D z5XiC1dmuLaVhvk(U7PWWO1BZM=0oeiSG*VUAtHP{w5LybyG8~ioiwS&^OI>0ytlfF zTxw0R>R0Zd3&AX&3aRw!^|v;tu%De5h|Jgn!BL82X4f7CdkrId5#hVGMwk48agO- zXB3|$I)nmU<*vbT_s+iJ<97R@D^l+tdLlWh@Opz5tk;-F$TYKPLF2w0X)$bU!|sQw zlz3Tg`WMjq<}XzFs0NxlirmN*lN}>jWEv{LqJXf%O}r>JK3&iJ(`!|Z<>{MpoMzyB z%>2Mdw=6qbS9@B%%B>_5)oP})BkRqxmh;Ta& z*Ar7``j$N1CYNue4CzgzWnO_T@Q`|LEVUi}YMXyig45(6r6M93b;wm!6$|#g3^_O# zDmp*T(Ia>{OR*FoVtV)`|Ivp^)uZ3;*h;XbqiOsc4d=tjZn z>~-?;qqu0MA)YR3WxoVnvfgAgt?M3?A3HXM#SbKh|v>H!%lJM2a z2IwxYibG*O*?_lTc$S<6odWa;&AyaZ9;fYnjR3#&W0F@<#KdK1)T)So z(k2BWrtjb&r025|4aux4rFeF zcZaIi>2IHV)=Y?2gg+W}=lm?kO<7^Jo6$42D+KO(-{2H^~p^IpI{K!D#+Ex*Bve8un%)A03OaTb7)H1Z!{uU^neZ zpka8qo%vc$#O?_Yf-qAIwX_?S^n3`eLHNGd{oI&yx}fTFL2GtRyKL)Yr3pIMD7m%e z9l6s{vY$xtvUCbqQ}hzs+4dH(tZkOK?3OQY20>i+#?HWAy6`$3wQX=68W+0!X(dt5 zl5BCC`R&WqF3xR0_@$P!^gFK9ubOr{fLbeAU9@pxb2A4qhlaris-d(U!+=Y`(F)<> z&vBAiE}p+bF52FN^o41iMFnVuPT)T78kTZ;Qlupw<(Le}LUa zYlo7a0WG5YIU#uukMX!%%zmiDP8mZc=7fn$U21Y)nfs#!kp|>I!L^D06HFWR-Ll+x zJ2l*~Y=alqcgM_KRqgf9Uz)j5@67kbYw_CvaB2r~)9TZ$MErGg&DDd8Y_9!@MzG1t|^vbmQzt>$>zb3*rOddxQ}6@o%v`fWq_!)GxM*wRB*atzq+Wd1<+;&CD4KYRF*H zPHKoF<@lAA=4qXG@Gr0;WFYFH9fiuI7t7>$5)!uH?rRKNfLbMtTcMjow%I{`{b9CBc^A=<+11rlS&Dm%#5KgVgLAviZ{$UIoVs*0Ut!* zhPUm3n1s#yq%9|9L}tiN9XSD&&99W*LVN{r$=eQT69s|KCF7mXMWIdx(}fK z0HV=u76oU*^F#yGms+WG#F~tU5#s?20^0^Hh$S%~4*^`YKfDe3i+4QC84pYqLkpU! zkBO{t$gAPaCl^(-o-)WwvmJi!*tpni=IkvJIp`a=bpf!I1w}U8DgzrMp{I=UOM0IW z3NIPzkJU%lh;V+ym0tMbb%d+%(R=Uivm~jr&tx6$Bh%zyB_D*J`hSf*(7i$ zE9pYR?IX=RPtJY59Sq{{AR1xcqG92y4|*%zCMUr7sFiWybEiUKszp_=B=QYRDsfU5 zrlY+bqSV|E|M8B)ez@bP|GDGt*tHk7P?v_|% zx5J$PBsTLbfJe|Rk=4U@A0U#P{@yu~o&dxjqaf^v!ICUs>*OigDIfr4?#-b{pzKW- zF&DVF@%Cpvu~2?sD~3_y?oWK$A8dH_@HR1#67Zd201sOgmRYo8G_}pfvK)`*P@I|$ z+nQAw9?KIwWk?dIA!+0s|6x)6mOqd;Q0yJZ4%qb+xfBLeQ#1oc8gIQd8)1cF@T5j( zz%APfu5|1Y%5(?TFR>9`efR-CRsP|M*aPYzJI526#4hA`x(l~y+ALylW&{In=#pkAhp`nVUGh1|gkkgTo(_7BB zufEET2_e(ar-bJE1D>Ag=(PK)eLG@ONo*IP;GtPS)MScJL=tJ)^J{u+7vVXV-*mBnZX}qb08iD>kmaf`GK<=Qt{?XK;7P#3w(PLr z8rQ0!v=l4%rJ#Hp?PaAn#!cNj<`3jY59)3_eDK2SumaPRcFxuO*^HI;j0Oe$GYX8_ z3jegvE~3J~V`+9j!@J;;1c*+BcR10Qm7wA}4n5#`5+{_)Gvw@SHEfe8Vd~&Pc&{_Y z6sMld)*UK-*XrF<+xjntnZ=$E0-q>89kU%)>E@&TBtC?*Ez@Xc3Rka)l3Sck9GtBU zPbP{2<;>K@M)1vV*Imzzk8A@@b$HN`Ev~9!n{dC;sP;1Gvn~4{!@3=tMtrYBLkmDY`n2;I`)M2D%CZk|!+hpB5`0j})sza`6P2m@5i z_3?xnebjT?W{r#y5yd4D?l<;0DDj}eJ-m*k!mZ@gcg9~WhsGf6+OuB#3!ob*C$2#x3!&WcYSX_ z`_x$v^7~w6bO@ZL@@9O#mb7s<$VVn=Rk-pw>AXPF;L!(wEP|7mLec$)6N{^N4}MfU;OnmD}P z$bw?3IzI=YkUq=%F3#%RSfbIz!yV>u|2J^JFN1QqDeT= z`K;@cx7szNnTtK;d!P=!f@soA?KY2R8i9`}h$;$R#B7JuwPsl-nCh{vbq7AQ=^ni# zy&7N6Ss~&Sfc%7(PS6crD2y#feb@u3-)sGvck`X3_Ur(hqjO36())QbM-PknhqpFN z*{3&$82k?HM!$$2eb?W{sIz3rlN}!YLr1Y6P)yLDf8cK4XZhAA0K6u8tOCgI4?uTq z#CGXn)FEVP5^Tn!uoq1f>Ki>)|j21Uu3UbA{I z%bAm{`v6e@gS?sa0};a;n4mx|?|*;R5ib(glsz2)>f<qE zGH=P;$Zorz{mjQXs$tDPfzdzl06aHwQfprPZX~Lx>ZI#O1J>wse5YZrM{vKNyG4IMwVo(XRwxF9<3B8W6SmSYEYV-?`~UT?RS z_CW7b0s0!#hpsKVkpi+0(4$~d`>jGJB=d>RxAY;DZO1N+I*{Daw}Ct)RY2#?L&=9N z3yt;%*uMw=s(GNfc}z*Y+lHrCOf}>2@`F>U2^fW79?tBg>(4gDc07mGms{PX-)v?D zGGcX&ht7$vvb1TLl3u}u@R)fa@_E-$by) z+sTE&z@F!5k&7baIhf74FI2Wrmy2vbzOtNU+pT7FG;~^H>kQ@Hb9J&88dg zOdH8Jjh!yJ<lUg9+aqelv(B## zt8d-LK=G;HU(vZb`0rvU{hvP%Ker){(hnVfRSj0J?^pcBoMoc4BIdyh4_ik{^#{E@ zDkWx=pIy@%kzsIp{CV_xhV@fuz9IsakJ53!pgVN_1sz@ImBfq|{KKjXmc82Hn<%@l>o~pV=LI>_Wv~P2Z6LS& zXqCMchrpCQ?D8C~v6a(ZxnZ_c@{C%_##H(enL9G7VGtga%%hywm_!fK(mDyE15tcp z0>sZh$5(24_q$Pk4GHiU zAM@X-j?n#gJn6TSM=fd*g(cxch{GC0T+`%}c3${L+GOfyL2AmwdL zu$QhqK^;G3Jp@Uhb!t$>rNC^Y||I zZIJuDYw!xZlCm8be@~%P_x^mjb50T`_C_86a}{-V{q+FiH{`bbJf8IH`WgPMajDJ# zeOYe^1I(O3t{)icH)K3>2*&}QP7(%6paw$TWCgE#Kl>5)GAQB8&bvVrT6FmfUvgFD z+F#vOD(x`B)rbHH!}gf9K4Qq37qUj5&vnYj3+5ArsO}59N^jhvpm5V6?ps{>1rdj* zO0$)y0$5{*|I>Uc7!^@>?TplmONKJfJLWiOPq_hCYva9@^9cF~GD2JZUJes}bPx16 z)${TIn}PC0=zNi{5~o+Y_38!w+6L@6O+{r2362OFQN5INOvv*ps-z?=J0Ld8m0?u* zD#mS+#3>HVks@UKol{>w0)Qnktrbzs74Ya014g;08t6s1OQ)HtU5iS zGlYsv1>^`C`GBG_AJ-7_b6qI*syg`+%w9ujH`<2`gmW!aTMe*9@<}}6y9y00hs$y9YX%^4%!F*McnErriZXMIOiq69S1h z1w6s;z6B%VyHNl_VG2p52B8B`QGI{ay+AzHBBRjZ0RUHUG69%wNz7m(9pKu%(D?3- zR!t^{Z}J`{0c@%$@NzI}fOrWD+)U{c^{@@D8XykqM&N>>-wmQO%BVq3okV5rf!5?m zc{;m*XC@2z?j|dJHweKe7~1=eWfMVGhVDP8KTq2I2la;~zrUjPSJWR2=)URu|80-* z4<|AT8{E~ZqJhKVi4#GL^n z0zaa~5!k2*u|McVi@A28i6?TF%C3$e5%=<@tTLQNcP+l#ivMy$=Lh5>{MzZPxnJFfeVD-ciqM}>ly_CR)!Kz;AE4fO*fZ`5zK zI5>24(Nhx_SFWDVrTIfVeMuVgM`(e?0avoshW9?o$5`UJ|e6Nq9`G$sv%{WyW{8^XrhZ6x8HN{>akR3S5 zk26f^y=y?*7|JS$rzp^abv{^_2IvM9J!@3u3a#XxrYe80B^$GFS;Khx%t;~LEbidD zHe*1ZK=brpA;nOvcl-qlB4JmUn6NxSasjkddMuHh!T4J++$?~7h>oRUg|7kGn%4mH z@eexCzlcln&mQx=wyjqejCKgoLVg7F@L9Lp1AX}N2t0W6uQ1@~Ft~cCALs#}BpddQMLDN$Y z=PWa*pzQ@ShV;5zsQZ|oz^Z=wh4$v}K+gDBGSKgC{%$ucNyI>ZM6tW=ayAopD5c)( z1Q5t94uqDyfG4-2)1PfZn2eY#lhrS@0|d%f1C9r|ZaH&9MNN}^JapoKs#|CkE9{ib z(5f&-yzXIx{+H9$$-?wQ4Jc7p+A1u#8;PTv$JG4L-W{{8>=wd{e$ zb-vCt?188gZGlYE=4`~DbI||Se!~SkT>$vA4zo(2Q710ul44NPWv&QPD^MuP6ITWa zn^@EJGy=#z0G1r@Jds~Qj1>l;-!cTi28z~c?AZf(!Z0LtD_9MX_}E2&a3@88^YK)IqADsSmaIPu!p@nbmWjPjnS^U+i|1h@Hgs5sc=Fky(%W5 zfmJ8)ktsq&XoJ4eTi~mdwW9`QWNOov3tr$0?wQpilsK7xE0@Uj~2 zP{}JeP5ksdAW`zuV?g@@?cbyC=EVLy`pL5Tt4l;)JhYP4Hf=?WByyHRb^LnDy6`m) z8K$YY)#U@&r*(5}ZkUi${>DKjjkur<&TA2HGqC>7L<6)~eu0HT0k4N12_cO5uc6~M zX+zCwSXbpY<;~9^w9n>e@N6+* zl>((7;JCL6agLr>@GuLp#DK`YmDE^1|BDkiocm%#WUff$(N}h>R}O9`(2}BM#feY) zCUF)`Hg{*`dqm3w%}2JTSf^93RJ&=v-#FVi>2|3^pCp6#z>d@)Xgy_E{H5tXG^FeC ze*Ffww1_?_qIPB{)oG#WS#>pt;=W|K58^OU5DTsOgg2v); z#FA))co@pt^*-`ns0{`^p8St&%z1Kd-RA1~Q? z0RClS&9D+m{d#E-a-)g338$XgV2>YS>NaMfs4R@|!b& zenY1w5YuUGnf2IP5j%UXg{_?|4Fa+ZQ{O7{8fHpma(zEwigwReX&#}wSOpW&L& z!a*x{JCtxTAsxJn>(UN*Q* zx1lXiD$O2tj6RFnQ}Cig)ELJxMlFNZ5y7kds$TI^qhKJ?h=H6J1^l9&VV{`0{>D z4sKK4f^+nhc8=Rjx^$_&^H=kv0^s)N*@Sf zxE?*&XLp2XiHA+)$P;+$*hruI=Ew5Kx>enHMp_07c+9bqJ5Ehvoa6D`Gdgh7=~r7a ziot7k48$jRRrIO(%WWR@ukws)M|k|1qP|VpqU)*8bxZmB@PEX{hF6}Ns<0HQ63=*smF(>mgzZ#g-@Y;Eg}3Vzh3h4kfvH^yHC0l@ zQH!-#KNo+9JkCRZg(qA_ys`S~Y~JaI<-6S?cXdKKU&VF#F}31-8^^)e_Z>mb6~``4 z*{f!~#<)P1QaIZ16vhu62)BrI#Ssd;!Q2mdS;P7l00K!>6a!Sh-Fd!FMMd~^FVB`z zMVBG3ADq_{imUuEQd_>6kaRV7>X4(&TRY?{G>oFGiD|5_(IKkRsJ=)4Vse4AjfGOD zz}ve6b~%NMH%?#PcH*Hw=zehJ`t;UJX|t@br$AYPlr@5Ru3MG=`3-|PRnbe;AlvEa z?w21Gh1z^VJh;0aAur*S8WDcuM=M^{)f;mc6qg5(Y|5Dv%w$8^FD#`GzUYG;B|75O zFogP^4G6=qs`GhTc2R0UqrnYLy>5}FL9m?hbiYO9REBcSTFMjKUc9?c z=i9plD;Q`(29ag)Z!OR$Mk|LgT{Rmg?#ALzH&m5a&7~rlN@X|a6Hh&^qQ}poErN(o z(anXSI+{f#F93}MeK#BXFf#?t2ZmRc(xOEY?RHNrM_#U*apb~zzQ$c8GwrY+cvLAaQ}|KP2B!I;aO_}NZLYmb`q9_p8-us zGz=Sl>#O=cQ2WE*-}STNUkSz=x02P@fpi)2ErN6fkaDO6$ccZUmG*nM^#ABN_x`rh z-G7pU_2X;VceeJOtzYVFWs?jvKXqn#-B37Y4-}lu)pxo(s&?3U;*`}10lL<~9na{~%LHp%o^Wzy&y3D74{w71pj(z3Hm zdSfE3OvOuKm#!;xB2hOMstL!f0r?PE*JDqWqy(2tij81)T~&)_CbvwZBiIzi z<;hQq&h@0g9qefsPN-l`vQ8^#v1Yt;*-?f2jDm>yYd)i)+E*Wd-pl%y_A- zm|m&@(@T=?t-!={hfV!XDNRI#(MCqO-@gwo1yogJjAuH~?XjuVUxP9hGG|Rwnhx34 zoEmY{-pz51T{4~g%xi>mL1N->ip9ae4R%{M9v?3-Vx@XpQl{|2Pv*emO;E_!vsVWL z(I!hlbs4p9KXym~Rnb7@Qgl7@r3J{4{e0K0w^If?{jAC|q9;e^yxyHhUIqG%Lm@<= zDqk{#*Hs(of|=nJUNCL>nsiwT59P^rk(161@UemOQwXYgpb1x1657c2;?_Wy2xYY( zWBlD49g2!|6wC8*-%5+Ar1_DoTnLWEWE-lL(Jg#xUA7$8s3SQBKql$h+>+^Sv6kjIgH6Po`za|?% z0hKd;KrlnJ7=@E-m{GgzMI8b>+VnbAIdK=-`kw4^%44@Dx5KOW1bfLRKAkWa=ExuI z;Hm?^R=n}x?W!dEqy@;w{>aA(x=O7aPf>h8`a-AjR)L-|t@Ye)fUm0x#$MvIH~hr` zc5myAkuAN@6O%grLyYI0;9sxRm~IU^DAd$*!qayD;*!x7Y#mXk2X1vt-uhDG;g=xy|}@GDIx{#$K)+P8Ls(N6DjN5iO* z=dlQ1Y1OGVTVb%PcFQW#{P5O!nv9UXu|Yot)&=#uplNS}957dZe6vGI{@mBeVlOj< zQf}TEoTen`orcIiOMIVWHTfP_)gS}eF?>B>6)uS@39USVLHH-|$U<<8CL?$JxZ~Ma zDKd4w8F6^kY@7}r1*nuBO%sgF3kd2#>YQb|AzO>c2LWHXxh}SCzYDV$^_G)3q=SSH zLDqCk0Un$Jk{lrDl}He148ro)Jq~6pLp?lwKacQuinn+2zy@Q+{Rh&T870Z3nz>Ud z>RC_`IEQPNKHdTcR_}Wsx%@D{l6jzO6HJMXuAj7*1CdT1lmrbd*R<0~h~bSet2+=e zB!PAeF}H;rX?tqa?J1fvwm7`}MQ>0~(LBMDj!6@q8eL5hr3_-QE;$zyqg;{VwLuFE$Uk`*Tzy`@lm37`hZ31Raxr%tpP<7*acz`1H!9nU*8k zI;RmQ6c-Ho@~ziQ>)|3eosi)nqQ=Lu1>~db2(i%|ey+Sj-n!8(6k@xQ1SUiae;;(| zK48zf4fN-~e0X)XF|oGml@PR|vP2we1@%j~h<}S7JLAcjKbw ziwkd~El={;H*p56C3Rb?`iB;=?v>5Y{H&n4eFjwDKFbHO5d{zVGni} zDIDYuzhku?M}1q=0M%VvqqbIB74UQt@(gxD_MCok&ii@vW7a^HlKdkkkJIZ(H+YgloYZL_rTHOzYXO@ue7_1?oeeq%vBJ>S7){`GX>x+mFF}hlYkN`y&Q* zy zJq=&97>a%OKxT|$+@6Su9KjV;B_gP?D5qNjuq6(uO%G59&6 zTsN83_3Cy*T=GuUHTsbe-=bV09*jiIa&#-F{rh+9I`yzm1PES5`c9d|l`HjOLk!~h z0Xc%hLJ2MSdEpI{(~(HqY2&YRT*@7N@~BxOMu)rp6vLkfb_Uy@L?c@}@ly>67jejj za7J2^iOQzT^#ygI{_evMb?YFn__z!wJ?K=Xqa3aKY!GIvq2k&HH|Ae;mfdN!6C72& zM3vwjL)FWCNT-xsPd?T?Q_@d#b7E-qIy$9R^l-MtD1;|X$%N2ryK#sv9SR?~0u~5; zMm`}Q74fsH`1Rfctm&Gi&4#YyKK$Z&=0nw7k^AJ?kStK%`-zE^rhM$=<< zY7g|&xQ@S;1Yz5x;T1avwwgjf3XD8lL{>oRGc0ExY*R zQ0hPF^?q2lAJ+ZSunx(NCrmDOuoKS@TvofpW-uKpw49>xDoWLY;W0&-^I@ejrllvE znm+H?IlpGKG-Pt)q|lK1kO@Co@gm%fJXGHl!MBl?VcLAJ^@^=c0#-KoXYzr zZ72ONw({*q_JjwUdhe* zD1PmUwMW}f;``mE{PJtbD_s9u4jpF@^$yOp9t=XXb2Cx=6+6H5 z>t?D0n(w9~gLfMDKwBF4F$?h+%Fx3LE7ei7BlhVN3@xWjvAI39u)Oqo8SQTd4NqO% zIWo9iby%JrdODn!D2x+iHB0RrZ${9h`S+ z%9yxGsliopADB>Ia}OREi1J|fVj?^sDq!sbFSiO)J}M73S{S~aVZ6rI^`)VhSMlDt zF+X2+rn}10oC;ns*i|&rPxj;^#2}ox_)=EHHVZ@i`lvFcc=I5{8^pInsphFSg&Le_ zyjl`mBx72~*8X}+XZxPf1z2Hc8|$0am$HWUC`aDeHg~*Fm*%jNu(MDzYPHu&x?0)o zqG}pPim2kkOVzN22VO=oF7T(f<;uo$L@S4xK7Bq)d31rM>1#-9gyf#ycjV-txwHov;I&ktOy+8X(yHiuHaUBCTp`p$qeai83nwUYns0Z*YLV!ga zP%d28Ty&W8^e5G!vjtC{n1nlDexJg01g~_+k0;C#5K*t2qNJY6u^CBT7%(FpT84QL zkCR?is$#dBuD~zj6thf)w;a``4F*}w#@7{b468g253ZLMiob z!zS){TkrNq9uC`Fk87Kavw1UXQb{kQJpU^5Tch;#Tr?6rQfeGtu;n?-KCm1KXur8Y z35WE7p3ja0J&F0@^)M=9Pnj+_r$PoF?y!$>i{RUo6h@ECw8JMelxih-&ht1$)?`Ee z!Dp3Y=L5+f2!eCsXF3`a`1&53liO7)Lp&%1-i|*S=Q5fO6X4U~1+l+#S?s#~itFT% z=8GqGSkagBUxGv2QzpYtUR39>wjE>9uHc>HwIXQ%u*kV*;J~B9(YV<7<0|n#+Nuv4=WtEmPi{f&hJRL(E&Nl zH+}GW-hv0DYEwM~QlR7aq=50>Ty$;bn!aVR!zfEN`g#-VHN?bekAW8QB~loiYhJt? zQOhk@Tw&rCSeR*TPql5tb4El)esY&C=F9vZDBrHJb?Bg>rFK7!@~IW!`xit<1LL%( z=5PAeqX!B?1w96Nmp;l`h(_RBaVKggj&D|2BdJ{<4%EGJvE+i!NTkFqx*d|PJ*#!d z6l9(ky{^*@$uDUX4oINHdJXt_>U=zQb$4C&)eJY!-IJbWr=KwveoQ+dcnbX5`)b_m zD#}EiL&?r+_~GZ&4k`XqF^L_|xNWZl4w<}c21^QLhDnGW4p>sd(W#aWX!aNC3Wk6$ zEstX?4{i^K9=ev8MH8o)7m>5v>W7z=Mpm#xnDdat;nQY*I%exn3UcwprUgIK^LKzrx=OwFvj# zO|Jn!G$VPV-us`cdb|0aySya^P6ZZNIDKS(C`jt^mYNMeg-;@!!I#vJU+Jql!*(=BCQX!e?l;YQ}C04o2{&rbdMHRz8WU;!C(^PY8~BIS?4sT>_&5JLk~ zFCo;# zC>yaEJz-?3Jlm+70NdptgPB2gN`V@c3!szjo(5Z5!g&&rZj?6NBWuG35?W#~3H9Ln=a zGjfPAzt5^`W_FS4ko$m&F+Y|YtnA!}MPorvJup9ECvrfhY%K3I#X%9INsEF^Y+jl2j%9qvrM{t zEe#g|#g+G8e~ml(dmgjz3jeOI@Xrga{Ih%ezxw!nv;W^?_FKpjuKeT^tNv^=zKk9# z{S;3hf?B;kjBE#{jA8H1HGVb;4vx4N^1RseMch-Rbs#72!P100jHso;sT*{k32!YZ zeY@O$|EO@Jb1Y3&^GFIHxHAwoP}}SKe3Wx;+w?3?91zRDf1kN*V=HX?prG(YtMrx}o_f9~4>;k2Lpi;3UW#pi2`{qSS5HrS$Ubr;~~3FSNWG!^m>i zLP)nvbOXo$?SY;z6OT>ioT_!fH@>xGzbmrg7C6Qa>@?E?6QM4Q8ZhUR8EF6;QT!?J zhr*@b!dv?-$As)N!++21a9^$gv@h52lb-MY?%9a9+v>yWj6C6hG!^H~s9nAHz@^%0 zT7CUS{VtDpcy`QA6AaM&Kkj+nZYuGxwd{$~MlpUBuF$v1wj`1JNZJVb@sBP)yEKvorDi`PXmNa0OMTg^of5{cuNMWL*xb| zm(Jm2zIxbJD%qRgRRj;&1cd=8|LeNmi^#95bdPkZcyW~R=r)OmvvtNh^!A;I?Uu);g z9=}9Eg&DX$pq8{omFxA4a0<^)aKap(2(dLCvq3MKeq)dzXmvj78C-s$>=o7n%V1jX zSgM&s;^nJOSmt+dwzk>F-}MZ0X$L)bpS+&oFc=M!*BLVJm5Di$i-c9;@T5 zr~cJZ;J;(MeN_5)N2T{gDfYeL-`C>u8+I*K$|q0ET@79>>a|HLdgEpK=H?X{tm}4; z{&_Lyhg6dtfgAi2N3D0m1DxqY;;$?i=($!4o?vR;l4#zfEFrVuufsT9S8rh7-Csgg zD7-^zm8d5?sYU<5{2 z{$;j=k|{#Q+N;3JBZ}PNR}57yar)gky(@`~@IOYf8#jsoUo3Y4`v`4Sh%Y?z${kWEik5vDnf8DpK6KLs{`DnzxzUAHo>Y)cqg`EB(gE6#1=C8vCe*0|Xsb_hz7Vl2%8~-(jS*A; zKi9S!g*^jseEnvz2(te&fYKghF6+SGpYTDg?;wHC8$yWTO2mtHHLxAxz#a%I1STtG zBL>Q$t$0L@FoD^qJ)F#v2=EbiPZc7GNA#g+HzL4?OscpE0KR^?PUMr~lSm>NU~A)9 zfD>|e0j$YWSRFC~5OpWg0_As+bAZ|h@FNTW$A_SK=A*#tpNx_6lksPvXkR$Z9;jmm z1!NHI5oiDx{c3#lmJnt0hITT#QI#d+zdIcf148qhs!z0D2U#48v&q#Uc1A8W1fF}Wc>jO$1Vuf zfdrfy;Ih-te(O5?7=z4Epc6qvvC34)FF#(4{Hvkw%>Bv*%KVLAL#yth!Ru)U_rBS` z+>X6D`*#<0Z=L;ebM5WTe~X6fS&cnQyLUS6otwXaF?;9c-nsd|5YrBtdRvlopG_(t zx#qK?u55j8(&_OMcQ2KXMCD(RaB0uA$0-T;sYQb+hcq}Q1qFwe8>Y^|MY}DE-E5nS))zthXm?;^F2kdpiZ`-`g-BKQxm6lkI~O$ zMYLj4hAG5e7oNuEZAi^hrXN$cCcxAZjJmh>n}xkRetzjpjlVOel9M2Db6?E|k|m-3 z3zFj$>pbk?h@Rn?M6zq}ioubr>o;36$t~K9iE9A&V`coj!b!>==>$>4fJ8u z5LSyMhui2Y37#q^*k`dNw}&6#3?76&d_knAnVu&vK`Xc*ry5dJ`S_Glp&@|eG=8oi zVd4a=Lp(~3bcTE!V2E6W9HW@9{@B@wn4<-2=@Hw_EJeD-sn^#W#a&0w0|8bO(hW0X=P^zbiLnh=Z5Fmc|$xd?eufB#BYg z$uW7QHT9#zuELhwgHF33@$cZVG9!B6T2Mj%hS6@m)qW^XkMPxi+b1W{M6ozunIKxTyxzMj3cM|CQNgoJ$Ma1qoHU z?}E(VBR7U^H%?=eHsISzBbc4#r@Nr+9{3v${A4cDh#P%H%q)%}>o?t-*leTRH_rK@%lsB7^3NBIxklSBDu zrT2)&5U^qIycuyUu*Qn0jw8wT-7mf=wu0OF?(S5^>2AI+t>L4VDC#>VsRvOQ?wVxv zuJEjR^sHX2560bcKeBRzKUXxF3qIHtr``1GUZ)IO=aLP6cB>g7(MMDE_|BVXSsAaS z*rE)pe)Z7CSBdl3-Do01yvm(14{s(UM`9!&BAc}|F(C2>0%+aJ`=chgYB8*jen1jEZJrFr zC2-$!dU)7ZvMQ7Znwhk*7XIYJ;Oh=0S>!-;pkPd%RyI_%|B0enrty#AJ85=lZyZj1 z1^?j7KW_bfVoiak4;=%wL~$vXf7-JFsHUGhcBTng3JXwFxU_z% z$GW@gSTM46G}8-K?Scf|XS%8% zAac9ZI7qt0Q-9(j{X?+dANlubS;6!o=|vA8_1w?ndW>%SGFiOITZmBBoVHKTNYu45 zSY&0`ZY~BBY{G+4`7r?rysJjG@|a=w-7+0V^7=M!qA>+qRe_mlN5oNFkr4$yg<*y+ z{nA$hcPeqwblg^Hm3MYQ3&jKTY6!1+%$ipja&veNz_HnwtD?9I$YxXlrPD3pOEus- z{YlQ=uMu|KmfEix!il6q?*RwKl|L(<@ZY&Ea(7R6<-ap;zsF~sAxDwZR|%3-KS_X1 zp*qlp{RpOn@&m=^|G%zEAM`)}{eRJcTyz3+WEa#*tq1(stX)u#C~Q0q4-Z04(*Oqe z`)**n#TCqX0#iUyAe&eh>Ky|DI@^ek~c-Oi8nj!2I|DsC9SM z)lkvCHGIg{S&tD~O$nOHC%QUJoeDyZT2fuqn`R+RKv)6x*)iZ3WsiF$_kU{n-JTrE zKP~?JUF;;ui&#pntl>nom9}S^zac;)ByMXk1})7QrwI>QSyd(5hItJ7eAj*JJ#+iL ziEHL{*N1Pk%wt7_3tGs5p%mV3Hh}*-rq%a_~sL_!ZYX3Z(Ce0 zDHEJv?VHqlyFs5WgN#DqjU`9 zt|vF%13et_unB2$%RaXdpUR5L-jG|>5W*gnG$v}gIR(rwO!7)M8>C#1GARD^`MXTf z*}kOVcD_%V?)&?f?R&0gU*JC!(KpJL<*4(cvtEZ26IH`Uf;Br|5r;QC6HG0TW^z9m zv03%>72{`fQfGT9B-g&`cbG@wXRf!OO8NBU+PP!&m6v(--^hpRMX9;n z%8u38gsS9bgf^uAC+8KtG8xwGQs=K%T~>VYL3)}&l$-pN6L;fnKtHRf4!gnK15{g` zlcb%)C?RbyBteWH)W#t+0m)GU<+0^CyS!OgSll12%F$OrjlaP5x-9O3Upl9SigQO_ z1j2?kh{bDz57NHE4+xR6GCex=1|;tHzFShu>U(>;$!PwAc=?G)m;*h>;=K`(-`LuU(D`XyygsOeZ{Rc3A!#a# z?}AiP0m|k+pcCI@!P+ipN{+%7_65R46DGw@x;96-cF0aOl&vjF4JUip$BR6?Y!#_) z+>V zTWA`&$zKf>e)~`7G5rnijB!S;K5ARBlNUMAUjhit2l$ZTbl#VMko{Le8P&%YzH-0(5uZ6_siftRPop8i0xJ2{I^>Ou4ipcNuN z0==#@4Bxi_e7ZdBmqYwvkN>(gHf)RoU!6cf%|-#~Kv|%O@kzEX^+iUg$nQ~={YQ;K zw)7h-U{sU5~vrKoK!0;_I|Bl9+T14_>d5s1Xi6BIOXr}jPskobQ@dA_L z=MFC}3MZ_AixaRL5Zq^zI2j!dfwj0xhvVJck6+(p$Tn)u52Xr{SaHl?I&TiVq`yl` z!)+U7{vNvz7uMxRa$e7!Fc~fSxYCfc`9@Bap#vOhKd`1Qb!YPlQT-htyEC0Cv<}!2 zhWpf46vzZ*2{p`!n@vhGFrCeC={!0#d^#&<d}YRP50q`lp9qUbMyQ13iJjkr2FrPKX?qOIh*28=hY5_5NUn>0-*VfVFeDb#`Hn zB5MthmK|){ONELm`L?I!1|RlpBu5GFyzB|qq+6t8ELD3}R)-oHAR3YC^J>#cW=+KY zr0Vuy+=u>C30m*2t!Iw@+{T%*^FXh9HJ)GoiY<=myC_9pW2O79KS@iu$OtEZY-CHo+88 zlzg6%XUbB!T#W3bknc;&qYiZ6iaBI(Co^4VWO%9(XLZ#(rq3SbVxygrRH2L{tS;-5 zjRs#$B_5MObp2<3|@XmwLs_D^3FI;VD`yzWt@5p%-rL-VIGEOI$2GJnE z)d@xka{f4zBrTiwoT9>wm9M9<0?AjGog$q&wKFgPhH=0Sk|&fu;zuT}mpPm=bRd!9 z8&Rb`pLmD5xh2HoFX^e5VQ1K9^7HC^2U{6JgaBzOebOmHC$X)#tA-`J=;>REFkb2F zfcqBH>(W54As*Pl6z1e1dRG3mYZqodGqOFCzDQ9r74bF7mlj2@xy`jvFSiOna4*?Gj*cVng8Aqypq9DuLrOS3Mcgw)EXK!(4Ik&BLtLu z`&9ed2KKSl(i?YRc5U*rfz&-u!P65*w9ngysXTU!@#TW+h;jMdZ1TF6zP5ztu=l z3wJ>e(Lpt5D)CX_HK*rIAAY<$BC$0687l@3UwV1cE|Ssk(!EjGB;aY(6SgMiUI2{3 z49Icia~`pcZanTUHb;CAN(x4)sdg)-Q+h=)Cxh&@HzE=}YJo<{u>=V1&=6VFTc1!` zNMLNV;H{z!4M?!`QQ|A&`l_5qq1f1V6WM~xGo`+VTAMV`EzqGUqBcpAz)oBy<>1dW z^4N{ij^f|(^d{LAyBDcR+gTxP9F8o+`PZC@d)_*ok`}je*NAJdwFvkmSxU6x7y9?57~YWReobdo&4B>^9Y zJIhwvw@|^M#yKHE&--so-=3dW6%{?~cW}Z_o+l>X*w|#jO?LQUD$~gD@YR0q{+yAi6&9bY0E z>;za-{O`a6F;9>~$R_2JJyoK(sNfyJHwBLeE)1KPs)>5Wc8V}XXW!oUwE-m6nvdj% zS|WYn#gWxHq|C|eAf=VUY*QaU=1Q}nWxnAMe#4LkZH_n#b*q*ZG0$3bgU+xu4pkd9 zSU|**G@s&l%{t`jlFVyDCL^>gY#ipqIrH2;6(jD6X@rjL%f8aG9An#8i*wu@IPE-F zCRGQn`{XWo2S|A3*LC^`oOk`p| zq61vBzoQYSYCWZ$J)JwU2gesV^Jw2cm-*dz3-?I;vDR)v&{_dd(GBm5$uGa{!8!q-Hr&|lF*4n#%*bg7Jd<;S=z z9u>*bSzoQ)Wad$9Vn`d2suaCiX1wnJ`NG&ItL+g1yDJ^29$70jiRp8>0x^!D6CI9| z_q3%-xXpR>oo&aB9>8Em{YKs67B^p-eTfkG)K<$TtrGvx(l;N}D&z~?ZT?+Qtp>1w z!JtL91u2hCvfBz<`{{Y3Sa<_dij!l$I2O8e1Ka+y#E-W|jB+37&mKu}FQ=v<_Kzzk zlKqcV^X+Mc-CYh zNp@P%`IMEbQm_CIDQXh1pGe|OQq z-a5YazG}-foM1iB?corJW6Z_7vmMwBRG1K&AiyYRS~ono_t z`TE&g7zodQNk=y#N#YPnEHV&FN)~aEibZ8Qv;tPZ7 zv4NjNNCA_BCd;!-XYC}K-4lq>-20`wKR=q-&(T)Nx5PAjZ(h4ZO`G?VwG7AC&H~y6 zL@x$Zvyat*pwnc;qqeR-E0~hJvO1(Q2DK_P5j1qbJ-nSW;2#wSqcPQ!PnKYZBD3DV zL$2dp61~wa7l4W4L#INmI!R~yV<(j)z+upm;+^>NNhOb6&?61pwtZG`gZ0_1$8t<{ zvt|h`)@m*Xo!{S?27gaP-op&>*vXMaXdEP$E3k)~r6S4~qBa-no{(2NtDmt2?u(s{ zeT8y;P;*_RKR&-@Rrx5Q8%~cKUyfmrnJY5rV9qwHL@ zR{(;Y)(6FF+0?KNLz|<94(x)AdSsw1P-1w}VHlg1E0bEgR`#fMr#Rc%_m*zyuu9w5 z;E@$D30MouF1w%-p}Or!f^H;~&qMc3N&ky`mYOXyEYlXvJQKnRmSUml=UQ?=qQczw z&%01jW%X@@A3g)QIKy>kt;aqD3u}VZlw=*o-;FZ~)hKz)riQx=6P;0PyWL>tI8W!q ztpl#x|S~&J9mj$t4l%1f3-2yu!1-qc7NnA0;|} z^0fJUUNQF!N2BJ@I@;FD)81BeWNdW$F0~x_z$3B0jnpUsrU2 zN!+o@mmJqM6hRC~X$)R>b;x0&Y^glYTdaZv%Neuz_+vo6a`F1?nr%mWPHEcxa{^+p zM`^c~e?-rVb|FL&U8rJ7$}!j^!@w8pP)6I2t0XUGyI!=_!&0)=M+HPz-nYcH^d}IB zE;;Fx6}IzCY4vRjy)Vvn#ol(W1kMqkd)ZTG(a}4xQ@{xVBD9 zMR@+24X}?H_}2k0bcHC+ zOL8090io3Z7I|Yxi;jFq?U>&0nOFRKk43+`Cwuxwt)E|C=YKytfSwRVV^-N8fltOQ zw?HbR8eqcBU1?pxkYIgyA@qpDL?6&P8g5Xc@TRJ(m>k@4xlPl7SETd%KpO^s8|k}) zYTgA6p-sOl%GnQCoWfHG9{w6-YNK21L+`=_nB)`U$4v}DKLoohRDlr37iyLZDipha z3BhIy)8GnM<{uIFH*Ik``z@OFkga3rv*1^SRle3XYC`F&@&f4EIynk1a}& zR4N{xtf-D^hmgcN!zDL5{b>jAhQ)yjK3*1SYtu&#hh^6W=+nNDUp73;PwU(9!9#I1 zvG^by_yvOZ(TBIPJ4a&eo{$esB!POr<`14VOEaaK_{J+c*1we&n(s0yh4ZFv#RVVW!zwOZdJwkCnm*6M> zXWt}1NoNhtHUEMbLb;_bS=^v<6w++sx$Hd4A>rv;Ed_ zMX&rf_doC&=mLbtmmPplmk}Ij4TWC2pc`55#h?Vs#fThy(KMVSU`Qx|jcjzI(cFf7mq;O(2pW`~_kf+Q{Vo#>VX<}l^~ry($Xx!x{^ zuZY`D-cC=;AsaPJAn0XE=}Cr|`kiRA$*4SXGQbjvclk?`2gE*LNvl!7nUq_=2mQTy zNnVqjiP9L>`Ef{(B+roFE%B9-!mF2MFC6A5{aAZ)f{4cEQ{EIHy;hOUpyyQ|2L80Nr*6b+bOKq#x++J!gJ%c z!GP%qBz3$c1xRHJ;`+#3(*`Y zJ>$IfEs8wifQOft%w6m2LlCs+dgjC_N7M)n8ZR#UZS?2^PRDk>f!H|Ogc_?gc@6!h z;qI|CK_=d@BPG?z<>Sa&X^L5{M5gfQ4K)He-CM)H3mVMILe2-EvkLfh2sw+ppo=&>kcSuD z=ZE0{0)WNHH7y!1a?p7fvh(!+1ZK?&!hx^}bG=5p zjTV6$Z^v?soBBr%`{o)}pLPb{NpVFl^kYz{VLwfsA%7avJsdV-T;ii9>Hz7B*`3iU z{GoJXt70BQ0?5BY^FHTv?skn8q_MLwR%Tf+snW^K{M#K^9V&4Ng5QA#A~&>Uu#_XE zz;Xqu7=pSeQh>+q1n?^+T+4Pr>~J(Ef(y_8#)g3!82$Fn@Mu%4s zB*?6-QrNMR@ge!ZT~aCO(EsAb{;1{zDZuXis~!n%^TOz6;>++S+fIBhIj+i|YJLju zf>2H&fIMj?OQ9QMuiY5YAxWTWJ)A=6uQ@QchIQ{McU&bgOlY)=FQT&{~# zcq(cyX(`+Ds&q{jAXKbr$Koq#%&Jck5>We}OrJIKiehcLu}GgP%m$UGJ|js1nUjGp zPC7o}kofph%L zf($v@;{7?hySZvgN~>SzvJ*;@f2OH_p3ND5ZcmH9$Mq@Mzj1jcB!A-=VLWiyt>b{N z$x0{>BD@B&aVvbkB(m?7CjQA~jL<#h@x9dl-%S03(2Y?eT*Q;4)Co+8B{7d0$=uO(KBjh`FEJ=-pob5<3vM0#F}dHNmXs6^ic_yw3D z0DyMSAn83E8q!Yp5^1xduhV<%fb6mTQ?YId=+N_mje#Z<6M~C!!vG#^arArDt<%TD z7kBJR2s&H02<7m4jy4jU=txCXvHNi5;Uojck9DKdeF)~m^Zn7IP2&aU!@k~et9LSY zV14e8*zLZQ7I-JlC9g@BtkO_w@bqYff#?_sQ! z%rqk%xaO4wzsnpgj~^HHkenEcjQ$#X{i{@yslW~_!W$@K@%w0tISQQ|N3t3ma-^sGkqnQABA9-`sGO0(L(uV~*OM`P12-G) zW^89_lnqrMoX+2Hh5~W7yAFf!1}IZW0cx0iYANS7DfV4Rc1dXxytp;nr_AYd(&Up5 zF+|51W4~*UjqM*kE!%Vs6%Aq!N%bUaB=z|D&8XwR%Rus%0n)XpBs3Yd)DEeq-t3o49wNCGXNGs*2&If0L7iIGGCoD(Ws+U-)5Z$nz~YSO&tX$(iF^ zx2|0SS2nCkX$@XxDHlJza#A>U_RF+&)B=C#Y9#bXE}2VRizbBe2{-3nfBF=$kNzdN z5CQ#(dXVAK3kqNS?y+2~Qz z+wb*_=vO9`!pcYiZtjIhWM-&v;f2qyVR_4^ju>tAPj_ceyc?^-?8DgVfV^#}QM(}9 zL?GQ7kR)9(7a)_!GM;-TVkU4bJK{d3q)M3kO{BBpV9v>Nm2~Zbyj%TA^D$@CPXiF} zV)RRu#e*AJ{*ChN_5)fb@8?}@)(ar7l!3$Fua?$fnik8^9OB||>`_uw{9$5&4a4+R z?H|Wl9kT|y(k``baLidK0Pk!iK~m)=w(7@h&3gqM&W&w`-2W8b;=ynaun?NDUGCR) za?#z()<@3RuJF;r-7GM$#UyoZ^C0+48l}>u} zx&FkNTcsbxH_u;Bq}b++Oc>=SBVgY?@nil!(XXp3F8AcuTH;AF4VXP*GsEeT%H~Lv;jH)|Z zS0mwgLpYQ7F;dYq_CV;tE+{_wde@Cx+LzS@?DdWuuwAR1 zDqF_9^){#G(@r3|i2Us3J^DL5yJ zVTr2m>X$AlsS%=Gm&&~CAo+!I2|(`s9!Oe<%qk6R35b=R+rat*WNJI+No+$W3k6`J zAPTMJf;Sb+W$f)rj@6Jal{;}KPMSSxjXYhOGWTK>TkpTKsb(dn&6*v@3nf6;MD+9e z;l2Q7o8v_VBTG7$?h&5igc=j5?|`Hqx;Q(N7$Ui84%XJWxX7FM$zHIutd>i5fLqzM z^myQXLz5$C#z-c>CJV+Ni)VgIamTwArvKs!`# z*b>zf8KHa#@b9CZ60yPj4EVX=6~ARJp6obVclju_c;lhw3AJa@&H8x^hYcDTYaLD$JhjU?W!H@CghIW%G~pj< zM@aN|DcthnW5fZH4=#dfN11J{UZccs9y#(L9LP^c!QSh8EE;4?1q387j$zwBcyVit zXJTIZGSC@-Kws$7Ia(-J2rdW^UNYGGsZ2nB9wca^vP0|LyI7x&w&82tuQM!G$c{C$ z6+5EsMm0IA&?6`svmvg}&5)$yeMNv}c>3I`dvI$tb1Ov^IeZ3z=X2KptbyU7zQ4-y;&ZssuUJ}2YR~K18?xaN8=;rpN0AeTG z3qO@{8Em?g*(d_|pn4G+kNKjrhoyRP_b@@`Re-f@*NgT254+k9G&y~q>aQ-VhvH43 zV2?11kKdc??Cw-=Hrzfv^f<)x^2JN~pIB|V-Iz3(cm;efeN$i7;*e^(Cor0N0=|XX zX3@(no}=umvL!wzHQM5taa_U5V&n4z6%_fyjtYaucePHYJ;IF|`>{!1bZ|epd_|kZ zOPpi2HcMdoeZ<)Eo1bn5_#GZd`?A?$Dg4cVimxGoak-N0zJMvg26{{3$Ph*yTp*rG zZJg4SNH5E{r+8oKjnP53DeiAtNP}Kjq5AoHy`(%QS=*lz;HjH;wrz$43Ema9LxZ54IKdBX36Zo)#os9&mveoV@VB-vN` zM%L@Kcrr1Xnva=C8TjaZnzW9)OwpYX^-N+BT)NTDqZWglG|N5qXgZA1eJGo*=Q;Vk znonj9vK9#XS$S0}*`uF$n^-y(bC$$v`>C^x9*A6c8Fkgzhw&y=rB`}P0rn|DtFQ20 zb#bbjrh^kt`>{~3i2j(XKB^uSgaPBc9Oy{!>-bSUAJRsI@_3`!;>id)ifvJDUPRV$c^8pk zss)+`>JyRkY!O{IBLX#oelI<2iT6owgz8x|zdWlcd&-hkJz^2|dTBY!EMQd8udC$& z^OnhHx>^e-c$PHm#G#&Ww2@+a$&!tXVD*6Iwl=j4YDeWI7FFR{#-nkXXdn(z$0eI3 z7WUL50ct~bDmp20BlaQoQ%Y>g3V#Z<@3(7~9HsV5|Lghg7dCB?(bd&+1Jn0&d$mf$ zDNzl}U>dUwZrReXq`SG!++=*wc=B3NpJhdA*oXZBSNoVtyKm+~FMymzb49K(wJeVlUsimv8-DYdn9CTrBJv;f2ZzuOu(EgSk`+L8>XD9y=Y~1hh z9rx_yKfayp-@}u-YJZCF{SRX&{bm=3+lI~BTlEf}ydGm>bvHOTQ|xOq2y|HhFTC%W z=mazrS#}^c2VNG40NY^j(TifVo7h`uqW-B%4HpE@rp);|hw5n6RnFT~Y%&2p3W1YOXPH%tcoAfo+i;Rh) z&~NSwr2s{>f%F6+Di{z6n>dD|AfiZjp=`+Sn_wCpki~9Z*aa0x(hvv;UiAldjDnni z{qU)Vw-7n zJI~b+0PFs*-}Re8_Aa$Ifl&4Tcb5f$8lZ^GiBh;mm}Zt=%V|r)qPAkx&#dLgdccW8 zBuQFw*5d?a;hywX4_wM(*DJoMmU3N3Myj)J6#P!UW8byv)||Dn?KnP{XPKK9LrI!A z$>nk!hSfqH*BR=jiHp#8k0myW6AvU@I(=n3W^^v<^`}Tp`GGNAO+Lcg?-i|lq1-2K zoNK$TvfokV1dE49%2`vknf!OIb#EV{IhB8_NWCT*2H~a9;T^QN(!{C-*B*%5=9tl) z9cxm^f532S)BRj^QJN@D6g7N?_?oofC5ys4T=jw60?#BaM?Y}oj~O3j2;k+z?UT#4 z?W&#e2-m4*uo`>a*Kn0bsk1j06EOw1X)N^BrJ-yt{k%FJh6tE8fVNPS61CL_$RU1D6`dE@HxK;RCTJogMx+K>dOUlthK#zaRtvTK^)1vJWWRkLsem!)$MpkhNem(j8!l z`6AMF;lMz@e%o)xSp>?YP^civ(Y>qf&E&r>roC12n;H1^M*0u;8y5d1?JOTU@=ePE zE#TxXXn3QU8VyKiz!`yVQ6Avt{7%T%Goi$ly6Z%cLpYV&H!tCE+pqzEf+8#vj8VC- zU^9hf%k1P^-ptiOI;7V0nvdC>gF@wM5rap%EJgwYM)+{`WqBN14t2-~8i>@IU4ngq zzESmD)!b&_q`JF9+EU`FSVf1c?IV{btHK|`g6q9{VCG#tnyiQBqs)OSv2U_}r9>$b z)6U0Q)g#}`_t<1Cm?{5&h5#OPLd#o(U`rgu&jmRM;IVa;X9>!Am2G58d-A?EZBV$N zz~{?TGv{*r-u3ka))}HDOm9wWzrBkV^chn_nAGDOMy#iCFZ?VT! zM_Nkt9j^e>kpJ|@!V^RtLb;bQwUD%SAhFzGOvkB{+7(>9)1-Q#2i^ChX>BA#xrEM+|&{AAwG< zD*_59aMJ-=B*)e=f>4iHxj?HpGxZca^|Ry4=%uT_5CGrn`10q(kN!1|kK9u+{!`+2 zKj;4+BZjw+H!N8EWX$5?wZP-LZ(}r$pF1twE_Go7bU;Iq4jzYON1XLoC87cEj&cqi z5U@-Uu@hXFv+HVhj4tI_oPQpD5W1ML*t|btnt_NK37X8B^~Y6$0}%Xfv~I$sb;Ipp9Pq*W$g(nkOE6x2gV_ptRR zp(plYo@mF6&>jEZmEE>Yp3+&Gn}CPAT^u$4Qehp;alxU$ES+r{9A~ZjTpH1_PPb*^ zMR|^Qm|Ts3K3oMv#p>coO=e_JOP;OslDSwz&U7005joQv2%z-8T`D%>xcFMkk6Y2|oq`7*lqzQ!9@ibJOH1rj7Glw^mebDoUh&k?yJg4K z#9Z~w;dgZV`TW3FS>$U(s3A15&M5~_$3(wQw}BmcvwH_KRDEInp+(un-AkuAYZxmHDH8-_=zR8jL0 zN`No~Th+ZovGqw}A*W3>+K%bfed{^F-$n-5%=X-IbdOwRMgzBRQ^%z4y* z)aIGmJ6R*QmNS9l<1(Sb-(8qOLG<(I=0QMJ(Fq1|pJ5HrGcAD2@%k@fDZgl|^FMih z%vD@UyZ?z$_okPz!;_WU%`(*uwqkmx7P*ffRqut(t~P^*3QS45xyU*kiB+j1X(7`7 z{gYGoyN7bg-6|=GC!4%mP;OjM&x>3ebuWFdgHLwb$UJ29MSO$vZ(t*8I3HH94tqpt z8fa;EX>%0Sjb1&}`D)tvvM^SpW!P-Kjgm$xN*_nGVfie0(*aQiOo zTkAQo?`7SMqPm##Py%BYYa&H&J#5JWGbMRiAoiw>JzO~qG z^3t&C*7Ae>o;oq?XGq}I9ZNV5Vqh0^K%92UgU#Xi!g(<1hN2Afw|AMd&<0 z*Hg2TdeGZxk!+QS>8N~ws=Mu9^-IF;o_57QNn7nb5x;*0zkl@4e+2yZmmiu4}NOkwIfS^AW3c)6qI)w?4{hBV@JHy&lUDmNt%ui?Fw z*-4O$Z@0z!E4mlUSg5Ot%VGF6HfXcV3-)V(3=zC!sqB z(d@w|vjQ*=F)fR=l?ETTHjnAT4?nB@*$oLEKQ0a|EW-rWi&_Xc?b{bPZ4kq1pFNX-JbEK>4nnvPazHtBa0k}qIL(e0Q4XGL z!Z@AT=mt6?eNz1LcbKz(r8&`Y8}?@Uw$<&!6`c1p2D#ulFIP!fkX|$g771(53M~?nt0_fK}eV zwj)VNTgFn|%7N~mHt6r6q+4*p9016r#kq#e;$Q#vzxz*gz!GM97bK0` z*)9XVnUzl$oOuY@N&{5YHrE}1(0tn?@Ze41jFM*XfCX zWMIq~ftmJs6llNu2;C!3`AQ83R7lFauL643a?l-9(T#5yy`Z`%x)s1g-1hs6qw+Vh zV<6?wZL%S?0BFym#kNIO&?DvH4!&3Ac+^y4bL#pD)um`Z*7-rS0UjMy#XMDbVH2~T z6n2wv00ohB%^I)w+~gtOnm?01UBtMpZ=g>o@BUR-M%hu@ZC z8M~AY?&A52dRxA#eoth&%X3%8kr(hsvNiX&C)wP#(=6Pdj5RG;D&A%o{=X1;gGxbd zklPBFK&%%1E=W5Twm?PPMRf0i*4&XSHA#%LR6%sl&Nly9nt&4b!d=8qNpSDh(Vu1) z;qy~e2s5pLM^giUcJf_?h6t&L zZwviwWB5TZbr1XH@&Y{x{zVEl0pKL0@24?x+%&o01p< zXN3ifUA1nGcU!Bba73DL4D#{WFwM~a zQ77j8gC<7v&*@;}j6BmtQ`e;}*;3f;J6aDWMPE-wo8z427@`eg!c`a<8TtB#LBjd4 zq_otW<6O5Z{CdZ3mf{b+HKq)q6fCtG?4SAv@Fi7V`JWm^K3D^4Tgc)ZFbxu!z%;DE znvr-N)Ha(p4CpywjNG_^{-_MlL0aVrFzRzx2vsPi=BHkfH;_h+odm>o>jBA3HIMC8 za!L(6vF8Qt98?9sKP0Jvzhr|cU#LmY=@ps)RR*Z`kynN1Y;Hd%OCwvyC>lG!9olgT ztVs^Ugg~!3PSqSkBzCEBY&IwT+fiz$qLWMIeG!;HF zjDp${&(sBkUKwIZNrBBr{Eti}$9D2m=QdQFo>sYl+0lY$8~*hR zcSx8Coi3VM529d zGxOQ9g3+^CfhY&@zP^T>CyupD3DJW@!`m9lewc#;x}+XJ7E6Ov_-=kjxx{?}>r3OT zV%3-~P(QmCQvSB1k=!Wx+8xtD;L>#*6p`EKbW~8@nSF-EQZpSR(W? zI5YkD6_45H0Fn9&HA33%tn|n#qxp}gFAi=E>@@C-wx|coH5C{j?gqS$L?pLjp))AJA+)VJ{sR62B}yccqBqXuRaHrYk>E&YwI${hBLL zXot4T`cxevA-=+z5ieq(=zM+Z@VlH-anEZR{e(Y2P#C;sPBg|6dhlI%qaNAh;Gqdg z;)^-@?+;=(I}k7WxdOc_RJ#V)PA@==yY)HIC6Y zA&0@wDyxe=Jb&*n7dp&A?!JXP>Z5s7#Lj-%AziaTB=d8i%BvW`BjHMk8V4|EiZLXC z@u0~>eHe*Mux+f7?MoJ0t36#uFQ+?eL9J2eUVSC>9hTyK7dWhaJWzmIe@z}?gs4dh zn-o{j!)Lu6PNgO1Y95YowX#=iC04Pj9`n1@`_b=_fXTio1wg%x{9Mg@nJnV%fE+$E zAsJ9}Zfr!&I(PAQ$AL_{LxPu9pUirBhFZUjkw)AX5y=0%KjtDLB%2N{Oaj_m$&u6v zkg3w=TiguHQs%CVFToODx6lOm>2BVEzMLQV4S zp&P5A<7e@=jCh;}PsrV}ww1Gr*HFZVDJodq6C4n7n^9W`r3{e5@VrgfPf^QIvf?AW zw;@3;%+A|tiuqVYDA6-L;(kf*6V^;&iL)l0hM!OQJ3WtldILN!7%B{WyBJO`c7UCa zl{rpn9@+&RyxCml)YSR0f$X$UIoo_|y}zc3nhT)sLVe=PZkH2Mw@3kK4`wo_S4hhI z*Kzat)Z29OVjto!JfRMat*s(1w@|c$h%)`w)QTJ`ifb~m0#Hah+S?h*bh+0=E5CI* zYU5=s!l!&4+;$<-;|fyK05%P$$YUEJ8;&)A=TLJN@Dvtzl8F}77+2&_vuS@xg!&{h znBtsNl5ZxSmjAW%!!bwNlLPW|CRDCt(=It2k)i?S<+JYRjfnSc2nw;@BQ-+9G^2^fWK>kDj0 zz(SFlZ(pLrN1C&^R^7Y&UWPX~y(CHHbJM!&>Crp4(gR|yC)_*3^qDu=>t|#2oC!qb z8?8LbA+m$7xA}dZIjtB4a&oeW{cZb*|Bt=*jB2vox`l&)bP%MsAfSjerCNZfbP*9z zI!2{~RHcW6A|PErKtPF71f)cy*U*bJrAQSBO*#oBL{j)}pZ9$4cy@XBe$F@c_|86i zJUEXYtFgmvLk9H8=R0nE*?J8^=1l622TeYrp za(vhL+X^RKXeK8rKf^w$^4wBQ6gWT7V=kmn5f<0A4Po&cZkbW2B>IN!e^;=sYF772 z_h(u3Q)68*?^?gn&DMz^h+9!)5MWY3LYE4Usjvu71_WO|qigqOd&t$m!O1Mi!cf6y zK5%Sv-yayH%R#yX%!dG zO8o*%wT^(o4&NsP+RY2;w3e^m7MCnqy=Bu-DJiP=^3+RA>thdIH|>XsuZO93pHLW6 zJXQI-n!#su5`>j^kAD+mO>n8K*{Z#$rtPxdgwB9YX#l$bPWK(ARNg?yDJ3*ESe90$ zpIm#s=(PDt=gkQfc{{X!H?2a&lhp&2zu5p+;dMsP3?w~dE{k%CV2%^Jjw26tfq7jL z9jo=d4j&ieuKDm#%x_vO-+ly-ufL_kC*-nM`ifRd@yk^E@U(83c9`_m^#b8VtW+OG z5x5OH(G;F_iZDTIo*pJMzdp{PreIQ&&>uh1UNB_)_(dp=?rMwKy9dp-jHE9gfdFZ? zeqTLB2|8)IU>L1x6VTuIt~@bRGw@j!xwJ?4RfH-l=q=lrzL1XL2!?no)0<`bl2~7; zR-*jn*g`QSFSGy*z_@4%s|Z2){R;^b4)bhLdvg3vXAew_pw^luYq}$e$E++moUv&u zeC-8KDueIn9(LhD41aY$zCM=BI?FtNR?U5H(N1s*ckB*(v@svD6Ntqc$7 zQ7CqV%-y`2Kly!frnOqxSjUrT=aXj37c#v#KgpT^3`U_@Aw&_iEb}`MQC7z5EUl+B+JG#u`*zmVT#(zrKDdV(oi+s){j3kMP{ew40U(Bwz(~k#G$sc9Vd{qFaGc3>D8a zn4lc1sfWQK@yj7gM$4LpPXsexWIc-=9gLb~Z;-<#H1lt_Bl)HUTm{Rvq3-9dYe0XP2yV^e>vt?S>~Bq64nNtBs(2+g+CKQv!HXTvrI3 z)vtG68C6VBH}DxY#x57p_7&n2-Nik7n66y870P~YtIA*a^mLv)tIOe|>^UwZqR7eO zj&w%eW@AP*;}}QrRWcJhG!+fZ8h6FraE~?te^S{fWJh)#qEa)eN_b5!Kk5rLJa^`C zuG>eXvi~?cv#smT9phMF1_#HLwi&Sy*fpXCOb;g!)nM$yG}Hh7Rt#@q?WC;SySl6g z3=)CT{*;w1Dk2+gJCBhx{*(Au$T{3cJIM8mN=k6B-!7gCpvGk^2XThLVINsy-IOd~ zJwph<7S_~9%cY0vaKu;+S0Dgy zKh^x{X(gX5h>bY?>}0{Ckf?K?SM*({JDQ2dejV7q=!U=gqT|9zQ1r&4(Hl&_NxiC? zf}16s{6Wz~0#MGl37E_wwP6?q*}2tl5Ae&j1}w4k7E$ql009Zv5htK1t-yX?NxZKf zNcka`w)_+WiB9+efIUsj`>nr_IrMpmeFA_&ML`UJ&X`*-#(qPg`oRDQ#Q_IKty12c zLcPbJ<_*6JUfd1`zkh0^738@b{=eiW;Bbn>F#Hs-h;-3TM<70!k~%PBdAkJ}!DHWv zmr=h-uJe1JdUk1iwmvm5{ZvYhKUWgHak#8uIzFYEbdn8!K1`3_HjA;gCe!iwp@D-D z&*|XK?WCngbWJo5pG-E1VI$l1w+Rw*o0d2M9YRUYeQ*SV)BDWm(?;jcGjC)@3_PU; zwCP?ww2X*YzCdiLw7vb=6tT_&SC%+HHr-Yn@n`OM_t^g!d|0}onmDo50hC-^FI7Reu5gpVNvzBR;!b)YaupqPxk zkLo#Ueai;&dhVyllP*SSlR#(N9= z5Vu1&OU|T1FsXEjcWjx3o^;R6qmhF^QwWoqM%mhTq{aKm*>}Zl>EqX!%Pt&xVgdj>CBY8idu2q+dv=vp#EBZ!$U? zG&1vaPKv?vGJ6_{y3eWQ zr9UoZ?+m7P#8cOFU3$v^aYT*JV!)eMN*wutRLIHO&y946^W&tD{Mr?7+w^bO#W^%& zJ$hOM0$%@!4YGy~KsIxTvV?7*1PFTPcW{HyKR_=?VjIga?UL~ zvA)E`w)@a*&bya-i@)E%K__W%HF4HbX@0-@}fXquGONs;;`r$W(wz!)XLCI-Yq*RLe^ z`Ccfys9SZf56JdXm8IX}q`;f(ITd11YYiCn(sVIlLkag}fu{`}N0A1kbLwke z>yv4bB{Rgf!-k!T9X(gxctfdvFWV%(2PyWEh`|$V0>WIT`*j(h;;9k`osTu~Lx+cx zGyd>JufFG-l(jM%3fIp|L@0b1$x9I-IaHJ5AhxS~@mn;Kion|3(p83DpaIBpV0OV1^Z18 zNj@Cld`;^Cc@#1z8cjh^&JtAcSwK?aHZi>>%z@JyOHgNZDbvqY%UetkSS`2K5Y_g9 z?{0WWUW)f)OA|Y5eu5)-kVsGIRaYY5=3E69vdVC29g~*hexaI_zRH^P_Ne>@_b|mY zI^l=nf}K|dAAI$IzyXl4$Xa6JnWIZ2&?z zSMs_VQiiWqw2^Wub~>rI@qP}-+TLA6eN+cIr`C-%BO@&;lOsd7TQj7)?=C(p&c1jU zANggNa+xGKtbP%83TN8-#sVq|W_Q|l60m>NXsm;k z*GG;o;F0OD(qy`HKz}ae3pg8HfqIU1 zL^2bO&j5&)J+?Dt9?hwq!)(f((a_6jG|syyeXViAaF}1h!U2g3 z(W)*ys%kn9ekRORIaFaO6?gq`uAe!}prqJU8udxd`%P7La`>GtUQm`4UX(ApCQ2gY zn{Mvyl@$#sDdtf6xzI~Ari0K*L<~#@<32Gve-@`)_AvL2PHVIZp@%RlcBd_)sp!akG=#P<`Ttox-*F*1vxF#urW!oe)RHDlJtGBgCgR#}@HAsr0 z0Znz9Jk4!^W!r=o=dHkLqYxLiDLKsGMqbW%X`{Px<9v{vc}3%~o>7Su&XnE!#A^Q& z?gG@CKK9+3uBE1Z=($vYk+pC7#hXTyAA$0QO?$HxGFvmCB(Bbxg9WRPvMI7rk7iB; z=^Pu9YH{Lk>5U5}m$=1h?!7K$-MG^f?Cv-VsORTCAbB>D?_=eF>W+<|uhsDAThf|m zNoDu**M(0<S0RfVM<81SQP3DD83MH6<$6JOCtoeqMDco? zc+PfgRl3*Jw`>zPB&ld@y;%Iv9f(P(xyWXsH*y{s zThUKD9h~|}cX+18ecn=+TR*}m%S`*OuOii^;yoD^qq5OGqP6ACblJz-598-&90%^` z=G|Ud3yio!k1wkDeIwcb^qT5tI#D0skH3?Y4;{gWPczVl>i~}dw7(_S6I}PcK=xLZ z;K;FVoE+}d%Ah_q77#E=E#I00WK7h%+y9ib??Pg4y8~>s6u?%SqxbYsA1OdK+;a&~ z0)!}TlO^Jtc7ezHBw=t@H5Q69p9Bcz4Z+`3Y+76dpc{{tg)mhDVEJqEQRNX?_z2~6$hj|WPcY;XFMbzi#w^}C#^ zn`Las01G^xbb(NUB`$!&WmKK8vz8U#_UbFNXI(`rUeup;Kj*jG#AgaobfcyoF`12p zxnRJNO~Q3Jhj{N8H71=;*26QieIKu9g*{bp!SKge^%g*34^G^_XLn?vinaK1effddGK?7 z${Wn4vWQ;Ih?`BdMm53MpB7-TXrtzszd5vS$3WQB6$!WG1W6aZ*^DV(%Fmc^%ZWEb z1W~&tGC#@nlB632Tt942=+b4uhY%HAZ3z>B%{iS}kW}-$`WI8H0r%d2YaEdPahr`! zT-9x1k&g9wD^?^g1^01;R!WdK(-syv{9@)3TGha96s}s>_>2p+?dC~VA^WDfO8pd| zh8A#bto;D4Mv=sPkku;91{w=u+OsV1&KS`d+4a+nmOZik=O5f|*Ejz;RkJg;{L=*= zKjRV@<5wypbUIYiG-}~gVq(PILctR{BJme=*}4yKT_motR(5jJK{JI7XLVs${DNBb zE7Mvg7IJy=YQ+V-k}-w;r_9I^h(-PMU=VNgvLW~JjPvI?w5zUvrV__`UCtni0W3>7 zg$>?k!PVv$b34WqXRK)u8BuI!(wIK@UBSkqDpECFTrk*2>f9)-_WPfF8cK*z-L8L`UlFjO_Z*5dt3)JCi-Jp5dOz(V;Mj7@k?5W3GnsSH`g%<oo<>lW_dKCi3W)-f>AMes3X z8U+Yl=8(ynN1(Fpwu@g!-ze5rpA|{zpC;=#=K&$%7=fpV6hzM0N3r@n`d+$EW?crK za5CwZKj7ik7u92=`lctdlwu<^U9g>TlPzDJhj2xU5QP2FrcRID^XSNT%($2L@)*_g ziAPb_JlAY5d3B|VC-;ztjICtZkV5A=yEmK5DOcQ6Tj%GwlJp&1i)!E5 zpS?BOBSd!tM0u(Xf>{yP=g^Zb3%>0T;P+y3Af(L;Y&zqIZztaDJG44EJFT}wS-nNm z&lvI=bgCIu3&E5l+}#hA1!g}V9D$yrP7}flT>zz#`&6JYp)oMO-xr%Rzwt@vy5EV9 z61ZEi?jK^)n&h%k~`n@PsLV2QU448?HWW(FYS;9UQ6JN z4w(SGP)k8M<5AboWv>$z)pww$q-Z@+e8lK*7m&NFyLD@oU61qtpsSZ z#3F^TIeP&vS6R& zrz!!7*s>e2|AP8aMNJ+*?NpK`{FU*i6ommwv?N^gJ3$#luzR-;SN5wP1}3oe7YvlO z1v>e(^cQ>Sj_)qKdGpM6X|%K1rwa1e$&GIA2-M*oiVy;JcxIs!E^|&NZeNZQrc&7u z%HrNu*XE|1opm+phbVk0Nn7-SC#R>rKwU6nGPH7*mE@jFx`E}1gr9P}5`mmIkRQHV zWlCHXn$|xH1TiOHS9cGfXM(~QNYo&xsdHIV`h`!_S|hsPN{t`OlMRLi4b@^jtlK=e z?P62SOU2_v<2h6=`dn-lKwpJ8xPzc1X#&?AB(kpX3^3#V%VSqLc@5V(vzG&JV?&Eh z*+Cziy$S;;VOnQw__rLQnj@NBvACGKtLwALjOC)A9&Zt+L7G z@*dtAwZOvtkmW~*tDM2`9yT(OwcJfswq`xV@$~gT1=%3BQJ{@9ufWZ2uyB~SvtL66| zFRsW-v6I(a9_Q{knK4sqP_F{h7d6#o$ghAKQ{szvBs`zd%u>dFOD{ElM{7#FE~V9Q zLBws9x%z@`+qN3|rj2mF8wBHlXtDf}Mh=Q>g)(j$f4d-M8IoYocs^~_gDtujaT!O8KZ1$sopUt)o>A>@SHPs|eATEq; zih0EL%+GQP=+k*d#DnEsdPGTLHC4PDoJNau>!Y0a{M}_lT$2X{U1KrRl3iai9>9Tw zw8aLp80@D)0T>ywNE2#|krV-(RBhIihFGSSLYlALZJnu$&pf)o4;p`jK}(R67QQ61 z25`H0NRG!g{bxJ2e~Qm20Y`{0z%vZ#xqPunz4SuwWYN2o&t7cvQUmJpR@dCIX`K=N z9Oq|*MuTTso=~FXNS4J)LwxoX-2mRh1v7vF%?{@e*|Kq#n$Xt^L$;yoLOu0X^qeJb}$ zCusq>w#kRP(Kwj5k%ff=npQ~1b|IX8NqzM0>R84HE~A@&1v|d zO*%{DTXC{o*|6)2UQcFLqG9TF3dLuNCzVmsV=*BYSUJhi9VZ}F#b0nn51hLka%iK) zY5a#!K2+bVFrw$DBY1z-0C?)oWck0o@}uJjbPS%bBa7@z7zT72Xa%+Z6+VAcm;Py( zd;kCXK{bC4VE9*KoPYH5{sqTg~m`AtmoyJ{ZpY#5JxZ%!Bk)RhK01eI_EyKt9x-` z)INJc-qS2L;BYe}$yj^IvBR8j)lur=(`{YJzEb9vpB3JG;!1K!YV^~8h8oR~G-EYw zxqlpsXiH!*CqSA5)Uv{}$B%R4O)k*CGgvHFrZe$5ogQ!gDoIa5X&zjG+IWLa!{>dG zsX#yXDQ_usijlzEmpz!5no^KeIV;U49v2<=wY&IA>9?Ons~M6ZKab5~^$q#`sWoEo z(Ks)HheWDkIZX$RU+0VxJGU|}K|=U@(F)?(EcO<7q8_6h@?qTEY-Zi!TUoyK>ZkR? z+{FGM7p@H%<~aMT+tt+`rBi~M0}2uLe019Zl4fjua)Rt&1Tvqx#8~^lu zM^pS{T!Sfp+zVh_cB0+YWg&G*pDm*|Ns@b_XhX;BSKw62Y2Xg&!uw~=;<)qYEoa&N z=B46Hb^<4CVvNdc&1D6)>0dyTc%9IsBGeZ!kb}{viV;;|${z{Vb1`qUw{HwDWjQX5I#|Y} z21d%On~O!Cm-o9Hch|d9Phz|PaP4p>=R)k6J}tM5Gnqt9Lh0<)C>p2tmBoG0VZk|W z*@+-JUiL?gHW&vIM?KyNE1bh!KacwWEIVTz4&-Lfh&kW2f$j3EWj})t%(L#Pb-+`N zZZzvKpPy=;FF5NP9J$VaTI zdgFeOI0XRp2jegGhdVGTcLNfE-nsP)5PV>81yFx1pc=Z-(+j(#K`|bZiBE-*Rv_K^ z->RX0Fo0s)qQemU6bXXwe15wN!@diUt{hyp4S0$Ya7yzz5H*TB&4?l;~VHX@7xLftHNODD|)n%pVrnzg*;tetx%D;+|XLcGE{>#m%|bbLTzim!bGT^Yc#|h zvFzGcmfyAMKp|QwzfpWtf=G}#@a_n+a?|lq4 zn%2GB@1;Xbeuo;Cqk=)OPyobdGWV0f;1gWlIR*rzRF_v66y!zOKhl%l+R$@&WFFNc zK4t^#jShgcp(5B3wf!U;Sa1*nmtMuRP42W4x)19=)iT~Spm{4)OnpM*xVE7D$9eSS zN5IoJ^DEMN=GeqYeh0J8_6zblp7HU+K(PCE|%t+a!7kI(1v+f^4;^rUygm)|M#`T>9J)b1$IfS~K~wg^=eY zk0HY=R+m{c4C&3MJO!QJ1^0BZy!P#ffB1T<*-Kpvdp~hL;g~amO^Hu7O@Fi^ea~rz zZ$dV_vipbptOYcm>6MQl` zRGpPFlBM(s_ak8+ank89F5->wtHhOq)UTEm7kb1$+_0Lo!W`U~ID3~pHg*^4_Vp^5 znKA&y8g7Sy%X#9L36XPZ(DuWKe5Ge~KK=Lcllq>_eX(73m3d|MpPAjIa|-xcz)ya4 z5g{mFfben4Fa#o8xk_?(c877z_onUUk5pWb;ToCU{Wd?**_o`G7TdnzZ*Oy-))iR$ zq&|MBf!=0LW4q6XLfoAPp@){X?YZ zF(dkMO?kaR_xO^z?y1C)o%nET!*kb`(Q@9i1o6S}r~PiO4s&T85Kb86YA@?e-_C5!6uazyj+Uldv(D0LuyeJq9?ikl_?T9De_rJrvu8qVkJaRZ1?4mT(%iQCkeVI7FhQEiJMM%88;3&g;5~@;A)DN-kJt zpW;4X%&RJJ)DQ&~^!BJA-6UMsjd= zN-*IG{wc7x5iol4n@T%e&@-O*FpJqAs0=Jv_lf90SLRoz%eZD3Dd@PJ zstS3jAnFi!sa38PVrO(!*a%lYH~S0@fhl}b=klAI?#f*k1rP%X-K}?l{&yS~!x!T< zO}67~zcWmgm3Bxp zUBcXa#u^h64AD9JmaS)y@C3Qha|F^*0mO>fhwlNFwKU=HTtl0!WOuW@h5+?$Am(7B z3}c|*3SpD0%p@9^5I1*wil@6g&!#=Zuk3{h$Ur1EC}X!2)oiN1*b- z)@?8WF)s`BLkz6n0kq2Qg_Byo1?J>8`Bk2x3^d#)x_fF^K8xRO6ItYt+N0}&vko<# z@{_X03fG=)xA1-bbiG7=OeYQw)p_Xh!71(QE4Sk9hx#%83u-31i$JH(mryB8zYB#SjVRz^ zQRJN8a%Vgp3`@mZ{*?hl-Pzcr{@JkVle>hm)bWIGm(XgOP4>WZ*cQ}+Mz z;l4{<1vZ)F8O1HCQ$-kubM5*9UKQ}!*=pH5I}A83!!^GZ8j*UyJ`J6+bmjQ|>bae; zUY6636vMOP7p~^Bg|5-UTSylPK^R21I_+0=AwSu%jR4sY$5fxhleKu1^wzXnlFsSx zWxH2S&b$yR;WWB=?2lMzp%q{NYbvqy7BLnCq`Z1Xd!PU25|W3+a0uzHL-0ck3$mk0 zeFxWn_t9*h-6O#}{#gJ3gDP=30_iXk@lD4Fp1`N3FSs8benanhpwKP{@c@SFnXvyA zEb!-8^S|m${?}UZ{2}D)zbJtJ{ynIV{v5CNM^TG^_51$AQIOw-ia!*Q{=xg%`UWSV z0Jnvy9=`gE+Zz2XL#jXn8B&}3dq5PQ55zA@lTH*OicLGf3>*&V_@VN?zdRMdNW?!A zmZ<)-()1vmhxi(fNM8iXnCO9TK<4&f`8QXDKiIzaN8fu9^-ud9ppX7}DvH~kJ-7rz zE95hf?!rR>p$yic^w-+u`fJCA|5ES(qIN*Rle{-}1ln6=2~uGJ8YG@$x?pF?3V?!V zJwfsB(VPFOYf`%^UC14{1s&OU7_pauzFG8_7iw{cW@HX2CLfoxcL?10zQL!z|IvT? zApVE=ApSYL?q7Yn{L#<*Pd|mEcBb%gWHe0gJ?ti=ylW!|lY;xvemZ?q&dplbQb6Dt zWngx}hIR&r4T3k!L)BYd8KXsodk5dcAYD?>tvUO?ckK zaxPr+s~E@a*D_KeM1&Tsgvdp*#kqH(C%ORK?PP;jRh!ia^mfE*@xso-Crws!|Eg;90zGv zlk}CcLgv-3=vOCsy?2Nh2(sXGV*F6(Rls!Ot;1U(DZEMWA3X&BU3=ZnW;eJmRChrE zw5Plp=&^c!1Y&oaVWQ`IP*okG@%{eyZie_78u8&PF5ogL zjCw>U^*kz6`LaqYlKSS*={QQBpqtwZ;U?FP#*tn2;r{BXc{CzRz)%8FQ8$lBIjx#u9m*J!X zrn+@gq3s31S9f${dlP18C>>=A zQh`iBI5cWtw5mf-l_jb|=bsJlL#j0GWbEVU{TA9}I}s||JKD#ujLrPT$O(|K`RMT< zr*sN0=9_*7SMqEiurVrh4dG*L#{hJuuaxV5(tj^1NGunr# zd?H`yMj?*XN1&|2BTx`y209Zmm4iP)xJNukU}~i(VudT`S#Is#!wFut`ntAj(ZksK z#Xx!Kghg}9f#z|2_E5hqNbcvqSlz#0>3{F_zp)?-sK(GTXvf*9gZ2!E_BNs_{IfbA zR2X*MJZlKQ^mVDMtmc-m;$6q~1csgrokWpmv6miSyw9S}foQSXuUEuz&2}U(t*Yet zmL^wCSg7u6?FOxjZF_PTfB$k?7}|N8S_9$j`OvQkjFX9# z6sqie`=YFRmzma8_LP&4e<3(gQMdi21QRrSwhY>7$W00)zlO=-u5?K~R_fQX zCLm!~gAb&QmCvAo_0R8r{|-OCRU=J&XYhe}-TouJttVE#B#yLJygEH@dy{XjQC`o! z9Ke$DoqTp~-R;9p3>ICFJ9Y1#>^-VSoXmUFc_I)y$3IAd{r+72v#0KV3v>7n?Wr64 zv#0LQp1Q1fbCNgN8*&#odq|3h*x%u7|6koj+0r485ix0KYJi6v6og$L63Q8ME#~eu zNMz-g`mU{65pnMzJZ~2<$2Et*8n{oa-y-N?#S96NMc2>ZBHJBBzoE8I_ufoZpzI7x zD|k`GJsa|M62H`auM+)ST9jI8`-w+KSY}={ts^)~aPi-N#z^*ni%# zkT2F3s;@hb`r>?+`ez(p7CsurrNS*BxK*n96!)TJu%wJVd@p3I1)ia<&aE z?3bpEMQ#v%OZ;p!Goa-zaM$)kYm4^!rr|nX{JE5$(Tguvx5;0n*u<$ED)Dmlg`JRaP&wD_KK0K8z~xkYsso9q9zpMA z+@Qb#A!HV$Oek%WA;%JShfrVG8#D)DTQlXJghnL!D_h@3r5>=H9TzATa$NEx3Mkd*@rL@tn6qKU2CkLRy!y4t62Y1)Q;(yT2H?g`n|IC-<%Z`yD0 z+iV$nGnsDll4~i!p?yZM2AdF15;gLEBYW-Cvk3cyzS!;}@yFtKP|RTgg0R6Ju#;23 z{q%RMRg>y5PPF0SFZF0EODbHLPjv837798Z`%u6O41g)vRJ7)ArR?4-`&d=oIKn8< z`|6!$#$3DdyOfdRK}D@w64W7A`JWmAH&^VJ5*)l^iEu^|g#aLK==&qImDCP|!ccYu zI$ezi63Mb}a%7orQv0pX{@QEgfBHAwvco2@1|)p3Q>$+gtAG&nmyZ5#utu?VbbDlu znlxK$D}X_zUkL@UO1443`$`2McmeIn$Ku&T@v(7$Vq1JoFr_qS_)?O)pu&iM;$=(h ziy;p{AbmR*5FHLKfV}_XlV6Y}E&LqJ>&qE(8Nfzmm^KI5G;zI2|uD9$##THm-eTMs7xSv8_X9V)G)=d26OCg8;4&n zUM&h3wd z_vMp|=jx;`e3oNKy;8L0PH+WJ^-|(O0n3)3jlksgyNJJSQ+oma zWjf`IoD%3nawy6%5!Ug3jaYn0!FOqu!}1> z0@4nSLNYfA49+8;HPL5w9qw3PJGOeh+vXwjv+Yd!;;j?Gj0J=Jujlv))GdhWgH0BR z&h2BcQ-oTqr|QWg5JPDWSMHq|{U?GH{U)G0C=nEtpKx<*Jq`{uFSZyqNX~By!G|F< zFupmdh4+487L{3Dh7G$jQyaU6PYcB5JJL^_6;FCwb@`ZIZu4On9-xdvWBp7qs2B*w zh{X2Ao`A$LEW7BG50iSNH{C#&qB3axWgYIQJHF$!Ix!?AX@R>0?2EVHO7|8S7p)P5 z3na|vkSDCNR#U3LvFDtjn`P21Vo^GoRU?lV&kef!G8!^* zo_hJxM3U@610K_v*?g+wYP!Um%WbsS4*LK*MgUiPN-2<$0(r!7?pCy-k zh>vgO*3&QEOH};?>gjf!eyX%b=4_Ul15ZlfUjSt+A51%~b(Vp0+?p_ZHU1kz&bRC& zCl3G9R^1^FVxN<$KEG&Bj{8oJLKnPc8$eG);y1(QtAhatJmP}=oA)Huj|4=ZyOZCh zr+Bbp(V0a%Z&o|jOm0QytuE(K52@BOz$1^Oe3=!183w(FcY*0L+cRV{#dKuLN^_g6 zazWa#+RX=5(wFWAMkc1c`QSy@G5cw3Bix^O7iLe0hMAU5o557EgE4MyN(SVCCHILTtBX)}k^G>m7B_Th- zRGXx}3HwL-9D0hu1Vg+5xf-U0i=5{!!GaeY!cJo$?Qewn-1uk2Us_moF$h0kkaQC9 zHZiekh!TZ;CR3457Pn-tw3(`laC5iab)+q9+%euf1Dbkv-%VxX`@r;q>U_m&u<0U# zbkc^R@4gAN8ru{@4=syL*Ta7c3CfVgD#|DXe;H`J$gArB!GG&?`v*Jz??waDW%mTg zBB_Gya2rtG03GS+e|_c2{1GSwqVto-a6xDF*D#dytd-yWlt1UF%Gm)4(a)SC&{#j3 zk}3HX@(?I#uKphO_;-JeIQny}*8izz^q);9v85e>9?w3@Ky@C0CUUyKY^o66OtZT3 z=v{*ZLSFrFe*D(Oms!*XOS~bf$4I#QfcTRJLw;L>nds(#~-~v&0ecoT+mXMGPrUNZuLuL|FJ7>t4RXUb_3ocERxWIKGEX8&vdMn z$>5efaYxG4@ta=cNu6_w3RQfcmGMvM*3|6R`8!iEn`d^d$J|AR_cqlTWZkw(ZOz_= z^1dwZ5d+37d|(iNO$AL%MN|RZ{wG^JMQvX=63$+sws}Sq7q5h+@(){&Phq6=W`8An1bRD$8!1IpP}uqkd^n4as#6!-rQBQ z>$OAu%0JMV2?76wqBjtPu=Ny1h6O}S0Qi^vO4kX3PTQm=>H-#?AkSHEqHV;ColLF1 zko2U~$`r*xr}$_TinMQ(udnaA zUZTwr+&3C(fZ$=+G!hpW??M3FE*YnqAq)+dyz|I)fET2~-I1rOrK(fGArUK;1*VSU z=aqk;6iey0xwwA1&m}}bvG-gCc~?@iln91%y>e{*2)B&9&oh>E5k0xbe2uxwuWXs^ zn6m2)sGF=H?nnk3-9JUV?gAC6V2e25PuN(+kmcH&F7TWeH@RHV%TinQNVAk_+Txuz zZ?n@28;PW2$iZ!b1p;e2cqldlGqwoH3KpVmq5VQk01vE7!z z(Iy5009etQHsB&+oE8k9QJ6n{IfJe?xU=Lg6Q*H5M5Ry|WB%qq+F$Buja!g#?BH{4$Eg``F(d*79}rqZ3?Q;{fI9coRW zTaIvXlm*AW$_=U&i6-ZuP7#){I?c!ma9fEE2GuTLtQNk)am|yPwm)TvddX_4mhN%c zA|5F39^8Ay9df)tW^3*_#^quyWg(MX|6B9n>V%BSd?8amBh=>LW;Le{Q zKj)#aL#Umq(EMPyl?`bK594-ZDaw%f&9l)JFP!}XP z5wCnF=o{Cbk=vB<5(weEw6-$VW9LS{#vGvqSS}P=v3*T=j;Qc$L5DY8!gjR*)=$w= zkduVgwVB}?!#2^DQHz0vCiEHCI4(x0q=XiIzGoH|8~!*j9BxPXjQki;2JC)4;&sYU z-3kufA<#v1Gpxz^6sYFjH*-ho??tz zI0M-5fLt_^0zIVmC!4O2t0DG$2xn;6LTiT1UVuZ?Q~iJ zmZQ?L=9Imth;mwRrD+ndAwmmbKF?NWSP4Pz0c*4^1;LDxLnfDkdo`DcPm_9w3GXUo zFNd;TID`-{0@C0pEDCcg69bOUQmDiIh!RT;jA^u3U3|IhJ0lXW7nQOQlU+WS^|>hg zHk&u9dwWWZVz`aB0aUvva=itS4UfdRZ+c=JVd@AwB+ZKO`M}gV$^>PyR@Y)&Bw>Sc zM=$6>F<9R1)O1|V5?>FgfshIGHc=RTae&iMNRt8~3@|g2@g9uaUUu>rUkeB@{|sx9 zJG`!6a$|d!Z7%U*ZZjE|jRx>Lj1zE!p^%jXKj2)XmOcXgL_j^@eKR8D_o`ZRo7cDT zZ?TChFQOREr-vZZV1TPGr>F*QACS@B07qH z>kT#xgLvkRptGEQIV4x=E<^e1=^A`*iDM04T6)Wu?etYu=7d+l{?#PzlN8;w;3Lq6 zH$XiPN!5`(P|e6m1|oS(rs^bp+5e!MDVb`wum7Jt!g^Ld7JJBigYp(A3D?| zL!uiZQ5PC6`gLKxS6B!aK2$cDo1CPq4b4eCjDGb}dvWJe&hbuD$h&(#J&F31Her>z zUl2HpBvITi6mp!TLHlDwnu%UU=~Cu)cS&WA`58e2!GbRX;|^!1CI|wMDKKzk&(-j> zQ6S_@0PHSmdmcxLp`ECD5fa?zdgt(%p^4B=YvRelfHyre%!lxhc$MHq>_9Ur*?)Ul0x?R{&%%`CS9bIn zbxDEBbKOjB3pA+0khfiSitZCki9wX_JU)jion~(VcbV>+pQfE&gjTCK$I`R8E;qLC z9HRm|o^Q={zbg%b6a(A~oZXLS&OP|)EU?;Gi)kYg-WPT*G`U0}(P1Z<@Y}V3 z(~e0BQEn~uFbQKZzdUv)=}XxbTQZ{!WeQvZ#U=pIGeI)43o7UcmmrkSXF{Ld=NfjO zYfRStdRnulCR&B{(N4+Yn_P3w$9DC#=iV-MPKR#Mt>*y)u%PXbD4ea=_bC=yXnF83fo8!K9Z>8HH<%K@}1hNL>gUATkfG6vF zcfp+KIh2g5iyYunLUWG$b_YsEIV4MO3dP-3N~Qj?ly2Rc>rTtIZCQ1Ywqo>VwuY+b z1;3#?IRQl{n9e>9*5%_`KvbNm#7$i#xO)~*2C~3IB>e^UC&#pGif(?K%Cr~1G1u7f zfyXHJc=~a9e-X(CfkA%{>HuQ_tZNR1+|y|QxP*{Y1PP7Gf-}N^rq@s;>^KgR05hMP z4HpL20)F;|rA0-uIfYK2It15c`rcYT-+vW-W<4Jh^P2WYSc(TEr~uXLPD8o@d~eZ= zUz=71F25CV+}!abbn1PfS9NO3yK*N``bbCd05MfHrTxy6gp@kdHG@AKh5kEQk@|s- zU1TaCzP8?*B?BY<&i&PuQWz8~v2p|wT_rh^)d4B-uEO{K{%$}y4UudTMD#5CO;MUE zQDi}>?MVU?ri+y25Qko02i#A-wlFKnDNs_J3@D4p#j?VkP_w+xfp4 zXXzoQ@%lZ%=Kz^wCMt1}A8DsiF5Gz4zV|fe=XH_uc3I?z#K*?E9Yb+2!8z@`oQ|OlBtY zoq1-hHP3q1I8nqCeyRE$jxSRoo4|>FmP9iSzLTf81gQ+93u&HSRq&X+z2$9`4O|O1 zn5P3%upU?YL+y!@sQ5A!xwP!0^$2|84rocl>k(qD~BN zH5&Jn8rTdT0MG?gK0oI8P-em*s zvV-@pmv|`G{CNxUnfoNXxHH%(NgNNPM?#q)4}WI;d^<{yBqS~ZH@Q$CCG_AWvYckq@3UnI(6lE~^&rOj$ad=eA^XMj__5Vih``$kHI%XQWVV+D- zr)W*Jw4xth&vaUUiog8*HQ~Ye{ja-@$i5aH-$lkvs|m9}EuD~W3%ZY=o>wBHX%U+_ z1Qo^9HsD&(s~)_qk1S&?StfWDIpsenGG9sh&N%D}H1gvJb7AbP}stZ39c#4d2V^n(6NA4&!;fR1J__sL`ppmn4odHBS^(&?<9i ziY;4pCKe@ZafT{d{jKY>m#$U5;_SJ{tw-}DQ6uolZQx3FgL4)UJd`goveGo`awe?o z^0YX%hkZol$^H(9+tBJ|m(m)@n?V%09P5aS>3pQd`;VO(4)e;cS6RFgR+v45RvB)# zifxGPZ(0OB4!#rTq{lT{-#70i53s7@UjDpQWywLXDuOzO=r(aZPjO?jv3yQo0zHab9tDc*R~NHsAOMa$|2{8{DQ2= z`kpdJ?FZC+6M)$k`2T*JmG1tU4k4AL1F_R!|Qx&BiOHBzfK)(xq@?MOrB&n zbcANqhNQczf-@X+c&5WxT?TQ<~wM09Z+r+kI;(9RkLzZtt-w=h(ug!4IXy_%``$QC;WOgL3dgM-X;pNIEPv07IP;F`vpXL8QDjNW9q!e76wH+vF}kJ7_u!LmToou4r%UTXb`i<<$?_ zyRk)M`VM>R zrHGJamYXf~%L|W-{Ti;do2LjjXfAmxeOVdxiOxwMdr|I?WozMj*7^K>KR#}aFHeov z+vMr(P*Q-nR9HwM4!%G-PEZy~UzKufh(6GqfTcY>>pXH#c_ylG!AWvhiUX1yb#TFX zfc+{k=3f;B{`=48??3N448*^vn*!&ofsrfZi84(aQ*o4b9=Q-*v-@m0rHn&o3AwJB z{K7~A7c~b7aT|xVY~Nv_iIQ-8lK>l|CW-`~Y~FiHuZI1EEBgY|$0)?qfPJ2>@(Ii; zA^6F!IXd`VI$s}l<@lMFrG@db=__iJC<+qGN+KoUL>i7y^^#&ym`DHglW{}kZ55u} zGp|1F+)62S(ZvdDCap(*C!li9RbCdf*mh7#10ElSJoA^Q$5DB6=)XgG^P?I+(PCp1>J6J$QUO)n9OT((cA{LW^o_y_$Hdpwz!4uL=G8H~GXL#;-GKMmGq$$|= zHuNWnX?!faly#XzjrNoJjH}_Ix-k$3lXT}u*(qwt3;sitXfEf10@s$OAhgYlT0|FB*W}Xk5 zmTtB-yB(|xoqrfx40R-t$7_;{p;zHP0BNiqt3k}zIRs5uKxvX5E1hQ0>z|n;4tT!a z2gn=s!tf!)js^ozHRAxdDPqh8>>C3f0zna?lQB%Z4u}Z@mtpTwmZ*bkX8_GfB0z=< zRzC!tZNwV_anE~D0(do%V3LTRDR(}rXc*x`8%XLezj`TUU>Gab)9 z_EUi8g~}ItuKvqrAKH~U*-C|*U+UOHCEhP-Ht;-%Ekay$Rkni{uVA5%?_QAnO#8N#ebi%)wG7_wxRv(g*4aEbNyJP@&U*7w%wNsN>l@+RFN zHIaA{8xqdBigllyXgS;Xu9Au!{-^>VWoU|c`+RtnJ`~C3;f`*{7UEPf=P0bUZ2Icm z3PJ4MnvNl75_$|+@6O4bjj|_>9z;J*PT=u!(B%rhUw-p!cJ_67axaQizWFKt#Qd;2 zYL-sHq*QqcpRM`JK`S2>3WYZZyG|e50LMVJyk_amSnuy6`?pu8C$>(kK7QuA$el2$ z5Pj{`f&*vN>rIO3z-W{x7z<=$%w#-vA)h6qQBj}8sK*HZ-M&9Ga}`vo1;lPT4{gXH@w$A`%dyC%qj%ltbOLp zsdZ~pdHOV=AJ}|Ph`C|pv$vldto_BfN>dy5n_UVpQ=i-NKd*A0>+;iz{`be0dA^@Q zFvol}zEJVywehNxTm-TTXy}i016;RIS z)#q{D_@}r8>I*KlQ+Lo>sc-7E?%xVuIvedj-hJbk?}vh{ZW)TTRY2tu@iTytsa{OV zs+9;7n&b3dbyqFO+bn50PP4%oQC$e!RkTz~A8bPi&XFO#~8I%<$kK+r*1F)s((U!^uEa@mu>*GliO_1`+?h23 z&Yd|c_A$)>c^a8OZ5QQLlMkm`nPjnf-LRpG7<0|~vZkG(6WhIdglBIgS-kp7$0ab#ULc>)Z#h zS662uK>}Bbo|_q{=$xa1ch%h`3$nSc?0_S!(`-gnC)uuAP7C=%ieefNVQwD@qB#20 z$ohAY%UPehXe+$Q zHj)%5>E2-gLfqsIt8IMRjoADU3P`&p?5E=VibXbnXO(^9OpmayKb3tePTSZ zvU(L6fi!aby!y!b<&N=5`Zlk?tJ(Me^Q8Fs?<2w$YW@%;ia6K@*uQ;d|0@YsM>UK7 z$aw27`}#9tuX31V(j>Fh_!O_<_^mH$h$4$bbMVJVsBGhD9HoBuck`rZ$P{ud;~)dL z=A7{x{)>9V&k7Ppe}0oW0Kc1}0;=0=%K-cpsNN7Mlzwjmj({=P=D-INAOlJJNueIr zTGowv`&?=rtV7FG@a_86Y&uO+ky4ZC)Yg083Tz_|xPpH8pS&#crGy|LyS4%d78vFt zc1A6MvPH5x(0$o4)WL@RA?R}-G>IPl9yQlJKr*jTnKpV2JXm4lU$pR_E&c9)|9Dk} z|2I*ZJ<>b>C93_AuYYd@-JZjKW?(;sYo1OFz_vIwSj|f#0u4o`@5>*8T)EY~`>Au_ z-a}mgazb)dctzi^s9TgZJY;H~rGr4G<)8=v=$q>a4Z*VWAFm+y9$ z3J7i>H#n;c->RH!u;AAa;$5B=$-{CiX6v*<@=F_rE1l5^W49{ai)YQKmOHembqs!m zm_@QDJpN9~j~v$-9KfBs^5)Ax)HMgW$qO2R5r8e0clEcR0vxpw2;z&!ApCP+Tr-BI zjS>y6%&H-cb6&Pz<(WKC+FU34W0$jLAYyAwU&|63M z?Jx2Sjf6_z15!Lxns_Ky1-C{X zWK=^EnqDX~B0w>}xl>S%vXz>-@>qg{TWCr zFBq~ub@!4w?@D&w6%bfFPdN4os48AHV^Eygmr$65K}(b-T|m!VrY*BPrjjif7a`ok6&Ch+HdmSiQyo8z0qTI}h0t;qK7 zHwSW6_`3wNemN0b+Xc}OsfDLr7uyvU8^a3qKHoZNY#`&uS|TE6|A?S63-t$=sD;h; ziMFKm$}ps=d_A?map&!`_ueHc84R4~SvjU{tGcJEY0(}~o&E~fS0&bYHMVil`& z0~X@DG1B?`&1GT-2uk#JI;qFdl4wCf*lzD9NJ1uRmcJwi63?Q4L|f`^*&lM`;O@() z@9w3D-O;5(km_gDZN3>{L~~*mq1!2@rV99eu1VdW0om0I1weHYLeC*+ZE*@1S=62a z?B7A3=twg7m#4xX`TBQ0fqpj0`9d(=o-hFn%bmzu7_Ha|{d@tIu;}O9O=RH^E#rNf zTC%4)W(q$grE+(ofp3p5eO$%d~j6)fr9{w@UzbkK^hoTFZG5V&+5cK(uF7@!)0oP9GgSC zYaK`cE>eAz@J|5#oqPpAmLu)~B{`G`ypS<+QXth7iFyl#i-q)8+U$7awF3@H72q0( zx)fp_V)+x0eLPLV13B_3e>=!kBZ&ifV%A-velqGBpy^2(hU`4F255N*k3&!cfNOs< z4ZA`tL=MtGGCZdT`Y!QTe&pYd^5>a)i+Irk(OyQjsr{exDEhafB&q=FRresp&l9s8 zbQXAi{EdGzNK)DyA{Bh}AbwnJM-Sp?M;t-ZFY)(iNBpnY5w${eFu*OI0iR!GXBvPx zBR_VEJC(k#&zcZ*@5}8qxBxk($9@vi-8|(F=P5!*d(U+`+92LqDm5fBrj=_DNO zh@&0x59|no<^Y%#kOy{Zj0Hu%rpD>t{}}<&YW~TvPoPNX2Wm6}Hf>NTDu-}8 zJV{2RGiR07cD>?sVuyBU0G?J}pm~&FKAW*Q()Cp3>TPLuKs*0KDi0>KG^v&`0|NM~ zP;qma$%x@yQ~;tB>Q(e8QWa-zD&)U=;+;xH&&Ik|7|4f1RR~f?e{6ks+6~Z+2~I2$ ztfCIC7Jb2>=k)H}vei8Mqe)Hsg3&RSC$~ZEU&mc;!i#s8URP5B^g0&}#JT03GXTRo zW-M;pU}?Z`yHK|7B>TYX09I1xv~gbbPBCH#`aOTa#9q0-mq&WW=ClibkV)2`s6aufc?cETlpjYO^>dM`S(*+InrqVBi7EZ_3;P9K>xQ; z69|uS8$kIezs4ynUE=Y6p;X@iBmek+PT_gbg*HhpQmfMIM5r)=*|P`+`Q` zLy+Ae=n$lQ1sRe~!l4=u68ceIM97`pMIiI8K;~icpDSAQuL>-k*zW!t{7X0xA|z}~ z5uE@H&^`;~w?N!aP|OmL{c>X>4J~vF5aoKG_hM5-|0XIV z_()Ij-&IfXe+wS|JkBFb{4e}I!o)wBN)A3!;5)*^zpsk*d*ka7CLUqpZ<12-TiB!E z!y^f+hvb!KTud?wZ6x62pj5 zyQR5t)>JbsJp;|1(@Iw$0Vg_;-lX0PY$g~z204dVK9h3@n!0!hBETy<9`I3Xe@x%F zP&RNs>RzkLI}CKVV^wK3G!0uX*S*dX?D{c3v1s%F6H63Dh9G82;H-zBZw&eX%~AkR zh$ecN%}l%)Ye)e1$tXMvV`a{XuUc0YJdtUjSa9{_1qsmbO>XllBZC!1_O7`7Y<{&H zF``i+0O3d!=ZCScNjxjit46f$5+V>#VL!X<_a>I0RX~ZM3m@;ia5r#`N;k(}#34 z5s%L)*&9(=;a|YS6Be(6l?OR>*&ep7*c6{&wSM{F0l8*i(`UgDNxLp>v!>wr+;Hq= zdQ40p$_h-jB2lP|Ggqz{y2w>zAnMgiNu6n}6KPW>zmu83L@Xv;{xW&FG*FbUikXMQ zBbmu(-6CQ0_+1=$Jq!Gz9j`>y+1^cbTZay0>S5)ElfPKF<$lar89XQnw`W_38aH`t z?&F=3v@8#vXAUwLESfs^d@mN8f4#II@AW3nTQ8?(#@3rm+y}>6WlpazYNPJ3ILLI* zr8lSmI?9l9TQJqsM%Gf&OYyu`_?5pDmp%Lj$yGpTO53Cr9cboxvqer=t`7vK_B}X2=_-+)N4J zG7EYo!=F386dabz*M=}h2DyRjglJy4RaaR!J5%kxEm0_ME?5)Nkdjtbt5y_jubB<;h;jvr*Y7(LBhklCa}>@UZuu2mN9qZ8aZG zZALuOCKH#Gjwo(1DJ?CQ=k6^CE;%7`^)y8*KRH(!@>B`2SdK-_o{l@=T=zp`cUIJDu(Vh7E7C=v%Ss?S=iz@@o87t}~?H>9X8Ssh8vKm4SZJb%~Mx*qzsZ=|bH+{moWD z73OR<1y}y5QVSDw7A;v>wv?Em_zr|@bAB*ekhzzbo0I;Nb)d=eT6lQWOPaUx>;rfz zysR=e>XZy0cXn4(XF-SEgUh!4LrY5=fV|-4ET8}kQbmYJ$G39=3+Tc`@Xe?l>>!9N zmt9>AB!xA7wrsYg@--IInArOOMX7HIuhfksFg$ap`fi_&m%C%lW&I_-%pMT|*4Nz_ zS|0_oqoj{3aWLT>Puc6Hi=M7!lEY6X|Fvj-N_KBo-ptNtLlp(VOtaFf7$(4msKUa0Q z6n*7fXs`&=&-DyB0tZ7c#cR1)&v(V8q=w7V>4Xzha1+yDpBH(!z>TziZdJ?*Ht=$p znJlB1mb#kBdf7%Cb6I~dgXqND6b7EBZVU8it*MQ6lSuk}G_0ULf!#{p#11m?m>VG5 z)?}skK&)(zO*C^36nmy*C%6d=FrL1G2mfpyf3)i zq;4_dL#M9I@hh>L|IYV0@?ZXR|K%u`;MaVMKjOV3|K*SKU%sS!@xA9RiFa1w6_H9< zttW$DN=x>XBOibmkLlW^MJiz|$3}0^vg%yCWI^L`Hb~@Db8gQg$c(QwYS}LA5Ofl# zMHXSX!ydRjspCU}HXedL^z3FqnZ1}wz%ZzXB1dK z0A_|UZ>s)D&N?S|?MC5+j#Fxv19(n{Cx@A7F|wZ3nSzvzO;CfDg+CpFl&qj4;DhHJ zG3Lugm2+6Ix3U$Yk+!pFRee-1r~1}7hdJVA##%@nKZ!2Cb*QoV+(gVy^PTbJRe`P` zpwwGFRm`wyWTPDS#|`Tb5quPn6j&1Kltm1v4TBQzV{C#Eh1C8eCW~H|n0uAXlR-4> zFfR!2?67c+1uZ|5$gRnA?}1y3D4jJ4UB92c_6mI(j27>kFNv~lK&^J1r2bF=sV|kp z=8k@Nz*Zm4+g%oH>qwV7vY&&$LNG+3_X3~b9J9Kf_UvYy9;IXn(yya@_+hz_rU<#$ z79REylJ1C8pKgv7VtKA%u`lvD>)DfC{ws!wp|;TS-B49Mjno-IAJZrAA`R92WlZsm z76*I&$l@I824uRthfK_=K}%uVh01JQudmUNceFKpZ>1ukv@jik)5MaWj7*!=yWlNxqmr-1y$R?s1J#GkX zs)}n((S1BV)%w}UqM)*5h>!8Zt#_bROtflkNyf};G7ouzeR+wcWovfr_F0XhTd(&5 zBc$vHQ65?7l6sO-yAA$KIw_2P*8EXQC)4GuLy)J_^yl@yWe**o{FL+nOd(Yv2ezz6z(YD1l$VN2M=+e4ib0>fp z0MqesO~rZF4%su5_9dKY7nNCOI3<6bJ*Z48f3;x`Stz45(+O!LvGi98XWCpWk1vYu zEiyls)Fg3@Bc#oh2@rp(f#d-ZgWyRXz~W;;5E(6ZoXYK*JADFUJ|ytn&uv~XZ?YMA z2fK`qi&OA8lNvfBGW6QKJne`4M@*8x7p+VwctB!GFE7by#zk4P`?xJbre5R6!pa( zo@^#Xj1G=GMU75G6%EH}5C?OYG6|MA;m?GpJ=xjTHuHT#q9aE7mQle!eYy{FbZNgb zJ@yD)<0bcrBsrlkRy;rWWZ(Ci9>*j9si3U7{Ry$onC=S?6< z0STpzW<}R#=6eSOI#x`~c>^Sp8b}S*eASh`F!|}VvY@e*?vo3#>`rIAIo?w%jAst- znz#=Y!+RmLxg;inoa>IOOb%2#W?kFv>@(I3iz}eLyNpmpGg-bx$S{JWXhVAl8VW&? zg2gKE_O6E@j3S~NjQapY>k!Kmh;xY{s=R%nhFzs&n7jot%tiAS$T<=lE@c)K(B%Ee zbNj2sW^OLy{;THja%C2>xJb`aDzv*?8^(BQ90Ct%x1lrgr~t1i6u}j34?!|})=h|& zG;rR2A0kiYVg3f`8{RBG=JOU;yN%EkOJy5AIT$6BBE_4g;8aiJADhVUkdO1h2+br0 z$X#>^sFa-*RTNCHD(>KZZ_UZ=*>aEUydu-R7P(=bLL3WPhr}SBl&KpJ#dA7*or(Im zKJ{FLQr8!>%{3NM<+=vdf{!h!9)jNJ)LUMe+MwQ`43?E}W!KsAz*My73Sj|Zxwlh6 zkhQ_?L(rXwuiEG0Y%{$FA!tFHjnrlPobGZNs%fG`jT~(sj5D<|LT@FXabTfo@0rPF zGb59^$*Y@8jgIfsp_+_e(&+OSN}ZkHD)7On?|Q}HgB?JevFA4G7R20U|57y_fM!a- z8wEN`K)KWZyG!fh0^S=%K{_^(1PVY3pV|U>nwSK?+Kn!)x$uHn_k>P=+C^JHD87k~iSS zT=z+w5MbV1gy|B)Q%+U&3y$Op=H{|Sg{Z)`RXJOm^b@j`Yslhs#+c35<&y*=LQETm z>>pZ>?x?e9Ov>YX@G}E%R_{sW{*IS-&^AhoHi(OOFP3h@0Q;ed2oX`nwZaJTmb` zxz;;jns~;d3fh}SAA={lM@{aLy^dU2gT8@t4mv{UU6S{7F=PuiVrNPt7ImGk`&T>( z2I;>v_58$owT3Ng&j}?(;w5#o&vu_*HM)$0WUQ2Xb@C~@rU|r>dpS!Y1Ztli`^aPZ zZY=J&A_#lKjhN7+7RCD#sy1+RbGY#*5ntO2lq_%8jiF0I_ zNBXb>5`wG3^W(y12BS&b-;jvXqOTvc%^vFtexho^Dokd3q931ERB8_nUyv%T*$OJZ zX6!yApkA_T`JAdZ7*S0AUU(}`+d6VCEMSUSNJBtcYoN#?iL<(st0f#mT;|?qbQcLX z`e{i)DLRdZVG7#678t+9G>+%Pa`uSntEkbfIg9t!o4LF+E{*EX{0ZZ_fTi6lAvXvo zuHw6@jfwGaSyZFDO8l7y^+s}khvhdNCM>2E-qJq>mPzYU9&1*6PgBbYPe3NO_tR5k zS}$+sQuZHGpn z*u;X^+-H{p#biaaVnsuM`%<1ba*dV;H_xiV z?=Fva2g}jBG(aDJaLBPy{xBOM$&du*Yre$J^!Sz1ZArEe_`*;$OaXUenmUjs%O$y< zC?YmOzgy@kaj*Jg4QI`IF5|hna$6j^Zsxm*)Zjdv&&hUyu$UsDF@zfaxKIF0>}J)Y z`l{en<8b2bR^MA55^}PtE~S87FzVMZb-`f-CXq5qMXeBb@~c8*XW3WKl4Z+rpWAMk zp>7vBW~+ds70c51^rO><*_G)a=ZS>cXHQUD{5@WXX|Yik6|5M}HF-Q|DnQ6a411fx zC*RWAmbefc1KC4UKeP;eRLC4O(z^1UC?>91-?+`SxHY0PBX9@`sx-5j^H4lq&hCBv z16$L{###FdJjm!_C)qr5I7G4flFO7D&VG7BsYxnM!{APOGWg1+6D{A%n*u4P&4!<1 znQqGRW#;AO_h!%Z6}7wM2v~hnI(z<8=*@2qr!zqycWr2(%#CDR`>jfJx4#vsFMaBh za!RX)Q=S<|@cFiy>s(3nD>HcsbwNH7Th7~(nOfM$#pveRExg?epVqKC@zt_vF+6RU z{e0L0^cvw2&Ii&+&18V9o^2J~`x?j?Ov(9<`toseTdlR=9V99d%ZGck*-;){?HT8z z|M4ZY@kb5B4Ztw-y@t~{1j$3sBc>IQhoDP3QTmi&S?qctV&A2b^xm+|h9y=W!|SaY zoj^Oq%rL?vPR?4qeSdeusVAoWVyik+GgR+@YkF@(%?cybnCBw#=v!Beqgz37c8`H8 zrtoeE7nhg6&b&5CCowh^mwdO z;<@P2lB6#w9b7kDX&O(nReUIsH0i8)D1G7HG`O`zOwrpQOrOT9XCh}PCV^6Csuc3s z600_gs0}*_(+li(NtX8Cq z+kG{py(n8xEI>zN=0XyK%&KsP=@!}H&&xlFOtlJ$sJ-A0=rK7{=W8Nyv9(zq`Vw{> zCpq2yrex37#YoyO7MDIMXgz-CKyN-j0gC_NudgqlPE$Y3wpmiC#v^XGlWx=7V=H?DZe`)l40$7Li9g z8&;z#`@k9{{Yjyeu(G>$cfT~2Ugf=$;C2C}M?~aTdaDU?&$fP!J zxu8!y+&v=@Kkj^E!cr%L<Pxv6pY~rHARiMfbhnEP2 ztUUd9wGfDDw_i0E%0sDs$XSlfRauDaG*8L6Yg@|O)*b57Z>QVA-dVhvRa89=eDVr) z?yNa`8>pE#Z{j8DCAQl`FS^e9I3p^njhknTPRt@k=Vlj6T?(HMiH}m1i)*tyzMxTG z`hGjxCk&q?zk_^HMD)#$uo{}Y9{sp*&!lfqf{VBqUjsoiW4lk0+7Xm8T%yil#)8Gp zG-nG|BPid|tenog>ru)@v-a4XwJtX@hL=>q(Cru62Kc}q0J+VxGD?}aiW#i;tfBQW z8;>u#N}|hjnb9&fTC(&t=g5|GThe$ZG_>L*koiozr= zezeJYeg6R@h>3jF&>1_`dto4^UXHmedg1lyz3o)>6sOCklLqeA&>Tl2VPc33W$u(R zVkTa3seaZ-wfs|gskUs7VN}1n4OicZzy${&e&T#D^wuacNYI+ArEP44n<^A%9u3^H zhGMpiF3ZTt1$)Fx>(4vi|IBU^tDndKyNgSlJp=_xWxFARtRtS4o{j!i<)`({lOY zIadz5#`gz9d4w~>l$e=w0Ybh)qIbTG7`~u(7ie&1H)vf{qI=3q$2&}89&ND1M86xd zw{D9L+?*Vw;2y}1op>yhXUOU9HN2m?Z5%GoIA`){exBK@9(x0)V&=@&v8Ok%s#qJ$ zz;NAvitS@tX$acmJ=o3viEv)V2CdGfq)zf&+n}EU<|8(!Pwt}r^Qn;oQ%eTD0o2$f zAP9nKera1gQX+Xd;QvRbw&%Z&PSUeFwL-@U8pZjgn6o#=T0bWR4$d~opUuB(`;H~* z8?x>C={TpR2QYgQWBLq~coGKG&U$?jMF`NJL%U=S2Kq`*ik-n43pMbc%-HN zHI6rUDGn1#+YBz~t_QQZc&#;*hGkd`#pIfm;mI(mc5PFxZS8blpRGDg({_odIt--* zCa~RJ`KmZAURVKZ5^L9*nfMI zRMJC?t3=hx)fl?IEo};TWz7+{WWoqeWn4Z@Gh3$x*A@;wN)_>1%612lxCr-vvldJP z@vl_5#B|*Cq5OG1s!EOsnq%C%+!4y$yRv+%Tf@$zJ8*s=(xVR{p1Z$@cn*C7J_kSV z!lK-_qZ7N;Xud8%7LtK0pQoNky+{*D z>MLr12U;ecxt}WBqs6vx2s##{tsZr1E+0G80AT^5@aHPoGF+N916BM*ckawLdVZJ5 z%}@4nVRB}Y^?g7EyLSjGz4FE2J%RIht_u~s;q@jgJh81BgMs)u*f1_jBrsv9P@@j` z9hy$|`w_>^rqXzw&O1x7d<*%Wn;1xtcEhlpfC6jZtcnU>EvYpenn0$(QT+J+l+7x5~z~+~#EYCgs4S!PpqjO13oI zZ7@}>OYBocPHDp;v+wI8yj(Z&!)s7^L_HmW?-29}=?_6)8af1pU;P#H=)>8IQnZej z2Bwk*cz0MI88u9iqh16d0*nMp(bgGB@q(+nX5xhkwo6T&7es?|Pjf<}9#HV`1fSkI z1U*Oj>_KQr;8u&&PadW!F&ia(Z)JMvvfs|{Os0on>*im_s`-Hn{pwM^QnR>7MTx!g z;Cm})hqk#B?!Bcq31YPsyboAI=m%1`~XRh*{v+2g_ro@U& zju8ru5p1`NFc?0p2hI^A<<#$Jsmt%E2x7rsr1=TAvUp89RPCpN&E{jC$argnah76u zNP6(o&>MT&syC(2xre{{gjwh72xVaL+k0Mtj9GOk|9QDGohrk>3JC%GRtjt*&Xx`t zP-m;B1D3b8P<`TP-z<+mob&nUl``{m<@D9PZ@Mztd6hN{qpXT-j4ku){FGF2o=W85 zqbmsD9>zEMl_QdN%8J`NMc**mhQe_DZCr!aB~*|2s?%|Ch9 zMRQI>Bru(vsnPO5sGPk<2A|MczDNQapMt?4uE*KY6rI=@qy3<#BUZIV=k}eePkHZg zy}iYgFtAUF-kT-&hcn?Kz;rGaa}2^M3f%VBo_`L&l(ETc$aAn$aCpii$8vOj${XBi zuL3{vvF6`OikO_evW&T(ru#s0p0+P`-x0VBfWGlP^FG4EK&Dx^#oF`=^;7l-6uXm* z_`tsFwS!q2H&U@&)Os{Q!Cm0{#L^vxQs@Ti?Bt!B>J{rTG;KZ=b1uQ2YD4V1a}XAk zg{4qn0=pbTA3=gX`_#P!hSJb0Wx*+@h%H*jMTSS4?ah=KnL6DDhSnvX^ge5EqP-hO zC|FtJ#4ebtEp!*#;GD5MXh)wqwOK=_J?*=a-=74$>>En1e2o$ z3cCIMJ^Fj>reC)CyQ`OEO2v0z-K-`ivaifO=ZLsB%l6bkLrV$YV1iV?a{@D^PE3P~ z8%?Ubn&gTevcJITMPV8$oLEjC{eb*|vRvwrWH!MDSBxA{PJfYb6%{dRc8&Y_?Dsju{6u!Icc4$a!N+P&e4;B}o<_f_Z;qBK zt&m*Pc4Qj{3SSSK{C)b_WB8TQ0UH^KEWPI%`^@jK62c?x@fCvX;xyv!#x0Vm6H&Fy zv@b4R+*;_iKl=dUGp_{+7XxFfqYgokl0(qmE~E){aTojs!N6JlL8$U_Zl`VK2X1|) z%@g@DiDL8v-`#yBGok2AIAC&piwELR)46Mhpb#DZZMVd2z%Pb!Rjh`SY}U3QFA;zR zvrjBN1feoWq6o_s=r-Qw5QNYqSYo6}^lFXZ1KMJMv_U_Cz+^&Z9uWX9GD#W=$Z{J3 zCLMDc5vfV?KtNxS(!qTPT@9(o^OqK+Z(2Z?h!rV)}lum`ziT)cK7a#25rd`_p& zh7l=84?(2Un<(6XM-ZONg<;ml7p9&$h4WKG^@=LLj1~9YXQ!50Ze>z@oJbaRYaeDx z&a_xszo?m^F5mZJ(eZjuu)(`96tJpyLvQ^+SUoWV8BLkvX+RuzK|VlFz1bYQpC4Om zJvwtq$#vd>Tk+v{KG6BAGq3FITrO2VvKi%>)4ZlRThYOO^YLp!gDY~F%C!D~+TU2; z3ZYuqKYLr(w9-qmM|qPhu!eaNHKPp^1}5MR;2qYQ0h7jp5R7 z$a%bW60e=t?Idl{n`Eg^p3n{ivEO*TruQr)WjXJo2XoVC-6eV9vD8TD!GG|Aa_*ZQDr9<<_ysq49fY6gzahjTu3K({jdHU4d%ucdR zt-7ym3GozSB5@{29^=$W{~cbwmP62t2MkDZPAXLe>}o#(V1@haqU}k(6A~m6P`~w{ zQD_nBYSiTs)~*&h_5Cr-5MW*_AA;f?rwU35F+$XbpfbcEC^b^&1jbvduedvaba`MW z=uLTHMgQe!$`naunlLi(9Ycxrm02o=xdd#H!nOXt`wzF+904jKnZh+kL>|Fonk<>cVhPC^=-=st>U>1DNLrTiF^U zv%LhR!bH=dtGO)o;0uJ4bJ8oKQ>WLQ%H#XhnI`$1_}dvdRoG9RdQ9C^5&N}O*+_7{ zXfPOf4oSa-%IhE51~|d(hdK|0y&pqlbtZ?PFo@26!iLamH(+oEjXr+{82(WIn{P7^ zXVgwo+Xkqo$d3r3xaKW*9pD3a{xRF(w~1pM9_h3lf%=~Y>U`5eW9GHGs?@V5vk}ft zF)lSu(rKQF1b<4oOuntrZDf!fl^U2JJtV_VC%UJdjV;@-r{3aRDlxnz*Dxd~?pK_0 z)ln=(PWdzZlKKOO=ff#p*{NO>wPcQDnwGO_FaKjFA}!pk77H^*EtuV0OLh91t&UUA zMrc!{V7MPf?VQ*N!(K=0V0FC3z|0d$0lV#CSH{B+L4qZ3a+UDCG33NrsQHle4EUTb z?oQo-jxRr?-y%9(pU;$~5C=cEeG`;V%aO!I_u}1IUaNYK`%F6kH?bnRx>Ouda)aM?5`| zcjo#l@=x^By9Z`?a~vODr`F9m#LBeefUP<5)h(cIqJ9Ab4{_x7G15M=V-(j>=U0H_ zE^$lfVu$tj0o?kpA$8U1#PCX>c}j_f-63n!35%H)su6B8)s7FLC*|h&=O*|T0*S`N z2*S@pK-IN42EE5lx&%I}wo~d57@B_#_mO{#KpFY!-Wk==8F^tpo8GRvpQzTOK#wI4 z{YM`2|Fq8>0q&m*xJSx!f7XsT0^GjbMm_4Y5%qYmb+4bctvo+L#o`;lrwtcY1iwCof@OV=!Iq(Q2wV`_F~gEDt91Wq zh9|Fm7=&jf``zRC5}lE>Qb{hnSxFOK@u{=0LO{5ulRdl-CsZ$CbOZA&a>kNBz)|{Z z&fc+j|ITex4=ulk4}5V2d$C;0r{sevW8i2PUMaMV8&FGvy=D4rLQ7d205 z=8ZCgJiM2k)vIMuZj<4#)P9)@Ef}~$u$cLXJmpfTjV|8&soZS51n=LpqrDGaUh!pb zDp&I+osom!!jf=ieI7+am-JC;1-1BAJ9ld>UfC9;e~6?cUao?DEJEdD(m@bj3dct} zk9cz+8`rb%92LwHEBO%Ax;X)yJeG+>@mL}S@(qw-#|}qs%Z@^i z?*P4)1^pIX|I=;!pJ8F0i65(|fA%E4Ne;XQ`V9#qzjs^5j`EfNpNLO05{c`juBf5{@Sxf&x-V%-z%J#FK(3 z^l1d?N?7hglH;CVe#S`ReRZf9AVQ=|0LJktZHRPC?GV%eSXDptH*^&tg|8p(U++%4 zii`y=8na2K5#KZbb{{DH5H$PzZ+ra951v_n;bh+XPNx&`;}1mq*yU~;xT_kC6_dWP za-VMz_2UFWe(dpJfqDt*;{MM~sBFlCjsuOredG`G@ndgtWq0<6CfSds|3BC7(exj! z{v+`DE8HD{&+ml&{~vqr9o2NZt&2uQQL1#QQE5`6^d?ad5D*ZQUZT=LnzT@(AiW6) zC<;h#LZo*hT?9mW?@f9_34s*u?_1~Yb@u+&-RG=5?pb&3y{~^TU<|^`ue|Rp&wS=H zSL3GCT3{3DB0~ypj$GG9pWr2X&YXfEQlHNAoHVKcpnIte;8e#yw3u3sDPA>K>q#2i z8jo#zUJ-w&Xhi0FvoKH|pz%v%la z)f;|Xn(`SA1AmXpw5a)u&-|hD+bREVqMYAO`Tq|3e#b<=L(;#7=)XhK-xK{dG|2nYYVacR4SXEXi~Oyib{`+DcuOhe7{NjpKJ6;~&$e^7rEGh~GWO|Gj~; zM$}?{M;sM_?6vV}E;wsub2sIR$(-@c%u=L-^3pQjq@P!uPY9BMf};$p#xWN8)7YIn+%uD)7H zc(i%G$iHitg`iibLr##w)#1%Hix*K>%$uVYD1D5SzUQdCbRC#z*ZDzAxBW)mKv#~^ zXl5typlMrUgzeKQ2bZdB9#+htc13qC?h3a%E9_T3J%cY2ny)Cm6~ny#^bj#Nb9}-z z%OLo|Y=pMoTpkM}W(Pv*9bin2_dNX6@4LBp3)CjvU1qF!`T5d;XtaFf5rl@+0=slD zY%q2x0yBCSu&~< z7;%Pu+{Ky*-*yt%?%W=e3yD<-3&4F6SC!RnT5>U1oCydttJf~-l1cj;Us*SmU_c6q++i&H$*Pwq|5&!`Iyu^uE zq+$b5`_72lefl51E?R4vZ^!+AzSjf9pYE(VIxDVp5xTa7ANRZArS=1X?uJ$L6DjBr z^VYkkAaM4dR{)+CV}Lgu(4GvQZJSUoR|Lu=p&G<=#IJ`@r=W8X1da&)(;CR^8`+z+ zaeq8tuJ4@j`xyi=!>#>OkkV@yj@1vCdG_mXmIz=~0h_lY`n!(4U>|P9eFWgofBQJq z{=CNKukSZbcDPA_(5A58ujKbD`TI`q?^E(OR_C|j`m6E#ZMgo2kNbT}exH)x?)`rk z3I0AMzfZ~UQ}X+i{M+2-|37(2ku;)gcWd7x#ISYs0Q&U0VDMT(@$Eo{vhBS=8sj5 zznHTvdy`m+@a(SCBz%0+`{oYjDyz=}ne<|1JG)8F%G-j1X~Z~33cTeQ~9p=15c z1~cw8M-U1{7b5Sn$;?M=Pl>gwy^wY%Ts53zbI#9ql)Aa$tJQ0moI=4RFz?3WoL^s_ zKy8l8M?)9pI`9{2Fg71iPLHQ9s0D0^F*UsuJ*jzFIEUkYs2GWAhAWF_74>lEFLe`6=q})8C6FV__2-B-6OYrA7r$mUPz+Gy@d&Kgd)I%uXslsoM6|LE@g8_4xH z)cVhcT7RoH{k^dC|LM>De?S>uRJ;y9x`%UI(Cla0jKLSXRbP4h@`$0@>t6bn8h?3E z*GtF6xuCgAjaqme`0UbRO~<*b=)T4d?w8Ce^|wBjeCAjYS?b^Ac+qv0e&xL#eA3Aj z`w4ewjh<@TuZMf9B;QM2RMdU;`jxlmG`;rqCF^}z@S&s@w@A7OgHHe>1DJ9cKw}tWfK61vv$Knc{h*fD4w5%D zwHv+hB;>3bhuzJhqE8^u{27CSER@9aqkl@n$iGu50ylN2;OCRNK3bqX! z7QvTVd|BEd6dQ`P7#>B>(CkYwCoVDdIpI2LF)ytZvjVpH#0&J<=&N$6Y#{&{w|BMdSp&zyhNI&+c_uW(v+`CAm23n^M zl)wI&eEypU&-jn#y8o}%KXdw91?&H`@A!My`v?0Np-!OxW}5`|7agf`G*)Q9SFr^| zoeO1{Uh#%B+HrQ(17nB3!m3rXeM)g3TIQ$^hTfMNP5U5blXvdAkS`nD#f@<(qRQL8 z+l<5AhwmTFjk_=81hU{EdJH{s^XChzNg}+;Z#!G!VG;+ zo7{yD3w@Galj~k@jKAKBoB8^R<$$RS_VO8qrpaDE0Fe{WB=bV$9?-@2&rt*aucT@8 z_g<^e{v37}=P~pv7246n`M`TpxZBcC*k5{L#p&n$`|B$Yyn@HX;xvdCO96e{*IAgk zwz-doS?*M6yMlm_OK5PN(6I@xOt|^1q7<$igAH z`x~k$J;={EKjV`Pm8aggkGV7?-_!*>D zY&h+SC(+bYWwTZ+3MnT$1Ct#M)!+Q9ZlT}uu>aIZh4!~<)_+${2cSsB(5aw_cgDGB zrmUGut!Y`4e+)y!yo8BQtvv$*LVuz^Ij=BOgS7T z>H=XKx?)S|ziKf3pY*zEyMcZ%x;SdmP&yRdh!8$=2&Yp!M`SzpuQ&zy+wLQOYTzgr zc6$JInqHbS^`qjrZ`1*JSd%N^;}_lMxL)6?KOh@FwadS)=zo?xkM_6Z)qh_rTEb4! z*_k6XfQe$M_|ayH0n{>S8&IeyI|U61Ak!8zj#>KGj>UiWKx0v*1^>fp4sHEs*_!`d zu7mbFBJ32j=gTDq0Ny2*ryx}d{9f}p93XAWpSc7%IT?i>JVBy_j$%1aL2hw}17P-d z2v$H`)ncLbUuR{%rK)~QRYl(Tk355OeIzkN_ccrxG0GQ3O3;LTfR;fB;lS7tVn`S% zJQk(i{J;Et@h7l7Fv{iXzutxajGzC}n8W=4J3~n|<7iO+Q^IfCThB&QOKQ@wAyh@Q z^~U9fH$|78F=>NXC6D!`3CvKeRjgqwlp4OOZ*Wy^+`h$#W?m|XhPIY`5@j4tMe&7< zE{Il12rW*c;Gd^G3-`u;!BOVo5N)Zd@2!hwCy33HKRPMl&PN+xiha7-1iS0h$z5g1 znbxh}7K{|Ek7yC_R}9}~A(;d4czIwji;5ySX)uG18)rG+C)7S^gS?${dVyhQLhwJ@TRrAT#$ywR3fgT)bU*gXfM=8ALSK5>6A8+9PDqi%5AaWK*+Xn& z-n86qfBu;+Y>w*UGUzV!Z3bE&8rFOU?cELwVs55GkH%%T6_{-(?cA1XrMy>r$t^#G z{`37;Xx5iAAI}D81#ZJ#S}hpSo>BJcmj^tEG<_exjh;AtHh7bA+bBn)IB_$2%vmg% zP2!r~N0S#Q^UuBZ8rdJB)4P-bP$0o0gejy1mk*4pjn-PcZPBI?9Ua<)&hW=a8CXuRQy=r@&Js?|nJ#=Lv9;#F%l{%gID}TW1V|YUo7rq_r z)yGs+GYs55(K% zlICgwi?Yi8KefXjvq(#gy51g{E+o4Z)6Wx4$LO0Z0}8M^>njvL)O;0AY1Hf_ejmdZ z9{>-dc5yR1<~@ZWdOKF1Y^B$EWYNd1EJ`W9Pc*d&Y7l^Lx?Rg_IxP+;+Re zT=17UfORw89V7;H?W09=N9{pn(G}@2H&bh0E1&4bN9s+NIhmM3vf#j5nl z33(HwE;8NOK{kd_uX*v&Sw-=aAs~=Jn@D_r3i@S$86$z#QG^QQz_#XmeoKiBX-R)n z;rv3>=2RV<@s6{HpKM;Ts;sRyJW8BlI6)oR*N+o~v?4;%>4`}@RY(fBblZt&CRbD5 zb@TNT^ODaSrB+mA@v5cgXfF0&Z;F;4E*g$eRP$bSe~c~DHst+(I!vDlfUbVfdjc8m z5F@RId$bS(?l5sima>liaMJrRAfnkq*{hp6yXUQ^C)F}hbNl|Lx%XBaT4(-88UB_( zWTXml2L9~iWWV*~`4Nk>-0hDQTEcIN<-hIH+1l_Vv;(!c=6v*SD>8(1dH6!f0+jq0 z8!uWfXj6Mgq=b*6jm#%rwIoO`df)gNZ*bIGZgNl0+WDdesUO(L8_1i#C~lOxTVUc| z`-{|&=mXrf2Bl+qu=v`N8mcAkKI?CN5+4T63=9~j8dPOFj-s4@?rvAHKXY3%d63wZ zUOW9dHvKSPz1aDWIfvwZ-WgS})+z9$Mi18b174ZLz`n`g$B{)Q=Ns>QWTC9N8bOvv zCU$1!ZRdsUE~bOrKsI5(Q-LL4hP1#L*)4qO>?7N=#?$bcB-@7p}iTk$)13LJR4 zg1_Xi`bfz0gH3yg=cUE!ns6I+8#fNS+s5x+k`IsZT4EpzKMH+_8F{$kdkyu|4Bvuv zYZA=6K8=?%cOP^}G9TU-^%~Yyx%$`2l3?+iv6@FR#EpLXTW$jV29Gu8eY53Pn~_y_ z&I3C8V4lFSjH)rfKwI^nGu@o*Lt*>FCB5Mu=Jc|!#mpt1u=2)Z>tZjKH_SQG_ZD5y zR$B!OAU~qT6l&L}0Pk5ijJBXh|HxW36%+B8k>d*|e0wGro`Ajojr)1jTf`$n#Pe;o zp+y%0P=55HJx&goL^a?z3Q{Hg*?Dcz591e7s&;K#n z_!nsFydTYDbmfy_##~;%CZ}JqrW!e^O$l3p%=e-5l@_#6dk9Oo$k488c3TQ-*B3f% z#JuE*B%TYtgiXVAy*e~SP6oGD&$5n+K-$^dLLn91-cBn)yTaFvm68&#-W?be|i2w@uPuP;k0cj7lzsuc?Kow zT0k8>0p}Z*57@0d6^KIa8lxUDUc)fEl+nqMGWmO>6+8pWUem9mNfOiM$fst5fDxj) zk(Hfn^eJLBZB%AS@5h!>QNi*bhI;lTPgboyE)(6ia|)^$>ZoThNA#a5G-XBX#)*5c zo41zNhbgfdS^Yqocs@8^_MU5wRE8Gg}=cY_(&<@VAAp6I_mbHCB)G0P)q$IB-;kfd5c%T z@wx?^vA?eHFDw1Szr!de5ZxrZQ_$hQ3!rWG9iR1QNyoQ8!C&6~%a*y3_42Pr_doH^ z(BA@%zu}#K2i`%^K<9Ha_JFflQ9}$IN373M5WA3HcX2{eQH8ifY#0s#R7H33P~8!c zkfhw%Rh^1yGY7gZj)ufF^VpX1#%Q-b-}iFOy!;a+HANwu?QRSc&J7sbK1@Uc!Oo%! z6b&^5S_px*x+7@p*n?fCJ*> zQQp{&IYJ0r1>2gzxL|#7A?Q}xNYrH;%vS35L5$U2zxS;QQ`0Ejt6&Fj?q0FNW49xp zZP>_d$9Jta+XkX}J$D`VuLnE3JDEN~e(#^`nV%ytGAy2gI;Q$)7ieRg8u`)P+a-Zr zBF#CIR*@vVsQ4GyvZ}42gif zO2pl*V)vrR60JhV3-Og~OYYl_!ITCb8x|j(iK0$=f|`bwdyZ{@l#A-7lRm1dS(soj zTxG5|zf&t0@P=G5!@eQeHj%i*Mie^Nm4Q~*VI{}}lNkCZG8R=c0bO>*SgzH@fHK&fE=1URf&PgxOM){GRuOGdVOip1_CC!_gO`%q^ zkajS%LEHqpVcN4{(MFXlA+Y@H$LQXdf5 z_bmNLTciyEUwL&3dJUwFPZVk(6jObEHavS~{S+aW+?=GiQz$Zn^Vw?{PW)i6GSE76 zjBwk|474sPngl`Xx6atfttKsMskVAV%o~^Nc%~^nPV9--9rM~Aw!s;G4lb^+Qe&ZSmK)(xgh@?g|+k62PgrE!*!OblpB3*Vfs~ZQN4Q|=i z`SncogvK6JO1WvQtvVGql^1+Ey9K&X2#G*Bp>P6m;mBub&-U~)I770&bKAAaQx7i9 z%H~Ggn@s99W4@#CR_0rjEB{y2d^)PEGz9+$H)b-X;2!uBr_)kCDM`w3HWsa7bta5P z(p~LJqPgZG*|L8tg+!X6h#|bbs{9)d)Gk>n}kh z+r&Pl~E7TLSyL;3H!l;}UwCl2jHFEj$(qGUO^Dzs%A#$TP79(a9rlS}Mp z*Q8>%i?c^mVbEUZ5BQE1ah~&fAP*~hMTpBNYJ$H5%tnBrA$Lbmb|P$AES(NEHTAJ@ zmC7SJrIly3$!FsD)E`?Xg6O5sKWtG0wD01=yM~c8Ce0JHZ*iHIrOeI8AARP(}0+3DhKtEAckeX8vcJ++1AR||7f5E6yYXBa%rU<~#Z zcB!N7E+fSdwZvzuI8jO~yD7ai+LLZ;>pN2~trl->LeYA~X|_vY+d61(?87g$j!t6R zB`z*J(aWDFOM1TUiKSDTOqy2Y6Fr{Jq8t^t7ofCohBh`>us^>g^M~wTqh-buCaqFA z58E>z`=u|Z8zrdoB$_|`==zphPw3 z2IPL;)~Y6W?#cMu)}(!OOFvvlsR36*2@I6&QY^mJ0Mq7|qY!I#$AI{L$qRcWGoty2aS{gc9cbs^cB z;a|RaxA$_oet#ijtq`|{B3&w(cbp4_)zm~cb2>m)r{T7m7@8!W+OKaWW~bVD&JDBz zszw?V3hkY4A+8J1Z1gH@S1RGtRIHFqr_l=;Oentj||8=ysBJi zu5Q<`C{5LoY=oYJV$O9sV%M-z#J7RhNqvw-<3>-69KK7vw4|uTTJS;jsFSmmh~WFR zckg*<7`HFpL`eaPq7ZiGh%i_k%heD z>q1MYDF&<)<`lHey%0lr4-IZN-94k8Gt+l_a4I62El8uNh;NTCq~em^Bl(n7XYnBD zndYmcNdz0@6l5P@xfB=DsJY0DHh8~?_Yv_JciBl)PiUQ05-G8IDN}P{XLO|J8tmh7 zOgGusp?cQliCVY<^yy-n;0oX1p^%IxrQ^p1u1R=%AzuK+O{m5S@^x{LYheIv9?wD% zU-VIDWlWWrPLjk0V;fP##7dVax!jJ=A|bx1VyPJjmEbta@S+LvNI>5><^1aglod78vA?7ua^L+i>>hISnd=vW z7v?(ep^jS8*tiiAeN)(0gP-Hm#bZxO&veJoS75x%=b)$OriJb$?A}Uix4IgTqc}-u z9zxBhfGZIl-9rY%+-7l2@v?ozKE^TMgCZUDZhgY+jc_1XcDx=N9Gg)$nO>M@m+JWg z`FW=0=~G(uqGWuJ$M-$WlaRC#Zuca4dk=dvpq#p!|9?xL!@-ZNx~nQcw(YApJaH?!LRPErSVeYee6Vu&jS12(G} zmb%PWUtV1s94Moxcg57%H%?sfa0x}NC>l5bcq!W0SulYtX86B7r$xo)#V#_ACi#w@#&a}p1 zJKQF0ZH(tIGmYA*-mmL_G@;_I=bL?EkoBI9kB2|uF+woFzvUPB9k>dz#fynr>hJh4 z7jD6T>o0&iYBW?=MRL+5|7x-Nd9Mr_zdYUf!P;7^<{J&x`F@B0c{H7Z4qg<|qD0>2 z5(TDr_PkBo>g#m)BfoIYqMs&xz|79(*myD3p8T7&J}5!6U{dT3^4A_JHEuF&-YXNY z3RudA1a)+j&T!TsyRj4RYSVkFAa*~kvxAE^kIh^Xdt!nF1Sv05-st8c8Al`;{Rpw$ zxzQY@6{~QM(d46d-4=rR6y$`Q1Y=t<1QZ$KSuwSm#=sdN_mY+mrugtPlVkML9}%`D zYdZ_c-t)HZKKc$29Jfm}gdnTffFu~i5Ik>6%b2p-mP?y^H7zHK^z1yhap4g=+?%=r z{en2#e8yjbnC4IGGOrWr`)p#ebgZEvk=Ccc>`d_O-rDoi*ee%)_tFb9{ zug%I}eupAYkE;rcp%TEH_Y4No7zqqx_7^7R9yBRwLE0`{InZ){gpjhIau;f0>K1kp zX??jas;*OS6jYRv`_`}vT(j2Rq_beS^gCeBgtmRd}e`chT=K$ze< zRf1Ujw%=3YuZzd{+d)d&!Ab6LSmC3Br zR$ixnRdj319F+q^pR?d{S|XDOB?+GhOuQdMh8J1{V`c73q?kI8Y$X`^>NYC&qq@N8 z`w%+ZUD`;5txLpM_2gl=n5pT8!}B~Z4$|(!3hP_4Un$?Y>KN$uc>wnW*xMrcH6oqM^OlQ(NnHod{H$sTc59PeB8E zKT*4NP~1$QKCt<;1Fr`5WU%>P%k;mG(_OmFu7@GL3Si2~>PQnUt*lf2$WZ1j**L{1 z_M&L;$$*k)8D#v~{G^|}L&h=Lus!}@?i(qn07*tnQRJQ_m=V(z!35Duw9qac0m`kZwqXRQU{5Ch zB7#>mhDn2E_6Q9Fp|aH;$C3u0w6&Q6!-3_BitG z^Zu2!dH(GPyc!&_u(I|Q65Lm~$t8uUZseMJoNS9~s(CdZ3%TCMCtB9PXyfy4JL1gK z;Qjnr#R~w~duJnE7%*zD^RXegq(U>?2fee7wH_lZI*id`_iDzRxV4vLo^e0CC}VR) z(w20w4}H|i05|MB1u=?B{K~@!vt`+h9t~3WyI4JmwT%@1Uk$ zR8TTkho;W2`SVJqiU!4_VUm}kB&ij~34P|s8hD%ZgG+H(l3HGg(!GdB7qAa-y1E1- z-JBro$lc!W8)r+^W8R2EHjlR4@b@Q3!%(uyxo`-Tf$z#^WS--w8#sYeY36Z-D(!WF z_`%2I^2%F1Ogu!E#S+neQ*+_%VleL5&T{DE1VzDf>y4Mz*dv z&tGW=B~k{8T8*G2=@irZE&^su_s*Lbkexl-0GZV%^siee;!vs;`j8H%kDadmNTbZQ&` z8>g}xGGyP!6^vnlRiLK!`h4siJumD&Vno7Uji3O;qI?)-lhsaQpG%jXgbB5ov+RsOSQfUBcv>JWvWBkmO^U7sqkmI5YjvLud zIVEDa=<@Y=cT9Ka;P~3;!NfJEQGBv$WqpE}&%{lBb;taZ z5UET_vYm|iz+Yplu(xM&U}2WrX@8%F%nh=8{~?OV^c4IO7@y2BcW zML{j;t7d0+{HVz8?qwCdByWmp*Uc*&OI&?&`BxE@RE zcCA!gOMLw(MRxi{-$}m8iv^72jh@u>)x@BL%D5GVMV+lQ3`+~DYWFqNmZ-DHQJ)ds zc$XJ)M^f3Sn5IHs)r~~OU0e&}0PN0ix)$76{!TvfUhw{he`^_0onaba@C+_R;_CRm{xOBiN)ThV? z#065#;-p?LLon+p$T}|EHwK&e>CTa%ln`sha86Cs>KmnJwxL^2td2f(${|NFS#k*+ zbdnq|9MO*)?;9Wrjp|oO9OpBSIU>Hw*4@POdCz^}-!}KgKO*pCJjC2{Q(mH_oL0-< z3{-j@xz?-n(>#mjvUX9++b5UkurG7(;PX%vK=2Z+XR2OIaB<|IH2Ba~a`B)}ZdrGNg~2_6jAL82$T`~Xur{J~ zad(5zLG@O|toyR5NPoW;CFx?@Jow8lCZ)Z^<>3fVPmg5CN9Hd;?tX0J80PGoFkfRK z)JFi&XR>~4MRVlh4TuM|rlyY6_eov*r(Upa zDbv?V^FK0|+Z`hqpBmboJJCY+M`et^kRa9xqa1JZn^ad04ho1OJ*-0-k3FT!6WZ%* z<(Z`ojLnwZT&Mk~!hYQr{@x^5{<@%8NJRd&2j@i%fkJOZ6JiO}0YM)49Y+13FDS7mP=+T70UH;5XI>AiGX@JHYbnUd40;HER1?qrc0CFEvCR#pIv& znk<_&y1(;$QqSu%cJJ~feX+Aj;4vi5g?56R6qy`y3JL(&>Ybb1?cnOLEv>~S8bG+v zf(J0ReVQ60BFmMHm33n3ROkn}=9~}U*Isp~DA-70OUQ2=Y9YRI6za{2_75NIP84G! z(6DW3bbZ&NTJXN}R_EB`AuHGY^)bv#t5@I7xwc)1L7&SOdcsj~bVBk&%ztQx{A^|q zoV0-A#OH6@OQO!=QaSHd`fN`(iX&{*u~7mM&p9{khE$0?>F%#!Ka*TnuUIQpM0@!n zRh?Ax6`YTNvSO{4(m$~S;5T0tSueEU2RVlJfl19y02OUQ>kR&q3ZveCgnRkV{_MHm zv!Z@ie*XiN-xSPl9DyB;YE7Ay!M!Rr{pHJ?dU?iThMqgF*E8kb}M}Mx)to zZ1^+UN{%-k;w((RPF@}wa1p?HHh$N7iq z2S};M4ytAeQ7B7Ko{=Fa8xS4=k`Q~36we~YM)OZWxpGbbv1=b-vz+H9<^*0MJO?s7 zYSRVp$ZKOI3es+YCpl%N)2$-O_FLwc7&=&=f7T9sIOn~dG35eaKvmvbhnOx{Mk|Vf zU~gNxF^cW;;muNZbAh~xF8YzRc%vpnv~DUvyq{@f>BeIt4e6+%)DtJvH}d+U&wkN%5JznK^WONi>aDT)wXJSEKYWTracMEe z1^bqm?XTj;73>)}I*J}I&pAS#IsQ~L%VTOP=hPh6{0GmjT5%SzqPQm z8^#5Gcv4!DQ(<)PK9|!-c5d%2t9e?n`$=MO_HsC~2ZiH9Zht`cER40y;cUUtC$B9i zM;f68vj|)BjftwtBvBimyr4xxit3>@`TMjVb?;w2S4*dJc8yASc*4d^I4+SV;ylxgqf9meq?L|Rf*U-&a%%p98u)OX;5l~s=V3svh|JIIsZ0= z|I0)5ZPp_8rp3;BFuMeC`#qd9y{ zwE;Hfs^9JD4Qh-ha$E#eZ4|7vwcRp)WiLQGfuasaC3_qL;Rc4fCcJV=GtpMzr*Qnc ze0{@lOmFW%r3)A_ER6}Kc1{FAIqOrW!6mYD%3UGjZ!dOK%Rxa0GJE2w}wj& z0@yX9`Wu@X+&FG_y%FmTPzTZEyaDmNf(awqT2PiQCjuw7L>$lux$L{Q{Z*r6s*W!0MO?ONbT`ggrC}c1B_@0w~$BDCp9LS&i;^_z07Y z9*G}sI@dhYqq_Y4!qD|KFF6eCGYpM!8Ap*Koia!u2Ph%RqSPs*M8Rz3id5wR!LwQ(0m7*^A4u zh6hx%k6`sxXas?g68rcAHUp+n=V9sX>jzRfn!O%c$)g74|)?BRh56?VN+!Dq=U{j0@$5h#>-pl&?zKFsFhoL zVl^Ni|Dxx+P&9hhiH0gLq73;Y2tXEbc)9c_GUs@XWYmFZS5&}=Mn zaQK9CQf0c_>~bN8&kb$=_NBIYhtUi{gPjv@^^s`(DTN^{J0|%(hLS|_6a($7=Z^50 zv7luzoA^$%z+2W_Lnosc`%-!d_EQT1L6jNPEa;3cVLJge7R-`)aT(69*EOMVH+Od3ec8&#@Jl143t#GpJ3v2%(Gdb5p(soIi=U=5ILrEzU`0EHDnrjj9 zS4Z$B?=s?ojQs;FlX`o&-cp!$X5$(+c|LZM%hnNuhETS&leP$eC(wB`<_#ZH4)?SIJAm#CUudX;cpgq!t;VRbgs+oYYIORgzKBz{QT78% zGO~wqhI^9uJ4U#CtQ{@{lY)IdbSbROmsDtdEuvz79H<%*Z?*i=XuC;G8V$H*@?`CB zO-3isns?n#@`$1ctFG=^M#rw|DAelhzcs z(;jE{ki~tCn_}sNF`j~+?@j{ZZ9@yOpQ^c-(c9n5^&TXJYJRXXhKQEFy!t)aI$Brd zt5}e4c{ypw>?QgQ~3{c7$T8^ZhT1iltDmjzBM5 zf5%wH7k~o+%xn9wlqR?6asfw})pmIrT_(lW&>^v>(lU!paeKvMxpqSaEN6>NY=c(r zZf!0SxkS7HA{Bk3h?~8zlI5zy=;&U1KFLp6B0^YXqx|}p9ifpMgjy4zvk4CS{0waRY*2YkdG$kO75P%!}9tOuTmn#X>4Q4b5B z$NXrFBE{w6Ug$TdxexU=X^oa$h5D`8liQ6)8}9Gp4G7l6PYAoh14J~6NdliH)XJ9B zv6At6o9ThChdOz(^Z76S65IP%Q|E&?Lx0}66H%?J%(R`P5mRv7bg-q(=W%Riuy%Mz zdy;bs@<0eCG@Ibu@phzMFe5=XAII=DP_b;wS~aA)@S3;P z(o4q;ljDuI`Q-L_8Sf`^(tCx_vt6V|<^Ys42F%Lb5MT-n2k`TnxUI0v4Q~_0T#WR6 z(_&c@)@0t=H0FCUPk16(R9mimFJn4BN4pJ1YmbpAvi&ftE{s#aK|ar0-dR7`=88@R zDoS4R3eSzA=P+n0ggdfEa&x8Dw|H_EVx*WJCh60$H*u(T;H2UYfI_s)#3+Cim6?;u7iP&w$?S@{;SU^R1AqifnUt5pJDP=$5*)5Pj?M`7bp0 z4Y=jC6(*hvbyz&~In#6WhN4A$5%TPh4ro}#QCEV|dy-kpQ)MB7_m$RiH({N%qM*GLo zN1v?4Ko(LfxGZif4zEV)_k~3hbh76x;CY>U`&wfUOmce#Yi?;+g@-SB>Kjxg(BCAN z<#?lx7b0<*1O0p5gB3lkPq&_a86Bnm%Z4Ue_E zYZEzZeCO$fOb6D+ny1xP(|1-zp<_@W!mQERYQP{ggO2WDX5VMee*4s&ySd+$YtfGD z)~cZ@6yW;O7`5BdRTYyipgHyMgR5_`bbd-wtcgZi9beMGG6KD^J3d7UDFJGe*_Sw$*#obfhesn&S7I zu~ncD){hgi4XW%=WFWq;^dZEUOhQnNV+p^uwc2;%6lmbo+QQ0hinXm@lFED1~X;_=6ZYD4YG(qlip3FWyfcZ531^X zTSqm!+Qb06v60X|ltj@7C_qH`oPsPb05$JSb&Dk=X%1S>5-QoSOX~=w z_rM_!)|ad6Vuc)gLe#UKl{Q;R?Xo*PxjWfzgHi-uTh?6F(bf_s8|z$$)@cK?nQqok zr~XKLQ5|nGtJHbLxTkvkQ;ecn++u&OuWTT5dApJ}&6qiBh(r9c!`iyb7JxGH0ii9a zLqzBlbWbEe1eTmp!LmJqzX4|fXsn*|bIksCD~Ar#SlUtpk`9X}VDidtRDz`;+0|CO z_dE5&kC4TI9Hfc43YLxx<_R3b!cpAwDs#Vw^z5dP>l-txd+|B0F$#3qH&tvVY3`Gs zi|k?w`COz8Ttxt@$A(&xP=<~n9Y&g@j*2`5ZIJ`#eO)4HYOD)Z3E6hX%lgZdV_q8__5;ul_ zK)8hC!2E(S`NM2KImqRHOq?{)NYqhyllF~gg6xG@rl&R4*Ryv)Xh)1Y>5@5KjX;lM zUqFHF5zGpPjtf0$whxD_%S_+pKNVBv__pSuTVFcr`D0OT?UQ64eT-Ugv0amoQ{G8r z&eFD}_cSS@pulP8YD18Gu`#oqjY@*-j?^G4!Oo0`!J=^{XvNiGKh0ih!ixysdL6 zVsh6e0`Ps4Ls)0r`z+JVbY=j!+)K<`a`Zz`#~c`K@K)8?tt#Et*uH(2JM|EAkT2&^ zbl3bv?!KBNE3bgcuKTZ4p_Nk*C%}3uuW9>W&yNAO_nlSeW|f+>{yF08KJFuB;TMFM z1bOq&IIhB8!_a!bj1_-xVx|Nl7(vxY{@LPJYIxoLA^yFAfYa#3RGr(O2Y4u5>Xedw z2AbXWc3PzwZ|bkGNU~V(NqRm>D-BFD+?Pa$&6Br+nGr2_19=D(IQ&yLVV23*2EL#- zGu^iJzow(6o>y8MMLegh4|4lRMSmAOBoe5KXiSzRrqO>z?nJX%(}V9=zIizx<_2 zaT!^qyOWB7P_--cF3Zx~*P1f6RDufneZ|vSGwK&z->*imA<}B{o0y6$*EN%0q|CP7 z%I5Wm-vj^cH6UGZ40txedE!R}HN;|nh{^4l(ELJUPPs+XD16i>r|1ZQhY1Zgc$Xf1 zw2eL&X1s=u7&bD|q>?smQD%(M^7 zo@YA#J1F(Uk8) z2S)jN1I?N6DQ@9UF+KDy?^C#4qoem>iKucG0>dI~@{tzsh0Pp26wy*Jd~p(zm&S+} zmAnyk*%=~w!9r&FYWQN5B^iZs!8OMNphsO7o!E|GL0Jblx3zi=!W_~$o2oEW2CjuZ z&fFFBJR6a+wnlvMtjV5((!!_EKZPkd6vYx!k=em#~p4Woh+X#juC4;gKFX{_*EVs?iVWo*l3X+$j zw1DVcnxaA3V%-(i44tbtHdQ?Cv%zIxuM-pe&7V6-!a^+AYE=8>%-;=Ktqp22I4|v& z_H=*&D%956{EVEIVLO7JAmT)3k8*IR9_rmZ1wB{@nKh;@=Vl{h5;IZrIkUHL{Y8k@ zC}N~UjKPuK=*LM!t1<^Q=fStTbJ&Yl$ZO0St9qx{B&U@+@4RteC|DBwj&bs-9)yXj ze}8KLl+asPw-+kL0%c81OUFNDv<-afmU$dtbSANT-f$-gAq_=qA}3iE$hQs=7(Gag z1z%KK;wB_BH$Q{AqdQ%bZ}@zd6h`YiYa(y>j~($o1mICDEnbALo^cebAnC9J118)||*4CcFVQ>VO?f4U}4u z1D+*eX`k(_mmdF7Hj zMR(;=ruo$Ut-Iv8K5N?|XvjTaI2koOc)_6J`jmP>JMYl0u{Sa9VU7Iu+Se9A4ky=( zBJ5&osf1_5B&g%u6;fLucM~xMBcV0FwoyI3zfOCU1W zvWoUi-M0)a7I;z6aKbJZud$u+WB}IR6F3O1Cf`271hxTAxZ?j}@4dsCdeijrASx_^dh22Q7I9TCL&EhYD78+h*TjY2m;at1O${w??k!?B=o8vy>}3#CX^5$3BTj+ z%+M%SGwIb#d+m|lgV1u z_fBS5EnIs2#womrS{3@i+-UY=OsbVs(Z0tH)6G23iq^yk|M|aM@UV=^~f^a&L?ND^WvKkKt|P={}ae#E{BrXCz1FLV1+z( zjvR>wfI8|Cuhtooy*!tf{0-Iy*;ifJ)=e^_EGMZf^*ODoua2^pyn7y)0PK4snv_$n zX~Tv}xG+Nbc>v|I4w@SIS~M}%zA!E;U_Ei03*%VcF-`Lzs}F2BX?>lyf(go|S&N zerZJUdC!W65=cI~Yfm%hI(N$y? zD}$oI`sD5Kdrpn7UEW3B;#mzPrI2H>K#mgyE4OL=u~sH_WYi9NVpViqf1jWfZ=7#; z=gDAm(e5QNmrK=DFL?GWtZ&G8q6S%8*-rK3+OKa``oyW#=QlnAeB;9V|EEN?f6IA) z32*6|j(CklL@ zC*^i_wxe4G8(%dqG%W`PAI&)$c`d-K8V{X;`N?1Ny17vYVUX}D|9X5cJ;p(eHy)D0 zOc!3#fbV1zp=05=FMiEm$@>grrcp*_w~*Aql$Lg=zPchn@g;iLtSSK@$J8N6t^{ZaHb<3n@snW7T;_4#i4?wij z9@GNzl}a|UN`@*iI*uOILbrt`c;4W7}TCEwQQ3)H5z^i4@d@%$CG z=(zqMs<^lS5s<=BYs^i+=EWM(1l!gC%G}k3$W34086`$MlU=@UtXX8epfc>7Joqn; zf&ArNC0`o?G*pc_nA(e71#nDZS;cAW>I}|+@Vu%n3<2|h{8qaq+Wd9AG})J; zW#^Qcq>=kwe&94{-0OQSCR8NF_05#T#E2blfj`EAxN*Qq={^LN89H=_$g_m(phPV+ zoa!S|vO)t+o$kR4=gjC^MH_r%+FoG%G4TF|tHQ|3w4_q#Pj1-Mfz+8>U6TU%d?R;e zpg8gIG&nVOl|^LD&v#`V_5xXgu0xM>jVjZiRL=I2hF4-U-b$bA zT=Z)AYr4r}zVu4Y1{|;QISs#--LY-B`~$*4+#nn!$6)w~SUvn=1pI^~ho|u;X@gxw zg8@gPXEp83D=kMj`;xWT0iIsq|F-Z)-9sKOdDLzDyOSb+CFyNR81mJD))Jj zRg(TGaYp94_Bs~H)d%{|n)Kd0=i?u8sAf!MT#rwMiF?@)u9K5V9C&NZNKST~n@5U7 zJmEmwQDtqnH|KNz9sgOSikO+gH=h!5%v=mmE|b%~(n@!P?+fKr!(2XPe?GMrJKG9~ zBcw@B@$aB#S8h8hh z;6S~;o}CUb%0Ad6!5!q@TG*pr9Tl0nGuQ7pT2L|k!; zOEm1==WY`H5WyB(eI5YpWX&^MjKz+6#=G)QDT$Ai2CN%m;`Te0+cNFqRfVTEYN(xRsarfyZ^eaWRE7n7TIxe1cyD-MiLjiBVRz+#v(+=84)IRQuX zm6;06b_X#SmE!Pke!On=^n6q?`7G@^tXT8-g92Nrid(H9gKF)&UY~oD-es-VwB$Ae zt&8JuV+3Y$oIJf(Lu)G*OroKCkG2aO?OHcg(XQPz>`%3fTwk_rbbL(h*tUE^a;K0{ z-(9#Xy;gZ_OZck#ov2rmNTLAEs%epZf_GOcZuXkHuWSOt1$SSg$!oj?hM~=8mX!kp z0+sYQ{FvSY>DCwWE9?@W2Uzel0#MNXgND!%i+^iXyg_OsXi*-(A%A($HY^ZT3|Xzl z88;Iq<%o{cwr+)pb}My<5y>;R_huM)?tGW5u1cg&lD4|U$bRnHS6>4qAq$cAXC01c zeaXAD4*;KWrZ0w3Xrhk-UO&oxW`p6!U=k+5mnHOj$3Eky%0w`(o&800aPe{MjhdhJ z!T01?k`0nSJzW9qB{y&F5qzhgsW41hVAu2Ggd@vRPFwm1kP9qJLVw#u(hf^foMEuCP=dkDf>~SUCT_W2*8So)X}utI`06)BqXl z(I4apSV#BV4heVk_JvaCta z?iahq|G;)6`to{K_*G>dkMVGvlCK3Y)K|~xznQ3gI3OshqW}{mX_12g4mUP@QoM%v z0uQO{u}|UZXXg7{6Q$k%Bz*GrB~??=%c&7>x%1XVKKY4zq4RSJatGc^dpl;&KS)c7 zfSkxCF~|^jA_kR+PA7FvOcXg>y1sLq=r0$=MCb}g{lR(R+cuy^@j~>|JteG4Qi9wyfSCJy~io$l$cKFIU2cxD} zs+3JRygug#f3WvKUg)RCE6vYZ9L4kn?w^@Rt1T=nk0_AR*XCs=;0v^sSOZn(ZZYZI zng)ow9LFA}g)Uy2tMSAg)I%6Z(yqY1|H_Cj;gy6#4a<{_8N>APYvn_-8DX*I{Xx2I zTtnYmL!r|^3{Xl}?kPGMnCFFVoK>S0Eid1xZLYDu?~zkg5&wj$PE<&~3Ox`ik`{Tn zoI|KRP2j#bF?uiXXH>x(wfcT0KlAfoYl!TF<0k|3`UeHoI0w&;szp8ijyWK@MwD@yBXHb-rK^0g<*vTcVnLL+`mfH0;W=z z;U-PX#;_((gWp3+RnI|aMI&onV)={HI@}K0Sw7dKQU!Sel0Dmbr;%2sO-<5`e1hA7 z8Gd$(m7Gj@?whT-1>IO21~?3n1}lY3Bbry5`b<717r)7=uPy^>mwl9z*#|su$rJz* zBr5UZHMUQ)T$WXPHnh^ZTlhxFb_yqW#&^uh$|h@6G5ZHj$-%)XjPc5C|Lb!R$CYQewqKu@_u=Z zwc5i{rck#2h~t{4Li1!mB5V7C*+!YrnRc|wqc=QaArKm1W|Tr7i|qr-hCS0k?4Eqo zUxsayjQUu!rbAG7yYB|6o$%lg6bBIoRI{&u`7q@_DOQ2sXmqAl%yb~A3mcoY=h&a` zK9R^OaJ6vaOIvtPwa}vv)6ppo%bx`c?DgKOeATWXb%yKoaG@h)t$>MtKz5%_0l^`}y|k=AyhS6k_qJ95!EXKx z(?YRR7VXw#kj=VH@bKs>?olTFG|`{jzIbRG1(^Wh z`8o|og=ybV$wRi2aY!Wj+5@3U!WHojFq1U^ltN`t-Gyqa;Q(SdfiRb zQ<+e!Od}ZW>xbsK3!DT3&`@m+LsWDn45!>Z(qUXInjK2AJ66S8ro7ys7^Q^#7*4f* zVF(Qe>c##>ls3%KPwJgyunyi0f5mpJNqS8fD9?{(7SPFML?BH zk+cqG;V<$J70kKtZ@!2R&vT04YO~70LF+qVC)|DfSlLcqPE*gNTGBt)pv>;Ugw<#+ zYydKpzll#zy@{GR1d&pL!?7zX4*?;$KZb<%qX0oy`;u2D1ydeHz96#EL7odnj$4r3 zR9e16TFjLg4L&{n4~tR2J~72xjFhrAMfRuyywB~>-$F^dJ;?dppOxkEZc4HS;-x{u zV*o#d8tkR4iM{X!JQq!x|M(0)O&I@I{@`N3$|!C!mPKxH13Q$Z= zMv|p;Zy_4~6)Xb(7!vufo*(||3Hi_P&HnkB|Ki@+NB)UIr+=-_7TM$>WRkN;3bTMM z6^sPMNp4rjv-d6dsD~83%SZ}uyW5_i1Aa}Xr^ODPeBz(#^Yl9F+q`$L_ezD!^&~wI zsZ($@qGy&Fhl~#XewdvHo4LR5?a3R8-cRhPZN`}PW)2MCAl&h&nOciEn?QGw5P|-3 z!G-ta=l-DJnHRJ-?8b;^L_xPwDHeWf)Q6x=wf~L@y znOZFSZaHqJXmI88^}NAnQCNm;2FgjGR>cKl14J39L(m6JSZb-gk$d&qA|TOf)qBpQ zIj@0mrPOJgn0UcjzZrfdJfDwm=T2s;skF^LH7w_m;sWq}Oo&(U0yA>k*NBu8Z3EV* z)!pI=zPis|6^W3I=jj^(iA-wUgH`#{7eiYgglBhbSEdBLF8I+Kc6V{3;99-wh4{%k zabT+G06Mv51*uf?Clu4KU#>z;(cHPD5Oh59@khZ$96+&ht$Zd8RK`O?w`)3)lBuO)kJo-rwCyy%}FxvPIIcG0hRm znOt1gtDPtu7IlztJ$9X6>NM4EvpR2aLy+Nn?eqCpLEv1;y>=jI-h|?X@t+Ps*%8u* zpj)5NTI7%NbZ~WIc^1(ZepF|Z z@%)ZmS7-Hh)!lrzyCR5>#`PwAQA44$Jn)C#_KR`#}d;Zmxy+*Md5bnK=I z=@4X$oSHubu~OW3&?mhD8Ycxm;jGaP^A60F++D^u;zuj*@;s$oIWSA+)u7?ln+14b(dXcb;8Jk6Bto|JeUA>Wg!zB+ou04 ze&I(I-*3=>=>Q%3N{s9!P594PvL4=`X6XhxmIoLio}fV1i~ zp6dG6*3OH$Yofpq6vK0IMv*GzDcu#-qe%r$#;4_Mb=;+=+Jp>T!{VYWZ(`oi_4zoz zo8z=!gub_>PEkTieRhhCU$2*_-3LT_9?H#m9Wl?89_6(v2cHJP`5bS@jAP`M; zWuOyDEpp@p4_Cl&C`pF6fI~Ji92h|Zr$OSB-U&5gwb2cO06QBgS+(R9Qxag6%X7ftgQ%?=6k!$}Wc^{0e9Ul$(ExqF6Z z9jIrbNH5?3X$EG5q`Z(*1j?gyfE%;(3+xIe8;Hop4BC*?SX;oV1sp?|YTWmYOt;JX zdNkqb#HAF6=NJ9xZ(cv4>e_Cw$ZjwJse}fUW0^?O-(;<_jPBx>uBnM`v$bkz3eUBUE`$ad`wnu8>ok5U>{&t6-FEY+Q z5P2&;1yWX{?`Cpn7V9V>L>!Ri0&BE*2II=|o^s0D&c{C@a^% z_T)I6E74!`q-~5>xt@DP-`f3*v!JxqCX5GY8nGoyCnwU}Vl{9jR6NGlXP)g+-cy>0-AsN3@vwcE@peg_E)9DdYd00OuZOCekVl>{ zb^44aS9B`thFmPRI{qUW;$G*>8=3lcE>1G>z!fe42#R9s2d5Y$-g??|vU6&z_r%9) z#(hp%YC-u(?xMvMJ+bIKxZ*=uY-WmNDK* z`*+V~Mh42>+l@Q~i7hXlUJ$MIZ$4e7ubTHCjS;d1OaptKm~q&`zI<6Gis%TGwm+GX#n;IMN_c_wzE@! zT&jm53^v$hD07gNGMGmp6_G7?ApO; zzX5Ol=X9$6Gye>jn?VBswuwxFlHq`c>_Qd56&`kp#Juutgb@l zXe;-Xc_yn@XBCzdipV{@%8^Q^3r>}MY~$KF>UsRVl9f=0QTupC%rGuOonT2klW%_} zcY-KYZ(}`v=Zt9C9n`+n=@1A-CUmt7@Ykc2DC9Oh-r8U!{$nfdnsIHoIB)X_D{*K2 z$p?N4Po^V9dTa~%LJ9`nO-(kXGUcf-rI93wt}~qr{Un(gQwH^#dx4)y`U=+;w3O*M zuMY&N)OwU@8+JU4t$E)PV|*cn3pW%@GR$gE_e$0%AGl=6RbD%;E@2g{SpI@4`0)*n z{O0b}`~#?DPqjQ<`PRvMv;VfILVEMgKk>*^&zeScMf>6NKoa(K^XthE;TD^ak2Hf zZELyw#i?OeMVw=IQx#yMK)BoHcU{oY1VEy|IpFs9?fb3r}n2I}S1>)vUt@}$+5nrI;4L~2Wr!&Cj{f7oYP}x6k zd9=5Y2Gpvg^eyex)+6^FFu(CK>1;tgYCXK_lvn)4D7h zZu3Nq%B&r;32y&?j;2yGM_RVM_*xuZfcTqyNEesf-r zN-IAl*#Kq~y=ouFwTmjUHga~u;C@pFLICmN%%0KI1AI$ROzOq-P{NG~)zwb=XW7F; z;z$SZ$gm60Q>8hWj0b)*Hgu>&)NtiYZH77-ox41=W$|5zSL=>u$*YlIGQr^k06{7c zWe!2I?hw*xC`p5rY6nY_j9Ohg1S$UR6s+kK)>eWCAOV|gq!0nvI>MkGifey;1q5U3iQ|kGedR(ss+hDis%3t8KVS;fe&Vp z6iFDsv})ucu^)m`Zbng#Ln!=FL`z5jYO7Tn5JdxbU{lWrh%vJ9A*E|-TlOJxiUBxp z9(1MvY2&=lc?r4!ur`SUaDXgyIsoTN@mhuwFCd9Y(3#f=I%GG8${~mv2tFB<{d|FB z?~KKP4DuV^9IzbL1pM&;jc`yg`8{^Y3xIJkKma# zs8r_DLy*TL?b5wP%81iBIN~(o4 zujs6bJEsr$_3b*Jg$P!v{S_s|6+^FlLJm2BS8WncQk!}BkS5Z`XN4);qw}%P{hRdV z(vVqnkFy`ZW(VjeGIrlZg(4HtW38ACm8z#!O6)8b;Zzca*T+F3Eej^$@zhI6K(E-} z!UKNmb;#l1FVzr0TKH$+`M-z~|FgN_zetV@?mz-j+NL+BIKZbWv^WGQpE}sYP!o{= zj+Qznw!c3J-F}3|itI*m9D-b;c6uOeZ;>p4jM`>14S#%FBAzc{H+?FRJEMz$kT?r_ zTV!iW2}lekssTys5Om*Ba-SY{GK?ZihJE)b!yH=z-t5Z!$7lH8dj97j{NLqni|&Sw zi2)6x;8%X&jA!2ULe4Gch2)qR&38L6wH)=pt<7s*fAs9e9UjQFBUpQq8ooTZ5lOXz zxzX?E<>nydbjNaS%Zi%*4%mV>P|GI?kk!Z6@FC~0%nm5_8tax#f^mENpxSXoGmWk8 zD>NUJo`ysopQV{#{Ki>|gAhD=<=GAEXQ2#A9J`@>S_{cwj>wr^?o~?;*88;y)O?r^ zX`#3Nr^ZoSwfBK-rq)@u;wXM5o}j3 z(w+i>E~H%huH>JpHfMe7U@~bbhDU`vNdK7OL(8+?{xSg?S0s?uQBmH=R^*Y0yXG8~ zuiQ%F_nR}|!fkb{Nmrh4W&zymhWdo}RZ!)j+3z9G1y+j>w1+2*N)=|HXG>beZRiUF zSJs~TAk*$iqkTi6HLeFLihyWT2=s5fOQpYwDoS-Y^lOXxwZ%kYi*m@?fVdUcxB3r( zC@~1)*8^3!Jn424^x``W@InG+)Ep<?gwHA(J1H`3^Y;&`Ip(DKW$Ce)sE~XAA(L~uk9Uz6bu28h76EPvqEPW z$yn%;2$Vu&2PD$4tOt7J`@x%HRmj)183(9DEG`r=h1zBUa0BWxAcaq-&})uuQT%~2 z^0WtvBDrs+1kp_;g{{NpIeUG(zf2L8pw8XF29exoSuifw}J z{>1OI-p$?)p#wAOsxQ0A7Je)K=+VLUJD@?9r5=T(_kE z^cp0P4MGP9t9|2 zu#N@ zVOnCv$K>Ht&P1%A1&?{oWuZN`?4;va*^j<|Jv!1Vb-u!A{+?Q^Zk@b;5z!Oq^g5K$ zVQhHQx{6*$YJBw71) zhW^%=25(PZF_opomCneBK<$)^rB`nxe<}H+{tidJo)HH?sOJ&-5-l6f--iKWV`7;BD@SrbqL~>tziV zgX@uF*IK5|VnpoZ!Famp%&{NdjkTZIl-_EdPLr~Hydfgu-{~(ENvAM}>KWZ~d3g7e zUCw~fy7T=EdyyuYyVQdccEx1tNZG8#F+Px%mLhm;PMUVSRyZON)5&w}&K(wOYgrJe zUBFLdUQ;zGl+-~iJpgnxIo;`So{xT`4b60gIXp5Nk;!Zn+}pP}oFc{srO25Q;js)xr|jG1zh7(C4J$sdQbODsrc7ebug#W)Zr%U3 z{zWWt-r;$S+T2`J{G(SB2rCn}Ie+j9A}&WM-_FCkfUCeW9&f@Wce^9iPo60GHN11h zyl~AsNvDt%brKOOSi}HGas_`Hbp1<7CYUx`TbxIo?+|_5#e!r-k2oMM>XsOA$CTB*73szr;wa;G@`jK*?b&s8RUK~h|$+ycWU?oZ`D)m%^qwgSi;YM-<45VY~LhW!jB2yy9w(IFdY zh>MiqeB{B;5<6hIdjZ-C-IfE`B~w4E(hKY#d|Q>^K<)U?-X2AK1RQ<{`nKbI2to(| z>GGRrFLpVYaEqiX$VlXpcjX}n%K#+F9nhHok}FVxAHb4-R@@`CJ7~t;05Soto&uaU zb$N4q&T2~2q7fe<3aoug#}^p2RsSIf;%^j)z~N9w7+C4~v@csz-iPk2W&ZJs8)qk4 znyY|?gO{|jZ9MH9l8KM1-=Oh|oFR3FedX+11HW5Ox!&{))uLoi1YA&+oc%{be+o08j$tKMq@s}s{%7BQmhLpZ>11FE3;0iyo*>go@_{le0JVd?*9EFIi2Vc(DV z2B~oSd^wX6o$B@2#$VO=yJqPR=*rp1Kb_>w>72+Zae7cjSf!CV6ZSvx252XHG}XO{;{bzp*?6_3GYD zk7hw~9|O5TKsCq8NYaf!tVZyhF0GEwAhP8Vi!h)V+mnKt(2DO7WV6puw{3*e~%K z4hPhl`n+kp48HMPS9=Ug7CDAfvas&?fGB7(u!tl`{;(5q|N0jl4hzaT4sm@Q9=8sbVg~mZbAH~7e#lpFx8d3;7jW|NOPK2cz+a>8o+quJEq3rvM%nhBK z_^D4Hpj?y$t}9(MSc&mMje-eYxb7zOQG3yuTDq30W{)NQzM|Af89P3&VTRL@QbC62 zpG7R%7t`<@9e`0GhGECy#u*AO19=wi9?tDwlmgQO&!^ZKztthMs zTdrA$K4Z5zi47Gk7ot~Fca)Iq@BO%xU-snaezowy(7B+SOnYmW9rg}E`jSpzfkg#g z$W<5)HcQi}-p#Ngf3vsijdOZMd3mIojvB1P#*U4?8dQ^WbkoOWD2n_U12(2*6AMFd zmPQH$Hm8(byj4A@PyX7t24beW=hVu(t}t3FGo7%8z@C@qMNws%v~N4k+j>*H&1-_`eYaZ7ZkryY-Z zO^fztWq;+ChcV1b)PY6PggxSmjPa?ZDY{FKDv~H)khU<>3q9E{ERQN4X;ZKqKN;Om zA6LeI4d?PGiR@u zDxJZmjhKw5QYW?cLzeeh}dA&<>scAb%P236BhhpNgTk zvI6Qr_Nsm)w2Lcmw2=9Dn$qSzjeHhXM`BIBQ>|~UtWb)nvaB>n#_OU&V5Hz1VL{H& z4^*%OEKUo2Z21Z?9blxMeH@b1u-tkeY{v*M9#`Ov<)0gFi+PXT`7#un@Yok)v1adH zi`A@KLet%q%^{#i6bT+Uv*>9KkyeUepJTbNtBIf4?ID+tw6cmf)_jrD9UGR7*VZPs z9BHUgIW@+(^qHZE?L;>uJrU9Hokc6{Q{|ncOX0^u^{D2|hjSruaPtEx#31HKU(K0J zB6wD`&vt0^(vjXt{M>U#)oj&sVLs0vueA;Jn2Ic6eQF1%nA+v<) zof3~aKXm1teK*Rns_2Qktj(Ym|ND(h^k#9Ukj}ii;tbLsQnK6Ze3bOOcSp`u{o%G8 z-SYFU44aU&6iGE^2G;b1OY^y-w?s&{+@N_odn>t=DONCvzv8oIFkD7*-LEf$0j41o zw9xobmsjhUdEj#1D$71c5M~~a42Mfjiym2Q=DduJy5A=%wO9Jdy8ao{?X=?_k2R?j zBub%${qOi*MI`I%Q!4x2DK-lRMw z(ec=J|p-7dTo7Tx`&o{HntJnQxuF~VmuYR88tF@|J#mHEkqRkHbg zKfRNjv?~6n!g>?fdmihEq_US6Cn}P2Gw$?_6P@txEIbPF4yF<8O<)4G2#WAvD8WBn z_~B>7q^QVF-+up6zNGN8d7Fi)1~DemO`H>!zY0&&DDIVeQSX2wF_EXjP~20tt)s!@ z^fBGd9bV3>1isz1_qb%;K4X=Bd1eKd$DO6Co09o=XiD}jTv&^Y+Z3p8$DBbrc3a?+ zhO}<_c6_MBe2hz2Evl}3Ud)}~_EbeAUI*(o9}V~g+8vx^gH?c;C>t#G{g&sDQ&=%1 zMFytvR+w{e$DE&pcCLTNXtL)!7`?YQC#u*m8XQuzBS!sWmsKk6T8QXsk-*mE__UMW z8_?aLb`w(FqjRe5J6bRg52rcQODL$q*a9J|!q_ru| zRMGWnvYqVl(TC}1Gr1E2qws47c6Qz#$(&I|q^sZf%k)n4{78K=1M zQT?MeTj`mv3*liXRdvC(?O_+wxJ+AR!2aLExMhPB{-J0*w_`H93pqShifn~(7)k}^ znvld(cG5$A#T^9aORC-gQj93O7;|>I>A=RctfvnwrzwrYh6-83V|Ifd3Z#m8>HVMG zR!%iQeL&ZN!}gsUYDJp69dN-9Y6r?Rh1Au3SZ>FzKWb-VjCc>KKivkt-sui4M}f-a z91MZ3?PT>Peq~Iu`pfFh-Fc;smQ_vO8gpa0t)%I$rSiM)`cYywpUH@=Czon}h}e7Y z0HCv!=kE!f|1v^Pk?$L$#HcHjrUJ?MZ;^z&nNk*f8U|Ok&iR#L+9B476Od}SQD5VQ%saM zTcZA7p5e=@xE)LuUw=3s#eVEGRZ9;nYiG~pz;GDdh>W5z65nS<@!E?V``R@r+y2Dz z;rH&+x}IE;uk9n>MI}c4N53bT{ddT8)LU$nQvg=Q z4K0EsGna2okr+{wTa(m3>50I>w<^)8vH;MYgF z+Ok=*IRx<<=mM9KFGglB->zH*KxzK5Y3%--570!r5@^cwUme1@PqqE^?}P`yzxvky zQ|Qk>Z}9)a6liegA!vArqMpzswm%2l$eC$a4UsJ|00Gp6SlD3vyiR6J7Hq8%VqcfIYXcP*3K^4)W~0j0O? zB&`t-SEg{9QA|n_!Ht|Eed}qL;N?IgRvX&kt6^P7qqL6u9@7Gv|4pOJT_B3640idgwK+-cd(glTTso z$vU4wSHfT4Rb(XX4zb`}JAOf1b6X+L<#IU@^N*%lu^U%}1^u9Fb z1di5sbI(`xw1yT2E3M|b>6a^Sey_I4ow7e4!(#I(>7{o1BH^H&*57#UEQF zy1QrYmd2`#ly`gOH(((6iU7|U6r-U^j$LJLi7g*H=ggaMCM(%|p<|j{-#@d8%vkeaq-D`~=Pbpul0Di-bkgtO0Q!ajc z93@-k=*nY3?mGe=#2V$Gjaa^m3y)9v-$*%^>{*OAXb>CDu7`ok9bgPz*;=tppEHvS z2JvOLCp%akEWkR)*LZ{$)UTLqRbFq!!mWv#nIvo6Jotd}^-)Xr>Chc-k`4`W&JEO_$9hMfv7ql+v@uF6G5%ZuZt>a+p z=qD*gR4%%Fp`9DI!MM--=&@hoC-SiW1LDEt` zb~*)U3TD=x>DBUm!qVD7HLKY0=&hLBZL?NlEyr)cOgQ7dKSS0-<+;QBJ`!W^*k0?b z9A&B_C@=uAhwmw}McU_?_j5c1^ro^it=cx=BoTzyVtD!r~SwOjXRlLSS3ZLwt zqXMnvOHw=Tb0lDhC-h+Qf_X)djE~o#V47BRi=S{>PTfy?^J%Ky%(PF%*E@!Tzv>%E z241f>68sZ;l7F4fS1=m5*dEr2L#vWkEobf!M5Rj6+l_!jaFrCz06jq7krYLVNy>S# zAELyl_s3DwKjgW=_iPg5CGfR6l`7U&%E-_UQv_fGU#|!_PWvH}fLF9=Mg}dDRZq^p z?b|z5tOrng=eofA-%)LPNnid@h{2pM0mLXIfHS=EeF_k$#O*5mnX$0Y2dFvl1N^7* z34{f*9+)rlXQrY1`~83~6Rr0?LnCTa%nrG;0Mw$=1~EVk=pPI8@n)+-?(F0Oy?B{- zwgrNr^Jc(0zS04Fq*9^uM>Yvy@crjQmw}4_taZ}kG4bR`?EDxU zKu1iRk=qrs7`y-K2-Ge4#J@9~raJu9-Rt)m(f{`2uORiW2B{)j)w3IG%?0qQV=dItT^PKTAn02yrkT?`G0 zikO@a7sflinC+Y}RzB;S<|yCMKU(}LkRK*mB*x`QWnxv~*!5KPJEnqo5g*Wq;-s9n zMKag$Irv&-tgJj6#Muk6d#Z{$SydpfK8|_7;`K26#-3^y-7V0L_wN@8k#2+tN&Opw zj&ySfBjA-r+xcFkaWHFrSyY~0u8+&gL^&{8t@Cuel^)BbTSteQU^Lk2Z0r$)Bpi4X zGts7za;bDcR`KcJVBgf}aAwKPmQ4gc4HH*)@x%;UjEw6oNc#3)EqlV=V$VXS^HHUX zjc9g<$s+?K={cFO4Y0lRO{*^-AC6qolq`r~d)qYBqxP}neP*;8`>Y@Ieom1=9p-W$ zhRaK!aZqlHkZo~TSpm-WC{I}QO z4@+sGAYkA4fBq9`LfS$0E+VcSf<9UR`-ZyNgc;9)Du8Cw;!)%P$RX&q5omMcFH(^R zs5xwp8+-^d&+jH5VLiBvz47G`G@0jJI+jY309K)=NrC@OkN$rydRN3V3yyL_22HXd z8CQC`Mc?Qup7tNno9A>rcBVX00rW1#H8Syso-7;QcxE@MM>DXz+M()IdxiC8k-^ZF zHs*U^trNQ+z_)*2*F^_VfEsB#&K|qd2P7rEx-c&TfYM8goF_`c_J8C6K5RmHuOK;Z zw3W1ek6-@BqrM}dH2p`63SFkJqaE+ma_{pPDTK>r5Lb$?Aobnf;A$KR6_J#D&uL8P zox@c440NqnC7y1i77(PHdC`3r)cgA@`>jXxR~S*yW(o)H0}35u!erq;djWJH)lHF| z1|l#!QlMepAQHbwLw41i7yfGf2Pe7z2hxlPkSI}lQOD(ZJ1Wc|c)qfmA&#h#-NjW; zrLBmZlIgq1mE`Ma_dm#^!C#z-LQv9+8k(PGekjTdXV`5oSBlb_7^Mc_$88%8bt7>) z$USN=Fwma@N;j|2{NH7AvL}+;Sb_^cC2+&QklJY#-BQ@9(2lRD0lhF zQy4#0R7K1ru`r6OvHRtVP}l1p^#^MM%?>NNSMj*8I#iiKgEN)a`CCy6y|RX)88_ca z#dO?5+4eIZw-T>j<(A@dtmAw`br6Q@oQ--Rf7MHQtQAHlsW&L0Ud0zA6BqgroJjq~ z-8Nfw;r5B84)GJ_uNCCT2w`AZmxUV^!s&=>b5kR1tqe~*Yd%%=(ZX|f2Sq|o+xwV~ zyi7!nyz-Ph(7SaE?otF;nwA&@?bIqZj$$L5JV#CY2R(&2<8r&gB&*-f)AH)0+59?g zSz7D%pSw|1O~4SpVUNgD5ffVC`%aXH%uqUel%KY0*B;}s+PPA+_iCL-lC-!obqv+O zd4wo8Cq}Ql=7|^3>0dV!q6HJ^Xs(j%xkzJzij7~o!g0D2L~ zy6+G_YT175yXd;8Wsn+U$??eVf*Fk|;Yr*3f3hfUZUjSEG3QAp)kCZD91h!IK5HdBAO57Bs7;-JVO%8D(lPtAi&;7>9E!UO-eZ@SLJoCB0kLekFgfK9_uL-> z``?^-e`@UpPKG)__qac!$i9Zir3G{*)&jjJHFXRCp4q0zqMy)7$iMpk>~G*K+uz6z zek`uCQO{|V&*s8H;<5;X?XFypEszzt`Sm!^!Dwz+8mgbn6x+pta8a>cFZ*+B6!TGB(iw@3+k+a`cfGbW}+Wcd?Li zO(GAvfz9`Z0DywR4Kh{;%VxAI@nxR^ZP?RarTUL5QDLj4T&84)2m$jv9~JW$KJJUOifwmu6CJ)o7NIzjL3i9uGjoKDd-s$e=c(ZsWSe0a$u`+N8>=dB%tw}5B$&7EL~we z#Vx0p&-nbNj{fl9ycpHe8Q`)cch2WBH^VPcdR%z)b2qvzfr@rp37d6-8+OI4Q>>Dm zaWb9e{Uhk?mN`q6`l@ufZAog|P|Tk%hBdu=(Mz9@14zvN_oX#8Y~&i&<-3-zXy?u}XXRRmPHE(HdJkiRrhxvQQD?SE+$ zYU1-;_zRkI)y?We*LfZyZbfN+eH|na4U=P>K4LxQA=Ik$PkvxER2&s$FxMJhwmz`H zcbUaPab_Tl?Pn$Tt{XGjmr6qD+rG?i^WN`ycCg5@eQx|=R`Bh#fuXvzR9gX^`_W)i zB8b39{7HIf+l%)k3=v;e&Z$;^2rh$#^pzF3`zS^~9+YZqOvC73O6GBRGo-s~Bgcqs zOfD|ldQK@bZHwOJ@LkurJd}I-;c~V0ns_2|`E@fI^fqGvQdic8zVJs|rcT(o(k64f zPmbny5pR}-ZG&FBchV2aboZ5*R>Ws;<3?ha?3T6&kqy5%LxQZPM0E5#|8^mKi-++2 z)1C3lBJtu>rqNZiSYd5EW70d~-kPkOmY+o{+Jr&T zM5t)N@Ue~nOZi|XPoVx8wsIQm9Z-ojD`EhE-l_C(3qVIUN@r40;Msr8t~Zz)JLzXr zWN&w6AwujzakW??!vZ#H`PTu|+IkhWW3rOM0~e=sb&12-r#jp#iS2iBOObP{`S)8g zvy5Ew4c{33>ZmKKV~M`0BhGhp8SVKGYm#V9SfSJi5ZrL@bKk<`h68G1yA%SOekfy; z6#LYq1ahD1c2a{LL|==PiJ`mn(428W%{nXVLVo_{T60v$u=FdPBbl4;A8x55%0L+9 z`Eu`7$o@DJj~;n44Vom(1ROpdWIf`BAe0>ty~LhUc00>K5E8Fx;pJ)Cf!kinA5=P= z{N1XSA5L7f)~bOGQkk4Tl2ww(UL-NNG5-9^)e7!|cMX%fX;#<_@h`kqweu$qZL~5k z^yhk0OH#urnMG)IqyriQutrgQ8`D%4xK}N8fLOKsX%oqLTNW_65_#Eo&-6Da>&9y8 zOGUX0yVfbcuiQVh%(XCSW&WsWv`ixz-dGqACg~HMb@hl-t3&DW<0KW1t$CKJH8t<8~6ifTj!{+hC(0!A!d(KU;+~fs4u{4|cf|f5;9g$6I ziMfqFL{W5i+WU+ZFdwnkXu8PkFmyX^XSc{GRHIj@sy!9tlnd$L32~5u# zKr+I8@HIP7{IQh}`&Jic19faHp!K)AOWqhf;Q-(#%@4{Hp;zI#0db%^6x-00NDEuH{JsFaOYFtWG2?O1nLXZ1{S>0`)xM9Ip zZ*WLvJ@j&vGRU&I;gX36a_Dh>4)K-=5Q5x~!K!;rs`+S(2Rl(VH}?oI#WOL_gLvtVdDx)Ft?lWbF@#0i9Q5?9 z^kPHQp2Q7sY)v@O_bpEawh*h&>PbiAf%be6nJ9q%b%_ztxTdy*GeEuk;qJD`g>Oz& zu0qfVFIi-H-dHu7NnO8)ty-dOrFFRn=?Iwtkc~$1J}|~}8QCk(ffzzHnD!FeO{W=> zj-xcK_Lb{K*fM|JYik&X?^jPr4NEHBBI&QkrH(&AoKnAm_q`#^=p7^69yR}MjaLl^ zB@gmz0l|%&%~)BYsOi|x-#H)Dr>Y8_<{J0@vQYxTGVC-i(cM>Q&a^-F&)L|Iz$iDh)t zyfAvpBrUaO{{t%*l{8)K&NdP@>r}v_dkF0IzR`_~ z{MDu`j=l8do_W)#qR~^zCa0HAJ!W9Ilh!>}&|s4Q!5PTEOnU!mhU~RU!rI^DHyLuO zi{N=pS>Lyx4(b(r!xwkFX9$`}^&2WepVfpeqcHhYrh;+|kp{_d#I^$K_1N8qHbN+8s2{r7L66CKa;wZHTD2(69h6cb=ut2yF zlOI45SdkPaH@Xq@zoLV0D7=GRH*h~u1c3MakIJ+CYoT7|Ap!66%(+Q_tMxkH^-=By zZ3VI|w0#Z9p7Opb2-shq>(_$mx27{KRVp+#S0|qqJD&0sp$k{=#cRxm_?b8ZO8+jP zYs4C&1rUlgW66 zmnFXH>fi3~Gn}!Xt2bUeT)AlhJaTLF%&67-&B;u)vBqPew9Ijbf3hEvE7^*evYZm1 z7nrdEV)x+Jdy~i3u*Xn2pzLn5`r9NG68o`y^euN63!{uF)S36G$E10R62z>$rn{d~ zM7<$zCIIvd69F!$`fJ2EM98`au{zxB7!1G@YcPzA&^RSWOhi;A)!M)u@Iy5~iDG)=Gj8~)P1Us9UQAzgFD z;29p8J3_Ld{ur6)->0eux}NmdH-W^f;>xg3raJbh23n8rILKKc{#ZbxBMI%4B1SV_ z$eP1bBmq+jZeqmpsKXkl>Vbv8?``O*ufSx~J>)OfBTQH>DM=5ZN9LiFBW}Q&S8Jlk zN~<9Dgenb-$)^$P;7^YXx>UE+49+8Lex4EmEPL21&~KHpXl zcRH&}BtZaE`4CV_Jh)?t(@GX4Tjj7q)?4M7+~@EoPY_<>xiao z$oOt2_z21S`#6X4B9}y~hqwirKUllCT>^8XczFY|bj7X}N_LkLv3Sk(RihWO->Qix zW7Y%WnB-6Vovc`R&nSyyMDk~r*13z=$HdAq_LwrPl+9x4MBgo+Ot2|Huv!;Dz5Z{; zq9DwPBde+(aLt4)d`)~qf@f%Z)Rc+uVRPghPCE`CtELbZ6kQ2Cx04;eteT@K(aArG5QR?J5?|J!)cNMlwA)ue2R$^Tk+l zI6d=c+N=e%P?Ycs=%puoz5p&IA@O;sh=t}(vJm^J2asw(qt1Hp2?ttyEp0U*>#D>bU1`Z4 zdVi7RSJqn_Sbtxf$Dfd;xfC*d<~M`QEC_)!!^-0wdk~N5?o;RL?ttn&!WVr1)cv}n zpw31zC=Cl+M$Ln}ZI-eP{(Pv6Hu@rq4`dP!ZHQR-PopvTSC*}ONOEy(1t60{4WQvMT z3bTco0RMz@^=#yC46zQg)Mqsk?({^~8%XRCD%YAAD}%K#*%IJ#6&&*O(up>kHMPwH za%${359cJAlEv|;Z12;wF?lH6>6=XOMIGS2;)Tv^Z|s3*p{BT&Fav+;|rN``LKb z>VBrPYAZc^&)HXuTY6j;5B|Noz-LqZm3B-Q zonHi^zaZ@T62Znal;=fgpy%lZB1+1CHj8ZAf^qh=SswR6_?o6NjK|*?ur=(^UNC#X z>^)^R(PKCS+} zA$|0T!T4miG~R^DjKZ0%?)8IW(QE-eF~S$7HBH>h9{%hPQq6Y1GCtqh64#wE!sue1 z_QsV_=)5+G@&V~VktWzT;wS^9%UEPT6ql+sF6xGt*7YJ-uwQn+NUjpk(`=;KW!?}K zBs&9flpz#%HBU6dl4!d+B2nUdF+DIsMU22ehY(GgIP0eoL2HhM*Bidc^75oQ;pdM*lTy<7 zMR}r>e4qT8#d$R>Esn8o@%-2>p8+A9bldwKb$8aMN;X|L<Gk-&Y${pw=gS4-Z z?~YOVw-Bt;WUP4i3j8oE~@Qx4sYUiEVlr6QcCXK-u1NkNjxa>mFv5 z5J%)*^`V>nzN!T8dj9;|5Q|r+r<>pt4&NKs1tm+L10YoPrZlKOUmP@qH6My4VZV{DymZ2A5q4#IfcMZiSZP@u) zOdeIoInitLJ#nU|J3uIhQ!WGaoNx=v8hKgeZKET$TQF>uS8;Gzp(}eomv6-P-JM$> zKSmgd(cDluam53;L&gd{-hYvfQqaLz1-G4g=c23nMl5>zR+*KEbhT9F4WMTTPkwTi(Fxkfg}=bIrqa(g4>$lcObI>(AT7ikF8zWX|KhE>V2UP7Dq}j1aO@ zK8>9=`&#A;&@D9%yPtO)r{qP=6x|;c5Q;t~W<=4Pr>UuvUimKoO4r)^@c*C=0LcrL zneUiPcQ_3pd_fym{HNc;wZGK^BA@G!?L6cqE6-IJ#LI`SpWavX<;V2ckA?~afY@A^ zsYX_vd5Qi*TY-3v#D7Up&>k=90%B=22B$`$QStc>qTaARM9oY0*mPC6mh`^!h`WOA zv-8!`JHqbT*HR2>Fq+pIxZ;c2dJ0rJ96& zS8!R6Gnwa)y$;O9Qux>! zGPhpgLM)zWv;ltd;E_zgdj_$z$d8d}c>cz=S3`muLr_;Mz1M3NkYc z+Fx!$VPtg*n#xH;eW}McRxQ2S6QCIuQOmlGGJ0xp87N^wM2g!V%!1T_GvTAKS#*cp3Y5l!$}{!sC{(;{60h}oQ!{wZr^iW*ZVPm|tLQ&<wzHhtMLX7wJ>J zbTo7})lKH=F#E{FWsUtByyE)ODdG;kP6fJJGrbqHs5XWWBZ6Vvyk9# z>MH+SEOsn@cjaN=69bR6E^V^-1XT?#f`{~KP~tKD8C7q-UynGwe5EmahDq_mvw+9R zM<Uv!LzY0~vscnDZZx%Jo7U0Z zWp&xQqL!V$7Bj2)wwJ;2yL1zPbkvXx=5ArClklzI>yvunn54FBA*JUTMk0KBzc(;w zr$Zq|eOy<9bqv_v3@qinpN~?E?)09G*7?As#_` z)En+eY`&7w#t$*>Od)Q;(90+?*Dk4Fy=pNHuh>0n8mxpl;r%>)jn?n?%X1AU3ONkH zJ-Z>OnKlW!lUPa`z?GRQl$|2`c#$-SMOtSM%+iMgjoDGnH73YB{2!MQPl91)s;Qj0HXTXvu0LWej9+o7no8WX|TB0Pd{uDmp zt7DL>K5>DJhE3?^EQ)v+>7J2CGV72759)?L!_6=I24B%IMDv&)4L6<<8$)t~xe^@5 zFOT`R!x~2gw^I3@`AhX*I*&|d+g;p#am3ODEI42Ai}FT)$PdCv02-J zmt4T8vZPkb3!1+)=gDlqnG`{tdR~@Dy#!m`?#6Hf_E=TV%32G1{pA#sc=BDi80f;i z`NTxuG`$E401?GEut7Ki7&{sTzPOH_lsyn>;+?_Rez`gP;HuHP7lVn$79c-p(*twH zHS`XN6biqMgQQF>TVvy%VD6Tu54xXk*Oc}YQ$({u1h!6+MT6vH-sheKUurV^)#Rcz6!9Rju;iV19u27tEv&K^ z0meNrDeyiGg~m;D+&t#En72r_y?x&obC2Ckvo;al*=c4&i75()fYDDQOv-rh<)pk0s8PWiV0}rJ)S0ep9XRmL zyOKqiUvJaKGfX1lv0CAMK_>6LH#s}Uw6BwS4(^^~6W76y?u3z~h}nc9ydE_RQ@p9o z`lGC=Wk%eHHnR|_pexiNF6A2Vh$iiIrDu8&2RpjdEE>()0m3DGwnCgEhL-Af&X}MySaja(nq?*eX|B@~vea@JDdn5|DJU!~KZzMetjA``FX-75**}TW69}zYuoK zM`PyPkaDo>NJ>Pk*8}TKQfIy?5kw81^DkU7^AukAnuI?rU$;GT1@o_$gQu{`@ zrkRdeyd@y)fA8#NXRC#a!c}~?Xt%SLaCgy|n*J>O68RQ!PHIU#j#dBo-sIO8!hyMB z>Fj9><)RapTWi?KKw~^20`W!l1#GRmP`wrZKJvZ(3~y8F&u?LZ<^~6bwkGRNx?ws^++-OFb&C6Zj~p{6n) zf6OoYuzO)>g8cT+7(MMrKa~FEGdD`Og+uNvt%3Q8HNE_$-?m^)P704kIQn@Co~4gS zbw@qSr8(f%y>MM;@M>4PK2&e;C=a#g~y zOn&Tx$1=Q3ZM+HI54~8ofuhCo1c;^#3F8f!MA2mwPsFF~HrIrwO|=EE0*99R)~qMV z+Rg&lm8Uub4}$u`dTOY1sJgNkW$T%mE-9GJ>Q7O3&33lC0;KoMN{wDsd5;o8BNbi326S6#mpQE2z=XHvs~__0&EiVOJV)n<1Z<}>Bpf;3VM+0zy`l5JztVk}+F z4VFz6AXkygZ^8S4$T|om8AxWzv@W9`OYaL1$n6c;gjz~^p=5DD%D}nD6%kxW_f5@o zkdX9IJ;~(mUm8?7au4WSC(+o|4Ac-MOdD(B01x25G;{eq+7eQWf~`|4ioFtStfPJ( zYzAeXl|_g>T+=O7ShAsHSXr9`&@F4kc^$@v)zKs8$4U;Q_<4! zsii=F?n+aO-|r$N)|^r&*zo)TZAUmF-FnSzz))6G99WLtM9UAb$5QsNn43wBu`2@b z=`11RvAoA&tFkMJD|HAx?Hm$lb&t$NN3bKBt;{FcX}Z6MHJe)kx%4<$CE$FSR$rpx z+hLZ5Yx04?LN|qIpGgvdB8iXahu2s;9_;iX>=3`XUM=tm5}fV=)xPFF!>_aX^t)VD!KLEPAIvb+J z`j=YwcDo*s5Y)nb3*IN{FM?vFvjvRi-{Q{uV$inP=AQ!3Wh>NQ>pr6=mNDyh>&#Dt zhLGIMDum3vf4bB!B_~2eu7rA4UFHjyT$e5AD1RXQ{zfB{^ZmI=_Mw{DJhB(1^$^MT zj~oRZf%Jx)bszT#5%ldZhE-$a6k0r=J9*!#`qmI}eIenwUzAjhwZ&${gs-0CnN0 z!jwh7_TKnUyP*plw3kHfZHxpiKK!9nyP~7qO)jUrZ5V;lAbTvREU>{|V_6?f=#wl= z-N0En7M2R0wC-OS-WD%l!uJY`MfdhFq&}PMD5NvME;?OL9ybUEMF*T)O&5(xT+nw= zl-x1D@r*Fwc@RqQ$nQfnp|Q0{(j)uLiCJJ)P8i*$y?||IPo9Hd9DUexC$L-Au3gE= zUHp4PphLOQ=R?1V;^?4Vg~YUtIoAU1fZ)={>S4c<7fp=}60y6oS{yaRJxR##W+X)Cq0ru6eF9-qTj4W{O-koX0Z;-h* z2yHm*Uz$i2&|L9~-jA81PP5}haTIX!877#0`UG)LKZD;DcE5HupOO7`ve>|`HegB+ z;q`bPHH%*9Y{}Fdq2IksZ{{{&IBd@G~L9q~iBVbDb3@jc!*0VXb ztcr^D&o8{1j}Olv zgTXqJKe{VOv;gU>5Uv2|neL!YEw#d~t@-d1p(~@Wj?4sMGv*1#W6GX^ZJq6J0LOFK zGHaI0Q*Le@*QeY%V$3Ho1lmGIN~$*BtvXS|wmVU&3Nn!K_gm^S0Jp2h<}F@usm@b7 zdR+F6_LcFahfHr&lINy$*NA%awuP`Et~T1WUMe#!=^pim{iW6kq@&L(X=ITNPqHbr zPr}eeFv5vsS(RD8R${9B)j;%zzr{AtZMG&UQ^$PRh^j;sYKQGgtSGpr)q714=p)`g zszIY&G?t>((6k*uq06}VgJ`dH8KdFcfYEF{L#Oza@$%X?8JC|2xhy=tX3X%8YX-fb zmsGy&e!y8l$Nk-`h_=nwla|)!O26m3TeI9j#}-Dr&uK;I@V$hGc(nl#FS5s^G0Afc z9a9CDT~ouosfD^{-Ha7|ScT=ddS}!xP0Rs$*-8)(?cgQ~ktE>3<489^Y;zZl_q_Wl zjMsD$t`_9w&M+B25v=NKdox86EYM|RFl3Jy^4G*X zbs*_Ja5~S=`~mmPJ&jozjkmFWz^Fe-185BMgRgINBH+L~T@t8#7Vj3jT*+dX;%7rY zld{Nb)sioN0*~8_toOkUT)PxsJi%}Hy(+kLb7GjU=i!w$gH%q+4Ev6c`RpE44>4j7 z8iO;DZji6z79;r$JVDV7^U+Q;Ox|+Kwh3`}HAa+^H-3HuVNlESa5#}+4II_<+v+ck zW$l6gbl_~Uc|CwLu`Yd1Que4073C+6P?=UpR(~)vkSNpr`?qqL_KGcP%|;-oP2T7y}&V9Mds@u^T!+iP@Mu)$cO)2@;{Rf7*|hqa0V+^ zdS;YCtafr$tENwf_$o1*pt-kkSMF5ka(;`+xT==9W_iQj;1jqJRc}DfPx)L!;(%)a zw#a{^=RJENE++ZGNLRC{Gy^G(vIw|FtK~~k{;-x`=QFYUCR`Fuxl>#LE+Xf{z9}e@ zbpZ<|HZy9+F67YG`ZrMCv+q$&Ljjn+cHROg?S<6QcgVUQ+?QtgQKt_e0NLv=jVv!U zxEbhR17BH0URH#X6VO)(Tk|2B2GGSkF9SPFkT`FGD^(7BuyGYzA-p?{c$0hMeCeB- z^5p~7F{}y7`r=PQxedgGi@6UUSZ8H44T&e~4?Iu4xQ0{tPTc;?Z`}uG@LZ&ydC*j_ zDyzC@(l($5(Ba+QR3l^04rwLPAm|YNz<_v&2j~@wPDU9LxkM`mkP?@cpwO<)3$2%_ zze^QbDHv|bk0^(3$o}`P8lVsIjnaw!GwXwtUZP&^KoJy(Sos}?wIz1yAhMxk><^EE zhvJeO|Iznfbr5%{vzzBFy}UDT*BU>s9bOlE#rcZT*VxwB)fi70aNCvLWp|Eu%h7xx znphz%dFgdzs!k7ADmY14ol*vnDq`(fX5dV#;JHA8omwA%z;wQUyARWTb+OxQ_5En` zx%;!>dSO6*Pv48P?uW)e>j&N~FU6mpf48#TF3+*pmG4>J=a8|Z)Z=y45~N|;le0l5 zmPfK(HRwl0qt7YxX`0}b`tp!5{=}(VdxEpkRS89_i_y-x6b=;^t*GZq^`lrJ+%X{! zS6I4c7Cp9Q^nNq11al|pgDs0ox|?IN9X@=YPC)FVzM=0}rkObi{vYAvf5)Zlzqsgh zwsjZ~(f}JB-Zcp6EQI>1f%YJK#~0VWGMK1+LA7cXa83`^~;P z*XHpD54hFBLEc^G#*i!zz+Z|W^<~}D+sg%_xNv4do^;B#CAxsJGcz|>o3OHX{ttq4 z3`>Trv`aKl)PG!$z|b~b?`;k2K6Vk`^7M$8=9v$2jtWL5X|urPiE$qXtB4c5gwxVP zbJ;pm=`WR+^j$1Zg!Jh&gbTJOB|b(O=^W_H#g!boj+POuD5y~=qYagFA%#+9p|Ie3@dXlRZcQxztJ*OhdxOP(k#?bdi zz2uujzZGyiKL^ogpvfz&tn{&XUdJxxmwX`#W*>6ALifmXO+@9dd|UknUzVu<;*BiITXKV$BJWN|1LntJ8jltJx{Qx%PC4PLM6%ZXTz3@H=h$dXEOn#EaR#s^B;?@4YiA{R(r!FW|jS=@!Apv zwmF69N!GqR!#Ft)rW8X%#_W)oS@a3-I5)pPSli8naDh2 zh;wedi{LT&-Nth@du(gN{udN$lSDD9G}m5@uGx?3Iom4qS*BbuvOBNrzzcf|46jU_ zB->3<1u*0Xlyb7?ipj{FjHs8%{g#6w9Z?s_>lek&``Nc39e%Pj$L|hKkAbL@l}kWk z^)J(Z(cVKie~;xgsWhN}7@m?gF#SfVkq3Sm>F^CqgxkK*ZZbp?s`QZ#ok~PF^!n*6 zZ~>U9<4kTKn{shLXCM5fQOe%73`I%7uTlW3VjkERFt6UKq{`K3rgtQbN3l8w+1^2M z(6aHailX?f;#*wBBc_k|?v}jY6RFl6T;$PK#d+7PsI-#!reyP$Mz5W8+3)z(zt}x> zvWDupOMDRLF%Aqe*yy1|d!u6pEKt>X2GoT~1A+h=yLQfO#taBcjoXKc@ypaNz?zZ= zfP}A0|9qchD-`{1jkdB0&Nskq+O1HJ6db;zZCBg!7vP<0zHHtLo#_m1`NvBuoa7kBctY`j|De~y=^WYM;#)Ff-4zoQi(pmW-YxM#i9 zjE(Tcg~e2txj_tSzT~y+(CUSlMItVc4e*-=xbIN`TEN{MSxES0>)3iwB9)Y)Cq}ZK zMzB)iW>13bAv3-|8sBHNLUc7NPF{k4j6K(;r^$FZtg=I8rJxYfu(gr=yJODv4H*~P zCy`?gJya3F;AE{ae)K&}0bI~Zb9e+K`cT@f`hMxc$i~9Pq{-Fw$ET8Xm`=rP1;CnA zi6D(T%FYg0t9t5XY!Tu0%wTSL^!d1|lkYCQOKVDmx^U)7&HUAEoiP!fCLU4q=ySSC z^m>ig`JO(c7>UjNQTbQj(CZW|Hfmk`2r=%$dmJ^02=Sug#x@V`I8V;*1zS+ zJiJs>qz;f-ECHF$IGcVnV+oK#XrrA_jBpUq^c|o>vHH~9g+Gq3ygVg$bfcI}E2;C) zQ!LP2iFJTO^~}>2MMGP$@|zIdpB%T{e*MQVVsnG%o*VLWN^77PZ8b72E+(;orL@qk zVctu_^3@Zq>M~bm13%7k5?bwhftvnMZ#4H|7!87lib1mMpr4|WsC1O-E~feSaV1Mz z+hv}oSK?1p$A`AYzoZR70&9V}svpO~xy5uYzj%Re4Qw{I$Mgn2>scvO$x;>K6FgIf zKZ_PXFIOUNG~f$rdY9&cJ~NUG2GoyZy;St;UirACrF&{vrY2(Df3-XZ-LWJ!N@q4y%Wid1_gI zis@3vrDVjr=8P_i@DqGyj|mTOK|6!Ek-OvAXI}5|QIyITu$V{tJuNLQ85?dqx71i* zMsxhEbj`s6vw0`BROam!AwP4X(27s2jhL4_`BK-F=+GkG=g|T~7?sR+FV0G%(IDLdB^J{qd>YhbkHAq2u|t}lA}@^gzUKm@D7asp{}^P+3;j*;gd86 zd3-*2Tzjl2k5~M>^B_pXyqgk81mnb426sryo{%%-8{;c=5f_Vjv-5eeAxWR*_*b`X zsu_vCDZD$$=)qu4vq!dF2GStdaqmnQC;ok=dzIViD;Mc}>DeqdC;K@oMtWh(Xl9^r z3->fJoH|5ba96e2jSJu=6qL{R2e=2&F~-BLn&XEOuRA-7M5ssF03eP&rSQ~&F%4m4km06V`XB8)0(hmzq$6m}hsP6n9_a*% zJ~nkNhnsd9OufH1LVdX*qcHG0SV1}Bk;|aQ6S~x|pd~0R#C0$FFHJq_rK~0!?%-}R z!);w;xw`zkigc>N#KO?oM>!iT1+nKRX>W3$^pjjYrk9uj+!R`WJYdGf&KSL3r!Lcc z?~N{9Y5!M0!;PZYY>Q-l$WP%Z63_WyuJGayn;|aEWsf)czm@P3)Y2N%c$%+O{`e-4 zsHo}9T$k2Ef58(_vMrv600QQDzn+k#-pwlwL|Z)KxBm!MqFtFMU3r)*UI~>oZW3E9 z;+TDI{Py)>pM{U)=fIuJ+?wvXPFx{D;OB7%EGYJGt6Y<=N#|`ai(9LU=j;YW&hD?j zF#Gv%AEvATu|$Xyx6OzSxQ#xbiQ0Hu5kvGe>X>qhyUTCk&SETjpRysv1x%6$ZgfNd znJ#6ucnjIoJa}=U&t4wy@*zMq*5`tzYMSkkLuk(0v+|6u`th`hx?H+0YH;*hXd^nR z5yFr7ispo?6&r}n%-Hi!@-Iqsk?VB$avd!ehVHuw9mM1Ih*y!x{$>E&WzRlwIBdQM zbKdh0)8`iTR~qyc8wN5oQ<1zIO4Ko-B%zz6Ei{0hESIC|Vxo`0G#=mvRJhEH5ney4 z0T#KV`-T5~exP1Qy5Wa#mxQkZOBJ8(pn;QvJI-)h;Milrcf~Cu0q2Z;PmYhnRkPJ` zj_lXnclQ=9e++q@0xv-Zs=j+!0Hjp&Kv0$>dI6lSMkGbUer6#6U@>v}Q16tjG*ezo z0m}{>3iX}%pMGxKCl$b-XC+Z-Pd&jTXK1PAe}3VnusAOuku!ccZaI0#svgbP()#_} zDEV{}h3iKG;Ljh)x5#C^QNVe4X0r-K4(s_v8X8Xj~y(VV8slwHo19;3BoX&`L!i&n+a;N1!3pTb{c)eIXV z2F7WdBxH*p7U>;6xXA^2ThY)OPPV7icF~g6f$)bqJ5RifS$^!n%R3Sp9He2Y)g5(d zt_5CO{S$l49&&)`+WAjhx|%{@BLFGR{#hKD66S$CW#|lJS{XgzZ9t#y10iF~)97Wr z9@o8pPn!mOh!S9O!CtrgDQNzUx|TJqSTo|-;08U5_HGH zXb!-qK4q3}b+8YdbXwB~ikRl{+te115U4Vi^m*E_-^hwZ{d&PtQp)i(n6joO$V~AW z2N)S*GmRIOlRyKDf|EYG`A$4dd5t9pUp9#Mlwa3_pRk3<(gc_FpriAwdzPXW`HAku zUY=oRK1;h~>Mv<8lMlWcI4XbL2M5-SfQeEmkSuQ)e^OdF>9N&*)>%^ zWoc*zX}!EJ88<6(>0#3BchI}HpoI`XGsYMMibOAe0CP0h!E$yxZsvWpx@^xBn$aItG1v<(V+ zJo-6gX(^a)v`o8wlf!y7dj}l^N(4G=XfCqp+YGq^SDqGOCvdxiP=Dup9l;CxXGSQ? zN_+NmBuB&&zz4h<8HSr*PA=n(h5LS}cqD+m5!GLvxeiYpk>aTPxqsU&Dgq)O@ebSs zgp6S7*N~d-lo;MZ8GL_hGoUp8s>Z9j@A|d2HkOm2J@VM)DORkwRx0MTGVLj^9v8sG z0+Bf)sRp1V)X_mPZ~|bB(XJIZSAr-pa|P(omJ#xa1-OjW{>czV0(P@Lo^bR^bvUTZ zOyibV=9iBKzFa$FLkO#r;FBl>UQgzJUq<(~*b51N|4W&f(K__cb%fYxjP!!V`=BY% zvt69FCVqI(0RP>@u`{L(%~Hon$?dX^KQ&O!y7oRKEyN6%72+NS?Q1jZ9r3aeU8$+> zsNdolX0^WdIQs!C-sloo*=v7@y*7ezk(qX9iCek-o8L-IqO$3ACA%&D^JShiI@yZf zye^AaY_}v@ug8!%KmIqyL%)BTTo0&tWa3*RO=HK!yUgm{Lnbc1u*pV z3!as}Z|^FQT~4G;w=rTaUk>@f$c{(bPr&7IK7+y{Qws*}jw{%^kC+CpH>EPr909!) zgBLezM$L#~$+^Kk0K|x?{4(Mbyz0m$7D0DWR%FrOsp7Iz&_(QE6k-}EmW69cHn0pc zN)E&&Klmt2$)YpSgFix4Kks$wCuf!x7Y*q^;b-YB0`UsxPtuCy zujJ;0(+C;W02Z!M-vC#D7!(_Fc@bbsB>!Oi9Yp4!qv}AoA=`Vm0aCZTC&2>^Af?N% z7a=%sM8jyDFL9(VPd{QNNL|Ucx-5(#H|O%Ax5QQd1>Wc1l@e2IC@+9NyN82NJKZi^gRO!-5ja)4V;>L)oN1K1+RG|Mr?^+I6K+|}( z=_iRLazEhsdY6XogZOyI0pO#-M!g7k`r$Cq5%6vkAu&E1-1Nzh-FmQ`nM&_)=qv^{_dGyRnL0`K@Ef@7mj>N6ae0+C z4Btu*kNIUOhlO^DKYo5n!(yy7E~UB1b+g4QJ`loxyHo5*G@EvxjB5aMyWcrc#EQJG3ON(qR-+v6@x$Kid25xTdx({~*1Kf;1s0C@LU| z6qOQDX(A#b0#c%)AR=I+Nk}Ntn}C3#5~_fJQM!PHj)F)Pq!WsCNGKtY!f$)$y*F3x z%)Ghpy_q}j{qhGNIEUn9pPha7TI;*M>$?b?7pYG{#`MWk5>`*I*?+FrzdR}zV(;k0 z!JYRuRH5z=c`_~Tb~f~D2t}S6C+~vp4J1;)TC-P&o<*O*cLn8tG4H%5YDjA;@YR9G zx5O#fx-h@x3(&2CmGW;E4*nzCFMOp_)9BQ+e|Ss7roXBE!f&Z*tGtmQ683|MmG4Qj z-+=5;lfF8_;B3QT(SJ5qV2tBqT8_&3g8TLCV~_5z&%hs}3%}=*U1%LNUUEnC1TiSVy+_uO8G4cqv^wMY)cB;Y0Z=hi<E@bf#v6Ai?U~e*l%1&UTUambXP8T{qih!>Dt0LC=`{2^D8J>L%S>b@EMN~a>G^}-PJU%_S*&OyFa;F^q8H9!)vSJwlYL}NN1@<8$7sZ48b&^ zfR|b&1+!h?cMmlt$Snkw-xa9O_E4XFSC{!MPd1+C`juB!$Mx8lO9p4ZP3wKfUf7q! z`>BO=A3X~KfKw_FAkMi8ic=QfME(coux67fA9=+{y!cbqu>6J^2VVa{w)dS*%efln z-y^Ipxs<%OE4eQ@9(^>GQQBYktB&RMXs-~^?Rp#)ihXA~+d`MIA+u(LyRXLgS6#LH~Q#m{ah@2BkTxJRaq@(} z&asL?J=;+6(JbnLgpUL5fLNX_u z16hZ9R{+gdj?H$*)Qey!QfNMk#nMc|n~CV7Utct~o?JvOo@jr$*hsRs+;Wjw0OYRg zVcXr8s)o3ghPERPU>Lz5!`8 zMKYnjWy#aN&&&>mqTV^rHWSKB;%miWc=Z?SwapcdXX^C|X0p&i14nxG1Ydj`RR~n` zG#$f)E5Z7j>ahhFKa{;^i+8v3da<8keTQ7Zw?_e851fl`jM*H-qdG*B8yeMTmgR{E z5|w-%ae@?o1BV3>Fw-a=<^SDxe7-PBHMz)r#5Ra2PJ2o1)0T!pZSA?9>IBF%f*rhU zj`|psnY^8O=;pJlbHVYOnqkg><*maq`#-|$619t^)q52j=G;>vgxZCSKsuizD2dsG z5dt|1;qgUl9XbjPf%80&4@L93ECf{SO_(3jCvZRSvC_Y~&v#t%9*@nv9L6oMU~^rZ z4^s#Ql=K81qkTp%A8}s*U!@3`umdwI5g`!Di~rz1Qv_6%7}i!dT@QuZL+H4DrSDvF z2IS6tU(>U!ixTAS8D@TS2K}>d{myhaDwbWC<9@-{SAXNal>hGYug&}RJZA(CTg>^H z%X=e740bP_ATY;Pq`#Wp`r*SsdZ&Zp_8N&Asi5I(86GxCfee7q8N1g2Hv_+>rmqrG z!Av68qB!R>q@Lb>iII2&#rZ$#>OSynf>)J%)yHiaSjkA5Oz)?^?=#>2pd!dMZ zkMCECnFsHA8vVI8f193Cdz;oFkY-6mU5EN&3#gCw6L<}xxvzaWB9{36RcYV!pBd=qU!#5+)ERQ#OG z3N1vIwFUqtuwgU`C{#lODx^ssNxeg#Tt>MMjOu(v=-idP;IOxAN?G@@ZtK%4*0>9@ z+Zepa+G<0%NXoVrq9@6izYBo=OHkU*39d7Pl_@@SfH`j;Z=!2q-U836T++FktQ*?aY(N)u6-f* zLMNx$CH{T!J50Hrofh>ixzKa_dNdL!_jto#8ce7v6(lpQ1+`tVC8UD8tK8fxduso^ zIKnNrE{p>$ma}raeXwx=J@$B5u--8cF}gh!g={j}mnE8*xnvOKZqH<0yB7v-Ru_y*HMO ztzOBd@0jkwUn^e7V_eD}S*2{>PIMvFjOrmAvaCs=HD8Evu15A1(1hw1gJR!Ce&0O- zf^VNDee;eg4;u@6fXM{|*^ZB&CF5JpkxYi4hilL1c8KFf;*DS0mD;|KO22nmF__=U z#ycqKp`8?&nZJ_q3JWZz2JLhAYO!GM2uw`7ds}(BsnOdzoYA`6U>kV2Vr#4ZNv*pJ zo-a5XjBg#}I*dXrpoz>&%Kut=4&vj}K%>eyg!J1PxfSW)LU zX5-k zK%Ur~dMQIGSRlO6 z)+d$ZIkGo7cM5;g?Vh!TM(BNkvi!#9Lb}qvBPv3SthVD5Oj|V9Z9}dg&!K9-)@y6H zE?n*gxSHH58<5xs|G_zz^#-jSCy=fbL2ysD2quy!K}MUDfwQ__*IioVFBRQemkI9` zy|$>`CN|@I!&#F14bqBiNZ11U>l^@H3nOWjd;}p*O#eBWDWtTlK-d<`ff1zp{>XhDSO2rQ@=SECyr1H`%RsOrBJl(R$KK?O;*-Et>M1kdI8OuYvk~nCV*L zoV?FN@J7qJL^}c;mzz-s=hDGB%=E|t)2MPmkAu~fk44nl#bnA<6#-rmd%7q9R@_zV6trp?KDa&-kS31nBK zt6l?ItAWl2M9<*j3F_&TkORL65XdaX(>TFm*^33v{{gH%~%a<6JjESeIe$E=(-77{%F%2(0Y1>gDD&#T!z-ayF zUdO&$y_r$0)KmXtnep`G>-`5pkOZns3V7-rDc7h4sGI0O)HatEW|BV9j$jx1;N^kQ zPla8xv|i%sQ~^}^i1RB;ZT<=GJ=YE|T^ZK_DVI4vf*&!Rnp4i0>Mnxn$*89ZSxH`w zG!xvPF&$rTymNci`0VlPqW34921=IekA0*C?@MDHLs8U3i8(;rT#JCA5?-Sg6DkI& z&yb2h>~sJprvoQN;cHAuaL*fFL^D~J`v=J-MJ!8EcEyFU7q=IDS5FHIQ1f3u6LRG~ zO$Lt%EWeA(HLRk^z6&*OTM4z7U2v2Zj<|V4)ZFlnr!U)qJDN;eU?MF*Mfn!8LE}K@ zis83a^T2v*_Rewp$Ur6YY!Z z@IKq97EW7V1-O3@YEd_Un&3X-g6-eCTmZRJsGz_{KffsV*5?zmL3x6%>am*F+#v~+ zmn7#AFGJ!uSWUk6P!Tm~#(*Zi8)uMI>}OOGo@x;vbPoSQWgubXyBAIaUmUiBqaTRx z;JQZ)=d$rwz!egK4W|sTR|t}t_c}sr#W~{!hxht|u( zmjk)%IxoiF>It$Pr&LwruC;hy&9%VHWS`(9#8xosaAd;~OVa(}J;djPQ?C6GWVgn4>gztDJ>f%nqF~#Nw)y}?s!`XlKKHW5 z)l%AL=EKDPxkZb48;R zO5&;A{z~eX>SeNXcdQimo9Rn5osx7sY3|i#@%7>uPjAQ-#1Pq-)?6V#&8!d@pr{kL zuvaSrG(A&qg*+durV7MDowP|W&C;@>-WxIjx;1e6)6kGy9} zx(>xl(UX3eOH$_dNc_h2UdtCYsCGC1aB&=@g>A2j_St8!TQ^^^j;^DstPoN~AfAA+ zms>zXlu;k|DQd%xyc#;{|6F(!X4_JTSRokWROWoh&XXFuNuLP!HL-YS|8nV+X%!?N z-YT~olQ}fBwkO$a&YWveF--7t!s$zQlr=>HWU;MszhZnZkkLu%{LTyqn6W+@X z>lQ~1G=_f}nma5#So(T@|CT@XJYoF~^p^fgk7I`k?0?;3rNfiq&xvHlXu^c=vSH95 zXBUNaM00=p3R!rWjNL_ff7&=%dmriO)fc{+!qaRYF<&A{4~l2Oc6kaKj>W5<+klKa zB2#`a%4k3Q^J~bKLuJaH$-*wR-sMrK6k*uVuGdB#j44Wve7J9$SAI zYkuY}6Q3`ygr7b@D(?Lv5Nu1~BBf?ox(8Mtv2y3VR4Tg|uB?bQh}J%K@OJ;38ro-t z)9BfWgtcMtP)Z|AAFw>jLf9o*?LS;3KO1bhRn@~Fa~5tB6M2T3lH#qgkBY`#Y4O2A zT!hpNZaCf@fp52X**e`@rK5}q+wQpKKpo%mJ#o!1I~haB*8k>^GLA*|9wEw;j*)fW z0X;cK<){&NoY~cG#rAE(DPFaS$}Gp)9wI7_S_^cV*2n>$K9QgvDk{c0s`Rz!>4Y3# z`;C*ZVZLbw=*%LJnsWsfHWe>T*=B=d2~~50Z&fqNbx$63tQWl=d8R17r&BceEvo04 z;Rj?mLWN|6pTM#BsvW_1*AO4FB$}y3^=7mj@$p_dQmY6#ZO*}>`f))r7?I6%yD;HwH4 zGPru!khr&`>?tr?MQ3G*mqH+TLmyPWVYPfupKi=Kl5?7eikohh=j(xDbfz`)m`DCr zh~?6FeU^}#e~Z$>1EUi=dF!Bo;$oz-VQvS2<8fC{9iPMY%wKLdJmA6*`!)5R5X+_W z+9pp%nfRjMXc&IVxu=O1024(Gy8^~gV=r)cy`US~)j(tWA^a<2f#(g5)@d&!@6S2-NG{K4XXC}Z!%Q-m z!3&xYpQRpoGdg?Be_~N^%J*@rR*5VgiT*In! zGPh*QA^pLF8D{*;iq%Tj-|enCD)2S-#iJ3y_OWo^#N-6g;WwyZ&V)WZ$YQHj?^q8R zLTHivvmD+z4@rr*gxJrLW;^ud`nGyLP8v;SO`!UwcprrY3~?bif%ZpS1v|+tO*7Sg zM_OJDkG`HHM8y31wHDcMpZEQ7M;VW9DQo<>qYl`;lKvR6h%S0Yj-HYG-^$1-uOW{k zPKK8_?_G#Y$2TJrOs5rT{O-JWKoRyGa6drim6b~%##eHZ+O>Aw;n^J_?l`FBGoOAl9R z>_%is>p?^J2Ltz@8agpektQ+MoTcWh8k>Dya7Eu8#OeY&`UNy%+haN#e$~tQp<=Vs zedpb0B;!F#?kC4;ZgYH7$5)cOC#n4B|4n1}Pru=NDJW{F1~aXFa8C!tig3K?eEh`@ zS?%XsT`DcNx${0QzE*%Vx|T<1LZHu?9Ve9SMOTsv9?^LSoXCT{*M&ZcRb z117~=jXZ*>;bo)Pl2AE_BZPtS;>$bU@4P$Ez?I7s_$hX8c-(1;EOW_AViAWxt^(&w zdH@{#@C}H@aX=R3MsGlZfQ!D5aRlQF>cRzQr|_Z;UGQxb)~m0%-Ofe0=iVsqluA76 z|Ji`+k&geRy(%}>@>uS%+|lX%Gp6+`yzS4p+i!kv>I`iR7qh$aGv-@j2E#mUJ1rdB%F^+gR_3j5yp3@hymho3#;spU%`M$KD zRx4l${#VDW8{KpZPPgFycnfYAcqH->st6OLrkaHu>8^DXENVS+=ef%ci@x*f_o}W5 z(If#q5QYiFI`aBmMh7c4!9uNhA`Is++)09=ET>!SM1{9q@B2b_+fy=eRT{RBwGC?r z?G@A})!-%{G+%I^D>uKo)uQj@NotxzL$3t1Hur1iz3{3v*O>La<{{w-wd=)~Va9bB zgK9^pL7SGqq|i?`<-fCq{a<+vBAk57y}qvo%{*TKJH*+-H=ucggK^2@?(r5G8*;J@ z8)`_raCs=W+%U;q^>ir#8jQKtu{@(Fueh`mq6#^le;8+?X{!b?K*IaNJ&7%(DS;+U zC5$gZ!}N}mTDC;b0o^rZhig+9kBQD*@pCS(>z|0}ec&?+jmgs(qCP>$!5-0=+;8>H zak+^+x-flj%b~j-l6rzP&HZq#&hs_g1&90kQX2Tr@bR&HH8Jvr?1ZpFE*7q(KYWv` zchSqLo^RM1J=}eg;CvI?*LTK?6n4GpuoUR*-D6~ zdO1MX519_dk{ft7ASDg!lab+{VPVxF`!IKKe*vpNBW{@5GJH+F54%2hA24A$;K>4O z3n?JYG(P~gUk5Z*If2TCc~l2LDkNq}y%)Y^8NB;_=&vuqLE`C}0!kNmFI&UW2fIz* zpVo0=MBVIJ+YiRV>WqUUP3y6REj6B08=ZH6j6IH;syJiV%U?VUTgYYaIVT-&6IGe3d(z%_nFI1HUF`kgtVz``&VlvMqB*`u_rYoK=!Ey#YK_x z7#ZTXWRsIK9Xp}({O)1a>xcJ~zf2@evglR&>UW)o~#*bYuU&XY5<)#{OT`*oR&s^UlrP zP<$cVQOm!+R;m*RBaDWS2eBFzN581?l8s0*^?8W6e2r&!)n2lEbK)}QB5Or{DL*Kg zHsSNcbR|{C6@KvYCv=V?=nb^h3us#WhWfpk3jSA*`4YJi%!E|pvA9)pXDDTBxyX*Z zXs_gg@yC6qZD%UFE>`(`qA@OB$DhB0q^6YKDJd=SSZcq1F+(_8m-4QVnt{F9@<{YS zWT-X2m-bN&&HEmlz508Pj!f_I^w1$|3MI}OJeUGbK6^)_pR~_+?*4PPblQ^3?w+$?SqADpEqn~H1u2&p}rm|G{?mRQM(9!+rg&|`PIuVV>haaIm3XP-) z%Wps=jX)xctphfxTLRF%Xh2$3LO$AnR3FA+)|tKm?v5ggVgSX5xjWE&lwl-pkoVed zO3Q1Yd4VR1jMMUKSWG#E2v~xT?9t0omZ;%Rs5OyDlDqb^4aiBY1{zm9h%K_0rD=ST z+^E*Q4I2=K)D6f8(Byw)Qv+XS2Ue{T9FP)VU1mUF1KU7@cmWfjva*U!9QwOQs9x6ID~K*s{LuAPj#UO9|JZs7am$^@zJi z0htnnRUf~uZwKvA8v?MC+reAC+kmKuB5KnV&&Z-ChQJ#j8o)F^UnjS;IB%N8%uTb5 zJ&D2z;k&6@ZlmxbFxuY8%_FDYh@_AysA1Ml_!0{4u{QUcuNwOE44Y0GQY6Iz>nq71 zlEw(4&{{Cm&Ew7iUl|$|Nr9|~(wt`&VCvYPW-xX01XBTyU`q=GFfmXg zR5R6UVxoBS1a|&B!SH0*&nr@A^RVeFl)gggE0n&6()ZB67$N!|O1JXAczkp#PxnLV ze&{bT2i*_-b4>Ry6)9!!2J-7mgiA%J{BrK$i=exg)`VpfLXQ|AlneqeukI<bz%@~`Y5%7lmMFn_PHiNOkC+Ax72&_e9TH`H9B3E=&o7UTzhcZDhDH=f{@#e5xj z_h}LWfg~~X8CmaDIg%UV`aEwo;`K#IL&qP`t=hN0Khc)_z9gW1(4s7!uZBZ0`q*Tq zpA`BEGX!ZuISg~6=BeGkD=5R=RUAVbZ>&XKCa+^PP}hxAf@yo*M;jKiSRNo^s8sE- zFFM_;mOyR~xfW%7r>YJ%lT2`*vd#yv@CU!JUk{S9w7KG7q9PP9{>uQF$?6Sixz}NN zcg1!=ipM(k^Qt|9vlYDgyX>#8us>QmI#ugHpboRS+4ZgN5`LW`Ui=Jr=UT&_iFzah zL7pOu_KrVdVX(a*H>2;Zd6IP8R+hCJ{$^^Ow#8Ruw+ za5ax3+hACSV^+ESBPWiuX?dY7X=OMVCn@o;V9;`?n9;?nTI1#S=hg*{BdfD?dG{Ok zr4FZN+6G#jMEU28ex$sTTmcEvn)`@twC{x=I<*IC4h~i{MueEF?BKQzO^v9>Fo_eO z&bQi+bPS*!i6GOAP}zV87(Qc&1+opzcztq0H;n;YL@bpi`g}NkRS833G^D9s#^RG` zJgC+T@UJ264M?34=+4DEJVE7nh@#?$C?-2Ua$!hL&c5*eE-aoKMw)}-`-hmY?{iVZ zA}B&H;Gg=l;_uV^)nPP}Gwnbm={$-RHfh`eT3!VJbS3lqi5sY&2M#cnfbXO|)Mmg| zhJe>abYUp_V1DT3{Qyu}tw9kkqBh@#jsm01Ps7%ssHjxQ&pW_LENF^rAquBS0h!}u zLy%Ce5Z!=;q|*4IRW0lMpdy!y!;)Sfdn^q9Y1}Z}`wDi{{mTH4Q3U+h!t71A4c$B~ zpS^+J)6e4uh{R7bn+xB3^P46o;yR1zPXmwqX=ZQz_WRS>G&A=l6tF*!9FX>YUKXaC zZXNcUxuLHK`kL7My!;j^J>i| z=EBXn6t0J2QHozi`}P@TVoab68a#|>(&^;|GN3UNOukOSc-2^O9!xZGJn?zP=MQ^* zyAR!_V0|iIT)^?9@A@Ft4xz272ns0NV3DQ5=O&%R!+}jY#=f(U$hyQ=3^vRvy~#q^JC~gz)D7vo@m& zpD_-<$yoTIHIy1x@st|j1I>5#UD|-C$-|b5Mk-EH^Oc^?B8AMSR0E%9O+WVj@cE8p z8MLa1x4vS6`uxFupb7-7T(_LQU^wgP8E;&5sf=aVSC#Mkm5xc)VvrU2T|}UbHhRYG zUo_)3D&MD5E&tjbs!wn!b&5GvcKGaxDQ6FVDe4~GO3)g(qWKM~4!QF!0Tr+!&vnaB zx%6d0+~UsbZwTI_)U=~l=b5jDq|Vu&LEk@PJeCmEO5q^%B6LVbxEB6rYE92>w{s49 z2)YiHK3A`wxKIPDuI$e39$%gH8Vy|tfbkW!c+(D}BHa+>zW-A1#k|DcLW@az z)7WRa+4nXzUxUqhYQEUMXIN$z>pQd4VZ5(H*7sufqwJyEttbf6R2pIzzMyXT1CLu# z;>|U~f)}EnBCkoD{`Q`>=ZeOv#w$a=IB5Z)Jt>_NbtV_5idxL6QHb3%G1A3^y2jfj z1m@287h#8dU@lwN#d1b_W~MKvrcV_;RDN!sX5SX%D4P^9$kuQ=WDiF+336ZsxpFc( zzM*}&nd%|$mWwZr$x)UihU0Z`n zHQ3Xfa{=+jam;yWZ^y^OXZ5ajuO`-Gtz;Ha#9|U`ME((a>n>_ag|N0we&U$H>xOOP za?Vm~);dOAoaK*c(T6{Yc5}Nj&YqEJs^F)X;wM1C-(F1W$KB=rCeAs+`Emsr@21|1 zvfB6rh=;L>r|SMF-uR#Skr{XHl^z|>@K)?8m&BRZ()N8Ylzkep@K#5HJQulkTa()B z0(B>NSBk3=P8gC;(%LGZB%|bG@doYl8lUdV+8yxb+e1lO7Pqv2YnT0sVa#-n`$PGT zIKt&Vi3p&w6V89-z`jbxZww)%NTNJ7@lA!GyOXoHdm|$>1fjKci?GhZ?c2dTlD8N4 z#Cm%$j9tAr9MIB#@fYRV-*d;j8|`!}`mbq4e}EpOGU98J5z0#dTi3$M8fwS_u;6C7cVQx z;jwCta^Lc@vo1k=4{45Vby(^iX{g5RK=2UmA#6!UTbRSP3BSorv8rxCt=HXb7%I5i ziDG>Vi3}eJ^SOqb%cAJ7lgp?Rn7Gjo&&T2#X4D0i8Y&}urK{m01y2H03{-042;Y~^ zxUEGTZ(>mU#7A6&bRSe?IL2Pb@_XD<#Cs)8q@?kg`l7CWQ(7|it*3qW}eTweCwr>>)G!qnB9SM z#$-(kgfzZ}cX@0A5U5^6TddAc;c-F?QYF4q7FATd?IrF(s)P@tXNBN@XM;5Po*f~7V@C-hl zwwMf&)rBmkRx&YEo?!Hvg1^1<<>cE3)HIqj6;;d)c7tcsbxPAbl;KIWFLjO#WBa!C_8QK@LVA_zpJiGU z$0{}F*xhs)UMreE9TnAokcN6>Iz#n9Mmmh)6rny4)i+jy zcCU$Orb6M%j-YbYx;^jQ?tp3G6vkGMR#n3M%4YzMmLNrmgmdo!@Y#nVlqxc|!EiSa z01QpeJ`Lz(;n)qx&Q#hC)1NN8geAH0)}Yo!3R}qEhd`%Y0O|4INY0=X{L(L10-s&_ zkYN&y&#M6VV(Zrw)Nnm`T?9Z$Ic0DyRPM{tG%iPwz!~=#qNoPqu;9!DbqQRceiCq` z?oa>-o16{gYksKIlLkcSm!i)VeKF7<9Qw}i_wAwv1QlHA!3lzOK$6?>@Dk{{LJ4{+ zvJK8cQQfXclPdb~*zWda3!|=d`3!dos zIZmMjQu6Ry&ZoJZcJa23AKc_GuSXK^P{ZaB?3t$syd$;mW;FH>5rgD7J&0Y#+sm5W zZm+FEmdfTO@0C4eh28>6wTavC8ZQ*ltdqpcN=fzC@_cr2=@2wpIg80>^)w1QjP3wm z_VH%d<*yw>H#+D6+aDLOdEfM&Vx|gi4NU zJ^p8`1Jm85N6sgKZM@iu(*e`Uih+1F^zqQ0@B<5Gh};I>zg5xG>VW)HEjUh7bj?% z)MOnjs3pi!G#xLd$iw^eY5uOjGX=^k;ZXbsl%xE*0PuC07HEp7*Pu>d{KwE>1^ZS3 z<6~uS2&HJ#bvF-m1rDWP(QB+ke{lfV4IxPNFbzvl)7?g2Eskrt?*t_xh_Zely|d#$i|u!u)>)-jPZcnigkd@>RRSo#-k zVw#*cPwS=`G$DYlkZYiT9Cg!Z0r2pr4FuMJ2fgXSn`d#l0=9;NE%MU88~S%ce{Sf{ z&F|dP>3bU8-q7vM@Arl1&kg;#p+7hD=Y}5N(BqqbWbFBLND%8tJ?n8PK{oDoKZ}Uv z;ZXwm9__)w9Szw0AHgB^PtmbLc~b*gSVNei=s#3{oSOb*T0u^LGE=6ziAGUl{<*-!Oy8Pd9*Ts=`@?FWC+YZp?H8^hFYWyB#nc_oodx1 zSATwRjyLnTIOjq3kgr~r`Fx!UB9j%o$firy;^l@y2!mLq4=zJ37PdBW3|NlQyRmAp>j&}<~Ts#5p%a=BL)_Hn69>7~pEbqK2W{v?-toIHyOeEUr)r3`=q zb+x0@CIBP+u=F4DB0(v{F>0|B2&C2jRQP~ZFXuuPfVQ^-PIJe0#N0a8KvnSj2+P8> zCXm!DKG?%le(B2qP$tW9|35;3>F*&N{r(*H-;x*q{qNc6q~o!F5FWdW!RL}Nt1maw z6Zz>JLLRh7N@RXIcRj+SYJT12Qz+E(jA5$?l>_r-Xd8@jV5pbYWEQh}No2XTu@?VI zU5mRstf9@0YhudkDaVW0QR)810*|D&bve-Zq+eX(A0g60zsBzqy18)VK$fipL_u#D zvfrUeL)kqYA%@4)K5X@h;gl{aJ~q)(O8tEOVXWQ2vVg$eWI^fHyQZ!>A5nR47WgSQ z2*nXW13RPoOEe-gt=It|JaqUirnMA6twaTUlRb)Ofuf@@7h{2SmIWMQPR;SG4G1>C z2!6%1@|;0Y&qBH*V9sUzAw*h?|15TF1EPppUn|~#blmW2gLC$vKG6Wyyz+x=@T&19 z@3%95L%QfU8HNAFZ6CVvuh>+Uc6iGW8^tL#3;#Wbm9|A6o&eZ2`=NNhnbDH3K9u2z z>?Ei?5Ji*#)Fj9s`6EDZo_jw0UJ1%Eg*^Vwcw#b!nm8WsD>tvpQ45B=?>uZsi5Pp$ zJ?2CQ#W?Af_|C7!Ua!)f_Y|a-nDd84YFj4}B}8uW7=o&s2uV^PenFd{jPF*c-1UKx z^KtHdz%Z<|`olr2D$0&`+ccEDVxI$ynPNt>G%emE_pHRQD2dv4@S$9%h3l%6 z!~#6Ugh=8#nX9Fb0pgK{(T-qoS_SO-JB153*QwBt|7%%V1~@bF+n~(*uNaCd9)0?A zx0`YLc&*;o^e0apZPwq}NkNH*>0ZSn>Zr5$H~y#*bzAt}rgJ{?dy(Yxb`UpPwSDut z0(kk^)s$(JV1@h)Ot@T6Sh;I^LELnIMsJ$c+xoPX9j(Lbes5PX(4)1P7l;mSYhq82 zyTu=w^lBN7X4NZvUa2s_`KeK$j{I8 z_g^HD1DnanDF%<-BSWx&c=Wgd1DRcm|H2<)BvSsi>Jr9{f5J`zv4p`Fy;xthQ)x;4 z-K8dTCE~Bl#2{3M#YiHw!n94z^wq@EgEr=N zL2b_->^qGebkrCNBFtX1z2db$*PFWKKM}P4t8#n)U{8*LfSH5iU(J|zTp=an9=Uui z*aN-2cu&gH?8|tp?gWDS%fnfziSaETY=#BvX5b-%yb%_~THO!6>MHHiX0WZ_;R5Y{ z!bLtLnZ!i)OZk|-ljRcAR&7nz%-z_dNNJK}EjmB2mQ7?JwCgH%-d{w6Y`7pm%8lt8BjEpboK0&YsyS-eAHCRpcpvl|# z9rHRb9S=bj@9`RaTfX}74Y8tr`-L+`55-jtR1bmf0FVAi8~6X$XTx_R+kh6JX;oLd zJ7?7q;d1?lDaXM=><8JdSr6OL(GEanAntnP+6^a#cJb#vE&ZR!FkFkz18kr;ZwF;hI^vVPxb1Tx z`w8UrDD0q<-;0B+n%0tJWeN|B=Rq97FgS&K#Oea|f zxC&{3px9dx_talM=#*^q1syE!RsWAw;{25gp9(ROE4pt3QoPuo(JU6$Ej#8)R({eN zNeN>1s{Wjr-tTWBEQN;%5F%$`w+EG}NfZ~to+ls5l~?acLWg6FOSuJUCnHWUE3(d5 z@f-aQRuuh}`}iB?kN2NYfF6SR2PnXmGpXA*!XeE&Su;fF`s%Q!T>bBxsY>Lx}XIc##jeza=fUbPma8`RS^s z(|6Qt=absWf##gFFgu#Z`+5b2`W+u+d2EjJw3rc(&0HNdw$2z>Hm!#8q8u!m_s-Dx z;Niy~5LJpk?~bM&6&5o?wKNwo?w`MWxMh{~GTBspP*bfp_lc+=Uwl*0twgSZQ|g7oH?hM{j}sBnDWXzpEqeKa&IZhm1ApF^hqRT`e?h zh_^!IIYyL5lRZK`BHW($0wO3t3$m40%29h=7iL`0c!Q+2K5Ix5eQT-snq5KdFD( zi$0+;nG$m1pUIm-ZT#~Iu0t}%L-vojOKU|R<4;Y6n8XIKN#HfbwDdqjM;TJQ?guKM zLk8Qh%TsnCC7Pm3eAqcy8Es3jeI{1>y6jq+;lO|vZ7e&W-lO+kMu`$(u#hZ^(8cdaT3@ZgZqwhj zGf2ew-9W6^){@=Afp4gOy;#l6*I_TLT9v$7zK~J9`lA^&<~tfj0t2{bZ@R86Rd!v_ zqsh8b@avwOnb;hb(k>6v9Me&nE!-&Zem7t%BcOnuTc!`LIRXgI zXx0tLq!VE5E|4%1K;%l1WUv8&UGAna0~&k%zTceL5A=C1(o9H!omcx;e(lXOQy+ugyF(9wxe3QKs4cFgd&9e=D7F(>Hy``^r88OpaH$Sp&w|&recp; zrGRn^&JF-AQn`EKR3KzF2F2H-*|8HdKNPz%v81}+9QVb-Vv)O6gxu6oza9e^zW)>+ zMGKgdrvYKGMP8DP;iI9Y6`)^s5l*=lx#@7O5#5O0x*n#Qi2Zp4{HW?>5)2duy2fun zP<0-xl*1X-&TH#H743jL?Xb?KL*lsMI6TNpTdW2C^8jE!&3?HbO{fE>LZJdBGXcR3 zh*0Y0WAeR>MNF+mD$fK4$bKS8TbGrl%JwGJ zfEtHnpZYAetWxeW>Etvogc_3Bokh_)o8S0h8wK^*fte>~(QqrR4+#xYwBCjvAD;~z z*OO1zcWHU^k@EfOT&z+pEEwg$8@2&?-!A(dKOYNY(LF!)?zTE*O|Rr`M1{G;`a`dd zBzM*-@f|hp_cc2TCZLP$gT0E6sg~Rm1f_0Mf!j@d#yWCp19FI;u%Dj2B|2w2AF zQcSJm83WhZ;-|#7J3>0&k1af=5v@I1=9l_K$ed@|AAI1cmXp^i@U8#CP;^vo)GSqV z_BBKxS?f;m{VRVoMbY#r#flV@L6O6oOavbc`Oqe=|6%7sT_PBW2-k zmhA|oG%JVR@kaA+J=!-C?0Ez(BGY0j8KZR}+Z=}BTsOt{Q42H_WX{BVbC=Y-V(XNs zm34cTHI{7B2KRb>=A748O-+(D_W5ayfbf4A`QmcM~e^^bfH z?>}Mtf?tRzn1~I?t;inNno-->4G6n@zz!Lh@Kl>)fOfSGisO3FUZ>Bn@fU&f=-3M5 zSn@W&Rq`UqlTS`-h;nkpvNma5X+DFGS_o)o0m*=#Xe*QZ3~{mAY-x}6XX)x80x9R zGAIoS!#ct;tERKw=U4T0m7^-*Tab#huMY>X;TqCb21z7cG2+@O;b_S(eWI>k7s;bmdi|LbZu*b=>o!T3V6FY7a?UBw@<1DVbG=JuW+N{FvN8-n-D%~*M z@&Qn;av6L~6%omW568yZ-&Sdo8E(F>%1~kdl;Qml^aR9&;RNHUN+bjyUjyUrb2qMf zhs>D=-A^;*_U37InBAnLnur_YqC*Xk<@3gT-Cmn;E;+3cxulgh&j5%5EXQDr!WfGV z)XfFo(iA_|5V;ZQ*Zp-$@1d(iC1?~T8<5(z4>yEcjT5B(3Z6e3lloBWI^%q&cD=d?q}0u5qi8vk7<7nyXpQB z-9MuHM|A&)?jOjo8@gq8Z^e==Ti5#KaCh0h(rxB2kPXO&_x4R!vQc~Rl*|bh9 z^MiE9gubDV*u^jHU3SuwpM#+^bt|u8(35%?AuD2KTw4sC{p5BFaDXf1_-Tcc$DytzH$3S9tmM19>=39pcM9 zySBWI@w^#jKNW+$d6G4V(!zOj`{+IE`HrN0o?g#1-#?Eq{mg8*>W_TuZh>3%LGVFi zLCrYtRKg)i2c_7w^QyeWm;6V(%wnwk1!q|s;H=ndXn#1DH8ezbmL)*kCp2uN^-o(S0^8{Lr|Vbs7a}`d^p`GrOkV^4?KQx-(ewWR Dqie@k literal 0 HcmV?d00001 diff --git a/imgs/diagram2.jpg b/imgs/diagram2.jpg new file mode 100644 index 0000000000000000000000000000000000000000..ca2c8340767baa0a6b75a72e1a8e1e617e16203e GIT binary patch literal 329019 zcmeFa2UHZzwlCgDQcw`dAfSK(5|t!z1SE?HlA}rn$x+e>NRTvw0wzGoK^PGbi6cRx zg5;cYo*@halV0;XVW2e<|Rz-fS-xT&nELv~yvc>IyS@<;ak07v{N4ERE}`t;1}4UBRqaqiSDO%)aEd-}R+ns-!> zI|ZB)Q@X9Jdg?p?xVrgx>8mSWGBGu~MEM)+7d1c+hy!vDZM;2{?%lg{T&J76o82FE z|CbN+&~e)VpkMg7uK#lBfB%EZ#>2}8EQSNq4O=^J8*m`Rz`TpUj|X_3Yc;xa& z{_}C(%RpZRJl_K5X&nB{4;<$o{h41l&U=BK0L$zhmv{Ihf9mvc{?VWLi^q8%yMW{8 z0xIqvPrRHQ9DOd`5EB!-q-5*<$nMhpC*D4GuHKh4-E7>wJlwq=`q{&7ws0RTP-0RU~vKh9mf4glvx0ifYM@jF0wnnI7phLnUGI7LT7N=HI$ z0l2`SCMWsh_eg@jE?-m*pWvBrxJxWK?v_^VsBYAqJmLIKc?H!$c{R4wT!y}_(vvczci%ZKZt81v8-MxME0p{@NxL+gy z>7U&KKmY96f9n?=*soJ$WTa%2$NeHX0?>r z86I(cB;zBmUMePDiPh5ujm>_0m8kA95C83LB@u#O&Gd`wcY8uHXK{BCl zYuwtvgRg@)OrCoyM~zpv@SSH1iF>MBZt>2SXX2u9va>Z(pNr!5PYD>sTG}8vG!lW^D@0&smk4|lnDplogy^rpyLA7{-3-v?E=oLo zHW7&EA zhLeeN!WsVH!6#hwL`?jLKt3Uc6Jj_ah7$mJ0=7@Ii4%3{M72E8ok1(b2`D-NMJJ%> z1Qh*SgQAz*2w}+VVg%uNFA->5CITLY>+Tov8s@+Y@HA8d@9MA*(4*;fqqL=1qvm7Fba^rNpS{NaFb6e4ySf za)y7O#6|4?YnbwL_!#o)Ud}DI!cGMp;j(bo`zy14FB5*Ik?B;~8nE6i9%pRY2Vo&UD*_+(6vIptYwm$mJ z-FaL}c=E)UgesrmfrmMe`Q7tVh^xaUw)hn_@@=ao&~|` zD9b_o&uE{|s|DQTJ$&LlOLEKAI|F#Zz597mC|LihYVZ(`LW{1(N+RarL;7VXZD^-8 ziTur?2gpy%U*M*aXY6W)Li*INhiZ@qeoaTN&!S%xy)}-Ka1qP&F&|Mn&vnpAwNU`S z5%BhlznA?Qo#ok;y@adRD}_p41u19c5PtSUmiuV2dzF5%Fc-x|Q$GQyy;J7yDkc8N z3{o!9bGR2lzzbVuffr}(Mso3Q@}NCATnDR;|M^aZPuR$`M`>vLH$*`31#~($8!LW? z2xMwNw)+Oh_|fHCOqQ|Mqi-E>M@mE>G!?e-OPmmLi3lLHjUBVcdcK`J_GFMxNa|z) zov@1&=6E83PUP(gx;Vj7C&=*xC!Z)IC#u(pqIsfL|35b(!2Tg`i~JSYkc)G#>iRzA z-^blBZ*AVW=HeU++Bgt(7G)bx?v^7(XQt{tNs3Z9mi7$Jl_yTA5CPI>JcPjzZCi7;(8Z z1Ub&)0LkMnh3-Xkf&D2o{vpp`$wR`^+vk zXuVxu@h$dV;8sGm1q}(j*K7f2Ipcmh;6U4zy;WAHw8YUn@*7N;74m}}mLWw1oK7pg zhTBlLFmi92T3#F!^9*cRY2d^eVW22oEy4&=q};ve_Q&9n7q7lOtx}Q@Axp~mHt~V8 zW%%P3|O5&H?UdeV_bur zA_A@}m4bUnt~N(wrQt^}H=6G|{;ID?E*vvjyW05mrGh!9v3~GpiqN!kaoI7(Ia?kE zx%>*cy|LFMk~mbdDU8@(MZ8d2QLogHDSavS7Y&5|?+Z3ai39(7Ybt0-y+Ao{tq|Iq z$+>48rbz9oe=F@R`U9shcO&d*)WBQlX>b$E7wV*r_IpY)r;PnbnbAr3T%0tL?>5ut zn0*MNwVGL*&g4#3hCDV|Mk5TH9rXfN99Eq+C;E&Clusu#Krj&mX6Cl_+WfM5ySHN< z9f>aOVG~6RHXB0`kZT2Jn^VS4`wigV6G+z~jFqd33OF|>Nzu(S4TBGz{AB7vrFyP; zFii%koM$&7X-fs%`+fr~9F)$7b>lY|@xQpt^GOg@>UZ4>Ve4ZTWH)KK zH~u~DqUVQ=A_`eT$hvyQo}M-TxZAe(?>#F1tfydl@$Y1MKWXc~kDG)-+*%Ijg?}&4 zjLK@<%Ddf%Q)hcLZ4^o3_kB(-l4aM1H0))y=T1^PcFb0TJ~Gv6Au~a#H;G-ZO%h$N zLe?oLTDu;IC7EyCnCQG&FuKb7L~`Y(0_||@wVQ7&Nk5*AC()--qRhLdwb%XN-+&F1 z5(odaEI5bnVqd@6QyBycrd$On9VIEsj7j!%&096v_Vm2GUKw~TabuaPc%TgMa@kRt zMMTvpVIKxN4utXt9Px27^x54uztPg7M}rMI-7ybv-SFe^=c=(K3zXh0L(!UIp3hIx zqCJsbNoQ!g#CKMW=1vqsi@+SL)E6ocK&^&aN{Eawthyj?Ud6(vukZML%O=UxyVWye z|A>>Go^3D1B;$&i+l8_f27S`EW-H=!;SJ=v(OlGZa(5!ADn1P~E;L>qP2?LlepTb6P$RY& z86L}DN_y|#KnnhM#pLAozvpf&q{*n|hzdjuC(R&^{Zpx{uen3mJJy|%-HQ>RQXlEr zqi21N(4;6nD9=0(WyArf`%muwkUua=Dw}l|8t<%0PzY`@^bCtv`!$8Q9fEpqytut7 z$}mk1b#gz0v+w)e=29RpZ7g?lm$#gI3PmCNB=ytNqtvSnanUIGN)F~>n>beLQk#7g zRMuC?Ro+-k-P>(WBTqG1+Db+6Y`8*_`?EYv>rK0!ji=r_JhHIO~m{ zuE@=?LhN+3g3M8r@l87#5P@lIzV}f{Xbl@K7XS1RU%YjB? z@67#y6;PR^2Gp+jZhP~#H#v`#xf-lxW#znWSusR)Un2(FcCz+(g%j8*h1WM*=uf0 zodp@^rT+zS|5d>AzkFMyZR;e+XJ%YN2Dt4=sS)%@)*0{jKcCwzcR$d?A;j~~;0!|3 z^;8*=l%@X(9g=FzT8X35(BT*el2pYqXb$mQ*hgdOtgGw08&i|7)-HXGm*@jD$ip`+ z!dqxuej*;j#$dPcDGe8T<_^wVVbTn|?Pe#X9{Ej7(WNHe%8^cT%aPBa%S@3L@Rh_Q zVdcO8X;#F{2ZF>vs7&x<)Rq0rD65%9siO80-(VD{tHcUy>tob;t!*lsga$+PhgYZX zQ$CHKSs(Tbmnj-@+G#clNtoxt2pu#h$nIzapFu903=8+h(61RISItp4C7#&5nSItv zM`5O%oZw=DevH=I8ZXMYX;NGFY1KAw|9%X7(s)qc+~ro=$T!aYBWmO_ngRc+fn^mn zvdTqM;c8^p=rS2PDH)gVi8F_j6-AFps&2#XHvh={V!Y8cA9VFIinf`Sy5?qM>hPVY z)&*L$o3IgU8q(8}mM#tMdEeE)T0W&g#O6JQ7VALhfmWEu(MA(^OnmEXR|1RTgf&pf z`d1&7&tu|6FIi!Vhq)@J8`<5*Xdt6+E%lcP^qQwW=s7R_v`|2drILE~|8mrL*!nX) zHv(6AD2+7)7g7jSLZZKV;w zaYNbo2jq)rVz4QS2fc#vorhd>zOi<+lwHz@t{n}3epSp&g1_f8zdc>+hqA?(t_v+M z>u%IZnrKzBS_vq~=Bc#Y6;{(AR62gpv%cvU$>4kQgLhvXO`|FUr)=+oaw`7qSpM^R zsw|3`%lW&Y3{W`4)#$zV{oqH%PXr*aTm}G?2A9cg*T~nU@_S%IrSA>$vYPJpR)=8~ z2m_EaP^VvlCWE0&R+e{b7(30aRe~N5^{X$ti?x&RGQ8qpytKS{IXpvfB@ibHzJGyb ztlS(LjB2-@oyJq@!6#|I6ATAmKb%*qD{Qt^WtCCVjAYPv;8Cb|iBnOF%z}YT2Nadr zBYJ!LKbS(!gYr%FDStK(4yAVP^us?mP+~p1eO2Np_RVl+Yyt&#mb2VB5g)R8Qc@X9D z3Kdg*?SO_S{)vZG$K|dUHyFaE5CxDx+#1;B0xnE5>;l)(b8s`GBU6qL3R($YLA7_` z!|jWO${iizAHg!N0rRbp^9Vav`j!m2AvjK{ShH{~NdcYjabPTxG$E$yWGl46;Bg~> zg#&=s3+~1d&KUM=JoyM6u{I_GeW~!?v7K_V)T>S+c>|U+uR$)->d1Hq!v+T5z*p6I z&*`3%&f{dOj0wjUT}-iaQ+zzU+IEO@1c_z2 z(mlF#r6-*iulZgk1-8sgU>zq=A;loGmr;&Km?c^`o(!r5I!Nqcv5?B>NQ5i6*Ak8e z(>342U}0hALeX#BC+a&|No_RgxO?p;y*63I*-v67q+2%$scmV2`XPsqeH#U1DhLlvSN zEB9#P3822~I?{mE{GP z5t4AUGl;V|8D!MU8EcA>wtUB$D>;6CMyNfFB#$!+rmq*%J0>=?rA*!u0>M4wUX1zU zu5eW#;_F@+I)llqqL z9H2sm+(`VqO@OlD`1*)|4Ky~C4kW49q+)|OHv}DXQ`&?$q zkNygm^Xz5e6y54uZGDLp9tsHB&Kl&mj(ba*!CI|`0=p)%yQ++DO4iMcqxQgl)45b# zA9bp+tf;C=6PFs9sj5=pO_tdxh}A@w8kBA%a1P6C$3W=h>5=dz|EZgp$WP{uft>F@ z=GWFdI!}MVXmF}eWBJ+bvl{{TbQv)nsAvK;pNm6*rIYn3+=aLC*RPxSLg_kDZ6Y+% z!U?rP?`RE$J>r#ERppI4I2BQ8tuTzh_U0AJh+vkh{dHIJ>k{(E@0f1{-hIRF8icJ> zsVuc8bKtseZ(^{?3QFkFY4kM=9ahFks=1ksv7va5R~2gPkVM)?Y@Nwjli6-#Pr=Z!S`#mDz`)Bpv^r9H{HW?M4*W|J0wD;4aai?8}%IC z#uxitCrk!KH*RBu(krJvy5t7?A@x_0osIT`I2j?>#oO=QT-c+Wq-Z`F&AujSx;}^S z#u8+3(4N^%Yu?b`M4(LfJ8Vo^v)Y>8(eFq%CPy7B8dK4pJVjvDI5g7_Q|%)ilBqgN zUs3$l+VR;f!cpXN=xtuWXdM)^&$ z1NJ?{vQTwO)ZRr4t_btiN6^=SBAq-9Nr;@YynnktlwsP+Y-F;>mE*@y#aC~w&(%6T zlq0!2ujjA$f2Fl@LAQ;A%A9ou5vW>jfWy!0QDrVQ?`P*Md)1q{dm|^Xs(par8)?0o007m6wb3&Yf+7LqfLbghe1R1*6wSw|nO zEcSDE-p4UWmDOYzo0F^yk8Pg$>>a%RrasN)?fbPsBlWq5;LI%v9m!zKkV7zGAkA4r z3sJZ0d$%_lRl2!fSmwJu+s3)SD z$*IHaJc1%5+yV^ry{z50@XUzMWrL6N`+emCN;gIHvfrNRwTsmld61ob>Qjz~5(`g+ zbvFXXP=&sQT;9MItU$OFslcGe(_0Az&Yq)_tLVF^1UaLYG%<^@2TS}Dw~4^D6q9sj zd(x-XdKt7#co?5hjY+jyuH>%}+Li9u!#1=!rZEULjrK+AwoDq36s{QwyBBP>vZ0$y zg++M3xAqFXs0a(9B%NwVgj1EsD7#&l_*6A&$~y0@xP>{iY% zoQ#J2cH(?@^Ab({wPiHP94|1nb+(iNG&!LJR}0hENgrDq7)}w z;P_RrAUdeAKuLo0QOo!COA%c!#7oZ?PE=pQ<$?cQ1Bi0Nr-N7}EdW%J&TK+p(0vY< zugJ7!aDP@nI|g@VHi4`8xt~FIjZS2J%&St*Iwdx@*7^8lR>{TTmYGG0!hWZtcdhBS zw?;=n=)c6y#T`0gU77b1%Nro5jic0+tZL{`Ciph&6}aVkp0kxp<@>Uxw%zU@uyFQwrXl53O|pSq zBA|_K-@JClP4I9Hp9aR&u0rf!Pcv>HGb6xlVZUOgTgLi&9x8M$wdq!A+s035RO2^l zzwp4e7MQ%BGUC(FmiTbRYlNX1Y;XWR$Jg?1TXRiI(_WX?GS>7@fPb0q})! z5jdaMR9e6PrAVSktHiiV$92i(;+^;Uv9)qgW^gC&=q>mP7jQjt~Sa zVYAj3Li?e}JDJZATy^(d=iRBDNoUbzyw!t==?~JFYGNI(Bz#LHkDVW~-QWzT{xj6dnL?)s2TBP36oLl-IQ| z%rmbB9zKt4F2*DpC(3wuRzG$fwH*m8bb0pZbf>^vg9hp#zCi-os0(%CmuCmfSLw6D z3Jb1^V~?h7`h42QU8X0CI7+<5cy1oX-Dt{p{1v(q+6|%yl212_M5ztNZG8lS&LXj5QXuDauPi-kUUlpFF8)ZZ-1)uG(4VdGd z_coaj*Zl1JsOs!@8afywHgg))Gf#lhIv?_&qw%q!WTCw^I-QtzDph^Ks@#y#VAZ_a zsRzhT_0GOmR3a}p%YJ=(ke+LP_Ogwb_0`b$P2a{77v0wM{J%RFJrt;gh|fx3Bb6pDcZ}PPaxH(jJOKFF;3h z)j`8W`}&>{LKZPo#I<8jxIzRzXMhHuT+d-YOTsSYQcN-O1_E~>pKxba8NAj|23`}k z&aOQC0S4=VEbFD*Z^VY^C+MoS@yaG^8g@|ENQZXzLsqQdvw>sJiry6BeQoC99dNtp zvLXmxl8TT(8A$LJfi7N;Ahd!N>fj8M{53tlgJa-Biosv!Z?)fvOq|(i&Rwo}ndk6m*MMF3CuN7W`t{Kcz|DVRUng z$2!-l7divys(?Q8HTgu~51>}63sbYL(hi#B+>b6uHg!7>osO{njee86S|c29W)E{B zk4*nYeXjnK_Sx$ND|F|{ErLi)GQ^OO2*pb)eVCv&SdSD>Vg0X(OFS8~wno5_ z*aBw|6{Nx=ZPCYv>vLgE(vI=Q4{UJod3;`8baRbPO9MM9qSdnE+`WP)erKyI(xJW{ z47M|_X^uiRfPKRhd^r;h+LproGQ+>#$A#kG+tz>W^?7cDz2C?ER;{M@tC-*uJ26EU zC3>&f*B!LeXYWa;9f5WMG8F#P7Q!hr(t9;SEQP&|lSa(Ux%4yzVagEVP(R+vrW2nW z_B}~E_~W2jz)wa#-SwLeTl<#b>6+eNy54(CF!!ESLIBP&d)-Po#9y{*1ZRob#xV&h zA)^y~r>RVWh3W?`_g1nOlX!c75`OjNos${&FOn~>ek3D&s(BFdhSn6|Y_gGVyS;G8DA9MiywF*X=* zo9OU-5|m{!VR2`60-AhNQe8`m3YD#bZEMCb=KRawb7}xfwwrp&9HO{<3nPxS)~YW@M*M0RSAUKxm$)v* z%=$8W=z3xm;<2l8CFxc9`Wxj`P)-H98AS$i%<(2o> zzCNY0ubj!9Y&y+eF%2sn50Ds>-MRfVjp&MWolC*&voMU%a?5&%y)?MK22ZoA`GjJj zZ@IdnMnm&3=1ImZN80<~Seol?R}qc~2O=;gIt$$tm?@jrjq=}=@c0}{1azyZ8PSYo$Q|$B3~(Wj0oEl47Dij5!Ay^s>yIW6K#zh!;xjE9E>x zUtr7gd*K3YS7zDv247Za`_vVbam-#1^AzR%2~{@a2YmZVZ3K*{j+VuznBO#3ql)J_N}7`{Ls%MYsN?L2-~+a zuID&@c1fjQS`G6QlERwjje7SX@&eJ~?F77TPO{8r_=G1I;aq2v!=DA)#q-x!u^2BA z0UYD~Ir4*Wh;51Xo&J%W4ACJW31;7$c9GAjlEXGu9c|pvCc~@bp?9H;k0e~)feQ=s zn~!p9%0=GHQ%h$8DJFU4^{}A8N6K-T==ybpP;5YffdBPR)8&5Pf4{gw+jLI+`*gX5 zH614zVHAbm|FN)}^oBek{)@S}3IT-cdh1KOze$e5tU=^@6Q`XY@DhC!6Fel6r*nh) z*Ns(53YpE)CCienc0GJEskH|YxO>g}Ox5#unV!90!of%r##Y=fw@@o+qe;X0)eLF; zJ6=p;>MFi$hI&2dn*-?ucJ@P?%IfGzZFzmrUR5(+NO|o1G7KPKTc^KRrRO=HwSC#d z*8TB=+J>fmWN__BSdXoC8QamdFw1EiLtIOse>Bv_oeN*1YAUI*;j?a_V4D%tPBXaR zRaRWRM->1k1*?-=WtM`JtH(&nJ?(s(7Vpk^Hl8ApU6B8PH2(cJ-#zvaZ>s_GRFlIa zZIv{F^-5^ja2o`9PxMec6ZF!esiTR2)(pI?cs>)u&y0K1(?SHW#gJU_}p?l+b!|QhL;M=SJ*&U7iZM@8kV>Dy2#lw6%cyIlpf#=BECK@Jm zmMU%dm2s&Y1KwYtP&NPouMCP3AL#?dU(;$6Ap(KXMc0b(;~+L}6of8x2g?zGhdMT3 z`==0Ug1ec7Gp67}y=S+vRO?(vM*BzC4c|cPbq8Z%;4|Y0eUKeDBEW#y&_>Y`-Yvr& z;mr6P=)xpH06LO3$Ay>fvA{s*)CbvgXB`%*aCF)PrD;&FT}MPi_c+uLJ}$^w!s+bp zbW{MeA4&t7FJu!!SBCw(2?wHS3pUXNwqyD(_W=EH031|)U1<*`X+hbG7IcOj2@UtB z>~d{pgYEl>GAI0SRR>pEv8^^irj?##Ig5H`#)0M(ZQW7v*|yfWNr$RLsybb#SSa#Da+31d8OjH8PtXi|dw zb;CA-2xwkF*sWK|779GdWmTX{WV}N58>HBUbdFO9Y0za*lzCpXjt+ap*~~uU2QMnL z?BR#n!e$|%D|N4E9kf;0pWyJMv^Q5?ek zSex(6LkAw+6ueT>J8drBv^A*#xe7$Uw@sf`1w_k5DEvVJ!nR)S&HzgX-!sW{m0JlT z$-k%${mV!*+S49M?irq{MPLM&WA?Ub2(42PtWWG0=cJLh&A3#x?5cK1@FMRADV zcpI?cKO8iSmyL0ZDug@JEeJIIvE(b2#WTXY;h1aDxHpLB&<#G2PF5{^$J3y7DuZ;! zGj>qS6?NR3sYsCCLu^2LH$$kq9Q(xeKzi~&c8Z()%_%M}dQg<{=`B~Yk}8AonSx_K zaCSXZCJnOlx)F5l7(kDl8S$)%`?w|Wy>;49;uF9sRtt#26=n&nN?&Q?u zI(whb*@<}moJ(TYo=_H`w=sGgeN62HJ%mGM9M>7&>2ZHO%mG$qy)e)5_gYQnbK#uS zsin;;181jK#EQ&SB%UhOX*?^?TL{Z|N?3z7gIedKur{2~YYY)6P=phKc0&vgmM^q> z`W%5TbYQINJ6HTLTi)w3kun=ciNm?dZ-jyVD_ysjO!CN{(CMZC9N!(U)9=Gy71268t>4yQ^Yo7uOymDvfZq1ae3L!+0-mlo0_XcUEwIboPVpR+sLD zE~Y+v++ZEd9(2csClH$7CcHli{fMHOS{hs8i*mH<^>xtXdBNywC&kNX$9vv8X=HeT zc7t(ln<`ilydzv^wkL}1rE|s^)a|3C=lPbdsSvrlf>#z_-nd)VQExWI`)G}J3N)Z+ z^AJvBu|i>CMVKxkKw*@Li?E7Af=n$9tAJz2#C^owMP}sAy{UAkop@Jl(17@wJo!HR zDzC}LoYyy-@1ExUEi+E{-wS*_OfwwlHdyP_(*1bE>6m@A3vLpL8WDzqb`PWhgf^3j zFrLAMEb111XWF~RA%E96AZF51_k2jT<+#5CE9*WZUdVVCWY*;12)&BJP!g&Gj6unF z!MHj}dUJfoK}vK+_a`2XPlwpUqcY1y!{(9DW~`Xo)iYNMi!J!2YZ97Z2=T<&YDEi| zXSeQBXfqw1_PDMdDA-o4fB)V4^wB!*tWTg9`V*e&ue#>xq+S1)YtjB2_%E?@ncg8C zfUfsJ@g&7s&Ld;VSE<9m){WJd<=mHqcTZcsP=gLuv+IS_iEyU`3Q}8+mb~fEzYwt$ zhRx61-OoK5-hBvKNcjCX;aDjN#j}{v*+Spfn@X|Q=W5yC32Ua@WOrxo+HG84lI=8) zs7q`JD~2{Y5-$C6Dp$rhWRFgge^1`l%UDyu!%~yJPX@W;f(E*HTBaw;t#XA7Wb~QeEe2Wvmj#Qsh$1zBwpMpYB74!)~ zY-Mcw_Z}AH=Efv<3)l{^NN>B9wxFt`dhdz59-2NPU%33a43p9m1xlI^ARON`Yl2)D zw;I7HVT@oA(sMOY6$%FVY(ik=y8d$ce&Sv0-`h z!b>{FE#ghwsRn1++pBbX7R;l7&9mA`)m;yjHwu0?Ds^V-XS%h>bQV__MUPBd>3Uo7 zVbyRPWtcOhTc>A!-QFObg^h(y*16BJ&LD|E zi@639|JEXz>6+(lMGf~;6c0KTO_mLXil5o}QdjLnG+T2(+#w@$ppTLYDJyrat&;UL9!(F5CKE8ep3O z4=lMdwJ2}km$(edQS#IHd=aP%SF9Q31|E4+yL3hNZqDVf4I&WmcB)Ex%ShvCyW=Gz zpTs+xt~-iaj5gRt?9JedUohlI?I!4%jYae5-y2^iCoVPh1bJ*K3`9KjtLT&ZxkK-` zX?=~*0{zS!1+l00MYYA{N3?L!xy?9cY>DZlrZHrOvWu;;zKQPQ-T3(0&d^Xh8qZSj z^ZGr{M9%1D&iXdB3$^bLPTgXar!~VY6R600HoQ?cp#vgx7@Nl55$-bQ@`9-JS2@jEhvClrGY@!{#C?B>rtB@)+{&|B&2zY8?&DceHhTaU=cTNR3(+n(&ul&n>?~h z20L$Lt3Y@xvRT~w{vli8wF9G2+lNJ#UM5Fu2pP~>1Nu{%FJdCXA#*O-Xd;lG3;&&9 zWvMl-S)Zw1rCp*d_{6I3jCEI{>7Zr;E7Gr6kwhU3zT_}p)dG%!ahvE_Yn(JD0lEG| z+|k=gU4H1Te}o9r4RlY|mAE5gVFe551{FBpht-G*rq9yO5Tz%YvNSGaS?)_2J1*|ugFgUZLT$qsob5YATn zIEmO!&1o)FsThr_JfP!%wq=h|IpaPOpXJ$5UEs?Kmp1b;1E~&B|c{Kjzw;t&X+U7iL6sVils5L(Mx4@jVqLuXzG?pl2Aa8@_l(NnE62yM;Z zOaF+8P(mrb<1Cvk(dse!{Q7g^TI-zL>x+fW~Xe=nh<-8@aDcrl>u?w7&RRP?HdJgdK-nVk~L<-CeV*^Z>A>iY?7 z*#s(3M^e^}g(Ab!j@7hcuGG7gPYmKyGT$Vytz9p_Lx^92FGt_TgNEptPcPTd9+@No zQ48|z^6wC&U9Rp|H4g3GZTvoT461tlPF*e%syvk7dF9g$%a+gGC?0J#seScp)clV{ zW@v#KTVq&Uqb{wRUpiL2C`DBvj&TlJ;odmT1F0J6h0a+0s;QzVf#C{Qkp0c8$M8@{$hMFVN{ZkA7c^f2kNK(-KZD)GYH3b2mOmwZvfaSoo~AutR@lHEBL=jK(B`6| zN6@s9Z{5d;z;YG3u9XYBkA6%97POF1`e0vtJ;c2lGE0R_O!9Z1jT^ddF}lLkXX5zt z*$lph;NZGOX^`w1uinMELA4yEX?9T5XSsF%hq~jIFBEwXHs-aAF2m%02<@3BeO9v- zk+Y`E!r621yky-wbkR2EY*aY8gT_Ml&@|7&MYH2URrvlNvWEU37RJ_gt1r9Nd9}!B!*zHs}Xc))xb60_2rYOj{Jsx8})4ojf%U zX3J?lzIh$|t%7r;x)P)cE%U zE*b()Fa#C36zMO|Oy5WuE+YJ9YO*DXup=kwLHaaQUmSKPV)NmRH~l57oi6GViy4=- z&hhpPf#xL*2(m4Z86UY1!wWd$IhGJ{cXjD<8rdJ-)lyO<@ znv}zyL()1ymGRI9ONFz?S1WSkl!q!Z$F!RQqu$I0NTg+)Q!)6RshlF((ktZI%Ete! zao&jazcd^>e@(Tnp|k=kOnXLTU#yEberlR)*eTo&3yI~Pe3L)CC9<<*0vMl5Ul zK}Szv3G(%sIeHJ5yIW1ghAKW#RlMx*?i&z-2*h!rB|%L!@1q99ITIr&jX$G!jY}5* zSx~#-&NiBMb1L*EwD~ro8N!B0R2;{D5T%XSmQNCk>)=|M`>k4`z7tmU_3mBG12I;g zg56zB7j`$V!IB;qzK?ikEX{!NF37{qfkQ}c55D!&y0HkZKkJr&R6=l!uR0?L=b;SJ zKX1B|Xcax#3T?T$zhIoPqlNg{uxnkSh7~^&$)5hb55`gK8&e~j@1qhck@HPQh!zC} z2{?n*D%1USsq0)|jIf4be!Q3GS7o)yUsZWat-8M3R`O|rRW^ACkoRy5e^28yTj;Op zio_JGL9n=~YsIF&UW5U&w^tfR7VVmi2kNuOUnKDaD&ANGV;3gx%mLRq#yE8H1II52mKxYeqS{1D}uBF z&SpA|`MS9fB^Pu%HORd}EjOXM_O{DIDaHm}@yk)o(U)~+?-tHaV+7ncKSXHu?QI73 zH@|(lGp2B300UJ`=9_(%mi!vGCpgIY#7kBrkPsF61B%q)ke=a+`J^ZmY%+LhxX$ho z>)yEFx#`iG$BCb!^tXx*#K|8qq}+~Qc>0rZaG-1DUf!aWf70I7Dtu$B^R1#y!6zy z{frf0t6)IUHikbMmm~h2kMJ4;x?~oWwfdlA(*&xjmqdVRxy4df_mtH|PUvbF{8i{R zCrFh;DvOUnP|zOk2wu--g50%cjvKkyrGXS znY6!rH1kzjD%ARS|G*wju(L(aCvUYX$WQuNb;_}i5lAxLu2>cgTb9W|Cc2tDJ0oLT(qgoJuw>#i}XhrjYc^TZS-dd1-aTrBEV>KyhCz zf8n)Ra86$;Sc(;lnPPutYU5ei`~5*@(0MP~xocVidHvrM{BK4eyJoBF2)`8>de05x z4hX-#?p`Mxq-D0&-h320btRnKWL~M#5HK|4c*??Z^e89m-TSu{=`GoeUqFXJ&O2nk5&^!c)L7XGfB*CG@%lu-BC|V|f8FzV5ho=WL=So= zsTO_Vrvi9dUWVkiSaJ4MYQ~WMtosr^i0T z;Wqvq80L-N7KJ4EdHi6k({0I}*w z8cXT_*%v3P2QG;dVaX=Ny#>E1U%u>i%!(!BDEPkF)}P3q6*d`l+&123@HP?;LPo{$ zE>ZqHQ0qYc4`*Gin=?33r%vy0igfAUl8UUWN}M5C{U7YTcU)85nl>B+M7l`tN)hP- zQj`)9X(A#B0#bq^0wU6-g@hs?MGz2BK!S9nM5WizK>?AD)DW69NvHvm@NLhW^UgWX znR#dC{buGl&+qU@;FrzL&Svek?sb>zy6#BUaMdD3JuH9l_Q{!dzCPCnU-N`I+0#*h z&HD|!y-Yp7j8xa$3V474p7$09uu6+Bs_b35A0-<7O-6n0*KI(10L*~RHay+m2;fZr zgDUPF-`8>V=|AUxQ2pN8jQ?$x{@C66Wtop(|8ryTPv{2zR@N}_(!(IOKhge0Whp_D zEN^(}B>@1owmZ<1_D!~1CS}&YoI%zL$Vcd<%3dII%$dB<3!E9WlzJC%Q4=qL%8ef; z13I-p7XeVYkzV`&aKRf}E0oc$#%ytbP+$eJxcK!NS3zU;=I6!qx35 zbZx6rgTmwSW6z2Y?&CFS(&JmZ-b1dE+lSH|TEgu^g%qN@;{COHr%X8&&~%Bhx~%)& zxYb=-eDCZA7rv-nQ#x5awYFsedwO33K(&n>y0x@XV7#3zCRNIpb{>B3|cVGTTyDG!ZKJy_NyzBd1-@$^z5hyzkIr`-9kNwg- z^FnlQU2#LS>nsnm7(qY*fGkH81>nXUgV~SA;D2Qf{8NJNzx_p|^{Tr%*;xypx8<<%u%NI7VYB{oV+5DN+XNl6u zx;h!OgT&7s(8BAv^Mz-@`a6txQLTiVX8Kr)va8%=Kjlp$yY@^fUXmYyPRI}XI+JMR z(c*{IXq;JCg`@zxlGA#A?7p2^ajxzC#%hWKavQnQthzq@Yg+JJ9q|P^_qPIJqwc?OPwk+I3Vh zEsq~g;*EFBPDL1zm2jqIvdb*op6n7dT7^hx0TpyK?)%3xR=#z*`aKSxbsc;){r&Qt z?NkY<9?YQwb}j3MtTJAy++818tcRnK9l_{p0&k7TC0jo>5;&QzHfab@vu zC(+`Ms7zgf(K>^dlW%itjK=7a*B0psHx!yTD@imz0ZO##Cjx67Ug07LEY2;d4~yhe zLI|SXrFXT?8TolWmAGSSQyjl9ck%X+>$u-Mc{@z|&`mX9D{ho(-|V{@4>3|r%o#;5 zr6yq0>yY!|Q^29M*hbHx)i(i7*>;oSn=5KskJAxp_H62bJLruGB)Snbt3L&Alb!Sh zYQ~1Ni_0E`)u|qnWRGw`=Q+^{r;&Ha{E%!zD0I%a@gvGhaVM;-%*orTxKcGPLwpCO zO^v~;@A!81^+z+7GTZ_?hwM@h8Jkca4clG02;f8vIdB(R!evwD=F@M~hP}^7E!=0- zjnM@U|Gcbn26Qg^6Z!T8+I8I$yENzh`P&+FoxANEm*HCXKwX~6Lh7{XzCFmpj0XK+ zeVn>frxQ`7(+nr~jXi8V$!lj(Gnf|;5Lv$Jdw1&L^K~!AOW0&F4T|?keOH}vhAoYP zL-qU^1G)Aqm%_QH&aa49bMQd>FWNF(DPrL8p$LVT!Uku`*q=AD_66Y1kCR3YTe-fz z*ZQ>K-4Kja`J5ztweFO9u8(+v8$*9OrHlF@98hiu34=1Dk{{F#Rvc2sQVW}9jGsJn zg|7IzK=sRwm)P7OtDSoz^LE*llRJen55w|bEL z*7t?VoxSABJWb*9#Q9R*SK>k1BZ3@4APx`Sm;BjWd+WnkAn_8I68Tu_$&T{s&izys zCd&G-#Bj@y&hF>rP0DF*3*EP$m`0Z-`hQjm7qL(G*b0TLyWOXrqXM8rpSx<#Sw60?qDQ(_dqbu}ry0Y(c z=hMY5i`zn;p%t$_DKK!L=Y~DRv4~x6+|BHFuy0qi6P*PmftvS*1X8f?%gReVcTT}~ z;zH^UrPMpfDPvjLM|a5=T%SWKU7PwM#=}NlsO5T=JW_blZ|Iscu}`vk?qN1VUYSycy3V5THEGEa)(6PxyuZ=E66w=WQ$K<`ltDa>J~AYRamcodp3hD&@E zMlm$9b55*EVU5m5q4ax8FEjMZO$J7>F=f4GWYUrxvsO8uM4N#`dH`lB18F{P%zs2j`0G+KwP;S z!%u_jf*&2^r-a*sBWJiJZ&u{$ zoQ!{W@`AjidTmboO-|cu#sjCdsrPU3DL$|@eaUaT48|G<%IfD@dp3DaShDTsln=9E zv~K^1bEWwRYywe-h*@w4B4UPf+h>@-2w$q_)|yIRU9cW6qYIXJkimHNO0xFZ*;od! zXrnN!8F8kbb~bH><;Ouu#PiI-cL8Z>zGrl$t{I6sIQEB1q^W

2c6tE4Ft(;d)07i*Adc}_ z@5Tl+nSEO3;;g|vd`B$?Q15anQZt*2lEFe$+H%JD-|wKJk34aNBA zL$g!i`(n>8y9r^s`B(ct-dDeM$oYEKB$e>;R}eVO&%eW3b_DA0wuCdQvHC8}@-;#) z&y`$Wd%}C;<@J(9%gGJ~y7=oTab&?t4Ox)N9g$$vyf=Vna>b{9cV9kS$fMex(qg$| z`yWMhysMicyC;r7@nxNeoiBYyARPlp>D1pJw0Y`6S_Y>qdd-5P;s)Pe$Z7=b{>o7Q zL)Vf16x9Fss&@ak*13-F@4u#~F8*5y$%@~Qw*hhNKu#?D->7>M8i8%+?{p^f_|^7+ zyvm;yN&hk1U-2LH|4ZPQqxPyiJP1q&ezN{_=??Lox8xNk+Vj!*V;0v?lNRULuQ7Uz zQY>MSNH{tJ1{(0%h)At!(-Y7cmXF?-FupI_Z!u1>&yryVeU{w3^vEF-nF4m5p`La` za7RRPg8QL5c@qXKLGFv=7pmgrhzllH{jqb{ZN!-7+(tN5&^Zu`=rD74il4EOC#3{< zp4H`YI-@jS>GN2OZH!CS_rAG23s^+TG_}u zcm~cgtvy!fBCAX4bsZFYXjd`MKXoI>_aRl(0nn1JO`3sl8~gC>9D-K45m6|}Y7u0S z70;0qubcUjm*cdXuByh_5X)-*uZl7Cnx2?Gc4sw_x}==6J3~^goD&H*Hs!W{fRxso zkUyArpW9jR6HpDrMAs3uIWBEqx7S-qS>6t}UgS!AhfkM(}05SEf-g;J2aJDaI12d>%n5W76 zqRgtYtK!1FTOTiZ@Tc^Rov3B5nOL-%4|~kmpfERH?HZ{@_KkENFK&tjKeuCadavHU z(IiQi{d(a>ESDl##FLA@LT28n`*OQ4i3NmnShxnNzufYNHzSt;vzF66>N9}}IvmW_ zcIPPk=mf#a>7WzIwlDd^7^E+~&VoKbIT$PN2-7*ioO~?A|(>6FPZVt zjw}R^=+4}z6YJ6x<Z!HB7&Vyv1>P)fXJLLl4mw)219!2 zuK5)hfqj@9f>BU+684ykzJsWA-Ani2lX55DmhzF5@Cq)$C~gGNc?)m3ah; z@db28*W~h_0?2y5Ror7Y89dDNQ0CC*kpero?CZ!BIy%60 zoc($N#^eQkZ05VSAt5(J$VGTErYjD(4}IaE8y=Al8Vv$mTo?UG#$MD|p()DA^;9@0 z4xh>t|Luj^Dt{6zl{Bdy_r0@CBo4nn=m%h@t80)wu49cDS_lAPl(XuJ*9Mmd``Esx zHMc6@R00AmRXyY&a^iXDp&~vg7U47q-!2uq!Pp%)wg&Ie^OYX#1K|Aw+)>1pQTY;) zR)4KU6w+G9KHmx3(B9jYPt9T!Q^vfedResw+06Kz##a*MICIj#Q$UNW&nM+6O}4`A z-~`|Kmuh*9tAGiJ@vSl$RH2@YqqflP|Gru^$~?`gbVf3y!|p|cNqzH2;yhJ_LJ*EI z230ls!h7oKoGxBBI&=9#JNvEFOUWek37EGTJ&%}<*7(;eKdFK@8S-&;b5ck-g96{V zHelSgJ35Fz643wBS`#(nQY@1%4bfg&&Bl}(1j6CWmT+Vq_jlRB>(MNVJsW}53V zKOe%XslYJFKL$Jv*k?r9UbsY7Swst)|Fif4v+AKe8-3BAy^Cjp5L%`XbU24fvm%O3U^Wo<9#<4HByS|tvJy-Ee_bE1vs0JXWd#!4S2{vBU z(laOnl#{;USZ8wv_lTFdSD*~R=JC(_gX`t$7=6n@?o&2!fotJ1JYg2enhD_Ga1BBy zmNo~bjGa%oXlh{7{w5NA;jOIRHVYY1fdqa(*EaC)Jzml~Wnc&n7#juqQFHe(T0TBp0s&yXxV` z=r@`=l5LOX@-#0}ZOao?oesQX6YX4cm!IP9T8wLdXr>SojJ+@i5)&vOGgWUQ4-(&h z-fv-M@!_G;iN!N|XvTEDKqchz&yj<#2TbnvDn3knhOok4H$=W~+^DZ%OGvSg#qZKe?)30=X5 ztpI~bc>u-@hy%qCZ}A@zgxl}NHS^`uKT!sBmDriY`YHktR4wiy=$GbLg(Q)+sn*={R6R2l zsMcPQP84~)j_|hL?hNDizT&Z)I(>A>?&S%Ts_sJ9yIS9MshZefkxet3SMUL(mP#x5 zggtT;IRV~{z#_s3sS!-De@~I zbNmk+Y30#*!!^nykf1{xcr^(@icLjX*ZtkG`n3t-09?9fxdqP3pKoHM1tnWMmVW<( zOTGV+Y4{_({xj0_2Xbhjz;V8c;0M(J+QHO!E0B(0(Y3iqWi1Uk@mjH`_FM@-PKh$eKP9YR^YoZyLlny%C*#>h$(ca)ZSLNP#>UP3U zc2coR=5vQW5AXY%l(1bW9o~|vc_!T7Flb~P$ADFRuhIGvZfPxc!a)SFG-m3VGig zj;sdAw!jKeEWVKDX=&W_`%4IFC&k*~?HF1eXXfi)IEYJv&y4-+SdE6}Qb}PGXmGPm z?V&TCu@&a_^HR|*xfQeSal=Nr4V#GUA6G;oTuvfpiE5)aDyZB-zOqz3XPy+gX9f;q z|K+rb!9I&)VYlayd=(8FQH#;`^ChMVaCf9L9MC7s_|tJlm~@ll*+C-u|4*p+-9Lan$kAez>5K^N`! z02<`5Bk0s2r*Q*k_?mH184w7^83yg_dqK{aPdSb^!~~V!7S|GE1&bFkoKpHyn~-B$ zD0s4ThHwoZTx4+sa(I++eni@ZW_?p+NF-UZF^%tP_3rY4*>)sG`joF(`$$W7yT1aW zxT$7>@0~O27b$=A^+tqBr87{QV z8Im~piuJvSa_4pJ34;**w9o6AegakDtWq1|1s8%Yh$P5Oq%QidxI>0aW7F(&$8%%T zT#L%8#vnhw9I2Fr*KRT|K;SU0NBNcmDJV z!=K}tN>?+Xcsd=jA_TG8tB+s0gJ@=qlVE?5eZ{gfYx0Ur1>5xXC$Sb_W^FT(9SNhpAj!onKoD5D7ccc`_j67*2(L;@qrFqWtShH|pE8?8)SU5)AztK8+T4USysaux z17IeK7PFAc)=qR6MBeU}c|vB9EG_4EGpOK65#%at1pH}$;8-5r!N(wD>04(Q@kLbp zakNpDRZ`?@Y(gQp?j_c<0;}*T5E*wJq*jhB;O}vWRFT9W$(<#$@!2=)`zypfINH6r zTScfMjNPs$sF@jStWcwe^Kg5y^PfmPaHf@YCtze2576yLAgJpEFdec>d_7x9Lgfm4 zf`bw}mUmVu*XwNGgks4~fv6Jkp6#CXd`cpNCGcD0594wj zE3-PaKUICGG``;Ia;B9laVSh31P*hYOCMY$$0_d8f4~Q+$=#j)5pN?B-kv))@_=U5 z@yC64(0%yR2Z!1%nb5Ic^I^B$@oeg?Q>(rDzr0}e|65M|IG_F>gbBwv@BdoP`+su0 z{z>!ce|+`RW1RK>9M1Z9Z2xs^{|PbYLw`YOUie-5;vN%Hj!7hc5F*V#p>Y`gSK|N> zNGduBS8+nq^jP*t6^JX%q`|vo_Jdb$HRpr^bop#!bk54$;PF)F4G%Da#Pee}8M&AE zu@TFfq-lq25}(E#{D65INubUsdc`>EFTN@G*T>@UepD|2iDttA6!yITWp$!Y7D@m- zJI|+h1bPR)egtZI^8?U-ed#+xdPWonFxw8<$5%NXm*e^Jzq5}1r7b)^p9F3RKKUJ3 zr{9+u2`r%<01hP{toLhmzJS(Yb>>J&tiH*}j)C~~%AvHox(Qm<@!zxs9^R{R+CcFf zn6cf9cx$Edj=s0RK-;NoFCch2Chjhw2w2#m_%3))ejbdS*&R@R=I?-Si!P(^Osde7 zT{iKLKZs8do;$Y%NB;HnK2n$}U>i<|0H%d;4t&6}JwrH^5x1sdwi&l-a)@~UhOhjA z|L6kbudl|B#lkrO1>1Z;sRn&*8-5RidZkujSaVPqzpAZM0t33Gw>A?1F4@%#KuCiFMd2M$Ft>l5gpr>W2<<)Ssd@7e|A)kU5jIn>)2O3 zcA<|Wi{pUnzcW;P^D7P=0NQ2f#CXWfs$M({%(B%52d{2tAJVc<;22A8gH3)Qh4G>| z2Yq}W+FZpxZ@eOUf8g%axH2^zyA0*STWF~Tv6U}w3>**0Z7OU`uY2T+P(OJwXkZOU z+THqvMg3h8|9^z<{afkDM|Y$}{l4Rwyflbdb0pT)uJ;Y``S9)~HuquY5lBB1hPy zG_~8W_ESrooXhdnS}bJyz<$%B6*f=M)h#&ZH7 zk^P(N6IHWfA5tx{6O=7)0IBH%IDu9A2qX-MLI3R+m>vXZ@$@kENaLSY0&7?k5PQap zK}grL|Mm-tws)g0zvh1p`P)&@`OW3cme*N4FM=DZ4v_OOqmgX6gAA2y=A;_Axtf1+7@ z(OhTC^F}&6uAcK`-oYoy97TwuqgEa4@Tr-jpG=H*FYGY30^fb;0b~c=6G_bqkV94f z8Z|qc3fSF*+K;_a*{52T`E6i;*n_q=*p+DtzATv=SO;PH(~%0pLyn)Q?c{;RDJ1hH zz5977o~3b3AyF4f$<_Y|x#ZvL9{(wG*uNFh|6i_g9FrP;Z&JgFzq2&3UWVTqpMW=1 zhkacO9Z;%K#0Nz}e93K6hcc2VT#l@A#z>EGlXOQ4k3e?3qojm!vx$n%)FV(s-_Ur< zFRO!8`Sw4_RQ#h~`=69)`F|wuf1jG_vE4bgJO4Or>)*qM{gc|AKP#sGUOwir-8r^9 z$94zwk`EA|v`GZ$QS^8JIh2|Q{*@p4d)S`;4!gtp0>jAU2xA#|B0qBm(ww)vTU2Wq z9l?|p`t1ZfGLB5A#}M@Jy^P0G4X=uaeftOBE-&{DrVNHh96$u%sc~*K?)hT;F>$ZvJM(1QllEz$ccVFBRk&a8B*eQ+XqV~gA!>j3zMh$_3TZ+iA<*8SwZXukx~MM6#$dOP)h57 zPL`Z*#>2unOA z!{;}j0}xcy{1K=hqV@pdk?9D8Gu@v9FdBOw0F>3DD}fC_SqTAryx$xkmFVoZu6BPs z;Qj5#P2ep$vl|CA7I5@6IKdR=3vl}y*1$jf0LTVqG?0S21pn>(A|sO9!R8t);%`67 z|F{1zBm?{};+jcv6^ouuq{-)ShZ7|*FqWlbj zdG9s=57qky^$Pb|P?=IikHc59thzJ~Bp>Rb<0kacg@=%c3O|B=zDB~ms_HB00aW)~ zyc*rQ*3ZoQ?-f77POcx;SjQ?2O{Icw2maXIMh2^~lO|K8a(x^5@C|wV3@bF#w`Z^`jzlB6`!Y7r#`i+ND0U4j@esS=uzsikL(}-G-p1lQr{JWb!6S2w=wR{7#PE$_A>?rVT>MD2ArP=L5EOAbEk3Z*xJ&2O zf3nNm$d;YBnfWYL0JfS3duFdYuB$Zqj;4RUpj=GO-ABh_wvWlNQSw`Hz0T}J^+x$B z{#oT#2kegKM8-3wkbF7@4N%C*DVR0vtC~EHs!2M!>Iej?50sixG^*QNo4>r7U6*o_ z(@q2-w*E9kS#5It-0BW{)&3C(yrjCiwFaY}eP8XRnksKH2YaW*Vn$u|kKR-apgOAm zdeK}Nos(Yg1{hl%hKCg2;cGjGm;Ub1&jCPWH0I&*ra339UHl!X0e1wWH+ ztyZ1rev$~?6At(UrFYkl9{NC?n9)V>`lyd5M*4XMIX>XYyx+%5P12VGwP#(1<{D>& zFbxuUAw`ifkbu|sg}bTjX5e*UWI=5?~S)E*ArhH9wrnN*m+^-HK=l-&?f7jpqvj7JcD-ASV zUbFFa*2fp-itE7N-AqpL$Y*eQ__%E$;&K#}5@@Ru@y%=mOaToz0?|s(x<=GP#KY@q z%b9HE;K3X=;h##g5~Ofu5%bm^TY7a&F%HZ^_86tzcoP!qWNkPL!e=CPNfM|>8M^FJNae35SH-?eu4J7Ngxoe3U$nK55Z!2_g zZ)?L1C>fpp2cDH=M}H-M`Ufm;L0-el<2F!_T_b?L<*3#!)!?B8C87Z=!)%d%o%0AJ zl7yWj)%p4yfo>X`)wCXgHX!Fc=D^{w*G5{bdlH+#FP3Nj{!GyV{crxwtnP(aBi$~N;F4tj+6{8fyMWdvJCeOH|6(%+d}N(9!wvg%i8ucR`xpb@eHdN70XE`CpyV5G#e$$H06$6P@;^TdF3F4 zc2C9Yw2aPFu&;BwO2=$Nm^9G*G`-@T`K@&Jd2a;o=Qh&_K~I~$?us(!Es7a7d;#ZG zlUTJmfin#EhCI7l8JB11DqmikGpLJe=6LK^tW^*bd(!>9D)&eVpzaX|VI#<6`&!2t zLa_mNM%E-sC~iHvs3)uC@h)vIimktcdi&wdS5KRt+*HPI`FwMGX1oq~5)0Dzt^0J3 zKwf~yOJ zUQ&OR)kD5*WP?7yr_IGNAA#=Uk+ZP;S!I3!y_>n-a^=^TUliQY_w}$!r!Uss?$ABZ z&$p2oRc(OPkG_pbpO`O5BD^TPF#h8LGNn<5G{nb?cPP<8BN>*<@W}Q-*{tQt2Vr6J zpsX(|rR`&C*_yH>?;F&>vDjhY$ybYK4h;7K-&=|3P@0ZX zi3g`1C=!;cmaK*gOmd|xN(=-qe73%r)d<5+9BTP0qs!fv_dezdp0$T9cpQp7OXylXOL4D~G zrNZw*hjmP1AAoz?Hv0lUg?i*d+u11K3c~kYN3`%s>d4TFf4bq>g=&gfiTSj*Ii;;L zB?-CXju;J{IDlVYDv5Y2>e1(sEidf#V0HYxqd!}A=_Q!Q@<`&;D=Nxorv~hll)g?n zQ1R#bEj3F=B5^*mBZ#@k;*)PACsUYIKXpAcRoE=|GaIj=W8ty2P4^taS9NT}%rKYJ z#+|`~b@A2!UO?$Xvh;e_!^E!ds*N_cid+PO+2-OG;S4v$m*C%L<{aAjPeP?X0@f>x z#JZ9pI*6{WeK541^F|;kC+W>Amx}nCEl(3THkHk?4JFgDKcAY_R_5LObbA48T!4(a zN6aB9eZJ(52=*VNYhvDwOhMLs0tM=kPd5%-?TPB4Nuc`T-dRNvg+_)aNk1Q9HXie4 zF|u0tlkY4=Z&p)N^{Fy>_oqo!$P|~w!}yRK$54r$PBL}!1m6>l!Xt2JLndFObscuE ziIH*=U$rJ#>2lq6^%29(Q(9yp3JfFhb0Sm=?Oyk=72=AYKQb3&*X+^rFHJYH))6yN zPGE9NUQ3Kw%PSWt0WM6Sn8ytnZ>eUXT5{S9^Y=?3TK zvSS-QB3c@4@STUZe0^p!D)>X{mGk;ADE1p)qVv8du(7{95iS0{j@?#+DXWZW^oh1d z_Em5DZc2|OVOGx-F7a75{NN#EqD9_0E{qMCzq2X0ML&Hd{)3gun@-TaYJk~CC^IpK zAc%{y@M5b>)4<7ReMIQhUA`}<bZK<5SNNCZFZf-iGhYFmsK98EF{7CB6L}>YfD^txjw?O)hTLEtKaZIhrW;A%;H4!@|zn z#$$|P^oH!prmMbW#o*6#BO#NAd-+s=BTwRh>U?Vy$IEthWbobfNNBz0Xf6aF`2VK&N1RPjb> z2!Xr1mlg+>-op_cjTU$!8WPR*9EC%Lkj`2AdK&a^N9HA74`)97EO|%I;#t&+r@$=C z_WE3i4tY=U5y+8oJhXjx73s@9Ya*zX1pUFaKQG%&y>MMl-vy@XKu}2mTP;m^5xIOQcNAE01S*dD}2^Nmuj#T{gEXvF99C; z?0tt`5#R8k1U|(E=hH+ax53G8k0)m<&q!1$(%0%RP4z@kH+>xjG2Vk*-R*^<4!Pl< z>+!Cn+7YoG@uXS$Qo$)@Kloe@cTc40!nLDWqu zzP0f6GtUB2Z^JMSeW*&su=;zLnXsp+4k3@FcDV5sX-?DJXYU%FXuVQq>tP}%<&L(&Q*249qj4pX^xAr`OzUTG{A-x0&hEm3Jp$`eyy`Rhirv<{;xF4*_u z)&e|wmk0BtFS#>Vq;;pxm-c_f1To-wm9tY!6Yf+t`oF2|zbp6iz4%uc8^H*RYM-Ie z#LUp@l5Q(&y1Ob+><;En$KJ|`L5G}DvOgQOLeMXq`7zBmR1qj`n0Tk|Q+XQc&2XYzCouypd1(D%IXLplArm_(NO-#xQyZOg@QEoXyLfE%XYsms-oJ_T#Of zZq>dfS~~(xPaR!wYtKQjQ>w6)mST2pSGfs83617<@rjK>X(t#P`MHvj3NE9jX<~{g?~v>!=`rInP^Y0E|!-kpZ@G{|0+7#Je2b) zx6JN^Zud2pel6B6#}**tpkc#(sP`k|ERMffn)$~xdqu|H?dqtpX38pAREjrkP+bx~srAbJAb>`{Mo|Uhnm-_A#Q_8_izOLxl z;B4R0fyK_-!5j5Iq?#>Ws!sN#g?h;5Fs(z>&61%U_*X|Db~QeyX_Y_~r-#I!x5gtI zzcF{c!SucPr1Enj-DOU7b!e5xOtCUWwyaK!ZQ%|Bm5rzz$=@u4V2Fc1Cos+G$#2l$ zAFZ~hEMGFBzcQf76DFkOBwHwWx}oW+-x`_xrfJ0bV2)ID;oE?gDmELziUvz=)iboA zDrLQ0o`U5v`x^W->Sp&lY4X#pd06j$T+AzHdEX(`bBM-iL4`#+`o7A05!5<2ry^6VwGuILJt$T^>))SY^o0>zSRedir&M zgRD`Zd3?fT{-=vFj z!I6yFY5)#3#2Mb1(#C(VnhoHj6}=BaAt^I|FQB;Hx-<>sRBr*vy5EON^`H1&^1qf! z{7;=Gr%v$3P)@Nskm-Qg|N&69p+VIZ{P+&@wP6L?Q!BWa^PES;>#-uqO@F zifptuzxVOjd0x5++7V(RI+9~%zAx?K@#2R!e0Nd%MVuzth|HPsp48BA3eyJkP4HKmf;otS&?sSU<& z{S9+>dCi-SI|{jh<_zG}#f5P7MKy}8Fs;;neS>i>k&&9K3?KUZxU#Y= z(-EyZH~B*Df^B9Jxyt-Y#&6gE2h+-eX~b)YpNM(qEe8_y>=B6HMiqEU{yJN=$N?wR zkREB7q>WO5qciw%J99G!OF3}m_giv^Jw09}LrnJeL<0-ZR7p)W97x;!L-%d}Q$ie1 zySvs8)w9cV1fN#9TrmBe_VUC{l%>Ud-F}+@7|hE(-9Z|ApB|vz6p1-FwU?NK)bgu ze%RPi)iFaB6crg=gngE5T?w+HK#g0H*wvJqFXHGzTT;?w*oF8Z{>nh zDuiJ!#?Va<)wbed;7R|f>iv7v#`-ak@}MJ7H0vDXkW!z}F0wY!*@OgYU}I9?#UWI= zAMiK!In5)`twMO}ApGGpjM7&k?trqB(CafnjGdV#(lOf%&Ig3KgPH0LMMCPyFw$%- z?;j3$br)5eY|H6zb2KkELmBU``+KAPM_F-#t!I2koA?BJJk+gm@p6*?S;sF$>VPvyxYV-%n|8&=-HkK&%78cHKhadl7ucMbX*z{C zU$Z~un52n;R_vnSTO|J@&cdpEtX zXzdlU@e_%AMeA04h?GY0e3_+#)+L*ax768BtQmt*kKre^W(D6tVOZED!2A4>`l8&- z_-dL~o5T6b!V@oga<92`*eH(QWYr2pL@6bIKF+T1^p4dHol~nbfNCDv z;lF~}jzITFeI!P~TR4WQLQ8#bmK&TdbJi`FQuw{!yw>%6@jNY#!fc}UX{7VL*$G$r zrJl;FPqCdMA^kb`RpKYkdRm%6s`J+sQD_HxdnxOG+W5{B-x2J&rdRfA zb1G~7Z@fz$HZ}S_*LU^(D%}IytRlMf(I5Q#bA&|{81=xFMF%?r!6~k7%!#VC7h62~ zG_~BTOktVpeeFS<(!%f=$4=qlu^1QRH~yxfhd!o=&FyV*hEd5{1Rrc{hOWGi33>&A z5e^|Hw!xS;f39zwBYT)I_2AZzpVjvTDRd(eitFt>9i~aAeQTFG5p*i@n2EWx5*@>E z{SdWVPgou&1#QcUpH`Kzp*pmK8Vo{Ju`6@4!=Y&?Cf};=vXBAtM)UQaC>tHEB?hYG zpv|7|oa62r2r7c0HyRwy$B9iMQBJ?j*W~TuIOlM$(UijNYF7{0Hh<9j$(h@6YI}o& zB%WKO^J(1R(?HbzjIj-|dkQ5;BIwzWAF{b)$+bHP#1;O7TRYqAv9rl@&3xxVD5Zr` zO;-eBi+jm~sA|qPdJ!W_*Gpk1mcMBT)F)T%;cjGZ#y*q<1yY;c-j+{iKjdjJo4-Af zrB<1h!rv`#JbuuzlV_>?JYQjxBbQ0ZlPBneX%JZ4HZ(NUO2O5{+3Rjrl<2PwmkgJ` zj>H()bk9yFqDz>1eE6h??|*n%*zCx@_<+JgvCEE%*X%6Td09GwpK+Tp+=g+mo_}`C zSVmC@C2bOZ1BfH7 zB#Jmxyo7dt;Jd3Y9&grr z^p2fX|M8S^&e@Kf9ITJtJ_4zjC02EyA{;OV`7P1b`s=WBwHA8e-|0T8f6LZ2cB1+c zSD`oV$KM_kvt|4iW}(fk`Xx1NxQBoIcE>0QgqOyEPdlCA@Ma5FR<>Z7%?_wxV;0Eh zxb*biPfE|3Pkk+K*=PG&*2RsZSOcBg?z~(v+q;?l6{sR>B`7I+T)mb<=RmoqaJe*k z_Z9Z$J0NBZAqjrF^nBcTCtSJPap;K?-+jo2H z&Rc_XGtVU(<)I!}a5IvsY9jIKklIY~WJ~kAXeUj9C!E~xBDsYSjk8KmMD3$s{S&ig zsC#A=<&%dH3^;Ng3kia1VaC**%HPVa{5(BH_ffk;UacJq{wluEH`X`X{-P=bf!VE8 zo5DcY`aG4bCqbL-Cwc|$na_vHo%q?x9c&br+?a)rpN&*;2E4^Kn=@fa!o%C$MM`h0 zjU@UnzDOIBp%?{FS09mW(aK0laEqjGMMNZ2Sha`V$>VAFC3?9Uv3!cx=H*W^c{4@9 z{%_exg^K!(jlt(@Min~88;(GI`>P~*tm1kcx~pEuOFC|vu>*nOWj3meTG74jSRFIp zDOBfP^Qz!Qb$7?1UP}S8@dI295eB9I&)Z9rg{ViU+Va)$cC#w!H+xc%h3zFjM!1H~ z=J@P>n0%k1YjNw!;TbZ*DlLYc4}`nO18>VX0v&;_slo3~_Fw8MH{fd34zB9F=S=xY zhC}$imb&ixOF47M=`P@G1^5p}_z@^esMLI7!bTagBL-n;i0g~{&c5sYO$CyWMZ!u2)*ArAj^0g zx8Dnc|G2VH)zmjW*mmF$#l7Y)-KG`$^UFR-m$F;No52v|S0drpM^WngI3nm(YQa04 zrQwk2pPGIBreJO(^n~R*^6~uc-e2 zvG?9#O?B(OXb=z!i1bcSK$I#XAX1_tT|q!VK$=Js0qLP7fCAE+fPfIC2#65rQbP|# zKx*hEfOJSGA&?Ny{MO$4-n+iF_qpdeYwdgYe$M(MJWu8m#+c)sW4`tG{)VnhaI@Sk zffFtCOY6f`v1QaG2Adi`FZJfQIzp)D7#+D~H~ezTs5!akyFs#cTjBkf#19_rQl2s2 z&J~Q=b_Yyow2t+`%Y`wS`|R1nOa24O#b_XK0REp{15I5+5MBWjeo(wO z>EfyY6;cUYj}~5plTKN}SF73j!hK74eAPyDQl|H$#!1a8TsU;giAZ~fT_JbD+XZ>~ zL%r96TfUED^>}R6c&~12DO_pF9`)+wb9+!fSfy!%(JQ& zA*~39s+WvJ7M2590&4j62a46oWRvj8Yt+&^=S9lr;<*#y3Z(wY7xKeWsNuZT+bTUq zEg^XWiN<0*7B=YR+H}Fhk+{2}9d~&{C)i5m5S5*`EHRGnwMVuM@N-+vIFshv(Q6$3 zd39Aw3M^`Qosy|nc-fqMh0H_NKkc45D(mpu1lPb@uW`}NCSrA-!Rltt?0z=|1ZU-)gdNmE-NAry`Op>tDf@j{xpt(~g+1#6X$|q#E zXGJkevI`}r_Du0XeO1}XZd}gkl4Z+pDBBmde)x-mOyfb!?q)jcgGHMoyjh3e(<yljskZ;ouJ_*>%$U^B9@SbWg@;%Gfg&E_EdP(|njxd-&A(zWW5 zxSx?Besp@;B)5;vycbgNbX&>dK4uZEGX`sKd{VPTVn3&RfBa}r1#mpPIVo%eoOKVE zA77baB=9{Semw#$BxT891I;zFx&U=H#M0&qOr?*%6_RRLd zS!`A4_4Bm{M8mQ{8--$}W+ZtqRD+`YCM)eeul!a~bs zxxTvSW%Onr-h3YUy0mKG?HpUxXE?93Nky{Y#Pl?$%Tk++pc+d~Wxu%(;~6$}Duv_U zAPSEl!FN6I;icc8?=FX6y=jvHNO?Xg#4E_elE{HqZJWG{w@fP>5dK<2@Y$6edGcs5 zFX_tD7{ADYKAvT$p%w7PwSFZ&ga3N;(|zM4-DQq4fvJc;t}EW@*xy$uESl^_WC3p} zT?YaPE0}MZgV~9UPrdP-uidF9^w_dy8j@OtXcP03*q*lQz0b@Ps|+KJLvj&}ftnO) z95|xERP;@n$*_c!oqn^aNTkI`fEe?wQcnwuKR|dFm;)?X)`Y@Pe~7BPBNVF)Pvo++7XF z;WRMTQA=&60!t1(mwTAZC4Yn%G#PDGv9kqPh-~6j!xq}sHKbm18Pl8`+g5!0{`#(3 zk3eG7wgHEaQT#{{q_#zWgPKXc$ zoykIJ{i5dnloZ4Iv&)ZMaERePF~h-y+&~F6f?{N zlH*FFFjpVj3ir4FBN5jBz1jZ$5ouUtcoPKPq6%@anjjf{$8{DLP7^cRQ)3JkwSU^` zq*W(EC){NkUa2>)c(^%n@P1rWF#%W*q)xtg?}RjghE=%9x4tLMb!ICvcc#gang(q@ ze`4wu7lzqoJJ_&3P~c2VqyOSeN4O0HK(2vGM9+nKMn1Cd;8uglVu`wJeNvmDTHWwI z;=1d_BgQ(h=&*quyM$X8q&Yby=Xv=7txfx$_)uaetvC>Z=d1cWPg8x!UcSFM*EWytf1mlx?O_2H>3h@lwA<+#ToMX?Wii1OlgK^7SiwkU^CaA-2`O^^O0|A7 zU4b7J&=@p~Yr{Icrbt5>HHpddJZ#;-d=0Wjz^Oe1J+A0SRRLAmD_8J35uSmbGJ7As;VDfb018+uA zw+PB*bN*}(J;!1ATv7{sS0bo|qzsz^gHTQylpi=rq$C0v-0#I;$2@FsHMq<%@p;m< zk*nf?>AZ!@t(eA|HgNcW&B;3o%g;$PB`7Y-)%rIG1+$zRLNUST^WXrD$?M-BhmZxg zN%MIjx|SNe^EWdKGbcn{P56FZjT|O*FuD3v36(}HD6;&`<*bfiNZ=|`k*K;T7XKD? zmdt@awJjSCXC?;dj4nm0tSg^<^(-%ihnaSPwfD6_3$QDJnmBkXnEJ&W6FDg0BJiXKNUNF65cCTHy``CRmV!@H+T5iwIyLtUhH6;V=a|rub926#aBJk!RmKgxHh7W_9&bc1ib-r5|Z8%fZ?9K!;5L2 zo64N$*kW9?CkElLdj<#-^J`TMX{n5EJgU@}n|PCC_F^v3MET+Is4Q?nC+7@rz&JiY#-tXv2ZMdy?52{ zeyZJ^gSL)K$O9x4W+W1<$5!xYddhs(yw}N>S&wFQP=_^&PbjvN%T$m4>n#DC z8VF_(_!LkBS(Kh85u)89eHpZBh)AFW4=4#w52&FMW%X4~LcrC-TV!vn4i*#iig-WaeQ)5K#p0 zFmDp6bQdqy;tz?G<*{O)o@nzdocy|rcCD5(I5V1=@M+05-XO>k0GSZ|cQyfE`Ys>P zia~n=jyGDhItQHVlLM)c>SW}1vbvxo@?~9rn{(?zzd?YfEohYq!Rav)kMTPvov@<&-gT#+Dnt17O4pffcwtsd7me&ZXdvmf`>BS^dJ zvcjf3H#rpfvpkA2#lSvWtcq?oTrOIY@;`Zc5<)(8bAZkn%p{4OQmJ_*zBv&Av8z<@ z;U9X?p?BiRc4SrHbm(9Ghi=Aml_KrqX3t=Xd&Ovs_?JGI>_c#*R(9AaoNna&2H$7p zD?MWNcAR^{`lJcQhB(uK+EV^Y?S+pB&PAWkWi9{c?*yu>(GG?GU*hZkpL4O%ju_}U z-(=GMsgzhQUP$HGdx{$5an`V_OE4-s%4uR+DL&jgenJsj+Gywb*%{1pP(LMBbxpak zBX3CUGXIwzZ-%@8TmDi0G?Fm+@y~rykcc{Qu4Ka0>|@;dfB;i$)J?t=jz`V>%_cLC zP5ggsSNOWv#QM)UsDI?=Dc zgG{L1=smNg_o-Imt#*O-CSkMkB1u1PHIHJ!<((LK1ziM8ctf8!)mHb8!ix8zFO^l4 zPLx3(avK@M{*t_2E?7*3@c|)aAhf?h&PNNBE(Esmi_=j{hO|I^%ers0*Sin?eOuWF zhc0ZxdeSAFyR(!pzg%O?YxmMx^d>4=A$0bc7V^v+lq>c0BBRLDoOH|WS9Lb$$oDH0 zJ)=#>SM-Z!Ftm6&;3tSe@yi;8v~kro{`*XHM9nN;BcLK*5P`+65|XSLIJ za)pEnHJJr$zta~}f4ENb8momfBs30VZ>wkGpN&~S!dRxyGR)F}cAWj5)A1+6t~71u z)LpY@`^0ZCv|W0?NUa_r8hH66)eAxejckA~Dx1MMq175UqDfVkZwcL^T{L#^Nw`20 zhvqXfZYs`+YOV4cO}jbM6T@nh@aEJRfs5*A1O;ACHeDV8QrNsisrEF=hT#NgPsyN(|!tRdELWtF4 zV+OxLCDEE%9MJ8&%af9fO&VVS5cvFI3;ZmZ?PuvtH+tpKA8A8h57T_(_)YVSCT~3| z{E~YM@+J+tl}$4wh?}K#|KvKthgv-Dh%@TqS}vY6i_7qm4fJ$yu7Q zaO>-0nX;9Y{eX>dh)jS9!+O}w=A!1XQmu{ti!CZwe4X+GtYLjh$it~K`T)|h-^8QF ztNR%Yl~bPkHcJG0qkvXo;PrMBEoDqau!ho(m+uI0^r|srjeVZvx5e|SrCQZ>AhCr( zN?_M{)#^3mloA_GPdgRU)+;=l3k5ZfY~PV*Sxm^~6|&yF7^G#}7hu7b|I|f0acNLW z;%w~If>#?Da=i9Yz#@3FWnnJTe*`9n+s=oCDOpg9#p?ce{s4c{nPQaK(9y|$-`o23 zb~D=n16vCBUcMw$S^M4Nlyra@O^ReSz(}|cI6hm3dj0f+k+idnh7IOE{7AdfG2GPHR~d~kANqL2RS)6{27vY?M;3b**2 z$C^0F7m11UZftExVluY60$a?9O_d*Z#U|P$bmgl`Cv6A56nWM9IuXM~x8^VAUmNx! zvdDbJNS#wW<}Qug=_PBU zZ;HVhU-X}Pt%$m1TNF zpW6O>De1Z&e+@ojAwGs8h|WhZfce)g&yvo*A0V8W)T{E#l-s#>lU~l{)=?B09Wpmr z__ZLmNHi+1W}o|WQn?E2C{R9*k5UmBE*LzRi>(_y3Hy0oxvDR3s6&9}A{WmiQT01Y zQE9p-?^MK{J_;F3Lr+65g$?MD)0=BU=`Q&pR~yTBa8m6Fy_~N?*QD(K=i22OTfSGn;YIsu|8n zHXBLbN4>3!58wCu8kXOm$WY(s3=y};GWZ2*X|qXr{hZ!`m+|w}Qb+6;(dZuFeRIS`QG=g#tseTFlX z1^tq=I4p5q^(CimZuP0t)bxT;a*#Q;Lq0YXA;o1M74Sl%ED~2$u<4C;yRcE$lt0fH zc}QXXHtJ@%vdQi8F7fND9iJ%XwZLraNZvy6CL$N|`_^I-r(l$+nZtb}Cr(iRofg{| z`s4u+x0u4a8VgEuSY+!C1KASyhH?>q-8*u|q2_zUDQD+5G(vB6)$a&h zR6m!b_^ZjhlE_0cCK`7KD$oB0MO7nnTj?M1tZIFayVM#cMcXTR8g%L@RdX}4{%Ub< zY>}?gmp;GZsK+B&6Sxl4W*F9rb4Jw~gng1@y-_eFqjBonzMp9`!_Upg3%9Q$ zYhH?%c-4yq-R_iTtIE@&zn0{K<~&!Noct50qF{<2KQ?Y3DaMzzo>K&?1im==(7=Iz zuU2HKC7FojxqsHBc#`T@aDiy~C&4}=CFGB<1-TbI7k%b{Mr7wLdboolob79=_~VzR zZrB^sFL^K6Re!f0-xeM~A*c6^-{D7X*!TcT{-Cg<9&zCbtcx2REqm1)9tTqzX)v}? zOl@U{mWr@VU1$b4Km4!)c&A+v|93^}1OYS(mr`b(o zZ@iIc@x#@p)~V<|FgL_Lh;Gp>+AE$3sBezOHf7q$eyAQRL#9ja_VMI>)r`rl*1S3u z0hTh`Gj|I?R009^)^AWbnGSDxZJ*dbE;w33M#o)hel*nKqfYlQkMV)Y^iAV$Kg85U zIqEFBy>ey-!VL*PohRN~CtxQYeo?YP!|p}P@Pjf2diu8Mu=_NxwD0qUkb13NuGP7O z#}`aF-8O3QsWx^OV#nS8WN<6@QDIbWFx#C|rGus>9gmCc@t8Bu zTwL8g;gG4)phLKFJDw->>(>H(fnw^=GcEmM+uUNMadP=rcU$M&KNJ@$P|roTMndVkkR%CD{)U&_5yiTPKz_^w$4P*hL{vsm6q%I5-4ZHjz`)1Ux zP~26iTrW*7b9e6>Pjx*scwG($I1l}=jiE=2Ik={*gqZRKJ@MVX9de$3CU93g1)jHI{S_6zRali`nUZb8%@e!p=D8oZAsTb92?tXmBWMhIJ zQ=@m#4|`kxg^68{e&om!KM>9hYNyKO-wL?3wW?tFa8HJ@{n&_5yD+1pF?7IH8PGdr zY8^_UYBG1?(==sezVT>R#X9KBx{7e+Nt}v+DKQDo(SlDliZ`u~w5}at?$r0aDSGkD ztS!tmjp<`c*O3PAInrd*V|VXsS3ZphKh*I!@0b@ldDT9pAnB%&pA}V}9f)1P+OF=y z<9+?7eRBq_e}((~Q=51loEfYh2msG%#sGY!)LX~_Mguq_*LCCIG)f9JpD~AD#?w*i zR)2$z8D?M~F>4V6jR4s6y9~`F=N;<`0cwU zgbjcASoale`H8-cO`_%DWoDw5WN4k308y5rnmsq!O7HkmIcffd|uP{;X-k= zBHul=d)>5sDZLisI@iIwJ;r{QJYLCRa=C zF!EIVjY;o*)oaU7aOdYn8;W0*&!tYNp1Q#N`cF(k{HhX>O^zo zJt`4pjY6c_K!NO00gwO^JSh%T0E)}(NL+<#QyiR^IM!*QAaUu{^KZkY@6hhv*Xg9U zV=7-cr25Q$d}FH`)QpQK3WCYW1CbB{_cx%DWGn z&Kb@R1jA&$Cr!0ZK4&+MX4ZVRcPVwWO0gt1K2;}MU{>MCuntcuS%^PJbZaqVK!i02 zel}a_)}x+769+&mwfgendMJ@ zY$iVEKWudwU#g~C71=C_C)z{aAP9m`-zNAkFm1pL6u9^sbOnt|_^>zcb^&1e_~r#( zG6B#+h&`g`9a`|Bx*GpGDq;``coaS6Dxz>qY6bOd0Fy!ef zkgfX9IvFF*?SL6x2Tw%yA&4RogdZ6LL1|vJs`7y4ku)ajr zT%qL3qL5J6qi+M={ThvMMVR1EH?kC#L8r|u$ImyzXnM>LX(J^0Xt97Mj?vv}h+_=J zk8*Vb0S>qfUVE;Ckod9!uU44Y#c5S-<`QMI^=|k5VXrhYXJJ!M!c;#9t{Tnr@cW)1 zH9-o;NWKE$+^WhfJRB!JV;{*AvU`X=uJ=BUxS|Gt_Pt43!%@U3!e!uhmr-XS3&M5r zb~{m}4=03d!t!WyLSPYxNsRgeWR>nx@eSrLSc_^iZktcNdLw{vcE5W4r%LW$#QgUV zE2#&w>JJ|c{s-7|`+x5Rh#vs1=8`FoAN{3M`7EN1!puMTi9Bqkio0D;Eea@QOM{k!hV1C^jZ2&w){w^l%Y|MxyA z=I?h^u2R!=@N)p#KQ>UYkf_t)bMZxnN{K5Wt=dC_c*i{jI(44^r1$SmA{clVIuq3F@1fhl|(#FS5dGA~}U-1}>3f>~e(tJBE7mpys zU@&NvTXAC1Q;sxAGp2XFE(<*!knLizn7+2GLwnx_@gYp?_+V8}1Ve_Lc<&;%5=nQ7 zRs??{AC>`bQWxWFR+7@6^>K}a&hiaXvSUi|I2(1URqM$sR$ImNyAP>w5HeE)MQg4d zL1J(M+-uzfk`~~JAbyxEGm@DF7q*cL@QFh+d};}`c|r66CcEvGK(B)xce4-|^|Fj# zk95oV?1SURd(^wmlyh_>0kSTBE~b)k(vSdk0KoB!ZBFMbCZ@W|EOf=E``o-=_TOv3 zGwbKNK96^Nq`d`a#_f>VFlhdBx-sQdA7uAXuPgnDJ>F3wm99$^-y_cn)zV3t4b-EEn5L;}y= z4w)DrWS`Up-d5oY+|$dh4X5yfk}`C(tsFNeE571#&sI_oFW?>+aT zF4&sm+y^5B4i6Oak9mD__gAVwut0!SuM)nchjZ@qSAUI@SzsH8s|@Iqb=~&XtUOVD z{A4?3NYMQK=D8y^CjCQA7@%^bW@LAz$ntP9t4Yn~9MC@V2Kg3fOqqLzdKKV#keea# z3i3Xl4vHeo;Pkdcu#A~R_IYX>__Xiv7$Fm%|#=d$~COyRq&U%JlhrtxHj%Onni z&Eu!)Dd$AtzovFn5V$B}L=E`@>Xkw+!mS5!70gXR!?^({t5nRf)Z3jV)in-2z`jmKWwEupaQK3>Xh@SC*)=eXnc?*YR6$ zPf5D=xcC~u`W38-ye|@pdVwNdv1;E6XooQFD*zp*^`_}Y(?V(N!{%ZvXKUGigBmIt z!k%JbFQ-ji*s&aVMr!$pWivVvwwVUU_LUcsM8N zrd37BkKZ80q#lb_%9iQ3^ySQrI>^AfQ>MHxyCG!}>uDPaPtrS#W|mO68qF-S`8*lb`|Y)jx{Gi|;h63CAMpE$jl(`4j4G zpi_}rfobVIH{rZ=^!+H=Ud@%kyUk1Uo>o~DiIWl)39`v(J`ULlnDw|#6rmA>AH?&Y6je``xfl0*U>n{Naz{A4Q{y@g7o2U<{R!l#_1KB!dlY8I z=vmQh=WdFVZOG*IGHN0qJ<>>U&>IN8P=@CI9gP`^PuNc~rGVAL;Q;FrB+ zSU3)+2ZH~s_zIr`eoXd=CqhMnA*-fikey;UMZt0kU{aV{SUEX&EJZmFBtC2!w}ek-%i>{t`_k?TkOBAGs~8846JkU z9lWhY3CNP(>o5Ba3If7ld=Fvn&jSGK|MNYMyo9`>Or_bjqZa0~0YCeb!xP{%BOs_F zE`$FhfyNpN8>(&Km~G#R%mFMP&kFyWTRs3545?lo$4mXSxHSH>exwV)ujGc?ql5)< z01uJ?NLUSwE1~eie*0)QpVoai2quFTQ%`%W?es&FirSX8)d4yMN68?KX@I2W&syeBT8%AV@_erD z3wQqC? z38#E|d+M6QL#Ka`>P1MS>c7_ zu!WNvNp$4j8Y;-&n4SQ)zt!D;V=mU^z~A96fT_0nlcDHJfCf0v{9 zPx1ZN6rbQQ(LE6)vevTlQo94sFIf}u1Y0ZmT1Joy)Wu|q*CYEl2VtQOFEfa22eYmB+c;~w~vc>nRcwG zplO6VM4b{bm3Y4GFoh)^)5#}$+sQ`}{5`#vfPy{^cZ7#jsFdI`+nLvWq^l3BD}}k5 zm(s=Ur0APoJNfRPYIxvAGy1upF{pSsr>IHnjcYVSYG|w=wLn=sQ9@LprobD zJ^c2X-=%N5m_~a0lKP4V>+=NAfY7knYJyy%034yHRD{#7LWU$dNo7lfZ_F&>{Mi{yy2m=PdPj! zMKm?OAz+Iw_9HahL2 za$JGv9fb0|Kb$eq4bv)al^}=oi>VKMT>T1Rgl4uiNem~O;F=1YicJ+JD<*y9 zT6D{1nqSTJv9^Swa_3h9P@2j+mGFUn(YNL&i;hO%uz6T~6qwNYy#jw4k>hN2q3VRs zTambV3GwL4G)H2qgEKl*-Q%(JF=p~NXeEl6N$3O+5U8*j6!yz&g_Te72gm{?Cp>Uw zZCjP6F_Z`Fs{Xa^*4&6(_|y8ze~g z0y*&6pZHT2cG#cv`AMH=W!b6pec69TvwM@R4tvi(zK+Ed>^Fxqx zG(NuF?G#z1S_jGPoN9Kjn^GcacV0Xzt}Fa`AbED9%;O+Xf4oPXyxNNo<28{U@RcW!X3Z;nFsW;wv4sbISDr1U=S_%ZxcWOIB17H-9F9I5)##UFnA>3u2A%F7 zZp(xl#_Ma}To!RG37X84pTjg>TW9ZilOwRK)xV%$sg^f46|Ukk9)1jF2; z34=Oeq?cd@vc6=-+zksMQ~H7r^Vja8N%jpZ9og53Hj7r1JL;okEi427Ve90TD5SGe zO+qz-khjODs)g#26iW6{OyTNcBczc5j+xiz(PR-7Ug`q!o2_pUJWxnEu;gd`#3t%$ z04um%xHOaAN9I5Is3eBZUNQLgbAQJCVf~PS{P%eM5W%OK+OZ|PN%TuzE(OC%i!)!c zvx=OK8)LY$lf4<1^IIb?WlyRlaXsFD?j`($Y1+O*NfnErhpKmbgV|n;-B!*^I+NtQ z@pdcM=}ec}jq5b?EFlA2$lG5GvWhxq)$xNb`i{jSafj{5h-`7xZL2Wy!@TvwP#Ni( zvc_<%K6k?Tm$BnpJmGq}cYu}yG}af;i4hBs1sTkySK2%KTLtgVW_iZ;UhGX7cy(QI zgv7PyVLGjl+t|MzwHzqC7=H%3+ft=R_kxhoSk70j{59mqbAmUi%Y7nPb|lq^rVIqq z5?TcLkM!J#sWq#h!5%y?6YC1p!XM5LyjgY*^6cb(>UrtXr%<;l?L437!J0j=oX|dU)qe9e=YlnOls6_u<9dlWaqaS ziZJ;$F8?=(U=`V*m*-^ii6(rOaLnTuDnIiqZXsAXPGQURs)EXsb#o`Nikh5;_zr-_ ziII4DT@1`j{L(s!eXPZPb)xjCP_BoJ`1wmlc1!Hdf^?tQhI{eg=2y^%fxdE$*4be1 z>5Ry%!0@HmFB8kVXU0_mV{Da-5hh=fT&46q)eaQR#CjT7@Tdj7c8k0FKt&^I_)(LZ zJxNX|)ZS=0N~kMl{({z{JG}eI$9)gA4PIA{hGztvSMzKV!NbEEI12d8JL;-FCpskM zn0KcN+k;!{--^$McsO@S09GnKm_z`Ypm}&`khU{@nsMJ*8ctdil8clW5!Oi<9T0S=o#GfC)$dD)Ik8 znfp)I|4-w_96BKbn2tYy9{<05{tIwp9`6GbG?>*32$>O1kJ)1Ws3nm+?`}f1i-%0BL5rY z10=66?7)w~Xv$d>sk}jKnNJ_n`?Lp8`Qgq5$k*aPhEMqzK9_O4NAM&r1mFkS>OR*7 z<)QPcv!K;Ew|>dcF>rT(PrWZd9^FNg6&nY@I7CbUP^&zdvU&m=Kv0{{n?xKa({I41 z;FBhyJ3rV_&v)_MpJ$q0)>p)=2(CSSau`gIS|?@d$6C4t9-oR|S=&(KgB~CeTATgF z2xYQ6@#Hg^S%tr@ak#(Ows__t?XY=2ySXFwobMMl>l3}6j=N}m%OfX0w?Z>jxPw6I z`S(LlK6p7!yBf&!pG$yqQ``=kyfevrlw^6U!#=nw3@Gd*va}%xXUhOKp|h4_PHAWc zZ3fqE&qrTZM8-E9bE5FN34h;27x-yhlgINoq{7RbKwq7U#4^x1^eH{ z83-%mQ*09$C-6HW{GA-9{m3{v{ z7-H3eIM;NUGUUHX%)|%ie}Ap{?$_9*-J63BmldB3^wNX3cFn7?9q3sKCk_#z#Ff{P z1GUn7ty>h%9CpL zj0~x5Z$-OP*c-R$R)rtntB&dCixj{@P(3t?4gMU=rm=uv*SJzK-`j1Pcrlsfl7f>9 z*Y_y9`EC}QC&~3(%#4HaYeyKVMJYN*ekI(=KzM_etK`dV6UyZMdA@S>8Ka*cLLuVM z!GbrtR~N5U2^UR-b@aTe`AJ|r3$1CRDBundQA$$Kv`LqJn}u}7dHr|0aRuQ9RE8fy zEQDd|P`Zw$t0xIfVpMkqDjcH{c!qOtt_eSI}QjXMA+ z@qY?FGf}{z&O&|B+-&G@C6i|vap}Gl{WXc{Mlmn>bRQL;;=0=>Um{T1qDM&gVbd{8rQNJ>&!=)4BVpZ36Yo!VH6(B0oJ;?_6 zv-MtohAgfFflE9kORR??1@E3AU-=C}Dk7KNtz4hOp288h4a;hIE~9&yzXD*NS=Z1R zX8eBhkT5VKjI(4FCmGBB&YMwcOB@K=wU%8cQd6db>!(2Oeg0s0yZ*+O1}uPkcSS+h zBza^;C^cgFLIJLz-HH?S0t_Zz= z5)UpIYkZ1k)7QQpU9JVwQ0CTms)hvxD&k0i)F;Jstpf~tVoNVcA zkOrOw7iU5*zB+$#j(5hwj0_ocogLO5T1e=$^PZg2y}|lUbht~!9}qkNpCWi=%5s)nw;-=C1Oe8U6a!JX*qO+eYZQTO?bW;PnD8T(Z5qz*o|A@O)zv?h zn7sYCQfK*`W*>t)qq$S9+TE@E{>T(gb_Cgp>bbp&zG=|uE0owpEha`EdPa$N57QW6 z*#5X6G_)Xpr)Yrl+GvtPAD9XLJpMIBesHB~$m^|=Y|(sXz}5}ORk4s@p%Bg3pE#c2 z@zu5xcSLzjyB_D~Vk|hsibcpT@a_VARppS}VQTji!BZ>0UWExgFAf|u#F3nJ2f0Rt5xyY}idmZrtS8tU%5WZya@hnQUAefyw zxs^*xd&T42S?SZ{N`6UivfAKR3#x+V5URsU{`x>qTX;mpaK@qYh z{7&4>qLRu+elWueA^Y<)*J$p7dFg_mUAqX78;f!hteqoIfG%=k|3JIhVKX@D#?9ly zu;d@*b&1hR1Z|^N7EKQ4%GL2@M^Os>axo``z|M2GqI0TfD}l`%4m*w~-po4lIakQR z|0vq^t%nBByIyXliEu?;PXF=}ZLjt9k^lg=5plLdT`PCpEe6cw(!>^cdrZj%c*@n% zv{fP9r<{wP2x+?a&n&T{)o3u?2pYJ<8Q7&sG(LH8YTEf2^Oj@FXN*I)mtJm&zI8}6 zLF?*W&6cy=7v)yMw&AYkVpE6^q(td`WBR|b_>@dmZhYI=XEtGtvweCRSGGy!ACLULcvN&MIgvyIS@GeC zl39!qC6$WF{NqxU-#Z!-zO8m>Y%lSDYM~q7RS_V%6hIH#z*T9l8>kmIx@FHcNJ_o* zBBkGWP|e`%EiV4mqeBx$B~&my&>M1$!F&RoRLIKl;@)piXI)%Y5XlcJI@?~9f!314 z1ZWC9a6#r%mHj;OxI*_?ELW=IaZ(YNVyVgQ&!~~1W#`&MSVf*w9VN{-$C-W2+ZGO- z+jCv>tk&g3?Ya*a{S5rANm1k$6j25@uu!n2;IshYT6OZ9pW^}`M$D==heao5G<#?Q zQbxX;YNUlv-|Kmk%>XM{QDz970U(-^$ykS0Qti#cZcLyG`tdL~G>U> zkeDu(q1y6IodOkI7vX%8UxrD6x94i6j&lHy=GV;}P3utExT`;H3~urm-B}EyrXGKW zl7~A>fuKC*#IOa_DX5@YNTBy3Ks|v%X}o*yQX3!8DYV;(E_f7;nPg3l`UmwZqv}Ntr<6MA7vC+X}CJ+KC;aYs`(jyC=j`(Z2B`LB{b@45vK{&;y_pv z6)}r89~HL`t$I8>sZl+W%Eb>J|mQ%wJ+(rQpk|lD@paE@!BD;bo_b=7d#4Fm~ z?WYn-?(WwT%GT<$Cax?DgfweCj=^;A1wcNq($Svdm>hy z(~xhV{j_`CYq$6bIT;`I0!)o^a?xv>I~AxBTlnJk&D*dn$NXOxdwmj>lCkP8Q}oWSHf5{z{ALAni-#U{|U_PLyGJ}GmCNhw0x6MH)$C6x|a z!!aaH-A%VliS4`7@^;lRc8`)PlOBicVoIUCtr-q+4N^r=4Kt@yv{6XOirn_IcY+?; zH3FXNXOzzfMy=JE^dc(J9RN!&^c4CY&aLhH{aHzT&|u~8coK5IxzfK z<4NX=8ga5E&c?MiLTh%nF6J^FQcnwYG;bOSf?m;SHxpAxJW!SvD@L*o7Jd%;+Nv_` z!4T4of7bkMUd{K5_jZ=+^7Q2}laI;mo24TrmMY++d5Z??5qn>yV0+SmuKauuD$ie$q01mo!a6PbDQ%iNz?=fNT}h_IH}W zyO*J_euGA?paJe?;lNKM<=>$04)V)I2>v=yWmO-rxQVZ_s!lnuT6xBIby5_~L^2>N z0CZq#IF0tX2=3?n{3DyP8_rkQ&o5~x+3_3A7PkoYi0T=eT&l6Q-Tn>YBm;|BY2SNX=qPaUhdjOe zO=y}5sd!N@1Vu$Q#GhY)#bRCPu!nDNMmrfi$<(cKN)=PM^gq~p@35xcY;8CQf}nuX zdr(kN6qF_iBqGv8q=5){2 zr~CWX98M-cKGofr;8W?Z6P!8pQkEXt3*YSH##>jBd61#aJZ(19PN4#81&%_#Hv;xf zO5eSCDdrH5UMWkxxwrEx=ADA7yy>&*LdQGa^q4($bxb*geL7yg$?|%huUs$QVl2VP zIMmI8^OrcN;J;wmzY4q3|Lpsxhh@|L79t%11s-JqG!AFBzR zCw^g?;Uoauz_0w(asQ7X@O{dEqkj+e#NTfEBd2Uu-%dlk{Z-(vy;$ZUxvq&udH%XC znX{R~_9wM1vhy_3;R#j_Gz|bC)?90AZgzck%?qq zRUk0agit~Q3ZBYWE&MlFW$S&8zSz0_-WB$#N!)p@Bv0U4M!!OTi1Ck5y9PMNcIf(W z0`Wy?{hkQ`I}Tt2lXWhCN-P+fx-I>fj<&VN;GEo1)RVJy@M>S~GcVZ4l|InWQcov} z@2I-JPR~U{n73I6w2;ZWuMx|RXfAWULvC`}4QX;IeZmpRetWfo+9;Fh<$$QV=Z<}N91*IESrr!jUWS`dS z`9q&z*RC+ObYBga&CWkaJW48Z`(V!tiZ>`%Rw}W98hW=22}g?$ahU6tn#N&OnYO}KlY#CbvuPURYX5Kp~XaYE=L zgg44d8aD-fi8+*uE8dP^xOd;r!mHsDX3>esgW&f2^tKO`L4=3C51h_028Vq z+?Zt-c=tBTt~=7oH&)PCYq;jxx4YqkUsQ%w?*5wWP8%-ogI>kL%$ zF+A1B2@Wk#4oko;4UrybuDud^&cXFa>A9HM_D7#lGvp5tHP3;?YpJ=`!^k`H2*0c4 zl~n-^dQE+t&k~wZ(yT}>8{5K}z3WfsM`9vhF}5FV+|O2F_~hcTD*A3~7r+&P72iuXIFT&H zlcROc=*swAe+j`cECb*aPDwPg`@s*d)6SykN(C}wbFH?q?2e7QF*OR z{yg|9B~=trLM^AjA7E_>20qo=?;c*XS-lf1#C*=TA|~Yt-OQR@sni;pl?l5^eMqai zW^|?6$thC$bvj;d(sCjUSM1bs2xLx}P@K+F4kv@y^B>OGn{Rd;jo~@IbD#*f<33kA ziZ2N-d53h;>!WC+E8pcf+8;8D3-LXkJY~WxbZio0sZ=KfcrK6F^CXtd&6>2*j9xh2 zNoC@7KMTy=>yH`A^>y7SFIWxPxMv_wp{8C68wVBIUI#c_vG9DL>T#KdZcd~}Z-<$P z>sD+TXF-gz`P=S2SuG!v*fVpouTnkNeE zT+15=lPp%wJ>k2TtFzj%|8#TW#+vTJelJ0vMbO)H&(p}S9_6<%YUzlDnHBj4uh&rYc?^mcp{N!coJpeEKbbl^j^as3p1 z7X>IU(!Xgh^ZP0dah#Iz{73EcGh!G)^8SL%bK@bWW;ow18iz%Xis^1X)lJ+9RXvx1 z9B8zNc(J`uz07Jlwwk4>^hgQhD;iJMUmx`LG^>LN4b&>o+KjuV&S2Cl2w3l4UGcv4 z6{DSz(=QDS1v^GvEKWk`f+b09@boRV3nqrm7o49&RhwTE`m(r$;(U)DtQ8}KRV`o{ zQS`YJ4rVOe$7^25E3P=lJ(!Z_li5k?@hszKsy|9{Bt%aZGAXF z{n2{9_Gx-K^{OK36(J`Lbw1RO91MSw{+N$e{u7d{L`#Hvz}t56Ke#8_OIw&w$7_Z- zQhpHRy3u^dZcD{Yu32mk9yy5ot@6kLo%+9epcxKAAQ|1wa5S=In|`)t!lhO zZ`Ub(Nu&4?x6xL%w2>%~K&!r+@r%^RJ%!_gNrCp-#e0un0(i!P8O<79ft&I@NA+C% zFS7rrSMIPAJ)GiGuR1fDJy)Em!0*{U{cu?eZGmZMB9)?5Bf>N$cS01yq{!#VN)}`D zN}y6tWyK3V1lq_5?8uNFI)zY~>LR%5*5Wh>Ks5j}k9ahjTupUPUu<^k?>yNh{m?UfO-yW|+5C@M}`unpA78G|G}-*62BM z(149ZZ$XF}zqFwXdlM!9gv+rC+7WPvZ(GpU_X6h^wXZ_YcG45?o+wW>J{L3k*s*=} zUU!EBA_&KmhgO}SJV5x-PDQD79e-Az#m5hiyw!S{{;j*$$?jWm&Ka$x@0QH@ zdDHQFH-V`bsm|t4M>*Fp*Y9v|bg!!8Ct8MAXgs7;{P!^@RrSf7(sD~7Mu%+S85b^& z^IQ+`hC-E9cjq9`ymBG7*Zb5zEA5#Hv#iD3P?CwvNXZnj#2#uSKUsJl+vYGWLywH= zxH%G7q+^smu2knPa1zp;dlPE0i3qaDT9qMRCOO>jWM{iYf;aFye>#?Mk^$?~Z^0!a z#FAiYU)`H>EW?3cB5H-pY%%aBB&TebD{%&zb!8}*0Y<({NwCj+WEq4 zHU)Om8-@o!8!@oV$TS@!V*;&32cAuEFAUtBd3vQ1oNJw6A&w-Q5ysZdK)Ri>RdP|9EP0M3VSa5JqHE3NSKf{p9F zy=?E~a*!+d){8cJXTG+b0!NbNjF;22oB!H2I}Zuij0P9?jhjjE8>TXdq zXgrwj`6K=^8n@L=ky-=#9J62nd8X=kA%4Jr!gDafR+7T5F&Re+1Nh9N>VWR4oj~Z+ zcmFvly$?&FmG?u%Vm4>2+MSa=U4HttoC#Z&;Vv5gaFBuj235yhomB5H@R4jJKWL(+_KW6tF~7 zx|uf>Sy*MPdnre_!`mY~J$v0p+nMG;{>n5d)8sUQp|R-V3obixQ!bO-Ge~Ya3OS?$7h!7$thrr1vtr*PvXn%EDEpIbtU;n&`Nus&1BH^s~Q zd{I2vLhhW&XzPR1Pn5b)%7Fa*sEzuXm)7DXgWr|DVD=qbXaFsoZ?G8)$5ZknjKY+VMy?;zS?|LddcTomE^5WL@<;C=j23^#MF=I39g5T9O$7a zIA*uwhjlR-`T||zx8+WO25yP34oH+;q4^OOw-#F!NT4)pe{w5DY9gTZ)Atf~szd~3 zb9?8c4_PeLx+8lb9-Rtu)l1*`GltKmW?XEgmk`2Q^ygz5FdL^9hJHd)yb5R`*R7aH zGs~dZMlHKL4=5mXXM$pmwFhb5Ky&;$8Kk%BZ#b&zy&ty6G8L2Zj#kDi@l5E&ugRR` zdoiL^-Be+eGzszWPWPDyu|pYX%Radtie?0znGza2&Id#{d(>hd9;@ih46t{Uemqka zGjn3qTl5^{)e}#%b!$4l)kT{2Ml%`;PNQ=T^9VCELBq+fQ&lxDLd%7or$rEcn?1u| zc&8&af5{>NtNu%;L3B*{AsXMokUpUOL`o;kqUGC?06w^Ns#T z<$`~2|G8wTO#|ZIfOLr(0%So>U%U6F3q|nT$w>M>J~}fPd~t7J(H3n%@q&*`l-l{r zx4G-lr;7@gwu)KZ-F&!%d>&WaqA3?AC}m_fBET5oFty5V@byu^nXM6XN5Cj?;W_|U zxA8>x z9YVZ6T)Qooc)Q?)acFe0fnFEXT53|?lGs9!u0lP-1&AE+d@n>>7-N>ckJ=%teY%C2 zXrZ1`sx}}$UY=MKzyv;ibY$1WQSl(k?yJ=g+=a~#_Xm*+;X#vgJFuUSopd}r26eEC zNDzLuOT*dq;u_*GtAOzU1NUfBF^0ws9g$a&rKQWQW9w)pXr_$!G2L41Pkqhs{Vv)FO={_UumbJh)z{4<%<3kSG3hKaL1y zDV7;jRtjDL&MUn1!E>8!ek_W{wDH?dWc`Z+&i~1e&?a`Vb;AC!pD0NiN*xOPcHe80 z1Z|I~quszO{@D;nPLPq9ZqRy&#F~lm|224L_g;3_V(52`z(3S7{@HH9pAaYZT|5@F zkt{C2r<3mo-iI2!-RTAc2dCdPs{@|epYH$jp~U=asQ)$8|C-hREC!_eidq$*zXl*i zY8Z)q^S3YfIAmhKNiqg`ODmn+)RQQU$b=eD=9zibww+WG+*P{ zkJ2VHEU~)bpBfcD#eQ5KIG3`e?K`dx{1rK~kr)tcz5&W}!L6O-5NZ4`Evp&%-+A4C zFMpTj;|~tirENp2| z(OaT|T+3ZQhLjeK(GdTn!%}!w?S_wN_;mGC8h_E`wX>?+nE++E1x!4sDLPhD8&Yoi ze*XjAv|HCl2?;VoGn3(1H&!avPriJ;GOGbI)dT{mE}0<9|>d{fF53f8d?&Xa7HY;0k)_{3uPbSEH_k zvX&G($@iAAM7A81<6Php8kj@`;~X#}2Z@8E&>V^iHR?9D5yn~AUYkmvnfJ9s+DO_- zff?d(KaL?ok$kUC)ZO2FU@am-ReoF!e?F*Mq=*_*GIoNj&v|H0rlgMG#5X@XmaIGz z?u_VOU(qD%+ao^ChobE8oW#%`C;21JAI>yYCZ3hwu&}xu%5yxJtL;qgCx2vS5KJz{ z)U4gxV*v<~-KKr3oV{yAaB6)k-VZs1TfC6DFp7lZV$EmiN41cvx0ph=*h!K*D`F36 z=gSCBNt^XND*OBNpDGsFJPvySnvslm|_N!pVja*Iq}DbX1?M^(vhot_ddqTJ`n%y?24atI1WV%g@gXxDFMSha)q~D#Owu z>03H+vgd?7dp|<4IQ&)i@Ch!OGUW{6c{;(;GOmet&n!qa!J%R%1Q^!UnODu^3{A;` z@_a3=X}Mxa=)01Qz?Dey$p_FvCqIP<<_GaVx`PBQzI{no00=Uj;W3@4vq7C_s}9;J ztJIuBm~FjdWDij_Np;*ZeZBnX4otCT8)q2QXHHLI2wD$BazM9rPZ5Rf#g1o z7@if)xI^=lT)lPO}#M35KF5A2`aXgHICEYV7+auALS0S%X}7z0WtM6 z&;f_1N0pweMlwpuSG7kElzr81{8GB1$^Dw?(@kk{J27(4QDQ+ac4%Z06M(Uccu~pQ zD08S;m|&P^SshJqi(n{rnMGs#(mz0q0w11W-qd#gCVO~Gh8Gi+QMmE z@v(wR)284$v{+BxMJPG%$Gtr>W>BH_D;x&8>DdNhD-^Ty5fsjM*|8+GZ^O+m5Br{H zUVTg)vlLY=jwRg?dJ7SUF34of?_t8URnLxHB9=);HJ^HooE40WEI(y}*J2ml7S4Xa z-i#g8Aoh^z$=bC3+EaZfGj}3}1%Y&#rgbzfiAAwqaL~;=rooja9vRG`TV3kLJ8Nqa zF6YDG>k-;6pk)jh&X3?`LL;sOzcWh?>js4C zMRQF&U4~-dBnop}P_b2E-GLiRC%aXfRpsCqx4l2jGia zW`O=t4@a{g4^A1ZOic-68i?wy7{Ld_=!(3D98>v^PgMEXn(xf~2%tM^{tCi$rlaT_ zgd`0oose0z%)6OiGmQz4Vn1BD8=mL(e(cm|%E$9gr*xipe2j>nDrS$sl}u1LH>bm+ zCnJVUH`ZGa?A!J%+O7(XOUGC5-Y#&?8q+U*f?qfO-Z#lD>Zso#O7p|9Z_?Zgy1GfH zS_9>~?1-BEC7y#Z`OkzAS89r*ADoWTe{u%Fl+7yKXeVqx$lhZmbG>i7Mz-%}ue4az zr*ER+OW&u(DwR{-YP2kQ=A2{@ne1QRTt*zHHCXt6&mteCNS9YRuEh&j`Yj3<7i#cP zj&Py5*WkRWuDp%x{gcUS=k`_vD@l`=Iyg{C+9&E7(bjjIb&q1q9oH-RO9S6S?(yhmPuLrGzZ4EC)Kw^&CBE%Z)AxX` zRDh?Jl|Tz4@W6-Wi7kBzmkE63;SB?~l1I%yml^m7JUntpi|2M@M|sd`JD1q~=AYqa zAUppMbrvWs;(#kvpHv3aAPYL7q?15B#t*>*W4}c)!OxYYcF#mGY6~_I zE?xMsT$WFVuD2B9ND>pPjRcobWZaBFi)9$k-WJH!7hw&nza=x-B;|2&XxKAfuQTWW z`g{?j$w|lIE8Ce!%PBqdSL*>ujnPoO_Zxi{i$+)Of`p;S+=F55M?d;H=KZkW zz0bmvj%P!Cl8=+%VC)5`FGZtU#~BGt6Gu>IvZg(k;TODgImThPx^3L!!ey1*ieFXc z>z-nCXaJ7+#0Z#-C2@5HftCI*=rsw~!g9yo6{V>r+k|$O>c<^chO{{yW!QJ|o=r*M z*nQgD?t-#j+#3Yx6m(@i4aG_7xjQ4nID9-Jkb+@t#+L*uHafkxybuc7RUH)E{nVb* zqxaE}OET4mdWLlMC#3mI`dyk2v36pkjTNOwzJpQ%X&|S9h4b(tXjpEwa_Y#Csz+F2 zbY5oTxcke?wRS^4WcXix@E<*^E-pOkRW=3Rg}sw~*l$V#&~KY@JO$fWAL!xSXBdXI{e_Fe$V#5;ma>;} zF0{ki=d|o&Miq&>=8|=M1#jWDSa3f};sP;`I}C>AXIjJ86&kZFtYPW*igJmM*E6Z5 z`vlv=5*|ddt8ea8Ti$WnWnV-D4zp9+nF?3h; zcM$9ZfM5~jmvHQ$#V~vW3FZxsinhn?Aw#_3PcSVZ@RksWR5Kbz@xZgM%;T4Kra^Kp z*7AXlZ*RNsyJf?wCs&{2#SZf)FhuE?T(k-@bQrGLGus>^+doVv#!_+B=g6uK!wrkp zZ1|$#AuHW8P0#Tu@nf#SS6toM`rl5D?0ekZB{2EamrgN`AV_23CS#W3+$Ij@PfQJX z^Vs>SBv`(G)^Xg>`P2H{>+bH7h78G9cGUw|w9DzoKo8szVsr@ohY^(f>*eDv=V6%w zyh1)i9~Iq~I~ydSY1}Q8*fhom&4B;%c5>nX$*s- zD;zH|-!M2fVrg380pH!x?c{*tPzOl|A zQ&#|ZHj!8R)ZG#snA&}$%B7QZB6PWy8AO}%1& zP;SD2RF%ud^Xb|);#N9j`yJD!4Pl@ez>r4lLw;uX7Z@&@v(WEFS^7Wjj@X3j+5dm5LAIj5X z2T)$bizesWv3QFkD*AY}*Lk@{{Drbg&)QUPMv z!&cex?G2komAwb)J8hq>D(q|EB2+#poJmyha9e34{L)W8O4hUo?Ne7d?XpR&SH2Ic z+vc|0)<*F)$mPun_(_vPt;Dkn|6jfHb)j#f4B&*sJ!e(gCV;1V&mrCeI+{5J ze2$*)19A@U0HB+3sW!o%m+V5TObeCtJ;8CZuZZXOeuaplnDT@%=jh<%`S`lThJj>qCu1_ug8z1?CSAds{KYkI<<=eZ!sN+;`GE)+1Z7H1bmdpY;G<0{`iqsq z$=SYZ<>7~2G`}6(FgVOWBbd2tH{5ka=ky-tzmlxJdV{}RCjPYX6-%rjii1Q*L0R?H zcGk-Sx}-(Qc~ikc;isKnIXkp;XT4@6n8XfwE!7HA-_`D)01Z6vkY?~N6|vkk4ILQ! zN9C5v<}=-49_}2RrRJZ94?Y`glIg`9fJxYcHmnq0$7xGjbLnqD!#-vHbA{nSI$GmC ze)b(C{H($@|9$v~v@S)DpjxfZrrlYprWHch#l4j1^M`WWTN2GOyC-RRd|vi79uuzkv6-OV zV1Wo`(9x{vB&<}1E6yLe)ntt9ubdL6uR#HQ{r%UIk+{257bUAmyZ)^guj#!Pr0G|k zj4DhvN9l*FyJ^fLWCzMA0_cR!hTt&pjry9SjovramW zX~w*`28<5I78?}Tx3u@jQPq@F#XkOZGNP;SV2;}no$kJS!5kv~70u}NjNntJKYe`W zdMGzb^!PCsE#9 zirYukSrM5O7mx55k{t-HtMT)p=;J61=@Z%Xp@-+9g<`F%ppF>JWsY$N-ZqT9GpwKE z%!h^#lzmr2Jmzpui@KH7_W?VMVAZXuEyF$2l+1UHFUc? z?F*VU9{1xWV-eU1yb)q3)P$OjKB(?uHS3dI&j)I)vZ9}NJ8 zHN`5+{`w`^O5|&U>`v!bpN2JSpLbt2dqJ43>@bffM~1bV1a2E%5Fd z2>K4D-V!t07f5}%hoJd5BP?ib&%i6w#wtQ?I2B38xTUTW8am0@#*E~{mll7VJ&yqYf`n$rK1CmRB z@O;;~8#V4U-m*&mzGTR(am2L^f72y@l6q?k-7#;dMV~F{U0HF)S|7-6+F( zb4j-PVV`~XvBvinQLtHJ?)aUU#qxb&5ixI`US;jv?LGi*`j7#ctRo}c`P=XlTotdrzq+{3Q;vtK>t270Y6?g#B2DT;&DQED7<&Nt2 zzRQfm2z8pdItD0}fL3x~FYZR|1zIoQ!(i;3*bMSfR|fJ{^G#)mm6xTXAG+l;-ViNi zaz6CreCc4EvYoKQ?h|Sj>?rC6HBD95nS2G=suyQ~AOD2jNQgm+u8t=_my?!H5RjUywPhW(@dNo|X0#C%h;R;rFgPUv?x`hudKMYH`!Es~n9R2Z^dATmdqU#zJpHaGI&j zbWB_F=+C3}|M-$sbhRv8CG2#l0zxS**O4wrJxVY2dhA%#8))CF%-kA5%bse@ER7rz znl@na5evI9_PWiPAwk!4NZdB&W1XL0J%fpeC_x6Wh~Cu}P3M_*X!Xq;wO%(Y5C6XZ z{=%WC!W4;*-STy#+$4|&*nboRldaSw5QA>&|Ah24-Pmh^KY)8DVWw=68sMgXhf>fu z0bndrut#7}WIC~kbTE(P(6pzRmt`Mk;b}cKI8p!9=@I9R;K45O$892qc~pXC;vv*u zqz0+az%j4gxA_yoE71TYseJ;{cm2Icr|G~(1Ac3a9SPoC$y4Q8GV!@jLCT@+d287G zJy{hS7doZ7&naxndzeT>mqDwO4^4msio5nJf2VPyw7;!w35&IueeH0>JQR~vEwi|z z`#AgFq4KC7sPGqSGvOsvDbGE#A5aQc715Mn(3B*jO-+Fv(Ue0D)Dh^OvL;WtyV)=# zql`yZW=C(f-|R7)bG<(jXJSm(hG~pPALIm#mVpo@AO!*L?n{uCX0s=q0cnzf5cqni z3{B2Dk1UF**Qynu*x{*xFKDM9#wK$RsD-C__w9cF-e?kuMko%O9+QtGjnQ-8ZauPQ zjm;$JaS<}UR<;RwbGd>(;a`1~>Q{BoKqwwSYDS*Ivp!S6g_%%9Q0~{@h~TmJeMFI^ zCc#eGW4VDWavsLyn|yYDYWVlfm5#@t@4L^WBkk4|ic}QDW)ot-&$Jv747vc)U_RHUm;>7+o0lL@zZ?L8}<*+-t!b%3y>02W;TyAMNm|6h9CHApgAZSW1-w>`} z>24OjPHdv4tZu7RAyK*lty~+&*jLDM{-&aAHuK?B2clfV`5lV_e|an8T}nqn7p&JE zOXsF5F4_6yETgU}9pXzZ5Ft650HVJ=@JB;|$_5<{d9D4E|16!s~=rVAi!nW$y6P zrxPB}TWWHdbta|$A~r=*MuE5TBk7-EDYdMRscz$ z9^>8`JxQZNm)|$P0l+&Jxsw*YWwyHV8#?uGJza&?L#uUd0Vnj(!(_>C?qz*vY%6TP z9P;Oix#(r}F@1EP75Ayz#|g+0%~+9^r?<&hV|QG%@7+SZqd8aJgs3r`ll{Op(xPl+ zWw82oT3H?!@I0Q2HSl{0U$1)NW8a~xx$yPL@Y*zLvg&bOU)mw0na*YA)1^lyZefsJ zp5&cT&zOm_g>%ET4$65RA@K_yZzL^LTZ?-%xu=Ey4T<w6oov z9Hlj}$`(WB)r35)<-o@UpqQq*;0-X=zB9#Mf_g#f_O|wX;e2-)qPVq<&13H?pKkgj z9_5e*^x(pP5k#=kda!r{oHwS}I^B6X$@u$xBkWZ9oR^*ENzSpee2hy>W&zj33rcK7 zA@}MaUTvBXv>>Jti@N(R;3Iygg&gXrFjT}&RPC|R{lcQ1z4CPFNrhT~LvO7RrXHxi zFP!gLf^wn|xya_oGKIWi-3*KNr@i`xw{CH(5%u|ZRuKhT#vg?c-e_SY@03&EnQAfo zrbgjc`OsUBN(zItGC#_$X?KZ-`BZ8jA9*i6VCHG>lzp??=6Tg*MR01Qy40Jo=O5c& zX)|nz?g zya3$o7t}Y~R>tesBW@8ggDT(7@eqgog9DDuAHV*k???25)r!HrXv7D3L#8idanPutwSC7*S9ga^@p3BI;@E{fp>`8uv25Nw#r@L+ksoo?s zEUoqM-8q_}uWTzsm|IdY1Vj#VvwkR;os)6!BKAg=4zIh`g|&q5nRI5?3);i(70M`E zDj6%i^?a1@g?mp$6Qb_m;Arc}os@WPq<-INBTbGMVMiFbZ)olFhd`JhEZAKlQ1d2W z!X}CU@naYWfleVp;>A6Zst?^OuFyI=ep6?#V`TJ%Fmv5#b^0WeDLwthz)f%)Rq_)) z78*7|*NC2c$NW6M$mpMt(6N4XC(`373lT2H++(S#P)!$Oy1o2``{!ql(B!7Iv5ppu31c@*N#~d51x5*~4TD zeH(diE`L47$l5#3KHhK*$+SA;d>zK8mW7&BD>Otohd(%>mwB^GtuD^!jlom#GB&HB zAr7ThRY+tSp-)-C4;0aLVcBsHW#}zPOw;0fNqI4`={)b9oHM$Gc+ZV$3Prlco=mqr zDYZ{P4qR42%7Ya4wsq3ef|af)gJ6mqX!5~&ejAjZTS-uq`-lMHN=;}5wLOb_PCp^1 zmbXJfPBYEUQ1H*h zQ3q)KoEl<}N{h=*UwvHn_&&XI%MO)j1-p%#0D74SH)D;bmin+TG2h8#NeX*BXJAP&rSjk-ODWk6`P83sVM6+ zPi&HRPaDokbhm&1$f=+sxtyCEp(#a2+L@FgiDfkiA6v1e=o0cPrc2G(Y>Ir(oM2Xo zl(tyA&(v?Lv5v?>97MBG&XJ_1rly?yYlS}HiHSP)9R2JGD%o}Jb1uD|lTQS+?zf_x ztz$ILvTv?opqtGoZn8S2{sN5=4Z_&X&PE!H0)pjRTM_eahzz%DpDenh5>IJ$wtj^; zY+`84<6*=I5#5N_(y!#!6L9zfIc3ZW$gU^-7QlT0t9W;W4ah5B^nLA`k%E!NoXTEf zzyEs@BEUnIoT!KXjDrZJ9*&_9mM?;$D@4Se$6pK2v=P^v+=$P%)}Gv+sQE9@wxZLv zpnM{MAWWhgtWyK}@ShMJe{>exzYE#+9&`PKpd+@wO?P6vyQ@8Wv^}JVM3e(ah`#du z{phiG7mUQZ9~x&ZVLHHT94#CSx3k8GA>PNDelj1bw}mu4Cy47XUCcfUze35QmhXO3 z6$Yd0%1&irp;{J1biv1MHz*NytQ2wZjRmUzPbA7e5*q)0--dtmIH{TLk&u3A*n!pN7#1Ednmm_D-}5SMU+`D!Btr5@#SJXRUxrF`a+sY8taBhu z0Gy_}?{?as2%P=R&#yjO>$WIU_M8coC=zU7r=l63IqqUj2(PkF_%*m>4v zwUvqP&7JCQq6H~*2J=#H8XHtA^-AN;K%{-8DVEW6ykAt~bh+@o=bLvAt+q+EFmj>K zFI&tNP3xP^+!|Q7!+n#UK<%7oyB9gQBfiJxmqHJr>)Sa|xPkywzb$CC@~&IlB~zy5iT2h6lYl{bLSao``F3jZC)Nl94) zLb6CYm?yxmSYWj%i7CK*W;X&F`MO|2Fy@`4=y>ttF%(Wqnrf{mcyz6xKOyQ>1>XcH zwZKzxz_i9SLHCxy7c882-Sb1dgTi*ejraL2CBYMCE|yQ z(-U?KSJQU{p~|@D@28AQIdTr)%wy9p#;(0!l*vU;*Oo8$;xtqZ z|K@}Kj~Ijh+GFUuXlF?waAwMBf?1HbW0*sx)q#ks-KY3~WZuiPS_?3VF(eN?XyEuU z0@nvKvcV0#dlEUvUtgSGth^63bdVt~kOJ=X$Va@0m*aP3eTZC_ITkvHDQap`=QnDT z?UZFgjFCh3b|zcB48Lt=g)6X zxo?W30>r2(Ipz24E;>B-`U?GI$4JH6Nb`mGw?Eujf{u#vioar>t6l7oFW=G^Xw(WG z)>%1YQ(|_T{;dB#My0ijb0w1b@ubR<+z%>)L45$(P79ek{r_S#jK1Seqa}dY@8%+q z!|VevYVXm%S>OksNT<3g6+tKE);pMEK#BV^e`M ztB%OQ%phK4%b=7Os9y^*(5CpcAcOP@iPA@%LkwsPHDXwSVX$^D|Esh&gd*iS^#huR z0wsN##Q0gCx!^NU?Imxx*yV7@#q#1~37)Sd9mUz73p<~myo@@m=SZ)x6(^hx`Jb4L z1yOKE?Cw!B43Xp0PsrCUFDHaJdIY|4DgP&A<@jAN9`PB*$Eb<8*$|`|t>zx+9Mo%8 z`q$R&vlG89+qmDBZ8>0Dy;-JUCoyfZ1UIU837mQ&s;crYHl!8Q|7rQzKof!}4Byjd z^;$;k$JE0yv+<-*S|f18bW;mz9Po!GsB3nkHlTxsFIc7Ie@!GH%<}hNGZfFs8kK3@ z7bQ@pr83^^%fCf3Ui&NM$>$B!#n5MBZW@V`pWo) z8O`ymXf&-8&RXIWhCQrc5HZ0yZP{_7>UmLs?HG6SB;S6cLeGegvRZjSVcZq7j&X&vNZ!$9nqz3O@cj!0G?wIoN;p{I6c{ zbuN88>Mh2kyp;(QcqCBn=?=I;rdAzQ=cydKxca@Vh)^VL%J-6hr`({b{$`!Q?P_eI z*P8A_ppj@TiSHk_wl5-*Fm#Xfi1g0Pohg$gC-|yYS#AM2!`4oC`Of znoil0hrBihRE2>znHL!gk(QE-k zz!{C7kW0Qepsm${I|+Xb-#tK5p;bJD?s0MNmC+OkyIJH;Tz+6t!0%%4&0m58zzI^T zwA-K}0h~{BZCe&m!^;F_9(JIK^*(E3uG8ySI5UX7s* zgThUe%w!m&LxMxXo5$jXA$peXhuGaPt_SRs>|Pz=uD-ipXFoIB_Oi7I@TFx*+^3DI zZ3s~FY8-M?%Kp3I|6%XV1EK8q{_)X5DAQuiG8IzUN@O=mwxmgAU#7AX60$ZEvTq@T zG6|{Blr_TGDQPSr>lkFoHe(sXEPX%jbKmEA&V9~#&Uwyre&6qNe$VqqVa#>8u4_Ka z`~7;qUaz<1d2w~mY5Dn2>TMFWDiG+vJz4W^g?4RRmq$?t%BZ+RnNJSkX5L^Q63_Xux`0t&*nto&>T9c%z<*f(%VRvm$h{m0B zSrvfTOAZ{5Xu?JQgzz4vhK*YrSOpFR3SZK$NzaW}t(178s>OBw_BKKHw#2vc;PWBur?i+C5k%1muV=YZ!)z3P2Bw23Hn;O6RsoDil z{4hgxs>6wBYczrHCxo7^2OYMMB+a1frO-}?(37~|UPrznlz22C_S2zM{k$L*vSZ8} zy4y=LeNR!BG?yPkjt{FELiCR&w?_&WRDN9LIQhD6JwRzm+aJ~%sUc%UKSGv*ZIh99 z3%W~blXv#m;lPvJk3ouk(Mh7NmRp}228W><7a5Xdi+(0Mo_3Rd`!SN)jpP^U?zqd0icPi0E&+h+K!COpw>*E7BsjDWo#00%i<7J$2R_L`G=NwO^f!W z;-1FPFoOUIb)6Vt?Z46wYr(PmWWF$R4`a5-=#mWeu9*;D4KCtEmW!)p-uxKHm1R7Z!6{A^DEJk9E>;y!uG^0_2==_7Jc z2LvBJ)C8U6b?(UR!cHM5ct$4k4C>RSN%F)V#|e>l<4t6dd{3tcd`X%hDE`-0Hcm#PQDZ^3!f&?&Jn(>(y|;DYkR3Y`P2eRF&NpY)G)d* zQE;Q0hxFlGyrAnwhPlRPb6ZGerRb12<7>|J-tFHH4L!|Yk6S$p-hL`bMde(bhL|gQ zuwK&@^VTx+CUr7WacR3cTh=AjtkRS^M)r=AJ1=S7*|iA0VAa1;1Nwy0QQ%1DAg``k z{vey)NitglVXxeSM7tzQo)X7>Wh0N%rYf@f58>UF?9~=OUrCq=P`1sG&yX@fH&Rd-Fy&dhV zF}?FfWRhXTsds+z3!=>j zrPsR9QfJ*>T6P@v(0p}Rj0Q18iTf!s*(YfFsINz$QMj^%CTlJIl9`oq2rPFLJ4kP(%RfCK{e&xc5Zu;DzmRezR=&ikFW=qTw zhw`UyQ_CMd)UVuW-nLV~lvRgqL8o$jiNnvdL zh5%X0O*TRyP}q3ywhmh_;Wo&sSj*>=XbZX($&tQq(d~}x0wErKzyn*>UME%+qZiXL zaCoh{Mple)bsI|E1rrBKoQWc$q-Yp73J*UZ>sB^*$gaHN>!X2B^U47Cx3^GKhnyVC zDtzW}AMT|-gKfqRZ~`0z1L~Jr6f4GC(bWDX{kv6nF-4;f;%8-HPT_;(hyGqtV+luR z^<~U``AkP~r8&=F&u0Fib{~I|vH$-%lNLJ$yheo)dBR(4@gd2Hpe!!Zc#s^au!$Pl z`+$e|SCMm+kpAAp85;zW?8Vi2p=;X7VQlr#yHRG)Dsp zR?9y_veQ7-*n_%E4F$|WZ#08-5qH^jwQ+hBa1<{826Fw$K>dFKGyR3Xx&7zAc5C@9 zilTW&OI$7$H1_B!Ygdw;cTcwKTi;ihsE1pS+@_=!uXM=v-9hiGhWXwi`P2DLh;I%% zzapYEI9(I6ZCVd!ND5Zk?Q3Cpd3cF9#0ZD7DKk$>;&aG9Aq!YiC@)I1%RNZnmW^Is zS*G$N5MJ$m>zh8_>eJ+AG~;3peVQIkc{{LpB%`!USBms7wZLn66FxN8tm3h$Q8Q+y z-9W1M5HA-(za{DEPJ?8$vBCWVbw8Xg2xDqvdx~E-?moT7151R`SCDO{0prL;)KR3- z3S16OBq}0TkLZFj|J9$6wo)`W5I1ukU@NQuh)Z-`ooEXME-{nGmO+&z%XNbTJtx6X zg}!_LlW7xuGffJjP7~6 z8NG-C0Og-vAIQTa9*m$nqhQQE2;kb*Kim52F_R!lQR`pkMi*jM=QW;xzyMw?iIj=m z+$RbI3$K7HxyA49y=>F-w}XDYa@hag>;HbPf9Dtmf?_ZdSuoVIzm2a84CUV@jn-}m z@39=n3s~oO#+98Yhf-{tt)$+d%H~ZG^_p7NGj8UgSwN(xA=zYeR2A zH{S{EkWLPs6Ky#)9zB~KQh+ufQd3JznPH!zq9jy zSEB!2b^o{nI&bX~>U8#BHyG1d{2wNH)~4x9 zo;VxPm%Z77d#$p~|H{1?IXG$CNo;F1*^ zUOQD$UQtpJ-~B}_oZrYcTIuVNBga^bjc-FhS6Lnf9^&{ZAJ_Jb92MfFlhkw3$KKp* z_^oUK_*r?vE;&_Pu}n9g|Ddhl#zY@(@-!Mqj;^9-9B|oq2)Zqbh^OuN251%!u&>8u ziC2|Qx{fBR3?6%4dvWQPqTnw*75?*X5Zpf4c32dMBZ4;33~wNASdBFOaeEG#3O@k0 z?u}I-;F$#h%Ise33nF5D1_Z;Gq*|%FX|2Bqhddlx-U9#IKXO{=tBm*HFwp#b^ZQHm z%w^Lb1Zw|xiN6G0*23j~Lj2R#Iw`jazbGiO{$Nn!JxymEE9`K!=vGtC8Ks6It3xmK z$j|x9U}a@;&8}C3@W?Fdi|&2>`dN}bgyl*6v+Wy%(tZ?Zk{}B@R3~u%2*8FP?MDgu zeIYg}>g{&*vY+~>P#HeKDqmeb+Abysee6C{m;~)Yu!Hc#7;OjN+bH;Bv-TY^9VVF5 zE1#Zwto5DiKJWYldMLUsvkt$1*ri)R50WiN`J8|J@Z_Q6goV)gy zXC?Tl#$Edjjztfg!KR4JChT}uXXA&BLTxESkAQaBnTQNzSXEZRSdo!&tfW}St8b@T zx9Ls8orK7hjuUX7_gHC0aIIpH9rY@C-GmWYt7iT2m7!f4XO5x#)DHvwg&TY~kG-(1 zS&%6G{OorT4Y-z(yI4s_htVijn+ zlDmB#69p$3;Rj@id8>nl{Q!w29>!IO+eI|?ExkM>8p|0rbvWnY9XdtY^=sR*!5N4^M8cB zMHg2})8vB0r1asWP(QC%czR>e+%lfY;Y*VZ+D0`eox_hSHey)K{CtsVO{pfb8c!TT zL_OsBWM(Nop6+s8$9L%P+lH_xGYl9hxXEv|`+h>c#SsY%#d3au{aIs(*|WdZn^tf zl#`ruOjDf&3qFdzbG&&+e=azB4ckb1<5-VeKI#OcZ~|nr>$tVTNjMBQR-9q~2)B)X zpisr(M}KojpG4ip&B}L`{%myiXIia7rn9*EsHrNd`j};Agq(qFcxi;Mdtrz3J~3J{ zG80BJhi)jMcYzz2a|4DLv`xm5EvB)UZ5^B<g-ZW_(Gr_#WmpvRL2w>R1*$Rms+Ys(k2Mp z*298b-pGZ!sl3bnw=M5A@L1(sx{JYlwr*OutT6{LjwGtidh<`nyXkn*p64rXmoNX!@BLNRSyjh!S&(94{$s9<_QZv#<~QM_2e)GODI~v%rGw-O}O(DLathd zQhn0qy+Ft}3bvEb7(7#1m#)%IQ3ji}2gr!)o2P-3#S69u80jh;#%#w4&<|$^>28TS z1h0@Op@BSw4b3AmZ%Qk*$WLP`i>AKKW*J+YQyItIMB6V#_TzZbj#x<0*{_q%K6@qyRzRcvpNBTG6?L~gDn|Agr3+YH!9(3H_1xk*??07&k0 zau=D?#&zn;o$Z@>zT*zllh+T3g*R=dXC)f6I0OB7Y znuhqm1m+44s>%=TfDjkmk&@iU7Z>_N!*(V>`s;o|id!3tJSNzhq_rp!)Od{^A>TNe ztYT=AYi}Lb{ps~HueY_Ro`k?g60Q21fH%(^tgNC{5*8r>ecIoUA%?A*h4*eaof{s_ zYE{#PETzm=Ppok^+6Z;gMW31ZIcio|TEh*4rN^SsVV7;i)}%(vvh)8LPoz(udyR!eYMAtU#w2RcA5GD_yz9`Tn z1R=A@l%4;upGy#5y^~XxX4G1Hb}?nic*BSm1l~q7XwHyrEKokp73c1;#Did+T8iwg znRwtX(%qk(LS&R5Ia!e&=f7NEGG-|_RCISQHxER!;QzgjBnQR-X5E7SJlX$(dITnat8$e<4@?{ znmcU!ZB5?FvUrS!RZee|{fB8(n<0Xt1Rj*vE9>FrXLYuz{=x`K*h^LOC?WsKCFDDi z{XL7NSPrK_>*e|PB|QsnQ;3{F|Myl2{$Y_!k9gwYxT!~B=dXNjeFm1^g{97`v_AKepO8Z_OPdrxztL2ndG%bK zaPz$(|I}5df4<+Sa|y67Olc(+pOSU%RU8)87;(LXV_k(E@QZ2a&oLs6=J~v^f^IlF zOP<#gj_+B4-aLi8N|mI1A}>bo?{B8uWge;!l5b~5`6R68Af?|e@k@L#jnh@mmp)o} z7r`cmJ+MlN-dL|kmJ%9}0=I(8PCvKNU>jJwdoa-Le%(&OcJZ15 z0)R5AzDqRJrs%}mmss9-^K(YjL~(8-3psTt9x;@_Jg310j2$c@m|;6nMIa+WT|o__ zm-mr;8F#+ISC2`qdC*-aRuJpyXlp1C_sDNmq^7p2H7v*z%;DXplnc}s*Cv?9=Mt&= zpVz)FgmF`C&yum>Yw%ruFTSYj>h`(W7uS}i9X?v|^n%L%+>@V@KRs-G$Cd$M2EoUk zA}g>V8at`(=ujB{gFcnr70WiW0h9aWXC1}A5YBKu?v&3mvX?17bd&Ssjf$OU&sEt$ zMGBg%5ba{Y*M#O6(VW9c7FtLiYgO&aGu4{^v~2LKxgwmd6&;J}c^a$C?#<`qcVTVOawZiFf!ho?zXxCN7X=V^(KIN+vlAlqZa4 z^5)l>QXQJGD?w(AYP3D!L56%)+VK4FoF7bumohj)ni{{*RhnEGON6ejWsa@MB zqwSf&?8UiYh9qnlr9sAdPenDm2fs^2ADC31OtnQ+l*D0J5hVka{#FpRy4+yg_BlA< zYe>ND5$wq3m#(hkP~OMi;E4r<=a#&}a;cXGOIR3vccABhXjrFOm575acGyy{$g^C#6X-K_{|x$q#j$75CKweYu;D@0V}wW?2izG69aQMR zgy%>1`E&12?N3#_x!Kck$WCgqZM!Yx1ytN?Q<&sS>1RCAkn?lFTXxf3bDahskXtE5 zg61{R4V!&;FIz~b?GC?QlsKhbBluEny!J7fEus|0>r{afBI`VLEpRp^Z;WS0-E31D4QA?TM(xykqt#78qNPmy^=?9i6p zUBq8^+R{=XZsg5Gig`w7)RB?E9VA-hsG7^$`UW=n>V)WOCki;(P-vnZhy1%q@eG>f0Wvj?;e zDO=%{`i+TZI7tsZkYM>CY3bZo`c)!PEVf~^ZuCezuzPH3CGMCGvSJ1P)U z?s&sUrtd*zq!!#L^lNcSw~OdqnaCSUWO_|8xGGH%SoEUg1p3A$yp7Lz(_Nll^LTT388mn=ar!QKe`SN~JAPe$7j&uz+XglWEiiA*4pQjp*e?adYowexgXr8=X@5PsL zK=bmM+3`3t-ihx=arfxD#09?QD%LzAdfz}RI?siYY(}v7%pM=;`rx>j+n3v)n(Vx0 z&SGN_^aBPIaS1r-4I6Tk%N6A79y8bP61Krzu>7?~W+%~_#o-1U*S$* zU&roBKd8Lh)z?ezu-)A&b?$?DU-sNHOm404xB#IGf{B)k>LzU0kPQ;=q;rz`oBL3Q z`c@Non|=H}oRWF;j+9h~4PWdkl-ZGVf*wDB7ut@@1?@%_BuS^o9Yce}NfUKUnUY>L z!#qDEf@YKPO8#^!#lY`Iriiyw(RUo1vzphsf1$K4lf9nC=TfnLFon<<+0=ify4zo+ zwrEG-@Z@~7;w3_^?4!*)^vyZfoK|fv#Tu1ZSdu-`*Vx@D4!t&fC*iSM$_J0Dkrh))t^}}z7=98u^4g%aZMP}Q-xpHM}ju?Nxz&! z?xP=fb}x9ZmeGOv3?DE$?jZ4ugB_bzyM;E&;p`F7DzTfN0~FRnmln-F%GV0KH_)@j zql-JZDQ(azqH!!58xk$@OF;TPKkISl=vOtP3Bk6M;v;+}r?%C`HnhFN2k~e;V#)la zovcYMZ03xw$X-U~!V7Xjv<%tJkwh;=RwB4}@hcUiLHI^)Bfw*Ti>?H845o zq_hRqJgQ_<7VvN{TQH$rCg1yBwwRXdvXbuZ{Y}(dt@RWvwSQq}4@3A|WYhIWCO0LA zG&q@Uuo7IIanq9l(ZjPp_Mp{OYSYNTd8+g;;jWH#& z#jI(@C3D)C*B?k&tVnYZqZ@ziWRoP%F*)#KH7C&x$7!c$4^Z2i_^xpJDM${PXZQ3H zz9Wwg9ry7$?7odB$}5C(6*&Ii4*~$~nF0?&zV14Xbj4!FZ-r{Z=3P|*HF0W^V?`mZ60j2=i5u?WT zS7+ndI=%l^*WbVSd()4waywH3eTo?SV<5A}OtHGm@=WjBsw@c_-N zIegVSWg%sq--D>zC9($@2e?p{0^q;@r}k62XE7IC-|q}kq}kKmGaFDaL|E;CluRU< z+pOxOeQw3O|zoHKIs4^#>DT*BWc2`t5kfh>J4FBgfLP zQX`kRdUuboU_*XF?2!=%`M_!%R`n8hac zk$8c2p~MQ9L6^4w+T4Z05q`z!m0Zzrnl8uh_}GLl);(Iz)v|=(f}y^w+JwFgCNOeNv|x;9_$R?587!8oxC5nzFXb2UBnz@zacoD zs+GBpduXm3MeN4+5Q>88{+CUwnH?JNpO7#wa)M^>bXxn{noOD;HMtChzkANzc2+1; z41^K=p+--$lad=pk7k?|pDnjE zSiGa%i(Sl>p0UEFC+P6Z`)s6GxIY<&X${A|c@q+Stgr=4#($btQFsGX(l`WSB3n=KG#qY)M$zdh>+aKBP<~!Y**ncbW+)U$$S#-fq$R0PE8W8Rh_?Rp< zpgOLO5}B>?p}c!JIIChO?dcyVf47g6Pe?M?yLPti`{S{|tTIqaA$3; z$LD^0PrPv>ciI+j_Bx*aa!cwQUe3ru&v?XuY6}*qX|F)#@;KOyyBG<<0KmgMWR_grK=k5% zcTJ$=|GTROqN6`M2gq&lmY&_x)3Dwm+v|Gr= z;{I{g$chsu53XF)uzD=~Sxz`Ni|Q>BQd>nrwqV0;)Cc$?)4mSfJ5apw_!6d|dGugF;RW(YUm_6`r4<*hpmQAGd ze$RpUbj|#}nxLaMqTD}v38lPUt#EIxU=9blXmH`_%YQ`C$g-4hs@rS2dwo&-X4V&Sfn5Sf%_JlLE&=)9 z5}5z9elIzR9&%*r850-}3el^lkyfT{K+e(+!aM+{8A-yh1o_Uc3Cs?rI>`U>8wgNp zVAH`(3m4wYDhQVH$~&?4cOj3W(z1owv7kyBo=F91rq+2hmECvCf_{bXJXL|L)s$ge zTait@v%K6eYf!ItBt>R;B$yZb!D}racLRn&tRV#;Y-}_ z{`r(%&eRoUC6)K$$G7lVV0qQEBb@;yM=gqn$&SF07OVZyuZj ze39QRgZ*{m%fsRpZ+s*i@OPg2w;UJSLYW&afkI|g5ny-sO>y)DUAjWW{0bNWK}hP( zK)~Z(+W=4TPnSNb13Ce|D*gk#{s~R?!T-9tCg%73^H=P94*AQN0$mDNU3Ddz|G4BA zQANjLA+@5j#V(_}dW+Uvosgd%HJRH;sD&jda?I#Wx*H{S<94b!k}AfbjqlyugIu#m zocE2Ef{r(*OtO1gfIe-zgC)I|* z8Zhji@L0cS^@{M_rKuD-;Y^54Pc;hjFGo$aqqVI?tA#f zZ243|?i}`Hlg^!M$LXh-Zye9bj;8@%8_Ca#{}r~~|L4d4&dlL|Lf@r-?QZ4&jO0Ui zLi_NSUBY@x-5J|K9b}9O;yHFi^CMDCZsvToy{@(-)SNF$yC$X zFCS<-U28@A)}VV`YSp7HJ1+fj{Sd)y_sB3G{(zxwt|_DebA3_`2%e^3bRHP<0=B%t z!AwOy2a##}`BlU#WiK=OP=|ne!D=#7m z{J&LLQEev{_*zxaanI9NKP1TMv1W8_bXGk|RVO&B`nG&#sjojYHo>z#5|rhpq97S~ z0iomD8JokY2cn1Njz98lf2$1t<6nifMKo8xE=Oso2JuJhL?Z;9F3dEW2~yAQRta74 z5uW=h?e4bZ_PnMv(E*^aM-sWddwZtXi-zn{X2oSLxH7d&H$aH}3MW0;zp6O48{m5E z#LsKYws+IaZ{mT20pnE5Nx|_ z6k++^K~QLUk%5L&CQohr6|?>7KbY+|J_cQW^8cBxOAlO&aO?2tpLGYrP(EJ`{_^A`TVqR)_Al-wqVS}&$VV$ zt9a`syWZT{Trb?4cU@Fx-RKbZ4V{MsB{~MHRhB;GmCS4-X)jP|7ikgX)J@t zhKsqOOHy^IZobsDBc*VeARdyzxNpK;!)H!jG5RVt*61A2XQh6!g#`aL>^g_tiE7%k zFK@@dToHF0Q%icTHS^xv-Mwud8gvAsg#;npCJvg%GuQdasnOi!4xaD0TXv(L7BT-m zedpeUh5+%r(BM#&7qoEL!o}}-qTk-}4AWp=leKwfT27qkGEuh59NywfZ+s1c{fQkG zJ@+q=sN1G6OLELAkrqL!6BrpQ|IE?7j;3a+6d_o3!eLMyLV1!vD@JAxh--dv zz8b^+nWrU+CG#hw2LF{73nz5~3y^86t!zeyZQ7L1Ey>gdYCUxS_jP7WbafAteH~1h z?cm}mJCTfI@inrbB{7i30d^yNZkhHIqTOucyj7|I7Zf~>rfrvHKGH>+BAD8;n?L*k zw(kcwb3X1YIf*~_3rpb-J3+tQdB=xg#ygVyAY7LadAuLq`e*r)Eyqn_NSSq;5pfF7 z1>E@D%4+8oI(mLWUPs+i6fql1x!m!szX4X9&}i*Cj*VY~4vLN|DJoU_%Xb~2m)N{v z%Xoc9t>E&u^K2}2^&-}H(EAiXANp$Qoc$P-1 zWuCC}aa{{fiwGU`nW}zzxW|9s!HirMz=68aD;z*3I;Zc$C(o0n86mgOtLIF6$$X?) z`WGRQ^8ZK@pGcswjDkYe3#<+HFqHu~^aiak%61UYbs1Xo zdyKdCa-cck`^9le2$&5saX_bN`YX2 z_wxlHIkFed{`JH7FLmAd{7csz)krWqHMb%iRKTAzx|Wmwl8q!R16|#|ITNVl@k_&8 z{J%@ea@Ytj0st^C1I;JuCw>d1cC!58TGP29rAEwq$F_Dm384(gmN2Dvt^;g!XD6`e zhWLRk1Ff!E0uE@QHQ65qcK45C==%+tRHjNM;0Xo=NQAdouY5u40X;LpsHv|HlCD2t zz5SX$K3n%0b`ambl6(Ibsf(^w=tb}sz{%jUU*b=Lbth*izyG(fl6)i$d*PR*NNI`6 zkX+#$@2B$^j8!yvL=JAD4L>2Aei)+~(#U+3&q&iLi)KzM&1Sph2Wcz=Ec_-XK17I~ zI1A4&Yjq)T)xuoYmt8WZ!{yy{maRPAf9P45P6;8&E$e)~tzt*kgrzhxIggW+R!NBH zmDOSZ9%V4@_F%7G=~?jMPf3)?j`ud9)!SXJ6Y|XR$2P&KQfwi>nZ_dm2bCaw347tZ zA5lmU!`^V*Q=nJip38dbNGfFcG_uSFY;uXVdaZP-C3+?=mvxQX=;98g7B2Wf`lEjI z*jw~A`8bDlgV1`WbftmvWW`E`ppwDk$FEcmPTvX9(Y!7wtf{^2HEbqbdR|(Du zQg?Z~h9uwi5+QHnuASN*o527R21eYRQGWcuXtxbj#*ysUb zbOL;o`4-CRJO5(MgJ)THp#;pa6HCkn6Zob8wrFlL;on1#*P_oOOVa3x2o4}BDa355 zTmWQB_&_^TFFy=D*N0#TiwD}@1M!{Fs&1(1#0_n3lNRvbWtKndFZ~xG;N$Vnryp2hUSNv?(y!gPO(WrZZtx9m_}r^{+4Tpgx7}B| zO+S{@fV1m?Iq~AdeN)hF)}y7eTKTyyDXl@SG-D|;hcn=MyZ)X>`A(5Lr$1N1j|tzk zo0z(aGzv1Oraz~Plg?yMsM{69`0N`TT4Z_Sp4%49Gq)Zop2_CIdTZ}4Y#7dNDLeq* z3>Eyf4*htfZP4Q}POASI@rALni1k|$E3IdqEoyHizqZfnobr3!K4R%#!qMaQ+H-g_ zhGIvRV5`Tm=!#??#O!kwl<_f#?8x4}ez$IAxdE!ABx4pDYdgyU(jz>`;ow)QH`nq^ z+;b}&x)M$l13agg|F5mX|6N}HpIVjvm+tIz_SX&e*UjtSSDOEG-kV!PLiEXHd=x$>h5*_09N17k=emFDvt7i$`g_*f3B zz&0A5+Z=3A-)?1EnSOXjQElg!`m;(HrH|Okm8>#4!OxYcV<^eQfi-&dX8&raO^eU{ zyl_v7wZ|s^jn@}^r@$1cKK<4~yJ=xYq+tO5z;=6T6ArN5xs?zx>$TSdRg=e4D?-kTVWR_#JoluT@CnI8NGBmGwc zER9mr2vj$k|2mbO1aHRioyp5d&Piz5fpf~N{@lM3p8Q2IW;AU827nd@G&oj$1Cg#+}&3}Kj28QLqzi_f=V7=>v@m;t|~40 zo<~EfBKH><3Wd2V@R{rsrjK>i?HbyrbN%%9M-1E#4UhIR@!N1#S-1ymXlYEf`4t^a zHQqBCJXPpr)$szKKbge(wYI|F%_vhzFy~fQXi?xB3;?Zekl-jy7Zq#bwTfAC!16v8LxzMDmp`@zk-%+gWwL60jV1)O=sedcX-`JhinZMHzo z1G!iG&K^9Lt|k03R*Wo5 zk0%f8*beC7PS={MLU=ZhFKXoUEYE^I^j<`u0D!e1!%)X7NWKgHq)+#R^y{nNmS8T` zT>GL%boE{k{)8^$jy&~gI-8M7f+f%e$?%2@biCTm0?RoSkym_~Zoan$bOahDceCnh zEmz5br_IkgUbz%QV67FVdz0)5!5ZSTr(CM+KVhUJw@r0h1(gi7hjd+t$l=QQe(TjC zrX=cP6(J6NQ+7zvi1A3x9xcB9AP9Nq-E5EIN6z8lqYE0F;vWZB!gx!LJP|m_?s42X zn6}2eeGd&hSkW%%q5g^dIz-gqdYC*cwBlewxVPTIBy#Vl^jKL{yxA3GrN;n-7T7yYrV?fTcX!Em`VOws}jUtl;cJR5$#(!}HsM9hw9g@{c(f9R^JyWT>^G59Vvpa_*9N?(RmeYwd0P=+==DmbP!nkl_`8eKM zLBCA`k+2XoCQAGXQFy5Ta&TbS%z9AwcmrNKw{T8PnTF>)%)xGammgkkaW^M_?%=&Q z*xX@lf7^SzeR=y&o&-YI6fNB&D)hqmT)Bt0&$f;AH^WGv9a|`9m;8!$(hql~S6cL* zWqtVpYUqWUx&xLqNgK&8-9Ly2TU%?)s#*#dizb8VU`1^-B|FZ?WLy4NQClD~3@&$# z`Eyy$cUE=mcYO1$?|L*;`?3m)ChR#3TTz6Pr2>8ZY1-8p4aq)vRp`LdWlKxWj|k4~=cO1x<5|OqxWKt; zMGPifG5bH>+_F|A+<0pAa3IFQ_GFV1aFH z9=K>Yc>)>V$jmB5GK627F3PCSM0Y}4@Db>(2QZk~oTbtkr0^PruZlKz35Y8z`dm&K zd~`=^clSV61M@MP#ZX3%?S7n(V?*p%&=)G16PPr9JMxJH% zqAU6v-~$gn5?l9-;|_A~uHt#{Ddd~dPK(V6u5w~<+hy$W9m2tSE_4**U9}tebRCie zAl!qlNVcZd7QTJX84l?bCygGjsUH?Q^Io0Q4NWg^3n~dM9h(S7K107F&<_Oak)%55 zR*c*vI1hE1f~a_r89=yI+LQlqBitbTPQ&7gr})ztorI(h-`Jgxvf;t@vlCD(LV{fe z)i4K2Wkbu+qz4T}N>7|D3OfaD^dAk!gvq>owwS75*1~>>OL8@kqRuFx^Uy5(0%-HR z`<*mSbao%@_4c=0d8B*%uw%vJ6B}<+cL=?%QrvygICH-9Bt%#P1BzBz2*BnZLo`6c zEGRYO2@xosp4B~9n~K>Ll;=D1pIl3Y$Xw9LjB-nSE#u$f96Sf_t94-Hp3*B!i7S4#w4 zW5Pu2&TyRNFD(wsk&|UL@frExT?v_=hr2Hgtxv2j6PS1;=i$;$-(oHA)B{Kvuec(# zH)&86`@H4-;;~-18mz;4zqEm1!i%Xt!sLroGZ= zRHYY%tp}5b+Q|f|e2F1`{@sKjC#90{goQMJW;56ImD#|Xp+L?7-&+|Sk0$;ssw2EU3?!hQ8H9xm?vVL4$MY1CFE`ae-SNtl_d?|9(cI%Qud60k< z0CPZ_@l>gGdU68TJSlN8g)}?fs-VWE}bceC+k8 zG}$A@js%^LBQYnME3~ted^l;AnXlZ-p9n~=&Rt2~MQ(Gp5`twY)bq51?L!YG=0}+D zZN=|mf~a%Pn~Rt6p4SK8njTRu;~W=zU=_BrI!5xQ%&tlMcAn2pu4|?gFUAv;Frc79 zN=c?6Qsb_;<6H#=)fXx&Z;F z^{E=?UbGf&V~z=kQoKFq@D>{$lvj)twe2(`>bB{|+Cvo~?M)_Kr=2pE8}{^q`Q>-~ zMtGp3ngQ2s-One9=4LPh=YXutqS?NxmN=h1YhkO$Jzag==fqBH9owBC`0B)`PiJ@R z-=(}{T9p{Ox`d3ukqi(qS*O4RkEFZN4$<{ez!qDdWIY1(v8lWb-P7~^l-HNoV-1fO z>}?gyb$`5_5;@He+!t4vs7EXtG};YRAN(NN5zp;}f>G^BS?eu*DybOC$1=P4AC`Xk zD|WGi!ET)6*Njc2KFf(+W@D|jpn_O`ry{ju91&;3K{c2lgr$xOXq@Q1B~MXA_@jENIWRn%QlZ5CP5c4r0JI0{Tx0;(1t2Q zN`{E6vi8@5Z=QFdmZ;3zT&h`LSvE&#mr&mbyKweJhsDS#LoTQz)d`>9lGcJvYTw&j z(?6zp$#XeWjmrih&DKrClNn z2f@iE57ne6Xo9})0Vg-<%chc^xy=Y>I&MNjc6a(=)b+*fDUAI~(aYANU~LxOKJJiB zPS7U3!PrkooA8FLn1l&9q#y;qjEtK34l1_o1@rKLh}Yb;KP!O#>#IXhKIr;$xJe|* zkpWt{%)Bq?fRAA?%a_#S-oU7Po3;JO!F0<2R0pfI7fi zIbZ{J-e;{8Aju#&d6T~bH@a`LQQtrxdGyOFNHGs_*u^L2sKxSJ+us}yG5RP*flbGk zZc?=_qT*?j zl-qa9H4J=2;bMm-4n4Fg;o8;OWt%{L^8|I|v`ZK~9NzmGs2c+;-#LMbyJ5pW&L7#T zIsD)G_b2wo1?Cp(^!sbD%~g=fYPxh|nj*R|Y+&V5z)iG|Lm56@0JRaUVw?qFF7;>y z-9P9o_+YEx%urwCONGrFD@$9wBliAx0W$x>b+G)4_wxID0jIz9J}c8E%!Y&w&}P1s z0d=k1WmDHbd&%T0O5w-xTli^wBXU{J8M(#)AxaJ}F83hQqgnxI1&*cw;J*(bOs8Bo z&th}O-DUxIK`WV!5(4^yrKtYX#&9ebkfdDhW!# z1(#wYc|F}Rjq6B=p%#TWNNH)mXzT?cDvC%g-YUn`9nP>H>H?27>ix(qTF zwyH)2sUzz;h8~bWwZibjX8>%$+_MCyuKAY<`C<{@t}>0+g_zwY!<(jK)6unZLHg88 z;u0HFkeZ&2tJd(=l(*l}RR8L)38Op)HfS!?CzL`P(Sdqts3|*J`{xGmnD@>C!1UM3(|_=F8J0j; zK40w#R&G@SgS&UG_jfF?oIP~2&1~Q)HV&^}+K{wi2fkkk`e2cNS+L26oz59sr>9_d zfVxg=E?CyD0UlU?O%tX$BD*zYV2khdIj8hDjP}1-UqI6-SvpU#Ya7mvER5Z(tVZPJ zwJI^b8AQO4qbE#fdxN@Y*Ms;gsT(v^Y9p~W_4Qy)@9R-#)%P8Yn4+fR?@6`JTKjA} zmE~Dv=Y3pXm@_{SI1YE8E0iWmA2sEyTbZiRmw;bAt#NOKps<>P0u!TN2JPY|f?$`O zuON#|&|u9P2P-RMwBl*&P~Th2rAg-F7hz?V7rRmO#8|tXun)ITpL|;b46bur6tV?{ zviK485`!TH5@Nv`M0DG!2%4Opnxe;Ea$4-;xJ~i6?uOJT#$5Z;q(~4k?!IwQtNz4m zEnc=!y6-dws|*avsK>Wij-m#UC2Qfe+%s1Ua;2D#C$1RYFqu9?PLPthS3pUt8x{LM z?7ev))b0K^KC*{o&yrCTk)W!&e4pq3Bcp44K6B0Wxt90xdcEFBEl6fyphh3< zS(bmT@J*)kvJ1;|wH@uMuXKq~OIdc@d7YhO@Bt5u0eCPvWkndv8_hP(a(9yDrLcLxNPV=IJGW~bR zwE;;<-V*d7<8?~M4A^J+4zzA!9%0>#w&YP!D57j9fVCb8w2HmWpk9bLh8%uMZ5`#N zut&`BZw^1AnS|r@Ww%aY_o26=T%g;g8{6WDXQ*G=F#9H--b}|`Kz(28Kt|b7%U{r} zjV?LIk*<$Ev;a4i1rNFVn9CH3B$m**mpQ0a&u9{qn#k zBfF8l;MXjYT|KL|q`!v@Y7dD5Guy^i=gylP`ZTr%PDm>xBLwTspn6Yj=dRu@8m&Vj ztQm~fJ7$98?tsg|UhU!k#<`Z2a5@2FGn*);@<_mSUGa`Z+flE#3tWZKrG2zs%9m6^ zXlaX{uV(Ry0PqUQQs9*;wXNy)J)LAzO@0Y z91sm5WCp=t6s%ayL!uffg9zEe4j4;0z~|HFIb@Bt9n1UEQS~y?>#ZmU6bme4zY#3! zZCha3>!%2V=cOv>BUh)^qP>~}F$B@NK}6GN1XYyeoqx^3CrQ7$d)m{cL*U!FuB|9| z_5E;!Ce1pg5&czmGQV>%f?(B*datuYEAsj6J5R5~#)}m&oBVf~CJw{hFi1&l*kPZS z{GNd9E2i*V#x#xrV8l{FHF=1MZT z;$(I{tmmT$jf#!NXO5@jhKu(-o=);iBk=kbGNVK#e8cceyP=Lb@7Vfk%wqOrMut5K zr?3jtK+(jjle_K8vg)N^?E|Dh{GufR6m{ku-IjI%Bz+d()`(4xV=3V)z~W1DA@Vg~ zSC2bGH^yB-`l>HTF&6;jj%kTk%$+~=)NTeudj3IZ0!WbU)i|}|K>b8o@qINpM=9h% zj`A_gvZbO8@DcLKtFc2p!Nnh5**3g{mr#dlJZ+zrq8nfOw#$zucelAJ3v27T6r`g_HR02&%n>_y6Vi3_|2D3=FSse8@voj52{?Madpit~K^VA0A*;sVks>=);BVg&EtIY_3Ktu}B+*gTtXd`pr%(X@2RWEc=+Hp91GwE>i(Z;5E1Coct+}8-yQg#Q`ER|x7xua z0yF_L3|~M*U`yl3*=s~3EQQJk@{W&zzx@(|97iRrgMx3J0BMx9(ENKa@1MTxKk;P^ z5_KnHUZy3BYFMPj@?5#2C;lA5m9FnkGd;=&J32ec9Ke$6({6V7?4B(zuc3l|Gk3J) zk>!(Tj^FlrQ;6dMBF1U>b_-JSq~Td&6e*gmH_lshuJ$ImXk>;>>2kvNp=dGv58*-% z?K~}{8S_5)E!jBU3}$?9H*Rc+epv9)PUgS?mWPckYHhKi_c@-rw(3Dqr}!vldtE08+hE;SV`mf5agJf1_+9M7q?D zgR%DoKyw}1zAU~fKCbO0|1ivBIVN0q%xtYD&pEa7=xg81dE>`!>pPLsj?o(y_E%%! zdrly_uOm-ThlGLIcVB0MoFP&Y=b9Sj+DFknfGE*o&Qi1N1EFsYE-Yz}RM*bz|Ey zoqjSg6MHhxxcAAEdH<+mV)1|#LHmb>?f*I-6;%cmhzO0NocIe<{?6Y@7|3D&Qo`Wg zE{>9(agC@x3raPg`T=nnC5emQN5U5_2N;q(a&tlh0;cpmU@fNw9<{~9DaCEZ8_2;? z2d?^6s@g|oh0G(i}xtWI97IhYSdk0)%PJF3P5-cJ&CBYCcYdK zhPS@7gEM)uha>Q2?lEJtwX*%G^?p|tzE>T6ku&$exZDn>v*z}dqu#VtgyJ%{GLTAT z4#pRa^}TkPjEhVS#Zje7neQVj_q%fwv(nK%Mk8^0Xv>`g=$&TZG`Nmpxqm5(lU zw-@4cQ+t2Hh`Ww$3ib26D@-Lo%ZP2Z zpWmvAS%LeS&rl53zMI?9aPj^5tkHaA3=(KD6rzGq*PcmTfkAsQ3KW!$IoIVcZeQ$8 z_3t!`hJ0gT%4+94BIq4iKpP2RtDs#n-FSbdMR006^ zmm6IsmAR!{^73!CBQ=7o>^{nW{<;c@!+bk{IRoScz%mYbP9#x4&>;*~_5<>P>aw{f z%9M7Eop_z{6z+zNK=Z73as{}OaIO;wX3J);vh;I)882Sf3>mSAIq-QE9KWjUr7Lto z)cK+u4xWRiVn0P43-ZEQlKP3ol&D&M>X*uMW&-V}!zPwsvQkC_`nOm0Ox03WWey+F zY7&f;e3_gj_Q<{>G%y*EBv_qLbl9;sAlYqjwh_9wq*cv+JkPLUP^_k~x-^OhE}5-@ zP4-~I!K}sYl&A0pm7R@fk`xNJ;DyJ$T&Cex*q$8?o4zexugYEzF$9 zPFIw!e}%7LPNy$9h$K$bpafHeeu3{XYkjLDn8oHqw`_kT_!?W_L>il~bI5)VpY1L@ zsWdrt=~69`;*|L;h=3iWZ9s65@8XjX__BH|r_Q)6pDm85XT#ZBQuER^-z$}3anQ8= z*G3+Eta?w6G)8~zq3*qpn#K+QK?Wm$AziJ--j>L$L&2#qFzW8qQ7HG4>v5zQ*$lrK zxwI(e?0WT!=QrD>LkV@J*EpTCkBLBZmu!aNh3;hT)sX{BOH`PJj*xC)CMI&Dfai)G zSfrfGLHBre9%}K@t{RP@7r_IhXTzhK0JoX+Z~~5FF*IuwK)#^=^xCen_T_8!?{6J9 z>l8-W}N>qA3Jcg-^VwPTv1?7e&Rj|wpyP}g?pf{#ao^jt1{ z9r2a|q=0fjq<#z0fgCeFUx&PbY#%McEVbh&C!V1rk;(yfr39TY>80hwNxisB*xr$8 zy-X=68EIK3%F$NXD8&_Yh4locM@8ZlgEscLQ-)-hY_;NqzF?ry`QGRLF72whO$A1* zp)R6Xw?CYjLqzXF2_BDfAq9Q95s|1uRO}7>`u7p7Zkd&%#Tj%C<&E@H_RUS_2;Z$G z1T{uQ`ytrZ`BIN$E$D>J{HERR)%sGHGedGd*K;aA;-4a|s<9|OaQua^p-`;Z?{1&$4< z0XK&UE9M-6V)U!9{HcD~gsc0tCpnM2tmHN40g3t)U#8X(?s(+nw#PaEt<7w4U#4A6 znv7WN2YuQ{h--%L2Q_$7Tk=(P@cBza`Y)YVZ<-DI4_XOd;*A0&g_Bb+i_cVhiR#T-3>B z#ga^`2uf+CZ5}}V!rkgPy=zRuRj~go@jM4GasQZ|vOS1el|c1h4neFiQS7r{W@D1p zRJ-?*6hQ*|i^q#O42mBUQFf_w&CIXq**?n?ic(M_~?*qWPoQ&w%h>BiUZl~2?cr9Y>|f8&M{1i~za zrxyrT;F%$iEl3tp*&aUajmyjRCT3Skj(@xWf#`u)sM&Lq4^OiQ%nH&WQ4+cTQfif1 zE3_0F1Rs|n!DX<{!aFN07s}=}+6B!hU+Rb#UtV)}T3Fcb{8HR5?S8(xt3;xy&zrb9 zWUc*8_}HVY*F;I(chN`O9ZVJYv<)UZc;lu!OHr+uFQZ?fb?^ZsTOaJux8}%=s$j<( zAC-5cU#Ncd*E_WzweT3zf#vbxGRMy}sh=JH8ky7U>Up}y{-Ruus@{9fENXiAC3SDJ z6?7wDNm!5=>s7=Y+YsCb}8Zx>oS0W~cqd zSAQ=6x(RSlm;0kraQnR+Pg$+fV-vm1VB{GG!ayfBE4FDlLq#qIGZ< zGc-VW3u2U-zXlm#?3D8L{v-o@N{;ArpG65 z`g!ILCVY;ZFr${NVwO&fZK>JgADYGvD1LK3qM!>AnjV7PP$#D((N;9OAX|jhA2yFN zF0J!tv!TX)pBN=GZ^cw`9jWqX%WhGhR9H=`IhwcTt$s@=DJ(9376{73KL4Ww{lDVx zHZdTR=YH^ps_gwrxA+6Tm9a&9AN(Fa4|jARoiO@TJA63ZbuJSxP`VGhcycEmwMa`JpxTJSvU z!t_(16KOK9z*bUyI)z|qB@%mp!y$%I>k7>kb~^^in>%lezlTJQ>x~$KlgU(f7o%gw zOwgz5r9Q+i(!U1a0{P@`{Xe(xAesGm*t(|Rzqb!aQdH(0kgn=)LJ$waw+-0>7Z5== zfd1uO*d+U3%6h!22O-73ugL+DCV$c7VEE&j99BS+gMEAcwmxMX`c^^cJ&x5?{*!2| zoXx;v$u}6WT`7(`K0JpoA@Ex(F^VeM&)DlR46UmRe%qPzP{+1JRg2i(GC|)p86)HV z_DQIc=!{&s^Ms_NF*RX8IrmH}L6(1h5VsUbnCP#k9!$|C3qCIb7#-PRtLt{+RrQk} zpN=1*yT(>QJEO3T&UC6oM9BNAGisIT>$Ab=%1XoKG_#F^-Z1##RW{VudP&}k-|(hG zW1T^nh1KT*Q6>YPc?QZ&kGDijsZ%1!3n9%$4*`A z#x86RqozzSb9=B)R@hLjZ7)&%8(3X zJeI%$xKMu1HvUjFn*Ol0;Y`Kd2Q233bjV%c{^}xMihBb>da` zv)`5B?ud{%(Zl9G;TqXN3(oE(g~M)@jEuv39m$Hgdh|8}>ERCujWl*kvRa2IM)Djp z5+wOI^9jp-zNHZ9>h7AzR~>xhM4onY$g`b&PKpHQiFG$-a37EAe(mw z+<_i{nR@>j7hsHmDZLl|yB=?#SOzHL8*Leazq=k3)0`aZq|gRvf!?Hyl9O$}gIlnS z{uw9~kdq^9`u#X3JtL7AHN-%JTGe*dYnlOWLKjLQ4^mpMXS zBCzAwLo8>O1T)Ducm?{2fywXNd~fv?_^!_Le&`x%g?FD$Hj&Uf&g6t+6pPCNQN0=} z>m>EeuY;kFx%=z=V|E8)_x?`5w)}N?2H)vNC@rtn_|r2Sv{ z$k4yc0s`gFX|+2if1Xy7|8QFUvIf48WgRyo`j7g!|1>2f<9^!I{8N9sKm0uX|1EnM zpp!8eksJTI>JT9Whut^?x<_nxRvAWhw#X1euR^lAU{HF-|8Uzz)rKeV*f1B1K`aC*4Q7yS&9)+RPNNq z?S%c-O$L2@LD!ewLF(KuMJstOs}m<9p!bREO9#8UBJ$g$ykW_OwMD&)W4-sbvMNd| zW5mOqp7`k|LO#sv&|Bz=thY#hL7I^HNs|+C1D#FmKpUD;jnjQCi^i*jCJ|)c38HH$_4DJp#^~>Q+z}-U9s?qZ(k-8jBeLWVi0F>B>@4MJw?Mr zp7cuj+^n4b?x^@*J=OnxuUTJ#DhO@*Do_MR@da?*|_sr=L!k>>ON~;3FT+ILT@5 zqkrM9kjFXQD5d(g(y~vA=PB1yX@$RVQ)qgOAG6baTQF&DoeRKnquKfbas%M66HxW&jjcd{ zjhw)M;6(@$)uus!Q-V{09GWObAGCy_TCroD+vHjxG2&qc;H+@?)N>y+wXPi?@HqPW zdcaN2QY)Ww0`j5G0u4XK<--b?REB)Z zpA@SfQN>`03Hf^fDOGY5o}S6J63 z)MbSLN&45e+J_IO(4q#D^)|NSyQGzp8(zg=qKo{Yjd+Ue4{*|oV4vXHUFpJ=AAW8r z&LX_fcNj8}t4ouOmU*^xm%FU40b{u>z$u5m@ z`kZ;ylO_0_YmW0lR`fpo;^Xkj=%$p7(sp9oOA=)(5Fuh7Vh1@Np|G60ec#0vkL8aTUSA{Fd2>0=7h{!YQ*LH|=J zY{8*o79yzqpQP3;W48_lqCT-NSo^%CS6MK*0n!l91L8nMnW53fRmp*Xv-s~LY4;+o zCC$ApYOboCz3wz}Vv)bYzvbDE6}59a+CL(S_e&M-uA`@*?1a4}ib27>X>?xzdEzp&KaoIPxLZD#+-Cv9Y+YJZGc;+ui2Ql+oz zo!5bH`+~#_$aXPk$~Fk&$LzYcXYpLr2o|HA4LC5>Fu6-h~=i!cJy! z$7fObS;qRwJ2#;u-qCR#qBIhq9*qi@(fD3C4Se=?@ec_0GN_pH20osP+=Kc&?)(FS z1pelv$v6t%ieSLb3|$2NHwb|MXFI-@4b@rt;s+$y6*$XR`Jq7gEH*Iu5n_<2&mF#;_r|HSekne(()Dj^KE+2 zKw0Qk(yV}I7@V+Z_B3vQee5%wu#^jRFIDQCv)PxtBS+@yetKRFCNpIl1;v3F8eND074&`gFaW#&yYAZ^0yU#lW zb$x}0)M*VnP1<;4=y~^)R82(2jq*qPG&@fwifSmWPKeV6wMUx`ZNq|Jki0&d`=E?U zdZdF}qq@1nPO6SW_&2Be%5M3Yy^Q#9tmmf5!B2kWE$fkI4Z7EtcpFB~ce`d57nPh5 zlG6+pjbXfQ9K?uJ&A8*MIGb5>Ezwkm3;17;|LQf|Mss7Q(tN6@b(UyqlAg`CpBjwK z#!_Eg{3Z-cMmh?J@wiOL?(9QTj)vE6U_!8CXzZ%tZV=WUgjBLW_m7m27~H9wrhmgbD~x;?VC zEu7U&t{*@zw{QgJE!+-(Uyw?#!Y0goX@M66oW}~GT-k+#J;r5OYSUb0w_l5NpVvM! zdoH!*oSW*5@D~`M;7i=XDxCs8z*jc-1$Z*@u>lV;M54*m@QRG^I9Q{eaXKOP<&T=u+25 zH~Yd6uat>du--r&cJc%D;vIC_*T3B)3#de{tQh`)1Ui{)JD_i#TGHvg4Yb%o|GeLy zxM`YfqEUUFM>#I{mDOmhf(+9$Ho!tlruKJ3{iC)Jn6umTD^2xfgA5=yu|B;fK?T zC4pN*JTt=TBt87X#Py;xlhXV8wlB%0`qO!P5Vyn)-?RF;4f;o$^1Od4t>q}lU3eC1L5=0_(y@}&9y{;=6UtLhGg2I0 z-?X|{J`a^KO)vQFYVe)&!%YnBk2OA-OGx!QwQO&168$LI0jh)|LuzNG`8t-{qD5fA z=o9CagEvaWQ=*eT2vu^0CWOPKA5X0{Vw~Bo`f;C-^i%JAC6Vx>f(I3G#WV8echxLoqP;#S$_?JFQ8Ki|D&S}0s$nrt1fV{$p;%Z6EfTxfc#5;&Sh4Dsg@is`$~Dlf^0WLx9LLRW^ZECd4gIBU*Y6%~ zzH`y{&D+9)>+Da3)|*{Xjn|N!*mb!MV4Uq>sizQ+)5RBi2#rmaS{XH2K9;_Vo=l?U zrH_V(#M4-#_@OQz-_g=0#P5?bqw=36h63o8wmX@n2t;q!X|{nu$Cj`I%*)S>id2?m zU}kne@dMDJ6$-vz*#HSr8orq1SYKJ3S{Xr%DZxGJ zOKMOnZ(LT*jxmdl-Iztt{(#&x3dvw08I5CDd>&e*3|;EEMSk))ET%UY>M!J`n`T6J zPhpENX%r0Sg$d7&;^Rr}8cBvd)xALXfP)cG zTmw&Ucj!`g)KQW( zS`}`C#M^Ig0_MnXKBa#;;^&)i|L$XmrU(Ezc|fUg{|*OP{qgsJD2LfT0Njvz&lw=m zj!_|1?3f0y6A+E;+$5K?{YTIjd)M>wT%2NJx*1b+TQ6Enm{?~_P1FL$VYngX1?sQU zZ|iXI&QavC?>?p7CfIuK zH_N${?R&&uU~H@xAqOZuYcsn=KYkIg&B{lblZ}2rl4gMOyzmOlrEE>?fD zssp>GOhfB`)1S(_A&T9)RKGYdjm+`Q^t)|lLE zPbHT<;A$?0kcYoN9!vC2sM@h4g_@BH2}zA;2w6dVc}YC%o!2V%R;5jg4(*$vp#W;u z-DtB}@B3ugY#*scOYbmwru(M_teM?8H&u0x3bNA|>IfF6P|_UR+GT351<9IY0w6pc!c)9+$eb{Ba^+j_(3m{_&~(?|t9y5F~m( z)4IYIX2+1s-V5VjFb?n~oxvKoNQI#%hF1qQH$8dxtH*HQ|j|qO%iPU)q>^vu1~0mdN2nUrO%FNef^hRlFkKz_VeZTtkLN zHIW^!EoI3CRTudSN3R8~7!Z}j;=e3D}nKf@>VE`9ozttRiy z7em~2s9Lbhveqj}pEU7^#)uyxnH|hI|gH;gY$msA{z$U@NhK{(zjR!t@GI z=*~>)KRdFKaQX#LP+6>p+nE$)u@UR+r!*V~hT0BSD~`o2WjPSg z6FlgkO#IWqvm<9c5%V{JEt{#g*7QrZ){Is-WWK^LLNCEic1}n3b!U_&p%*>l2~=dn90uBjB`sO z%9zf$@X@l;X9O->IyAVaKI!Y}65oTF!_Ty?bMX6}Fe-XArmnb`!U%~imfzF$Ke^(5 z{158RW_K{u9;0NTZVAc;*B&du-*^J-H@A6d*Mr}O^zOK3hA1;Lg>tlhT;xuw+sgz$ zeH#MnW0WuXj-aPX&LQ|~phUIq2T%A zUrxbaPs82U`@wzDQF(#Bt~nM)xwcACEKV8D*6Zh@d2cAqKv?@{jKTmB-BJciVCZa2 zMe-!JYxc@s`gBkWLu-BR2ueozdguq1;zX9*J6EoSe1#MTQA9rZUFtFGd-nT-KJhgd!Bvqr7300!+`-p0`H+dg$*zlpDsKRp#E7;k%mIC!0KBiQ$Y|IWVu z$2_Z_rWrlA*|Ev?p?t-muRFQ9-g`3lB6%ObSS;gp`(>t%EA}6^E)N?HSkKR5 z8Uh)C&fVzUcXNF`r1r~+$K1wrOdsw4@aaYH2PZmc3HuT)V~eZTkltt46ezn> z;`v)MiE?F%vLcNi_4s2?1((8@Y45HDJ;T+-4Y8Pz+_Nl6XK|%`0xglZPFvV$=nO7p z+NxFSnjDSslW;UOZqXfNL{mSZijYNwq{{*=?~WAUpFMh9Q3;j$rm|{R)=5Y7uD>Eo z;@Mt;H_Aqo*$NfoV@4zH4aEpFz-9Wn{hhwY@@yE6#p7Pvhl@=;{mj@7sEpt6DV;{n z_gvT2=&$`cPO7`Cy; z3mzTmEmdnfBFgzuiT2&;OtVoH@5L>=k$$DskP(A3?9Q{gb~o{h{`S{LvJRf1or^75 zXdTqR7Bwq zNN!Ck{C@HRyhw(z&Yc1ERS7kV!yNtP-7-qpBKFbld$Q#CzrOcu!e~sVce##iu<0f- zkr+jy-thD0i&DzYjJ?5km7v$meP!!`dX>M&-wuyojOqVU;pCsd_W!yi{|AFGzuPMQ zz;!<*{r+#s0)mnkqI$;$qnNJ(mT->x>y0*_?FoIOJ*3#>!zSb1?%9`A!gUWu%uCMY zwH;EA`vf20WF*BAW?IlZ?)@DusA6laDzv2Qg&V7cxl--~NatBZPPNzE(A+N&({}To z2C8h$MY<%!;5nn66HVVy(lcwA&+j(214P@oQ_nUe^#U6>Q}Yj=Ex&Vi{>9g^e}WH9 zHpbl;*-v_ybAu(%_hnCZnvz{RHNiD>{_XpO4I<{V5yQgV1eVDuLn0bdS^LZ-Fl?5s zN&gTuSPAn8?q+ojJ(g}T#^w5U;6qONkt3QqwL<*`)DFIrHUW%y>qO4;b9o0kvoCZ7 zljwQY0`%zS8Uo$C$87V3zk@Rnm+@ftkpDMUygd~qHHjW_2l7!|YEt-&5fC(}-YnJH z;5NLpW;84#QoNddE5ayU>?A$w*lQuyv8NB%3;klH))pol7x^3rP+a9qY&Idgls(_3 zq{m7o{r!V7hwme9eBKwzdA6L8a%3y96aw}^n_3bj-y4nFEJowYVbZA2OA~OipbZF4 z4d&5MAOQzR&V2PN;e$Gjx$Z+(3?;r@oqMsLAJ*d`joU8x#OMB`Y(;2NeWCYE2l6no z70L-a>;eu%ov?c`-pvAiSq@6Q0Yg?DniD?P2JG)FR4NO-9{j-6Iv%8+M_kCUU4Ojy zf<%W876*?R;V1Ep^$}p@ua=j+SLK&f6q%)mNo|mLuT1u|QAVdlJqT5TY(RNMJsEJN z=E;tgb$LP0%Yf#WbFqD;t=Z&U&HZZ*ecE@|g)YWJKNr~f8J8nH$seDI7z)weg}F`F+c>}wuC z>qSo{)E(Ol^`PC9iGO;xucDKQly`=J4PXBO;q|#O=PuuIfj(p8`lRHyv-{qBIAePG zLxIRxv{@{*w{o-z%1-9#S1<~{I_ARhm?ouzHT8s*eALlIk>>^1ZQnAO=-G$Ra5Cg9 z(cmqial%ZY^-1#`S;qyURU!s?hpm_8aFVyaUW?;jJN1+h`?NnifP)gXNM#|Pdru(4 zq*G1(b=?l_NI5UKL6s_c!%lSr)7vdn(hPe#vxcyV71Zp>)Ogupc}Q{%Yr)BY;}*Vu3kB7h|>3TwUaX4=iiM% zGxiO}!}KZDGDn{f?_;CPju$vr`kiA}x-3jajT+#Dv$y-_br!SK`k_UgA!5%S7W72h zmDwb;AC@5VXb3l8A)Ybb)`TN#H~pwt-fwIx-;^{@bz2*JcuwD5AswW0H~6dB*_UK} zQrwHLXJ0ziO7<-t&#yOk%~ue7U?0t?w>MJc;z_+RPw^TnOB#w?Qj{gtr3XCU@3*^r zMw_DM?_}TX_hl@F`%?{()719#mAGm>yqV?~s+jM}Tf>3in&b{eC&jwr}B`gWG+OO(RkO4DdmhH@3h!pM=nlE~{yx?+{-=h_zI!v|qeS?h1u z$2%j1`Jxx@IQxwx91!dnvKk(eVLv;)WShOwVI~3Xf!H}K`kPIxEOzeL`K&YwOLhnF z6WFh$TH!}tsCjAn_lR$<*mlOJGU!_LgY|RCx&kylc!z#w@pm6Oe*cR z+;PUs`UzWRYsxaI1oozsnWnpzE`Hg}4ZIATr1R|Ya;3gq&dC#7SXhOs@Z+tc}k|8 zoQ3xuj+2VgIT#l{UE_mu)C!C?s+|POsK(Uds+iH$ExP@6(Bm0d?|g^~*3VG}SJDnj zZ8i7T!pKg9qpy!*a(z0j^dn7=Tq~|g@0J~IDFl)(iE>R6$4#`Sk348QT2n=|CFK!% zOi3N%HAfqp1g5L(@A?Y>tvT;p`*GBQkAco+NJP!AdFAB9O(bexfC9mx zzJG*~V11_+9avDLLACDE<6_i_DX2SHu*@VH!XyR_+U35`ZQ?J4j>ovzz9-neS#|E? zGrNtGmwTTQax~#=@?KpryGbFlx$c<-YsX*86CK+vPXu82*{hc{kPOHU_$oq;ag-|V zh27>sY4MO3|I);~TR9Oy*^ABey93D<=jMvq$|A;7vgO%>(pg0`D^nvCjyU8vH{((x}Ro7sQ{Uv5mM*eH0wr)_I|XJma%DSq5CbsKJNu$m+9!9zu(}(kfkp zBOP~;Ci*@POx4TeZYWJ9SzD*eHnH!OTsUd&qH=PXwak^LId|BI@#7(7@dL^{y93`8 ztbG@V?bD-N<08@Q8-lKI9A6R%)A)A&s8#8j?3kvutzh`p*IX*IK5g`#v~P$KTjBoV zIBusDP^i((p}ME!0O$0ePpqkKw&0`f&`(Sv`+Y=&kI6ICD`m5?pI?Q?B6y2CL$Lcw z*oAKHr@S#wlYX18cx%USc!1;8@&`GK);6a6pbPZK0|A;O3L$i&_O)28NIynEFm;GG z&2Gj0M(~5dNIJ*qrI4Mcn^*l(Xt$5I&S~rPVbdb3l_yu&btr`%uUrJKLeWc?tUBG~ zRJX#+a{4MC*Q%0T!biG4!G%b{hYMUkOZ2+YTyCK~xOE#cZY9Z}EoTV32+tb3t8W{K zM>lzo$dVk!jkxEd1vX8)Zpq4|XPMG#y}1I=2tn>Jmr0jG6aR8{T2YB8yD(MC`DE;r3c zi@=f7q*45hK~#~o&syV&_QaQhX2o=Ji#kv0xBHzleb9}_BVq5pK7jxbuzBG3%?^K^#4W^ulxV-7Rgv&o>Cq>{QvJ>2@UXkyGHg?&3yrr-p z^`)vz#^8<~tE-BxnbJr;KTYA&Q>ROG7XDm*C5YffYU6?!2xt2R{02u@2QU!eJdX zg$M{uPY^pm;ccwr<_u+?Bf(;?hv!7XXg`Q0pP_!M*})0<-u6r130*QBUHbxGc|lbm zmtBMQjFvzRE*C(1-?T>49vT*WAr$xNS-IIbdQsVbvYGVl<)Dw7eoNOu8H7~~e@AM< zRBiub_ISl7W$ohA(n0%}F~jee#(E15CRkHTCRX7`_S`R;)W31LEs=Fg!s zYx786@-@O{J;h7fy}t5kyvXfM-jk;ko(*~=ryn1i@+h~*nb`TU(NGSDrk|w0jbc>` zd=+pJ&--w)kuq)$GtX`hnNlH!eVJPdZsT?#^bZX0dOKa<+3!c(=euS!7$RGQX}5lLLs zD}urH#saBhCA*KVgIJWig?3(xoYFnA)p&QLf{e6Y+sHd#hcaI9bdBCBoGkmOg1k3= z*G<F^jOxIYvb${pc$j#GuUHF)+h7!wU70)Ar4O8@glzL)7kt)Ar) ze!dhdbKx5^FAmWP`)*F4C7|6Yp#-ivVaZ2UB!{L-ZOo}X4XT198KL0brI@dT^>^6Y znD4|*{k~$smk%!$SN6Pnv}}^07^0!0sYox%C`5#Z1wPz?QwM-*+TAx6PPXbb2TR2Y2_aMt%=_%jFo6#vNBFIsa?J&)fFyQp|V z1fo|@cA#WpojP15Prn_!kv8p2<$j;)ng3$Tb{wa-eB#T4o!4D7%if$ccZso->=IP8 z-xDW4DgEo?QpfJnSEydAzNcn%8&;j|c*yT5_Ap|gisQHm+G%LeEuA)cGjOYU2F9h{rF~c;ZCaMK(>g z-kT9c^}CCgxGt1-%Rh8lTzorWZWqGCEaZ_}XF?kUdCs)%DtI1GOm@k1@+!12A2?Sq zRKJ%lR^Ao@LBVE{(tG|v%9XT91flsv;ZY*rd+H^#x73f=)ic#V&B+enz_Wy_pZvqO zYrP);SPc~Md1W`+Y6<4Iaz@f_sypQGM6v#r0+ir0{top2|FE`k*fCVwNrE>es02gK#4Gvd7MC-~Raj=qM-mYA2keo+o_78{$SQo!!Au7ST zkX!#{N&Gu%0bdfZl-Ps$`nK~ZQydwB3iClPi8?xAX{x>2>FnM`dYxgSp*vJRXS-y3 zWJeFxMn{;T1OW`+I<27`9E!Rcx1}7%RWbF5cAK+9uxFkYTFmz>%bCd}=1Y@tkW0z?1 zNA)?ZjP~oezaE5NobNh*nRT7cNO0MHz< zt$3AQv9E8QmtW+QVnHbpae~_O{0H`%R9s@e7#L?@Ho3XfwF4)4 z*YOGLmKvZN)XH%ltQr04$#Q`2+6mi}@`df3?8&@ZF^v)p;TJWwVvu$1hqVOtMCs1a zr#%jW2!Z@PL~0dEoS{6gmYr+`xy-N;=E}G$#Xat@(cGK7i^2@$=Mu%j#i7T8O|>1b zAJLPfQBu-nKMQ8O2dQs+<~+cxE#!>4+aIZYeS=xqsF)$@wmRR57LAP?>I>^*(f!|X zWUkN#zAoG(yRh{kE4_}=)SI~ML~ToF!vDwKdq*`HuKA+D&=Dd{dXZiQK`By#BE2a} zFHum6G?5lsf*`$vfP#Wb6A@9W(n2pHML>E<0O^5*8X$@HbMLd}&fc?UX5Vwq%sOY? z`v?Cdtd#G|`@YZfYtKF-^U$f@2^H@( z8}S6S3Mh+AV8pkkF3X1n<1UXj^l)#U|Mg;U__b?>*|md`2r@tl4?JKD)fNZetnI_D zmLj`rgTNz25a9NrU&lc)H?$@xlSBF`0mX^rCZ=FA55w_PQ;MkHlG*(zyrD;{#%OH| z_T1aW{ft~bG@j$*V3Kd66fM*j*qW|g6chm8tyhqEwpnNL>C;?|9#myB6_K^4Ok~Yi zoQLoe%3RWg-7i092g{px4qgQ({j7)}g~UwrxH;F=B@4xf-buN9^IcpaJ=<9j2n_PC zY#o{r&>mHXp6bBgkLuMMS&Mq86|xyJpSMf2zMmDr8@8*c3UJQJ2;#C8dIfl79>*6TnBL%G54+GFm5dI4A}j|m-2}JCKn0v z3swrNqJHxLd3u$gww3XrWPTbhY9aW1*(g3pnxa=YD)l-<+ob-kW{REBoxAuB?)2UZ zTEe^Rch6dCeqEHM>EI6Cm=_-N@^6$Nle(7sD77~RwFZJY0P&E!Pb5MEe-~#Kt!~7= z{o$1OoEX2D;>RhoD0x5GIW3wJW4(Mo35}uH9y142Kz}(6#C#nC@Mb-lARJAU&y}Hg z)|s9{`CUh@C00_|jOaameNAU2&24#*jQ&mieckmXiBAiy|lB;=0Z zu>MdXcrlO$K4MccGwN6EtYP?euN$lt(o%UEYE3`{d$pVkQyaPLAs<+jB+E-}vU&5?eeZi+VmR=)EzJ$#t4DtTXdXRjr6BkoW>(?2HMz$0Po7IUx$;qT zyZ?7BrI|y|KTApAiP-;GN+%-Hzg`2#e`ObB+ONy1MV^3PGTQvgP*GCmTip6p)RKWl zsh7<)BCL6mljr%%`x97>t!9zOh@p9E+CM8z`tB+vYg)K8KI$+Z_v$E$tWFqg-&VTO z{8Rj=;A8m;>et;E!~AHg?^0$?MS&&t;6uovGl3mb`4k4(pLvcI%IwUoCg3S`jk~d z9-ae+pX-FWUhP^M;8mSVxFKX>Q;{Ot0W4aAdS zutpO?j*daSVSVy$`u^b_(CsCZ3SKe0Lfj*dA>>=|r9B0lFvng;4d|^r!#d+^YxL;z znTV)QF1mi?(Mvn9;g-h~d@7ZzsfPu)teq%?I=tVkG3o96hTlduHZ==9#yNZ8_N?4< zE9ktrhP!Ml5Q?;Sm`ZTKDc=ApI9k!}ibePS@JgG|=i}FlUVU!m7L$K%t_*s-nk^oo znNmQeSH;-9G0f(P!p*f<$wm>xcrdY#Payu1v4^@S6>ze=W?TJj*dVs_%f*h7Vl z1Y&mHWKRGGrxo>U5g!?3l}P-;#!6EoP||!BXoFEn`kW_Pr|N5D9C+PJ`wePH1_1Rf zYL9hbrjHzkqXQMo9f+zRs^W9u-TihR`YyQ_IIa2n2QQdqf7g~T5Rs<@K|*+j>3)N} z3St3fRxVPpH1>69;~X`a@4j76e?J>@KU<>}A)!YyjLCFf;SpqMp=}{4UxFaM7zE5W zs@Oj*k9Shq)q7_b|Lo1(1!-xK&-D#gR|!vAd$u50i&JA5k)nQhtACiiLaWSiyF@RS1o!yK7At3ye; z&aCB;oS*fi3@Gy%81Aa?+yIKKw0ZV(gv!=o(~p-#vXy^PU**-7F?U^a{Gyi1gy=`r z)OXU#HK|oPgk2e{rA|>x=3X^>;^iau%g;;Xahy}O@ki~)*xu`%6C<`eMAmA|mBp{a z0oWjutg1UkA{@6Qdj!O@cnZ39f#6K>rJ(lDIFFuseuh;0YW$ft7UO!$SP!w?j&Hg0 z1HX(LANTToDmD%70wJ~MIfpL;5NnVzt|g7n(?3)#l;Q5GAFWp*bIDS--NU5(m3ogA zvnht2kfBb2C${|Mi(L7uH>=$Dr@UdJD|UL)Jk|U*O;vB6?|!FK&pq+}TWS11=(8ce zhyMl72QNWq8r!)m6Ug8J-=Z#=o!1WoPipX;%F0tqDQ==pSF?2TLIp4uGH_}Xk0uX% z1s1ER@CpBn+p(bHN>p`trg`FEUFPGgK?V8#mxTeAAoLMALQ_7>jo^p#)2nYHJPGX0 z%`{+aF1nc)|1t2%iqoa;uCw6t7lOg6f&%eQz{%>GIxTMW1;5Y+J?G#?CxT@=?5D_` zo?oI!;Bhy8tk-eoOy4hb@=J@-*XNs{fX!SGSM$Dn5lIc3^1>9DH70BcJgO3H(ab|} zr!MMs6-+4}KEq+VGs`v@Fg~ot?=O?=?u;h+&3t>x&SJ(y_^!ue<9PEmi!LYF(WnC1 zrb?Eutp=vJX+UmTtXS1p*qk9l~de4(fKlF@eM=qmq~7kHclfGhO(m7vaM31 zTrV%~%q>gY)DvGpTdfK99agsQOr9=%MByeDFTOy}G`w~aMm!_nQ!t(AGB4rr_MwU4)z>IkKe0` zl!lXgO6w-m1pDeuAAR8>N*{&oSGE_-low1(TSNDkN)g$cH?&Su4=I1_=Pf+(GYfv; zr5@|h%(EQL^+`AiEW&*X+_?^*`C|ZlHLY;Kl9fxCA=4cKY2WU^o^ow-fy6---j#k( zG8ev^IS6*P&mEmNL6NFm?qqJs7=6 zTO&xc0MnUi@F#u7mUNyc!*S>sC%uxumwr8l1mPvUt_7AbH+V!*M@U4_db;V*pV zrfjL(b)!o3f6bIDnSnu}a_yCqrHeTp7+Ps>*}9Vj22G2 zKb0P-pjxgEc`XQR6we->F?N8T;Ybx1(y+<;Oql*el17^)kS`851>tFI@Uby9zOStx zRu#9ew{<3-ExF8k&f*p#SQ|>Oc@X|H0B9a(@mH@k^miY!8q>^XcUxx$mHbK{grZds zE1$MV5>>|$tc0E01Y{*(CV;I2@vK+!8e7{JIaf_ebaZ=ds2>-;JmAfy*~-}xmdQX2 zaoc|FO}#nBO!M}*b7@b6WD=gB>#+ozR9`v_8QlYJi!5+@=uS*&t-RT$$s<~h`1cRR zBBXM+2j>@ch7Wize=h%YX5N%SFda6i6d8B2@)C&J^?pss|CEbbmkD0EF1_eO%tQiO z+{r&VpCj(l$Mv}1AYyFI=nOXSH^{7|dA$>|{v7^yKaIx(svGA&Pw;b7hmTJxe~c9>tLKfMR=FX(Z%@m-6$D&G_-BG##k3w=q-r$6teCHQ(7%gqzK{s9i_)|T3P4q;r`!jyLJk#w<(Pq>#mkP5T%p;629dMRuM2L zm~=i&25K$70`gg}&w#sf7Pp6Bw0h@&R|CH(Ze-k4!Fn;1sOsV7_twP}+t%8+@P40N6 zN2S}*G~Xe{>z$p6$0hAp=D}#rGC|Cz9vbS8FTdU|I=udHyR-Xv=4@TTxwP*xta%4?h&IJb`838w{z%i+OQYlBuRSygJ~bIFIxw`I@U6xXjR1Zl&zUPD_?OB}2#BK3#YxKo zlq~|HTP(y|B@m(LiZgqiE#gfnJ*HJjO;x=}&}$}}N!)t{17Xm_Vh@($^cp;B$?@yw zuzm>Rl>Wlq(Y;86-o4TuMrm-;<9AFy`((aTxE@B6-W&`i+y1Dj-Sbqx^x%S$C0B>x z>|!v!L;u>bRhHHxg&@U1WHofFD;#gRE5Jc$my}f(^|~OXY5>gZQcY3(d5%wms|2lKHNQ!^X3fp5-cPgn-|iX0xDGc0zL zbV_6Q4-mDnKBs$)uRIfH)eaC#Fvfu?LI8%5rhWD1Zr9Wg{~0fp*Zn!!ewBf zKG1MmWy76f-c<$g2}Rt}^E?532JDuHC;cY18ArGBrS0G`_j7}ob)!fnVH6WzKL+XJ zcb+s|^Y`=@V0OQn)$3HkW3(oo#yrNZC*sWijAHzj7I64NR|S&!Lj3ace}h(uhd_s; zTGZPe?ndEOIJ0|H)Vrz0pu_g!HPzdcaEbk+b>JPlH;~K-0k<5N4ja5?^1a7A_hMGa z^IXayUO|ino-PdzQ1j7Rk2@_R+pnAI!?4-&I@t<(_6iwHYI|B7ZiOv>F&H22oD5Uw zuu~2Etav8t7kv5A^(a}9BxcZ&NQA_h5XtmD-gi|uHrCJzRcY654<`liFBa?o#;rSw zv)4Qr?CpC$bprqYR7m2;IReV6#d^zL9R`f!H47!>(Io5}$SG5vUfobyap*)dMw(0w zd0KfF$x{W>pvD2C;-B}IhTi^JQ*nN5!9%(3@ccI|Mf-1`y6M)GRl%BbZs6+)%a@UH znrHBgz173&21O5VXHN@Nw?qbs1Tye^9;#DxK<;m1|EGLp0v8bf0e7_mtve#7O`*1= z9}wr8)eZqYQwAM+;RNqP;u8%!0!pegny5E(PY5q|{DIL;9vVu(33=haW-u5=^8(Qb zXVzXpLuP^TKlEMCW|V5eB$k;Md=vv@SfLLXQvV0c72{fNNf+PD8p@bFA-8I+J>;4ou&s~wp zQ-6Gy*W1#*3|<7HwolQzd+iMBe2Xx7P=HJGyyLfqo!ISdnZ-=zjgZH+KMNxemV3fn zshSy5N};~69~4}Llm~CoNQEkoe6{gK?z7V|6-ZvBM74YA3#-W+Mid3b;Q~11p#oq5 zmjdD(&RLsaOeoWK=N~eAe(@)7ogciB^!=*hQ{(%~`_M);Es>-%Auj_;of4n)5I9=N zd;~v?3AC++z3zO2cOFL$kR8qQSv6S1TiHOEWpJ(!YDnB9HIX@qck!i(mt~#Xb1jQ2 z;ej)z)`Wz zBgf9~ooJK(3>)IY*9+{LHQfd_NxKCgtz<-y&8a|MU;s_vz}G&fB7`rd8K7UC$1x#3 zq3KDPq~tJBJV#pr_2P)8aF?Hl|Mb&6Yn!>x?iHRkLUcTmBHij;>5;tbjH53h<=>W_ zlFU6Jt*J=@V5A#Yi^%5DNl$bDDbS<&`eMMC%!gG}3_Mr+SCs*M@B89Q(JE5%UpTvh z=So|BQmi|8@t~ZZs7z$i?gF!@ku*fRX3{gB zw(JQOR0?1~5vZxl%0>r|7;z;HF+Z>4){A!(I{ozBVCV{=Pq{TU8TSnj1=?`7^Vjb@ z`>{QHpZ8HevnBsi7RW<#>fy<)x{N^ZZqOk&!46;84rAUvC^+YKQW;BB0p_VRB$_AK z>3n(h?f9Btj)!6yPd)ZnOBgCYv`PDCCtWtj5+${|1ffu*m%vnBCz4&{6CoB&+cNdh z{jj}z&+OtmZ!hNj8}P)e+fs_3q)hFZ>$B(=p6QX#n|0*HWBbO5ikBW|N+>Ixb$Be_ zvD`$sa*Y2`9niiCLw1^g{%%;scE@|}NYvq0HmmP+u%k;z#4|e&d-=O}&7MDVCwF(zf~KGGSGIm3WsK)%=j2A+$53m$9=Jj} zf+E4zIKlpp+#p?72XvwG`_2r{p&1^UtgfxxS6F4Ho*MzDZ0 z65g+;P2IE-jRV396SQNNMk1iOv{xW;OF; zDk_=6aFn*B;zI$Cef640!YC)WM?PCzJg)wyBW%(G;BOC+1kJ#dn&$#2_5& zQh3(vp*ftU^CM0luh>yEXT&VgW!lFglv2uNNf{{*jAQpibif!8iUjRNo%!0zHQ;77 zU7Zg5;m}p4Bl>ps`}dZc)}r*^H(Fm|9+ju3e*vF#)W7@}NB(2CJcY8=S(G2|?lo*7nih?UlFIwRjh{A{2 zBUQ7Is|L=OUMwn}@6g9fcfta>;#F5rTw(-fd<&POI03mB*=v}Qt1*)lmBQsD)iE4- z4Ga50UNBS|eicD{MT%)TPjthjc7`^)c5-W$17aa2K25jnw_|U!e|WnFnn{STU|j+P z>qsaGKm!dTd7YXe2Cn+_yrO3yDOm&DIlKF!)tNS3;ujMr+98Uu?(geaZJ*-Mq> zN@TXD&cnA5uaU}{3IrqkZH#vb9$u(5R#SF2P!gX0x!y^2j&IB+IY#wconDxwMJiBa z5w*uI#PpbrhiL~ci-bDmW4pKRdS8gJ_sgeNRky;Xd_8qX3|-|f^({79l=S{pm;N@x zNLqCzHiY+F73JiT2A9F@$)!rs3dDi{h5sg<_vOA?6LXA3QXt-@Ml`Q(_4(U(L$?Pt zAlkN12s2AQl<-WVWDtt5Tqt+4u=aNXIJk)X| z971jlM4o^EKAxY@*eSq;5PRq-l`-5>wy3sz&SoY`m~rM_B-@hAw>Rf_@24?Q`@)8M zI^-CP(5bNqE?n4FrBY(i)Rgh&k*%B4o%Gmh6>)sAAQVX5@`1)cIn~`4D`>26`8j1C zEqt}3PoWP+3q!LbPY2Tags<_hiY~deJ}TW_66Pf%knM?tsRhhY0upBw44jGiS4bDo zOZ&w$*Y6^gk+?!lCFBoHycLHeFq9U&ejgY*Ss&rIKr)41C8y!_ z^*9TkLo!j$X0%~CIM=q$k(R%1#7TRTz(%ZSJ6Uz3oXgxG^(ax8QvIFx)Zz|S@$`zj z0KdP=MbDK~6TE45QXR)2U5a%daQ|oaf*+(N&g6XGB$i7aFS8o56a zPIt9FPb%1fSQnak+*ZJm01dWxgJ6MnkZ#STKB^rRl5%+lQ3!TO?3Z3j9^5j$ zO3{j@-=~)-`_CXF@b4dgB^rt@*W9F8wj#1U9Sn0vFMD+}7tdzVZ0{(7CXc#@eP`J5 zsqLs_D6=NxMr9d+kS4aaUU-^0<}UYk#p?w^NP!AbIt}W(fZ0U z81JwZakY}G}S9hSK`-)&|`*hKQeouyX^v0Ri(2`BV>zz`(pbH>!b01DZ9l*^c>x(f+-~VLU)hi&{T+tM%{q+k)fp>3DpoTmnQrqcE!I>~s z9IQiwF-!v;F2yL-XS!njM8S}7y4yPyEI=xi@ohze)b3s~pQNblh7f>podG7oivtD8 zwqjn2uum}}FCppP6^cBaW?C~!@>(sO@>JwT_@6R!`u;(C(yC$E?&p=01; zG%>J-wf-1A$L~e*TW-dX4rBzZ)+dP!cF)P@8?D*YaMf%2s+{cc$Wc=G%l#WJDK`ee zl=kJq{+vBmc5Lg3Y@t2M%nEA==8>(JAK5>a=B`m6v+voMiA0(8Q;KjO0vQ2ZQmyfuLh)|U6yL_%Xgr(0L7 zw8GSufb(B^NxZYH4-bvs(Hvx2uC7K_*_M`WznT7^=XCl!WMX}2>&0&n-D>C1RE{Hn zZYOPjEJ-ydkB<1~&9n~)+YEVrURHdNtMV(D-PBb6&ZE~%Gp(r4kX9sBKi}MZp6{aF zm)-}Nw$DsB0g0utur=o17Lcg3bWq$}(OldVm<>!vYmZb}N}{}@!)b9-9t0?F7c<=; zE8?B}0^?!g9~a<0jG4UTmcS;;0N6^oN(e7;5ba59GI+Q7xm0X^o^zi7R4p~yCSsSS9L$;n=P!^V5L6zy zA9AybrdJYKi}dSk1I7eglXMeaz-sJ&9_mr)rO(*Xb zj~Pjo9Z|%1EF}XI$#-yarp*c48#|rcFMU6`)HOCeaY_Tf`f#@{#+aY*$OC&St>&dU z!owhu!QkOG!s(P8SmfIc1XA!)fk2=&DLV(y0RCcHiy&ZbdEMygVEAqEN8ZOD>Yh)@ zT$L-Ku;G9LI(X!1N5d?{z0BRp%*U7KEL*Nv+xkpWIT$GV+PKL12|(=j-cYyCR3av} zdn5pIZo02@^9ehv)o5?Z>cf2-Ftx!Qf1a^Vypp#JmH8x-S(j+AMHIlP-Q>hv^m!E_AG)2A0nY)69=(zXa zfbRUz%-U>7C9*mU4Eh)FKk-J!EE$XG2<*uAG9JqYIPw5nqYpu8M2jqgk0~sBw~>AR zvo(0jIN9I#*usrwRVf*7wWL(IRL+Pr#Pip_gJ;;i>#DmbmTU09h2kFbw$!&y>@L10 zQg_x0>xvb}nY5^e$%ivtVB^0qI^|Q-$A=2Mm=)M0Gbw)mz2R!Lm-DMHAFDC-t&pb+ zbkFSx(jA9~6ElWah`&Di(5fqmJ*yVHHzxK|Gi&RCS%uMEirTM|U;7~F>2mZEpm606#I=5?Ft~#V9ZQP0p)HC$UMJSxU z82NQH9=QLUuufPbBkmS;*AEVKvi-X!fwzpjxVW+>ST97;M zaRTg!se&5u1fvT8TYTdza%}yko+pQ9hL<~G>ugL*DM02#dMF))8!gg&gM3eOS5My> z2l9h1v_wZjJYHHK zubZ`$H+2BtH;|bgJXvg^8eu~?!0&a!xDQApJD+g}ne~T(xjYfH!h<<95NRgTxkt@?2RlIfZU2=J ze+8973hDHOC;e9^GJi_+QF8Ja>K+7$Gd&xC0aqP_9($4V?V)_qyw zH&RkaT_`ZQA@DdD`r*+v#+pkrcDkQ+Sf1X{p?~*Yo{gdv zO60wz`-YjBn%x4(0{p|m{M7i{aLRub()KT*l{7u5dJbaRA;9Q0=j>)QyB-4i`oE6f zg^)N8mKXk`XZM=)h_olekD);k@R0;6P68S1*Wba1MSYqI$)+) zKUX=18Ar(=07SlT570#&i~@mrBNt#M?FBnOfcc;{sW`5q)DVds9mM=l@;zWJ{VQ9- zzt8;rGwk4h$NyN-;f=@!Ifi`p( zkwD-eIWeJW^e+Z3Q81uHJEVq@BvP8?$n=2b0C@Q*=;ki)sybbc?m$@qm_Ra~EFw?A za^z=vFgr7{4&-Fxkr4?a@Zs{anyg*VoooMS1N$hqXhzJeWCK(T9Jhdv8!TP(Zy)l6 z;)OS&WnbW-MAlRCjUjgAq$z~N3VY3d{KtAiNd}x}ihx^=HR?C$#>5&GB9AYX>JP_z z=`WE@VN0jC!`Si29#r&WI76G`l_uQ9*Av4IwWNaQh#zN-gqmyS@1#SYop$gl&+GIG z3$>)Yjes(x5?Oip@e^EFU$CYiZps#eE|Guv_wWh_FXVrZji2bmio0>r59jUZd*I=B3q9+SK zJm)dqzhYbR*+*b%`4y9uqMc_pMSfD*h1-J=LsCtBedIVT)~iteUbLmkQu1{np(LsI zDIm~Yik{c(%AV(Fw;>^cU_A1Wid0ILA^0q=l%Db;Mshf;Y!CDIIsh>!OK`or#@pjm zcaiT5_Ifgc176aX)O3e!xaCnbe2>G!uLfYr@X8Le>A*ooVKRLqF7nijTC!F}9eSl7 z-2e4!W370-wUfn()i$gdgs?~agnp{*E=UnzyW$f!PfutIe=|8}t5p|58M7{neNg|z zNs^)C(YtuX(&s(>l#2C?3%j9*)&xF$>|qW7m22{w;9(ZHptvS!?ta;5;!*X$)uI8a z!85aZpJt4Hm4jctpfTnqzlYiqnMfZ#_&}WnW;)uDH7!wW=>%AJ^_A}TX;HN=qw9Yz zPG7C=5^@j=`91~yH6TW_>9f^^^XY<~(PW(t)4<0jRjT_TsRp`+4zm^;I7c3H-Ayu( zsp4Ex6|CO1MoYBvyPrCdzZaZCy32}p)HzZSGQ-hwTL#|w8w>%@XEx5DZ!j0{ibvO9 z`&IWnR-nnJag3Dc9Paww#%?1dtk2gYh{c5R$0z>`Rq9^>_u9_V3Z}fCV8nYY>c-=u zFa_}laX8=#d=2+A%|9Lu>`;8&d9#d69LY-7u!)w3zA)n;vJeK|BF0W!w<<6`3AUy2 zR~o-o2sWW2S9WhdLIf^y51 zDC^pUaaq+7Uk`BSDUmp&{xwrTkp8{AsnH{jB@{u_wZqG&hkS|f$cx}5331V z#4E)V{+0Ev!NRNHAJ^P4NguUt3k7x|W)aX5NkNsJI89AlLHiCBV5&P8<{Oq982i@l z%D}IVz1lkw?-Qt3(kI^woy~S)yZ=(4Ep#Vgp%&0ku@&@im&RzGvo}G*VsiZx`9{Nw zv9cp#ecDJr+CA@&qF|wE_3lD0UM{m*WZMHx(T5>E(dtyVQnQy`?iF*6o7@TIUh@s` z1hxBjHFr7k^#t)>+0f}dqXHnL8*(xVE#B?}2~)%^bQUmOZ+K9I^v)L+^q9Mr7GAR6 zmnyT{OGlX*J^h->0<=Lh*Z?6i=V3Yn>D4XpJoYVPwEg|}Tz%YWofJDC=fw(dENT8+ z&Q}9gVF+SWplaw9Ui;93@C5k*$k+z^`j*;BR*l(SUQVr!&7QbR$WAf9;fpJR1nBrB3!mFK~DH z6o+XKqiww3BrZqYt~F==h`vp(NRMOH$zV(S7WnxNiFI=Xl_!^6z|z7K6X2^2r#t!t{($sOQ?=%3Lvw#5&D6Ig-t9q;6PL<9U~`r+MPi;4 zl~YgnYkq@B$`AdwXn62?WP0Vou=9iqXh`e=V*XdZB%-b%i|dgi;j(m1VE zIydnf-0j)KPZ-Xua?+}`fFVp6vyVg{Qh8*j2zl0j(~B1iL@Gt%{yfddxTplz5Ko_lys@7=YtUVL%U zbC%BG5AUaY{z?Y0dy9lmV3Fh>R@(#;oP4J+bq{!%hcw2w!7Dq{{Y%TpYFH~abn$6m z8M4go*fPYTs3@)&)!>yL{9LMArF)%Mk}8Xql7*J|h;Z*z0`XIz{#RCg*ABpjo%60i z(miA~QhITAW3MTWGgYDAL^o!7{>luSH;%BQI39b_Tc~TeYa2h?G+D6f zOa1uecMg%FT?6@B?GAAk?oPq%bQiRq|=fOX{k?158!*rMV(4rWMeMR9x_Q<$( zcwC&Pw_2)V!9#+_VIo2A)REjV&z9LPPt+RoL2$$0T6{{_G;GL~IB%Vr|LL;A`B1uI z=4>IF8JUOQ93~!5Y}Lo0&_xTM>*Kx&;?bkxX-QpW?)BrHuH$Bc?NFM^TlkXXQ+4t* z^lT-OI$vb8$?DC3Z0+}|HST8$v(qNv*yJO<6;A84JFzznFLAD3ux3D3F`+&X3J>oQ zTr1%*yIy*?8gReTzchaFlNnVI8`xEQ@T&LL*XJ3g2C8B$DVz4O5$cQp0~3Rw9VQD9 zEX8B>aHOZ);TgU2&c{j{Y#hkN!0r|G2k|N^4H||3hco)I)~IfV>ZO9cVK|HE#U30` z8Rav8_tXw?q^1=Dl{$>J9G17wu zJ9T;i@Z8=4HlMFh!kp;G*I^usNP;l*Nph3{+AQv*E2fllf%RcvnteOq4_xL6(lXV& zYsVkc1Z#)ZK(JOo-G?V+l@Jw4h54&p!1%UZI8-9)qhR&UF4W`VV zu3@gWt5VLUkM)@|NO`x#6mlC3)N}}u;U;GcNv#XP*_?Q5Bp}qSQsyICtuUW%?CRBm z>$ID_YkKVUuuK$A9~mDKo2W^#nSbV|Sny0+$PXih9w9Y81NHs5pkr5?nYC7?tdp+) z$6}BFQ-mIs0C4*d5}^zgXcD+rxE@jz;#gcXS36fd7>)fkAI&8)lWmXFj+ksaHie%! z0j_tTS&a1~KH%zZ#-#e}Ck~OduS~(s0GxTzMy?Ra2e0a$A27Y2YLH^Ha&N8jYUg{i zqXZ?$Lz3Iu@)u9q!_){q7)W$JS5!NK;j^7Ir$NxFfAzOk>TGw2obcWI`9P+E1Sm*b zW8LjPDA3%$eK6LxGM)(h+|bZ zKm*~Tj@tNGbnFvN6}RkZx#Ty1`1e|RNlin|GaX;=?K3Uy-`2E23VfW8m=vfk)2spu zJ2GR_nS9^q8sI4hn${(@0^F{bANi@B8IcQUHaII?1#qSXk%eUEd`UpnUk)W-F9t49 zKp4<`y

lJ}DrfB<Ef0vYOaNR` zK~`}3};w@0N}Dg=gPZ`husq7%iSJE zN(*{yp}=tQ4ir<9^gZ+fyw(df;hOWPNx0xxcT4|WN1`W|k^$;qxzuXXjC#M{5k zwtAZ@k}n=MJV`8FhTlOz=dkyIs2m;KHczzAj0Ng~pzfrPUX!xt0=|zTAIjBTH z3SFjPK!>wN>@{7WeeK7)mz+83bmWb>xWkrX{^>-rE=k~Y&1x%|?fALCg)nMTY8V5~ z=@7~avsVU`ww$D&*v{)JUUZz!K1_BV=k({l52QBMi$fg&IfI1fnFNV{olyTT;K#oL zME;UmPciWCq6!qhNB+gj^Pkai|0U1=Z=wLVMu?9Kbj)-Atldu?^it|x!Rgw$`B8ca z+M}1$d|&cf{_=&fAeUbOO3K!TRB~pY?TA62n51VIT?w*HE5JnCyml0j<@5~NB-{~OFf)Gt@+(^`SmA* z2BsPCPscj{{RFK4B{Q+C8%pE$8JQLbM{UL`JjKTN3TupBWQe^QrTlO&Zni`C$$;l_ zpx_bu@b&c{hN^-gBme3b2Tso)yGcRvNWrhBhF!wVbXYk`;~z{#X`EzeUvf**Mt?$HGZ>`+XH5*__V`a&`C76d9coVkj2G zW#U7;UUvaYU1f#x)c&SZf2sTD&zJ0OAW$Jz=*IMn5YTH7h3isKH=w->dx+;63lJJ_ zFey}6pMH307rP|Bqjagoic<#2*a9(0uN6#%9$IF0Q%@|4cZRx{P>dI)Dvdz#sT-lBY5yFdN2;r)Nq?*BXd zNk1h3CzVKl*TUhMG2r{=8g6g?n}-rml+E-pYr6sj@f~6&j2SuU{|DE+a#Zo>fcrP| ziCYzsM_&tkW69jWHEtTc3+Sl9d*%NG66u%&9BK3bK8S29I5-XmvS}78F9U}!0@l$4a)x@Ljk02>lk1fy1i@Y{&!PwW$rdr0slXKK+5R z|A~~H|F_EW5S9jY zvJ~;&9i|!SDMknYg@P<}87NBJ@{lv6lxaf%)k{!|FnmtqzfUw-A4l3Q6h{9ahc#uW|fOR!J^_W`}&F&+Rwz^%weW- zO&-zF)1%**d_d!IMn!O#rqBwr(*;y7MmrrtC%c~jxLCS@6b#4~k(kOhGbZswgyiO7 z3;)Q2uSWXY7lZ0wsFh#sj^}Pl>AICiUrJ%1PETYfy!i9^$C2owc?QB#F(F?%6}+B3 ze#>E_-z%U>+{iBOIcJiPbM5j?{p-|z!>k5RNL`AsPo_(UFI8As+(Y$uOr4a#4g&8jPkL)_7Tud0wR1S@<22H8Ew zvf2ryCu(~v@@also|-lCJ}FAp)tbLq&>+2aBKhPPSSytEgq`0Y2D`(M*w&Ng zp1jJitLc|tX!AC%XHa|4L8{(1fv1^g_b^DDrCdTo3jnFnLboc=;S(W4iIo)x45!v+ zLsFL)Tt_QXD_{AwTxX)aq&vq52NVZ6MAii|y}&#Bjf>Mh9Z&&n(avOU#V+bsWvY+9 z0i#jZlz(JVXsblcV_atq8euGupV$trK^bqw17wq~ZA~)&}5g#o?-e zAd?_=w572$MDIqvjGK=xvtPHxCbty2N{oAx-7Y%YoO@~1Hr*lo8NCO)NB*&Jrb+cw zmnbyeavq*c{x0{^^-~Ki-JmVoUUf`2Jf;ZBo zavG`AjHI8QRd0B3@JXRL$xrQ4?(j>7a;}#-?dR}c5e(i*pzvcryIDm_L9W>XTQJTy z7#Q6s3B`;fKLbnph0h;|f8b9OBCFxCo=Qy~1EN(@{nrlU7{c^$Kfgbg@R4%RWiX2F z9UAg^^uvTpGbtkFRXIZstj=t!8MiWSRKOBuILx(V4&1_z6So^Qqk60Nin!K$!3zl> z+zgB$y1EtY>c=?i$USD%CZzwSHgT3ERy|!}N%%8=H|jcS=$LF>*(Do9ruV~ZFVS>4 z@L=k$6o!o6jjqa}uO%u1IpIo?fO~Obmz|q!S#EF9Ijxfz({RtDP@j#ro59b;J-NiE*Dp!tyZI4Qs^sa@1=t-b^L%5A`O_EjDF1Lf%_20}MpO=0bP@D3NESC1d z=~~3@+a=ZGSk6HZ)Dh*1JXQvP85_Xysip;NLbTG8<$Iy%N-XwNnBa_Fh#)F|B;Kg0 z8LKHcyLPCYjdey0Fm~0xy!GvA#b=c3AArJeof^u<@I#@HUw zZFp&6d&^v7NRh^rEzy*SThJ2!y z;|Y@_+`~(W#x8O^tubSHFL~o?T>;gS;J&tkqBwL;IG6Y*d!hZ|bW9Z96{A^Q(tEFQ z)PJ+Q(RH)R?c&?}p8N`2dIyyaP}c&2By{T(kL);ttA)HUEx5ky}CVbv{w?PG8=V%rs(_ZZ)(wSWw;J=_`Y38$%VVUXdt4H^At39LBCjZ-psUC!QeE(j zJnTS35LoZI$?dcV!wu&r_j4T{cL_sv6)9lPk@Yl0HW(&)sAB+$MzxmzSj2{Q9*(-z zH$=Zx9mUFek9DcUz;dvPy~$NjX@BQH?D9KZ&}rzQ5b4bh${iUI;+lG8vM>?$xgk$? zyeW&0b$2GJPnW$9K+7kZ^9FmsOv`;htgcWxtTEaY(yEAf)4v^PVmFg9Sh zscC}YiD-_kr3Z!ZZ*yBfcBRJkCD@ouQTM5$FYnC`uybLYVDg-qq;OTfPWXhD!1qcb z>&~GEKsBWjB~TtAvXmYU9JoX)+sU7F4VaS$l14 zRcVandEzJ+aGP?ItK{frfN`hcC?Gz50^Gl9QcA3FM@RwYgCp=UP8Ro;R$H4jhfc2_ zEy_g;*0%XvHSz9q77RM;(ngeC1g4!Lad!%)8Zi~oUG-1o#0XK9QlDZLj4Tt{?r*s? zXI=L^igwYQT#3*uBQTuG69q}R*nm8N%VT=y4up zQnV*3Z=w_da4Wml)OmnJU|ArLv#2tE5sKEE*jM`mW!2aQav+mkOWFaPLGW*<13nzL z1ZWyT4Lx$RI50++yQUO>Vc!)ve{d!~gk1taemnRhNz~h@n;yHTfT;C1h#z(ix%n{_ zK#b-lHW(4l!%k;`4uSF?X)6BP9((GNod7ysT{Od9!cAZxDO*Iwr71ZXK>2Hycq@Ud za`y0DhLMb#y{_$pyG}#>JZJg!D;;o^De3}CuhbvrL&iO86CD*rU#=^)hpLzxDp!Ma z5PHZq0J>VPc7q+t00;K^gI{5?Z#NrOV-9E!d>{`wY#p{>8{0A~a8X#{8^(iG>hfoh z4F7{4Rtw9bk#{dA!nmpn`qT!JEfzx?E|kiZJp^M%C@+M(`Ow-Z8x&s)DT z3kVR^KcfD)lE$DTs9O9tNiUG!qko44rMx_?B^Tvj(1p-Jv}%*37Wk19 zfBaqPC6#JQzd`=F)R z>sr^k4)5!_RA0y(8R>1*nn7eJez6Yn07MvGq{_cMB1gLv7w$M;oI$WOc=C2mcdO+_ z%}u*gk_9o8=FP(Dz@ZY@lKRCufcM?Z#6st4U@DJ>EdPm zUu}%2&*n4?iGdVHa;Rg{@!Be@kFZd{>?Sp_rg!naljE`uWyDM6HIxr;gzsn#$EXe` zThfFV>D|Pv=re^rG51dp`PdD;p%a0_dNA);2eJ=^I?QKuAK>>!UK!jMN zi!3EokaknhS_$!;YzKL(b^tx#FAtt^2(MM zawEi=a)@A+AA)@*HIZJs6W`R-oNnUL1FNh(fxo5XJ&Y9CqwCujuJRb&0=M))sI_7> zTn(DLGGVdN*S#}>T_Jy1&<;=~@9JQV0api>c2pYnllX~~BWBXa!g=34?pv&-uJ&5! z!CQaVFpmrKu9WleCE|=**)WRF12*RSKERZ$CRz2SvF5Zba)&$N!P^^ZSP%q^)y?Wc8<&0j;< zM*%P%w7Zf1ahevR;_-V@hm8Py^e;&rjuE&yhRZ#9)BwYRr$A$Cj;cg=BXn-VaEYOE zPA>04(55tN5%bL#T|?!;iQ}`wVZrRzGvfpA3&)pQMa`}afK{Qj#SDLD578=1cpJ_PGjU7_mT&%BbdphI0Et7K~O~Qh24MR*0gyV zYzrM1=jC-a0%3c&97eWhgBG(p5Nj~EM3iNtfNEQrqwz0>CZQ-%sYmOiyjnG@N+VDl zvuA)nke z)sWCY2a{t1Bfp{+p$r3ym~~{*siPX>jF%S(S(b5yH&H)C73%Z+%H--Pf!pRV=b7Pr z{Pfca2wiylC(hC^&1#z5s=)nTJkB0qtb(!$rDE(#feJR~IhI`qilE~O<2whKh)gi; zRRd-*CE2_iw0thE&<>MV>hu&zfl0iaG;K~AUBT7z;H5|W#KBdF`N;#U5oW$ktpUq1 zu8@Su@9ZRtqzXu!?eN`1dNZ-}@Nl=a28P}HiOZ}LJf-x)mwfh385D#9RTyz3T_;TF zIno1x`Jl;>$*ui~6RSeM#85;N0Ht9!${cn!g$iR+t|8mUUVCOh!>t-UM z*|T%?aJPXzbqQS*NqcnyBTh-^`^552(`j(eUY?vNfWn;E&3*`~$&*lVu=Zcdxunw7X2Noo?SH+~BHyr6vFDoue1ueptFOS=7F5|E%=bC7CgU35hs#A zc|z9`?syDN@a&Wck4$~yoAD%6X0d%)J7}9BWU{I)5$6(^K;4AykS^yi7F+v;8$Qsn zA3gCHF39+pPo$sZ)4c_O{Ex^RZhsdsq)^Ac^N#DP6Fxfu3QH;cm?}-)pY$+vhf=Qd z_*8g(1@*BPo-e5D8yhuL_VOEjcvn%l-|*tO*uHl2H^lTN1;GNLX$jygm^@0nLkcW3 zwudzrK0e&HGhwoA_H|{P_h?lSY&e1RM6Ouoa4OmXCD&Ie=9A(d2fopRU-auiHl+spWzS6(Eh+V+gLNgCt4U%ty>qc zr7!SVhVgN!A7e}QBG@F(uPMO!I&z1nQU*!t>!{p9$sRpc!P4bR7LB(aFjiC8+Oy34 z_9Sj$q|u5riX>83X1F~=KKh1-kAcm?S(XjQ?Rt(CgXTbf;^UI> z*8POw!maE0-!l}IaxyRFsTYCr+}y{!rwMwav;1|^na<2`vb6U6PQ;+IsKIT!WLkXl zowD#s;;sy01iJH(f!Q{wxvm?~PD;K-7dxQ*WOa+@e#h-k)y}~mcZ4I4#dFL2sw_o{ zfQ&<~Knom~HRFRv&eTl^_ed^Wy!zM?^rLsix{RJNck^LA^?O~L)w}nwH?L*BF1%f3 zP*gTwDFT1kxO>1m@coVz&+s4_A9*=y&Wo=2kv=?jZQ0#r;pL<|w}NYzxM$n1jCYlM zgUhHg!VxU7k8tMm2Ez|LwJwj?O@^l?iZ&jvYSxpD@i18X{U(uBf9D~--%ts$=P<8# z6&+hf*ve?6y!;G8D?k$7g}9yn zK$!S9{)j&c8h^oo{~%!fcfy4KXTgDG;4b4%mH;gVcn&vCL39?AQ-K&Ed|1abTKY_uG$p@N`P)vQ(u(5O!oR zOm1v(c->^GWV~sPeRx;jUhB+PTg%=jt+tDq%sj1p@~ruji{TfK@5}c|?L@`Ev1)_3 z^cr(I7PlJQurjLqL2Dk}F8(w$@?0ez-t>Hmk&B88VTU}bHNB!}meu@yVvOv>@y<;o z<+L8#wW|qj*Q~x;^nR9|c=#l1ktJHAYiDz*iT<@efVvUYLumNNos7k&oM_o^jUq3; zF_Bo|b8Y+Q<)aUb)V``szs$>ztv#2Y6UBM3UMl?d@u=w8i}y+y_bBE}^!vlkKr5$8 zjE$yynDADGy7B$aTXISa_T?|k>XCZ<^gevG7+zW)d0;|$%>LZgTPSh#n;ZO_yEf@} zcP)7%BFP^?$Xy!h?8*nxRFHZibBj){wSPr~>iu(q@*JNWzm;9|rHK1GctPQjSBRZ? z_P5j)lX|1r>MQv)&!#6)n}YmpTNR1E77>$r^-da&%X0OK;+0pe7*qM@NN^c&l>UYU zzxm)MPm%MtDg+kQOd0qrsmZ4sy6uX>Jf%|Up%~HFo@kwjA-$k`2UnYfZX0xTUwE-P zG$lWM1UFw-cJjE47?+Oj+|5^BWvBr6x?2K8Qvh+Ap$rWYVqpk0d4&cV*1>MOe^{c- z4x9g6xWpdYUxitCq|*@snS`n!JGgb7lpvV106G4={F%e(r70RkCh|+|>3y%#ls@kK zpq6p$_{XgrqXD%#0B+cXyycQOa20JKv9lvgPsSUISXA$sVKh#1t!dqx8alW+JK{i+ zbLP|ZZS&_A+k^AP0jpq69D>H)rom$%CdmZnMK7f_)pb^lOxeFYi4wT=HiWQ~UgwI{ z+}u6ajpATctvqwH_4VTfr|%`LKKHDrX!;Ty!YyoZJvyiR^L7KWal_fg?M>BRZf#Uc z4IAHEJyboEnwq-c^=t)y=X6lW8OWC*4%CVwm~+|=np9|DPD3abH4zPr5!cD{F|h$T z!xhMW&VVnJ)PCCURi9Rj&!hE^9n4tTpCYRpj|9zm{o>gQ?crmG#fZ}^Z`Eh``ACgW z6X4aKheviS_uUdBbf9{@hI87Q^w;*=$LO45iEp87);()fwd#;J;Razg2oamZt!Q6_ zm^~*x8D=PziXxn=2BOT_V3Cv>hW-Rx_sh`S{?YJYCz1TtKkcNHe*&rOHc7G1ZOIw zWy|HVm+@#OLX(tFaOcsSi-;*UUsvnD z*O>T^GeA=PdDsfy)iqxNxmD$Ql;9D%qEn+)>g9vS&S=$kepI{7t<~J3aG^*Jr8$A_ zV=+yvx&y~_Ffb*3!!*1O8F){bUQbI?pVQlWKcj4vY3sb7qyGHXYQxU?x|N4~$=E7D zc~>B*zmY+c3C;p+8BE9;6#(|Nm>Tw7l}0s=6UlmJiG!B_#^ zSBkgr?ithbRbJzN;`|=3g?Ke&3*RLou*okl{F|RBuH{Ate|f>MeEQW%P+ut+T2`sE zCv~>84mnmgY8u+E%gAteCjJxmZN?N*zxbL&fEou519r1RlqS1wspoEK9bT6y3y0V) z1wI{%4rz@mEsd;fi?lKuxqPbd&ZqsG_A?5=kUy*h_{8Xup=dK@R+zryrd21j3tsOP z$O*;I`N>$+0f!jWNoQu#%bXwkk@j)V$v3>bXlx~-66QDVwEpVWii7T)&E~5Wd&1CrZY9_IZfW|QQ-&8YM4|MUF zY9`a>9QtU654XD{1`1H(-u4a{T)ceFN2j?;>#ga^bKZ(gWi%A}4$nVYq*@tMoMf{k z{!B}RU^sB^BI;SVynGTbkhTSO>=*FZW&)Qh+Kt^f33DAf&@i&5C@gGvY2NTLAw9`U z>kPY31=WWR1BGfC0hI@ylC?Dek%q4ah_n!(|K0(v-)#6Su=(DHPbIaAc9y2zf$!jt zuuuUompqe4TL5nf86r%qEeD$RUchZFU&7${pUo`J%+EBO7c{4WBuyFJt}C_miQhx} zL5qctm&LfQ^?G&HQS&R*8Pmb*bc7vzuxHqq^gO&(@M7?@6(NYBFUYr@!rMQvwYk2p`3!x~u7jl0Hnjmq& z__KZ+|JYL^b_<1&?G(%;sk(xiT0_3y!Tq;aUto&n!1hoB&5Zf;%$P5~hE6yzswv2| zLodMTgb~n{f18{Q_3!|FX1Et-hP&e=Aw|ogR|nNkIsyO-Fdkb3#z%Y7F2p9#6*$E8ZW2dq;gv&Mqj92DZ@hrwQ(Q~TqXWn?_cEindqP1*lcH;zR zR_n^UrR!r{grD5H4PCc}Z*3@)e~E+X2@>Eu#^B^WfaJ>Kf?U9gs9uo}4$vMRRovC` z)FnYp<_65#7jAdgJLH7y6rr4nsM2mvFgAYdI&sS--Dpc9za(rY^Qyxa+q;4}(s*yQ z_XRrn4hI|4rC=xK^`E#UzA1hx6c-Id?eeP6C@*0Cd-%$0~>)iNL4 zW7+snWk#$J)r_WP^IPH$J}DL z3Y-HbBNxU-unmaIXp28vph-C>cQvZIDwc^5c=G(Qert zJ#Eicd0JI3IV_Rh>Qn20H;=owBjGnJvBb~%Ke&O!S=3F#&GaCu9FkYjyeUlTdHg_3 z&}i!IS3~!#O2(9A&+Nuk128nBl7P5sH1Eu1UNnqxNdk@$MyrO5mnVtm89Yf^FvR&B zo?&lr=lz}B9l@N1l$flG$v{anv9!#7u zhsRJ*;O7}tZmD=pm3N^}1~c~%NAN<(Gw&Ns#LSyG0Ha$-Bf_6J!nvU&pN-fu`kSU>CUg^aSq`VM-E6SZO)bNLnMr_aclh zswasml)(TQC=fG37n;(ipFHN) zT>+=T=PjsP!w%uiiT80A&|WyMks)$ zmb}Fx!H_v2%nKN%kPlfO7zc4VM?lV%Y$%s7y4D-1g;DWLLUlWk4i;S(?o%w*&WB8` zz@W3$CiSTmge)L3JaTfM@!E7?1|&j;+(XtXL0^E)ZD~GE_#`Ai^M(j%YH0gc5p5bc=c6IlIi2S`hmj z$e>#8t07hVsGHCPyvTs&xiI6k%7vEH8Y1HkgE=p)YAlp_ia25})biwBhpf$kSkv?B zk|>mU!R;q*8wESAt$`hQ@knfX6YNZAUN^}Der^#D2duTn%7qrxul<<)o!#7%Fw#cN zqc!I7?Fr-S11IYzl>i+b;|P~iKZ|4M-k~0=0IQ082|h*%KYB{ITd`QTo~ar#7XA=+ zqBYA*^1dWO%d4;tWQG!7Qxp?InoC56Q_iMb@Y!@N)mKIR-5ApmjngVvk7gu5#I z1kp1VSz(AiRg3QdP7n}@XpMTLz#Z=h!p+oDT4O)|B4J#)9BFT-i}I6bjX(IVtMuh0 zusQ7n5reo*oYy*2_B2~;#t~$JDict%Em$3#Eg`~NR*5j+&LC&J;6tJ(66l8$Rl^=v zVSbT5^*uQY5XhtTY~Gunt2T}oDyj5y!IUAw6thL2>$`Xhx>dRz#?r3nUEE3 zgU*qg-e2LGC3PEoz}(H5oJh#t7>vg(x?B4Ln8fnAcEEL`4k4qu)DIn5ufeCRE$3ZhVfA2%kaXCggC@bC zdHg`7?!!uEP&TOwJg+%*6XM!#0e+ekem1ol$|@P`^n-YgG^{=e-(6AN9yH=*#Suy{i1I^gx%ahDJx(ao+BXIEh=;A3*Wg2}pHiH!2HZxe1R zs)9@JIZoWM-ThD8$32@%pVlz8H66Rb(0XZD@1sJEm z6tLy?QFr({E75N%Zh)rb3nAeNrbo!gH}1kK-1WDR=9ge%@;X5ek7mjVmh6FQ0jJ=s zL0WiEL_Y{#&qN-NS=i2lkbLph*kXO&R>81b2tWd|f6Nm-F%*}I75~aysmdA$=pw`( z^6$pZZ5HQc+yqmV4L)Wr%yIWUW8mx2We)bgPu5Rdj$=qS;T@}sS9J@|KJj+O$0=-p z>?zm5-XY*Iy%}r4`6OCXf9K)BP68g-H^qTZZie4TL2}rp*y8QH6+dzLX&szn74%f=$J|h^i@1j+dv)>i`=ze(`aPew;bW_JI6-JnL`DA@MjP%0Bft}>i z)qp215SDcy$^cE)t;GaM5$6Mqr z@fyWql?HgFkcO!nf&G^XkAI4-uXg&>8NxVJX z5~Hz7J8sw|1?cNS-*i@kp;lo;(S2;=zdL3IZ)1*U2<f%uafX8g`{?gOv*$%Y*9 z$v4qph8P3$d^aQK^t_0>2xi+F;ZZ#h9?Y%3!i^1vzOQrv{STL79nXPyz*Nc`a>wkZ zrwvtkI({~&$n_k+NxWooBaz#a-zcPpE)uqp`7DFW;*<<>%of9~dM&{0To+Ofhu9?r zWgnTS8wGP13N0cy~K zQ)QU_jeZBnpJ2UUOjuNrG}MneCXS7W2IHX$TuE^C3n-5*UM$m^4#LD(3iIffeAT6?GvY*iy%Mb_!P(4!r6M(fd0YaIAlgZ&?-(b1 zzEt;vWqOS{o5D>3W=JPuLVW+=O2Qzy){|g)0BX?r?MpS@pv{Yvjzd?gySYKEiKIJn zrwlf!!}G|fnqYs|Jw*Ux`0dH6Nx4?cb#F+zVvJu0XEvR4NPcdiw__gt#u7LP-j@vk z+b26vpBv8sWV58&F(=Kr$xoF%*?gKI(kxWJN37CIvOfQQ!S4h2ld7J81p-UXoSBq!15EStX3EjWr~A zArsv8*VG4^zdgUKh9tT`-zQP;%j!Q2VtWI;z3fjxe2&}9F03l2-3&)I+TmT6$s9mVqQWi*UOsJCmye3o{y zDkTo{5V?xfr2Ja-_oB5);3QaHg}$HZz0{z8MuQvJO*1BP1T!l>bR__vT>b`~0_*kw z0b6nx;TDri0;8;SggB8zh@(x0GsZM3$cIDRr+I`qRIt;( zhINrq8EaaI%ev3LD?|7$yonSWL@x5suKt39Q!$f%kBNt8tUb zwQvXB43>A=SJDL1g}cG&@G;`Ism6!Sj0!-!)}p(Ij$jvHXm=-w76cC&BZF-5=>%Qh zxk$aY*Ge*a1<)d(N&f-;DL^jAu|3dB;#-LR1365W7kUwFfOs%JWZcpV5$9!3a1DV> z;(wGTdccH}Ux?19pf?Q@6h~&DIl)w<4UB$o9@6wdWMbmZmFqTm3X%y?7dEU7nC*Bz zVszDUX|YWe-Tt^8jDfjtAjR=cinKj;U8fybDM|-u(%&f25l$P- zIq#|hv(?&c)GVYw@guH<-Y&Vja@Bks`!uL-7cP+$FiArtw5RX@g^iieqbzD9x1D!zfICSus3&pd0)q<&g!GoVJ<<$EuBOZyI>wQ-(Xq5c2gL`-r zO~UJNe`1mwjd73sK>thx<^#vp&jYh)nDabgP(J;QpW>sqrqfPxkxz&e=cS+32-!VFdMb8@94fT zuP$nhLI<*Fq}oy2tehJzpd9AOIFpHEhh>Rh4@>mfm$4c{y5^*f7BjmTOXv$tm#sKk zlVH!ZA%5fssVNY@zPx{okU32&fpg?;>#t1vH0pUJChAW1)S^eO%Avg~3rV~cXZPMS z;BF-+SJ5%1J{H9#kD7DkDg@zgDLe+}=tq#@buPWvV6-TmTDK;zB(x8=!|{mGUK>-@ z(+dNZi~k^vPk;3qCetB2?AnHFBqpNAYF$S>tlWA(de|*lNfa^c_>T$y*=}`vCB#wvD~?i>sAAc{9?k7!xD6i%|49eb$47x zm%fNt|6*2isYdk2b$NM8XLI$o7!gDbbD5+pI)$>EOs8i_lrZJ2kxV$8DYuL=>XR7h zV%R)-wRMHca_2{PulI7K8qLLV-%G^QCZzsLC3g%BMET5~kUUY)2=ji_FqEZ%-lfci z8+GAVt)9Qi9mSd3_iW+3#RI29H+t=MMJPu#vB zYLZmWv>gw^NOT}nq{qNm!~%gUP$#Ig$@;EOus^HNr-taQ#^?JwgRslH0so3Z{`b(y z|AVgQlS0X32Meu#;?8UaquU>!{{2svl2f>*Uz1&FYXEZtlK%&7016BtVfS{Ey#bQ) z&w2Dvad4{pJepb#ppyXk{CWFKz%R4|>U@6pdkwnOuzT$E(1yH>_PYwAz3qlM(;c0x z5KI#Zx@Ji4EL!hp+1Ic}tETjJ{58q^p73qX6IOo?V08vqLZL1a*k#utTmenQ=?V20 zc@j7CBfc@l^{X?EGVJm|%UjQ{X9(;H%$6Q_q9z(Jq}Z^XYOzCkoVX!%E8KX#*N4GY>gBQ9&+# z!V*c&0Bx>WPrJICFSTm=ptNwW{FXc4eYH(wzk0csQB`Cji8FSh37ke zEF8Ak!qW+}+E}jF!Rm-3DMy*-!Lu7Z<~!SdW@Cjl0OggvWDB4 zKrM9nF}(&zbd4uIP8WHSv$luCokr(#eW&F8QZo(0mU#xPp#6wfhTWR4h z9OpEJTdUZ{D&KSMefvd6{PvW)e&De}}i+x0nEe-#lh8 zb6}}0kc?`6(-zA#I1It;Mz~W83{v4eaeTfBOoD-G=Zsz7PCypT43_vyi@@TB*{U)I ze_+z^BKYh2a$t9S0mOQ+eQ%J<$rJNm13?V@fy4l7*e7LKkpY;@f7=h?m-e@bPv3}R zCNU8cRQo5+=rJChO9QINi(lIZ7MlOuFz|g#La|sd#d2J>Xx2rDD-Wia_G|Nx#L%)M zW-}z;H&>uROv9tU&eSofhA+o=w?=R}>a`?ZxdGX@ff8s(a zGy8rtzL6%pI>T)eK=qdeUU9`^Kza*0d2+C0`4!!Zo4a!F6l%M^TVry^)GvMHT#&d5 z&b^^{(JLSk8w}v$q9u~x0}q;;yT-ggjrwbSQ6LuE$-0eZ^z7WdksZ(G0WJvjcra3_ ztFU(+3aDSNwY8%u=kfe4)VkD+yn7VC+)k|?fvbsx@Y@uvoPnrJl`$4w^Q7t)z6F_g z&SY;gi@He>^e$bok}!I}_ePAqKtAEBX0|NJ zL^)&F=8lQ%>KU9F{PWu%JkG!B3;)~yX1u32N@9CiAhJ*m60OpvzV-a|(zT{MVLV2D zR1<`)g$^ZyG&|yrwto+1G(YMvD^xY%LPZ%?mea#eAWJO+|W4t zx18H+Sz$kM!!zE)8KZ;6;ILh(4}Amn4U#Cd<=xxM?YqTUb1}^k-o(~yGwU^3=%VL(+}KpmcJ`@wB3UyGGhITn-F7e zd6nEEpDxD2!RDYk(Qx$jqnr?e_p#<4?^#}>N4zXLS!K*Qr_-i_^)(Wktk+Dd@0qo~ zPSkX+br_MhdGx=4cJvXt!5{Dxp=1-hL9GG4K%QRRz7Sv=ff2oiW@Glx?vi&_z$G-s zfM+Lly-ylQ`lZ0y4;E~n@!zTGU!z!Nh5tz>79CpUJXX~OqjW<$h_TiJzUj5H6RjIC z5n=e{I{+mRqkB!og-=+Fjvx(yD%Q-A0R>e5zw+-AU5457$m=auVoAsD?YD0G<-!q* z&gkcd+Z2HX@K0%(0+;~sI%ehze4w^~P~*R{fq!}~1)I|Rz6BsG!2DXoT%6%IR1dgx z7qf>9(rZ!4@IZdbX8@I@j~&(rs`(kW_Z$YMiX^(mRN!QA0?3oH%J(9Y zmguafz~3%!kQhd>H|TA>5wY!b>&|$$y{RLm>yB#X9HLJ8aRfDNhHf{*38eddxrR`IruK(H;@yFz7!aSA!g4(o`vW}Cm?lgffyN3A(!-HdZ|9}Gu!Gy z6J}I@i@}UWZUP9pmZ_MTZvs}J2jn`S{j20qJwS?6?orAOIEz^!B63JK^>w-otd7^( zD(7sc2jxF_3gXt(($B;@5IjMjbu6tVnYmymQ0b zmxouI2EM$xRkcWS_89u;T(9rFC*8?a-oo{NH+pH3rK#;ucE@e_JSE6dBfL;LanL(~ z|FUb|m0N4SJ+Ke5jcn+!gy{GCWg7r9xbQ!$7~ewTYfkDB!A zw3DN8MRMNF=7Om*^(#lIl5-o4yiqD9` zF&!kDe+!X#?rXtwi3+E`9Ez5|akOPHWn+tKc0uHvjq4*VX1|)%ba|UsNmnub4}t%H zV*lO0@pqXss&E$knS3lh_{4}cT1 zC3dEW#%XogCsl)DrkrwuS34ZenOyslr(}2mufS+ zKX&0o9)O}IRu+hiL3Ty4nPC1|;Kcm$xJ86+-47 zVk{v~doq{iAXk#ZB~LlpjmoW4d{w6_t%T>FIG#c>g0xfG3>B%L=_@dmdEfQ5Id311 ztSgldLWHXl>rm5mZx05ttEK!>_>Vd4kt(hghZY5epgZP#Mo%gou4mS{2I9N+-jxLl z#8x)8na=y#6}^SDJvBg%(ItT^hl?Y3M-t@-;vsLlD7O!bgoq~?#oDf{b& zi&1UF9v1>C`DWD8T^sVl4Wb30LgyyxRjqP0>A3^Qmi*tQNEmQQjx7{OJ zsGp!&cB04Bg##V)UNo?7!kOobqH@HYHWfC!&5v}yxhLyl3zH(K{G!<*K9*$;>>|&x zdcF1Z?J23KgpZ`!aSemd_3}@)>goAha*VHlkEa*LM#xpW9XU4q%T9B|N)F z_x78IR$5uvYNkEWkV$t{HudU>x_5b#otTmRiZhp1a^UMA#g{Xv5$$W-P^irtF1MtV zx2f!^`Juh?V;F0CY}$Ofij%}nkQhJOIG7`=kH zxp;EEMI7z(d8+;F=CzRCBiGKWl`mBcJ$Hh2aH&a&XlN>~_>$-$>W-RhIpvH@0_EEq=UP{UP-5tbBi3lo=F&&x6hAIEzB}hOw zhg~XC1w{Jpt|{O7mfijIXlJ*#jyLpe;|m^H1@C+P?8&vqfva&MGXV8&5064l*$a)p z2D8+6p2tQZZu6>*)w}x=-a6DYpT`?1)vFtRJr=OVn{IAa3wI_GvKgh2v?T)bUn9r( z4el8Pr<^SMfkKC>_DJcSMG1}Mea+fXhsDp~cIV4H+o(0P&BA@?Q68<7aU+HaunZhYhJy1lylaHx_JCcz z7w#&3`nY7j(z=bFTlT0ZM5a7AjK5l{^%Q0SXvYFnliQEVmRHI{;hkTp+ff~o&$(0JECLLZSh@X*KN~#h)rFKscp=>=qi!<5jK2*6(U{AG24FP zxY`*?Q`wX0%Wa1S7v7Vtw97kwezu3OLVPMV6#XE&1yRh*yIHq#2!Z4kS`PYKc}owT ziVxL|G<9IS%UIi`k@e-^U2CiBZ@M?N+~0}2zJOK-hI1Sz<1xt6MVTjvj}5wHc0!lUTff(Iy^IPc3TdRxMHp+wwmg|Gp6>vxEi(>DZOVE|ftudD97PuLYE%?Ss?x>K@D_8YU zGYB?!xN`or+~86L)d^X5kf8Pmy_s&zv&negNM(5kG&kCiT%_~!>JuU& zRW`1QRh{jUzo;bLVz%wg9_%Vs$;_StY{TE1MbjpPknzgA9M-LK8GZ*;pS^WE%l~oZ z{q`26s3j{}aftBA6|IMaZ_&NeGukYpoQ_-z8MXh3+bi@04a6{h;#Q=yIG_M4#82ee zhi4NOInlGe$33u&ec|HlzPTtjLE&z>)^(f1VNk_UL1J-2^9R}55|Tl>PaA+CYS=Ho}DRiY?vl-_CBAy?dxIx1wf zRql8{4!20oB)Ab8dfnUo6@+%H6!D54B%Niu5AmuzHW!-Dx74KMHY`(H`zqyuy@GCu zt}c@DpW(@>;*%s$C1xpMq=jq07co)H_1!JHw|OKjdF7GweK~Cv_nz!hete-#2sdnZ zi$w@V7N0sYHLC7d@FNjIg75K$?0hYsx5FvJ_BpvxeYdC|cUCOd^lv&NrakfbUxJLO zQDdypouG!6is*rsDn;MLO&NQWyv9YxIAbFvJ$l`>JNefau2{Z}xoTI+>t;yvBGZM2 zsM4#>>#<50H@Jhviuaf07GPf<^qxEF9oF(;P3}X+?%qn=_Z>6b2Tbb$RKETv?jnqA zurGBu$1YY!w}c%2nzohy@mBV=CCl&WXB51?U%t%S)#LoCt&wU>Hc)~xiX}<22AZpa zP+2#PQ04mBmc?OySB|dqF){nBUDWEf?Q>E1yVi);XH3_uyeuX(Gck6#6n(YE+Jvrt z?$lC)tFLFfH77k2Zw^I2iBg!I2{z)0c$XD3xOh%YM`iK0EW_ii&Rg^9M$}iXJo~`J zBGNH>b@mZ4TEV#!?+NNw)LH`f1fF1(n8Be1yE!hqoE)PquhO*pdCwUqi#cD2Nh--h zs`-S1Ha*^CSM+Qi`Nm>U{29K8zb;?&G-=d?`y9@6eWLotRPD~%-Z843%t)Q(!S{3b z*dB}h{;bE3DO^cyJxpyVR_C>cxNw5MUi8)B`#jy~N&g(%SA9+S_R1T_n`Fw*W*qY* zKS{RBa*r1OAyC!&SF7ZVvLf-GoI8cyZDNk7ok!b?cJj$U?VaD*A>dI&tCX+NMvH)` zx1Azf&;;u+4vC_Htt`Mx2P?Gti6ibO8~knpJp)XjZNLO7&oTot+&<$|mQ$$zBtb9% zj7mmM-~O0!(vj4)dw>-PR_AYF)dPSX{}xx>JB2Q_!t{#)n2K#p0M$<3GV0|;Tc)RG zY*7E{+OB^SRR6pGcWpkr)%5Rb@V`}wXMTr&vj0+x|Cp`mKU9bRrY`?c4QBtP7XQg# z@E3;ezl@>#KcN=?-6iu&o+9gnUoKbyxXmrXu?-hlw*c#-cZ{tEC1}bn!2>ZO9D@aL zGAdK(t=O3)mrn?S^-LqRiN+BxjXyxFP~f!)I5jLF1Qogq_aI>v(R_hTbds5!o98u; z)uHp&g!doa^nJwWxOh4#&$|Md7FwaUqC8(Wjgb!F+9n%g&g00Mp_r=AF3O_Zs~CP@OV<`2-CG(_Q`vid_1$XX>hO6l zU-|1zzR2J4gZ**_4ra>l`H8znL=r|h(*n3KsvF{(YD{Y~q~J!UMx_Y7dtpyPUp)sKojW)OfNxufWi9=p+6!9JMZf!G_VG7mfWKxMc=I< zhpp8=OkVpjxwFvqftsWPXME2_<3(z&$ILoZH|GOfa-9Xj=1h&u)Dqrs5lQshG->x^ z>Y~8=$QkHN@p5zv7b^WRXAr|7o(bjg0|gg-?1I;f@9SAKR{ay_z5ks4+uT!G?7FP_ zE5b#VW&Ni0qj80qg||5Qc~56Yn92l#)LQe-pMSqPVBYYcg+a1F!B173YsWvpMMMDd z)R}0gkF4TYJRmF@T9(HnI-FB~dC@k^JZpCBsb|EkDGIsE``1On*973?P2md52xE`v zOJVlopSU5&g`5u(E{?ln3*3Zzogs0mL<{0vCP%UDA}g}CKb})h%5=6ioU_PBYtQ9% zYr1bp2gDt%_EdcZNPyg!RSt=xVhQMBUepbpnc}GX?H5fw);E4^lJn-a{?*r%75j4` z!Jfd`8CwH0E`uDvr58pieLQ-Z@B1aqKAUY+PkpIBb)%u!b{$vOVazWjm5{|mWgp^} zcBMT#@^#Uf>j*xBcXUd8iohVxl%33z)4^o{iHs)L*g!{iKxoJTfXYYIh$2~M5~@JQb|*^2_^!?c za{AIb{zx{WaqX2E+)223*%AcEqj9EwyDUOTZ`}L?x*B?xpLg^B(5HZ_mY7%*Fi(-r znq>5szoWkTryC4(Nfl>rmgnYhdU|PsDBZzmn<$ojQ0Hje(z3!^^Gz-;PPkrL ziJuVXkme(ll46BARH;*>*RiiAJ9%02moMLDnJhH@D%RQ`dFa%wO%;)5R1M&QHP__O z1!J_IxFf@%qOwsV!WZHwjk~kF18m{WcmY&?G9G)M!>b(_A2M%Q-M*sh{L`1r}K7TSlu}9V+-L!J$=+8nVkE?g@I3Al*OA-ko9cqLr-WB==4#u-J#(KyFX&rvMLS@e-c z+k~D&kXVi+DUd!l&HOlWFD2fj?U~MoM54!7$ueoI;QLwQ&}|E@2Mm=)S#{I!)G`na z4v((5*sg~B;38LEbOpoMmxW;!2!r{y_H{+R%upK=;XN_D-s`(tB>#k$B&Z^0i@G#lri>%Qgkaz?1 zy;4ZGPdkzo($5rD_Ki*Kusd2V%Bi2C>N0{L7e-T6H+w{Qp0kr221ygDEEQj93mk4K zizZ96y-tYl7*o%@I~~gViA%ZqrQLgBqQvBxw4&Xxm;E>h-AX!k7=B3;ee13ZeeiHD z=|~j}HqQc75A+K0y2;_?SZp>~wCa_`cMYfCt{TDbM|mw+F}O;2b@U9itGhi^HBoE= zKs64FwJJ;v*R!k1c`9fO^iG37S=fBLpSblN9F}l_GeKaXOubcWBwLLPSIU#hJ7y1KJJ~1GpK?aG z{Ww<8Y-G3SiJ4~52XVIryTV6IJdX1^0F7z)5Hk8J1~*;1J9z1ZSk?E~p*hiGw{x~Y zTcES#K)`u&J1UvWsNY}$N4_{L$!V9`Ds{KwFFu{KBU(oFwG(d4-P#**YegNkQ$gnk zdidS!{j=v~RLQ?uyLR;0@#SJhonqm*<+GTE%+BZ&1uo1HN6vX6M zvq5WgeN#`U!QoMd^Wn?yPhS|2Tli|$kAv6We1V^P?^q=TK|OkPuVu7Su5G^ZcBiBN zsWo|_+r^*A9L5_=r=aKTQJ@BExuXW&eg*^L({-YNNqR6gSCnPArc`L0lNJ&lgJG+d zO`Ry)y)2b|`SI&;puBl5ouwbW&eeJ-{t=EckalVX@qy(wcDM`Y2^ny1DPs z_`unAS>n}E)A#+41(z~DQ-IVn;=xnnpG9u*G>`J`=E$oj@O>7|^-9{GP?!_Y<$0=Y zao<|I#;e6rCvW@ajL*%Z0N<>m=&>!gijXjttpunZH@F zRqTU;Mf*=&hQ;V-4!xOaR`}Ipvw^-r_Z>ws_iKskf=zu=T&jbIzBSHmToq-r{o~$K zRC@`nllUS7aNhss<@lTO2w>%)p?^|lVXG*Q*%SO3fF`Uo`X&cE0J)=gNppb)8wL*y zs`cm75a~&g)Cj(UGzopyMG3BqtIKr+~la`tSalzYC`SgD^vcpI`q{k^fSWK?vGk zVP^k6R%h1#zdXl(=S06~#Q)tYvcUjI7qUakqK`0YAk?L{LDJYJCq)%RnHStrt|%QV zc|5ar-8bz;ThnZGkM6i`wR3+1dE0SE@vQGF`2gW7-p}~mPaJ~LwKx$~1gHA9?13qe z^heE0j-Sl^f7tuZfTp%J?I=w^L{LDaL@9#O6a=J3RHTUrDpiPzh=^2aQnC@Gmk1~d zDp9J45R_g+FCrjCkY1&igc1TNev5PG&fMcUbMJiLd^2?C{dtiASH?|R5%Nk1NITD!E}e#WSow`;w8uY>2K8JZuSyk)aXh{REu{by1*&? zU_($=^LTex`Lj-G#~hJWDXZDgxj*(Bdo{98kC;w+ zNEV=+gZgBMIh-LXmUxo(&D6< z(9^RGGoBI>t}MBu0ZL41C~nl3UzA7(_$G?#94^=OgAyR8-Seg9NUO>a!7LwWcf5xp z=d!l(uKdlLj~G~3QgWNxbeeO}W1b5j_GaL~Grk!cQf7}n=z$r_=JauvbdY~#ymVmk z@O9tR{KSS+mI_hH3N{y9s$R1XsP_@u$28?19y{~uy+(C|%Ph@@CQnLxPiw^BFPF6% zFU<`QALe=4B=jrLM!qg=97Y^nIh=bZxrs(EdIirse}Vmr%s?DXA3l!3g-pXqD<+Xp zwInpzR;~hORecaD>JC?)BJeDLS||n~f=9@MG3h+TA;1p({q` z98LurogO8a4YPt7(ienb=hXRU3`y2i5U-m9op!iZyovy#PPw(BR5j!N)2Nf9StTW> z=tSbW6HlXvK893CrVY0@nHq%{%^25|MSbB8FAE-5)ypoSD}l|9?pusm$M&HaX8URA zQ7Wqr;dXLqTait=*}z@z@CIRvfu@_9NzQ>w%(r%rdbAyV*h$`A%T(<_jAmoFKqRbg zo=fRzt6ZdhP~VH{0%|Cd%v?llwVg;HnF-CV8*9_t2v zyH2+S0+96%q&)2tZVye7a)M+ve2_$*5T`hepMBeYUx4D;>U=mqMu^#IdQfYBo`bvR zVAHOVd}juIkTyh+`hahXHOYPy9w~%332UY7E1-1h?QFRdaVVBueOG!s=jW#C80Jj{ zJo9Vz&+WUQPq%&b(VMFfRckS8gAs>maUvb*U7WTh>@*1P!Evc7!6R?;-ReaYu3JNg zRvw9{HtG*o)xFsz5|APwK|D)z#hcV)LPnVLv8=xL2u5Cw^&Xwqj&bb=iC`zwT=J zSn@5SUcLrQH0V0$3ZO6DgV-nzB$qUbGy(NSAfrxZw^>?TweuL#IIloIW=JD0LBzD1 zHHi26CnTQ*y0fbjCjq393`j?uf>Fo3Vxe#hox2;JCo1Xk14&&$HHDQ`k7d=9O7U$T zP6??|mS!d52lAdU&4o<>4&-`Aqafh8QzSoj;YL4TSZ^u|M2JO7N`2rrxo?m%cVTq5 zZEMM$Wz4)dt$=N#7QhhG4NjydURg+Vweqbw!!-S~7rP9vtTW`h$WIGL0&yzktcP21 zgg{~u6{F5z?+pc4ih7j}7 zW0f0=WulZcAXbKpv4etNDO3Qg(f3iybA0{S>s8RV+;f~#?(40V1@wj-fjjS~ zFVlSzJ%K6JUPk5sDTvjMPIqgv1($(^YQp=+TdJe*~)THy=HH1?+4Wk4L$0tP;XKoAd41# zCHs5d@1oF91)K6@TUzZ87`#%M_T`{h111o4^h>$Yk*E~YzG@dAKR;WDVKH?>cJqUL zcIv3~5zFjyh5HT4R3Ea4?+FqakF7Ef4kMrO8kga>_dFPPt^b;)>IP&}cp`ZdX;%`> zo7$3jZ~u<_)k>#elzh_hEn(2nEqq-^_J2}Hl_`KoTByFF7xkt={szb4&+W#_U*3OQ z_MjfMInkvG8K9nS7Lf1IsuVE!#zjs9i?PCwN&86=8D}~Dl26atzkPAf?`4Y!q9VX6 zcjv|M={r}CoykN#$>yQ4ijAtA@>O$U@d_UnF+EhCsL!%>DXU86WKLX}HC%Pm>GB2k zK}$WOu6!TXC=-*?;7<*mM-s=UrZmG3q-ex0EuDFXHPYFMOGJ{67A@M~SBb#{gOGAw z{AcwyX_uL)+!U|r(;mDLc?R|bGt8+Q^;*u4;Xaucu>Qeq$yc00O)vLO z62Sj}C1PDNDh3q~-9t#!XW04Nv(o5GeQIi(IcefY0EI6~Hh!ZrOe6!MXK|-wf!eWg zq90^RP^+8w%*>zN6~g9Vul(+uA+hdl=$pLN6St2(Bx^ElrA{ZKzg#KUG$SjcK4XfC z{MDuIpu|aKgyaD${L?^Pr?t214tkdrUGgtRz@K{B)7!6dso$oyMEV zwYbD7%or|eEB1RA%Oa{O8G=<$o=MRACbh(hpUcKj^mrJ6MbW6=09rP7VUCrzK*!Y zsN$wdzOSuKC-$&c{VU12w4K83boOcopKek2pt$yOg0G6iUYzvAp{G3R>6*>LVybcI z`($CLS`WJ8u7D9x7s?1;vyaRkdXyM0tLo4&k~_;Hb%bapYPj6vkFfWZBEZKsqGjCm z6|0kubjr_HaGnb>3e>L*UeZ$%Y5V%>rpJl+{wl}DV_KI^FKn)gtAVq<`%6 z9_$mGqrv7$C>%wDzl0{5k(ko<1@In&O8HmErEJ_CKE+_OS1C@5RI7H^eJdCtKE`lK z^yrzZ2C$@pW>N%kFNgqQyvoj&<9owVigxCOac}Exlzl8C2o{{&SNGtkkiyHeM-MrB zy=MOanmit{VrwM;axdxNRhknrIq54&Y!pWlYp3i#JJuEi4_0L&JUjp8WN7LG>knO& zv+oB6Qa*VqnRZ=dDSHv;FRP=blT#`4t&7Hj61gn4xZ_S%v7>NZ>A+)^$9s}?sQ1Cm zPosu=lPG2+=mxmc(BY_qbN7Uc2-0y6(i3!-R+7e#oO`loao^+lrGm223Ke7r1^&iP zU84K^hwMJPLXZCVWmlz9zt#f`aEYM*A9&4^!M? zeAQgtGvRtkgz~pSUty-{1rOjbEjLajDa@mr7nx@=4l{ExL$7Q=dYF@+Je%LWipbkNxg>R8as*e=azBJ4 z#Z`cx{}R*8vxQBAF}R`Jy!v_EoWNXko@F}eJ0aKUUh51&WsLrXK(!z%tZ!orWwYx)!v z6jZz_H}-H5;l>L!?l*jUE^4pC)vNsCK!YDE1_tn+q+ z$cv7;=Q+$^_nDnb1~G`wRYfzH1M08l@#$)COGXNh-m!(pa*{I;SgnNoC^)C~{-7&%?%( zwrW20Xusfl6u)(>{23kHqvu>=UD>FYfM)h#*&niDXEC^u+(IoFcerx+>-y}t>Gzjn z67(kmhV@I6&N$w_E&A#O%TBua%IT3r@gFeNjthUu#{SROyCA6MbP}eX8oGv(ut`H>A*07`S&-4EiKEWBSn-4z8av6tQ0{D^hCau z-@387405~TdjYZKzs%9;Ke_K6KRW(E>;B=;IthPL0)ek~goSeW!33OBX+_Fk`;EbR zkzA$6*#i@j-`c#71vL8Guf~ErGw}sAYdJ?I-@XSw62y5v%ELf3E&O4RYMtsp5#6%$ zCB<9xJ9lgq#LR1zjN^_kA#S!uTJeX@4eud*cFJsA4bpMEcgvQa@-ane(0k{ARwh>` zMSz;_>pr^7i>*QSvxo&uw_13~OFZVhBkCy3vl}OpTX|lLx52gkN$hKQ@|t1e#pfvm zDo~a}H?IASCv+1d0}(WBALyG^%chQ19vPHxHZy|S&%h8`r1y%`FK^xlN}fJ4-$lLK z7XTtJ!dDFu_rSMK%ujp8kvLG$n~{g4gr$5#pw;5*5t4R$|MoK;jlcN6HWhy6FALE2 zyJK76fUvRRy9H6*z@mLE)MU3^o9f&GMpTBWX9e zv0}exGS11i;TN#~&&h;;g#QwcNNJ$yTIxrLI|1KvEm3!A{x_S#ar6}|!80pxlGrjO z4hgE#-9RIpl;6nq<@%kH-YPk0qXgp;LOTfBw!G^)82IQ`vwka7We2`X0oj&^;}Drn zhW13u3J?w%Sb!utRE=5R^aFZCf7=2pbmjbCnkJX24)d~%qlvp71 z&WQZ3)gu;gdN82>x>A-7`2y4sQ?FFf6!7)EOVd&B9pmLTDleaOorFGmus7gzB-Tg^ z@4XCMz}3F_mwoAPK39JUVQPLyTL6T_x);1@Px3GASZ?rh`7>#5`#Wj_Wi|hTyfiQ z9B8)nSm%*UQt!O+e__~@;#V?R@31>9bW0^;8hOE&rBn1vB^yajKS5VJQR-#v(K+nN zo9CGZxvMt-+^vCNUi8$x}g@2IZK!57!-y*a~pS{9~zaGK>RV~fHy ziCpO5H3|2E+^*MpUP9NLVK4PgpXBl$Y8Jng^v0s!Ulmac6?sOTM6l16 zN{xgptn;yn;wWk+c0%0XL<9ThDw~pOB~>>*Bp#0d`BemPfOw#nX8(!u_VuIES22|8hs0`Si)RK ze%=$X1^e}`-4Xa@3*bl%YRs#_5I$Lo7#l9ct*PmNY2ghB3EXzHK($pA6Cmvx59sF) zL6`vauz%hn52m)-3I}M$I}Xe+XTh8U=I#)0kSF=FE=FSs0m^}2m;nEXosNK{vY10O z`j&0|wx2ijUIu1(>ji*4IA=iNVyEe)&;;h~ffr~uhI9;0d3Kt=h@#3~53L;qQyXcY z%r81>KW(ryps4ip(n2y3_$!D_AfouI7V%)!6;bWHAG;@yLDaN?k-;xERGW+B+jtj?wmgmONR7BPN&t5EmdsNh{pqd}i6d!Ra_ zx*WQ0Ig8@~TSi}NXc353ikC*Fo4cI!3wnKzQ^O9CB1Q#x8rmm#a+NEJ`q^^39wo~> z&lv)gQ2in0MXu>7#MMg%`#uy1`jCU4QB=k1F>B(p;FobJ{^^(fdV{42MWqJ(vStL{ z=uf{a2wdw}XfzdE>j(UsTGrWGdtGsOJcb+klCs@*u8eGp?EU(+I}*Rlirj*WfD5ku zFBhB}x2C>*!DF^B`2Fu{xZ~gJ__05qkS-9>RF?!7=d1z9!(`$}iF44{@Lzt{z0p^L z8k|jG8};*SV4YB`P*!`ifwNV<9;r8(=}=bLJ#as|O#c*Qqw}`@?vW47*VbhofjkU5 z<;bvNmnwW5$F7;)`2L!ft&^v{bLXz5+t*_xL+503CZ#nFsD)0V0#-+|AvFY39`NyV zsuqE7K3~IRC>r{pPz6+0w+YIY$%|KGM=xb^>6ppglh@JlsRrsM!O>| zB+A!~RF>w;hnMONbqv?Zym)X#FW;J0IUDjxyM3#eMt&K6ib>RUZIC?_vh!(HKS}FA z9Uvi6nx_V4T}5BjHnuf8>b81{@wPwRdBi6m)twP%G!`IXYF+q{-sMaL{~gAi$&oO% zV2RZUq8JI8*?uI0Fwnp^)$LxCsHQdzFL!^sacxMDNfy_XfqtTRn`?__fD6C5Bz5(D zX8nS9v92-txS=N3n81zgX#3ZY&;ORXroXl-{n7PDwE7Pfttu@7F||h0YSpj+2|Z@9 zyo;1P(w2=;d=r(Q2`nB9)|)nC}W7-kX?IUib+{9>E^1}v)a|BTXz=6 z$>w?k8$D*Ssm0`04yDGCM!I#Cm6U-380tnlS(DalC5|TZXy8wDEyE`j6}IHR#VX9c z94xCn@B`*`-8+1l#zgy+BxJB3TaSqL)VkDDKIX}Y5y9EraB1jsOly&lb=U6x7{F+7 z0E;`X>_&xZqM3Am#ku@*ha_zffoV*v;0TfDBhARk*)&h zVd-0p;Ud_tT%d8Igef46A6qbrAs<-7P>+S<-gwiz)!CtDa{vNFdK=K5Y9hZ>_zdb$ zOuhNNq@F)9)b#zNa^_zIMHqfZ_8vkJ!px)fTL2Pr{U%>@f3_MVL22hfa0gfjyUDa?VK>Yw5w~uKXE=L zrudfR^+3$9?4+yQW#yQF@&v<(xQ}Wfl`30?NQ@$)z@XlVf4DirR}6n&d&fWweScJy zKo|#ol&q4HFuk&dAX_WWa%nRiHfBA3`4Fw{&s#ZDR z^^>yw?Z4cRK`qeRH1*T99qu-%M&JWzL%3BSXU1rUp?Y1 zE3-HN@DWaE^mYOeNih8FmOpm=QxpBsAb&K-AGgdu*%$)H2cm|WSed`y^WZ5(uHUdMWRnV%`No7TcLU%%kpVWgSQs5|a2? z&%S*D9hSuR;zE)_-^rfS<8mW@`QO~>Dh1H5vAN}<69z1#=?e#OkJiQIB^>EaiY!GY zMF{N`Q~)M`PYy1nM5dUG+N#d9@uj>4r4XsjKrG}_Orbs{WuwvvM(>evkGw#9St$k)u+DCR$EWiE0K&0 zkxgk(r@nmENXeV6V$qrtkky`uR|vmqqQzil>S%nqnqKhr2G>A9qXFyXL=_LYES)RH z>h7e&d%eA09%J^Kx`B?pIiu zC@sD0pc;OPIy86}e~~HYK-|~)CFciGyU&zcRiKZhF`soqy)i@zctON*l2q3DKx5_f zh@)dc^_j1B5bbY20U*r|rv9=ZYBtU`omWuWprL^TZyMA9{K>BC)8+-B$_7!66J@ER)ZSkdmNP=&Krj-Jeu82MW z;VDH>c7Vuj(p!?L!_A}(gYSXzMyPB6up4Dt2Fgg_37aih4ZwRta2gDReJg6*bTg$A z(*{2u3LNw2(}~!zX34dhL6OHSfRj1v29fB%F`L$)S~FTZw5F&9SSgA)3R=^DOFDeB z>o@20o6}CN^5fC;1;E+Q=LG-Fd0$tL_>VQwOfFor1F8J;IcfdotWE!D%D>Uu{%Fcy z-zk6e%KvXS_+e@`!Zugd*Afn2oABEnL|h-P+3*Th{(uGfM&-~3kaQ=X_vMo-v`lYw zI7lW*4fmBCzwXoPZx0o0>sy8M7g093zV4V~>ei2|N|+b+P05h*M=|1={LB5w zNQwq1mJxa%Z?)&cV?bl$j45|{8KGxI5~JQ5@>}(ck{Y+Ql3@Z{f z#t>ojk9g+M^@;%q4`dTx+6;$;)I{~1=>OMJwOpoCKR#W3x?+} zj`Qn`Kmq)>l0&m0?G-g(wXX4(S@plO=S)Ak|3KmX-%&UXbw&a=VrCz>-I4`MKTVfg z-njqH>#}*5WVc%V6vmzYn6sS72idpHqqiQ*nH$>oOKAd)bOxweeG}gp(QXX^h$eX$ zcP5K~8|AVK|fCR)Eau3Cl66w>RDWBk!p|G@o9t@dXuxSYa>H~Rs5 z>%48{fqeA?w!iZ5cGVq^ucWW=I5Ol}t{Gowj%VK;^KiXN$wl6n)N8KyS5}eWCWNg? zA!`v#s$y^E3)^iW`;0?L!x~{iw?&D$bE%BHmzz{g+6Zi>x{*fq_wyKdk1BM`cLUfr zTVn^b#`IeEt?p* zYmtX3@W|+`*_FL=!S`;2)t!%0R62M$eQF`HJ$xizG0fKviw^n$+nJoWG&TE~^R7am z+s9mT%e^7tNSNnEmj*L!!{RNd2JtPWwqF}vhu}E^>O<3nZs%$_eW;tB5;AV`32tuw ze)(bYVP>slYga^3@NmH zL(MwpBt??Vs7z?j`Njrs(e(5e9;va1EJ7QpatR78a0)}nYWs9X9l9@KoV{92lO{xA z?_QR|Gm->a;@X&iKoIMs1(EAKpM1X-SB1dW-{B6_wAvT45%;W zi24YP)VT;j%(#WuM(aK1m8GlR%{y*hM3g^@x9Z~+p6Msyh?yidmodIELhsnkN{ow* z?BHBH5hD}3**+j-_{Em$x;E`{K-zw=l9^(ZNBS^YEMLVfp!+StL3aoW7}FXy?7bB@ zg}i7Yl8H@kaiM*6y)q2iz5%V7lRT)HjuHmvdaZ2 ztR0(Q|0AqeJ+QkVs0laPzO}6w(&1u~2vq}xnb%$zS`}b3rE&E3fblTqEEp6xLF!Ix zo=sFr)c1u7=-7$)?J`<%<5Z0;d+ws~@5oCU+P z%hd(TeG#LIp{aIG6anjfg%|Hd778Pl22}00Ob(8Ga9W^TJRjzk^5rhiDfr8$>y})d zABuyLUmWg2TYr}!-E8jzF^+#PM1q3>vmPKfyUoZ55W^n?Kn~p!f>gRy7>--qZLpe4 zbYAcUWaXdVM~p=vY(XGJX9?gRzeX_TBaJ(>h{3{}-+WGasDmpMEJ+32uo*T_KoHx2 zZ~NWWWAcCn(+*J9iC3QhQg+y^J1OL|9FzsMmn!h1P%SsA9fVnoWdL|0qqnVYe>%6zG=4(<<_uD3 z2l9v@LVPVhLSq_)2=40+`=L8G5wAk>LjJ?;gvdVuZ>#OA{jl=vHz%--bp6y0eioYW z{sZXg8w+FKHuZiw0k_|@LS=R`dU3bb9~a_pci2BJ#LxHSA9ut*%h1$`{#HbU=-~?% zDd;WePh;PwqyIXVO;_*`uafBAXy=)e)O$Rw?mv*PACFs#`!u^{QetPW9`m{{=hd5U z19m-O8&Zox+Cs?W*D%!8G)?Qv9L5m;i-V7hn@$5|X0EVbfjIw!WUc>U|IL43Unb4{ zhLbxQahnuz%1rXBDugmZSv+|Z{tEtTzo9dG8@erAyqIZPYZ~~T(XFPe0z1zgn;n}S znmjPd4ERQbKgtc|W~lj}{vyBUR5&;=Sd9EBllb$>asKNh0*;#u^O~SldE&N?W~H!E zOt;<`jMfrzPDLhJlN@!-&tQ))M4sF-ZTdEg#ohh=ahU9y#5mE z8UEg~F|#%sWl8}{$hc_`EY7EcuqpLS<%=N1ND3&p%7c%}Eeoz04u?}KFb4sSn)*v! z51=p8#S?Jh_b7llX;JT4>t=5G{u!TK(P!u5q3l^DENV^IINZ&V9hP3T^#_+54R~bw z9T~cNh|<)hX}%@fOWyZ%c8c9o*`pBtjhaU}x8+$Ig*YAbsqjOl%yUEq+dJM}KVZ0E zIn3RymQnT~A-rvMJIkHWha$>uCinf1`;x1tn=wWQ#Ge4duye0R)`WA6H!J0*hE z;1@@>RsCLR7zlcQQ!e)3ux*FcQcwR@kG;gVP9LAp{-eo{8MUISjg6TCc8PF&nZk)v zWb9qYr)XV8R!j*AzKC&V&Rwh@s*B1TdK`5o^Nmom&w<#bPw%`a=z$|i2l{Nr5O8yL z>GA$?OIfqaA?nvxM|pvaQpyu_w!@hWQSD|=A(wJv9J@Aq`5_vbBK zC}wXiwvI^z-e6?&NTm<}K>!HRdB=X)oFqYGCIgyXZyk~-fY{P!^P5Nd-~ItxzOO#P zPB{ts{DX9Gs7p-KCY1dWG|e9{MyU7u1}!4I9F(|kf|3lnI#9F9h@^@~SIGPast1u4 z1~g6ftvP2s>KOd}$tU?wSMDu?Il>4AI_N*tDUuW|k{Y;U?W+;Q6SIh|t6b2Tb;_Er z;Ll{*jp8^`?%FB5#R)JCZ9eh%GbM=ScSy49r+%jzyURI)yawfDa9dLt{eVibN(Zti zZ^9G|-H*VC@(W6e@}&*tDPgJ$tH!wG#Tsv#4(x%1k(oX59ew?^cDq>lIo{u8+PDIf zSius(+W&D#AeiamK{44I4P@3+!e$2fb0sonVGQ@^F@SrfU;OzT0V4Bn^rio)=e|B< z=K&FbjP#qpUievkx~f(!q`jhspQ^0E#{7UeU^fq&Kt#?D06=M#&;7F8H|JSQk{Qzx zQ4(s(P>*SvK^#i1NGvxXx`In{bPTz*9=Gl7V%3MdA41#j$1&PX`UZaWhaKCU@tRn@ z%;pg*X)vmDXMjkc)5P;Po330XiOyV6)Ox&KIt@)Gk|Joe;Ile!uod>Bz})_)f^pQ2 z7r>AHGdU802f!28)Qjy_g}*}nEyKb!97)`S5<%My95Gv#sXSZ{GPZ3qb(z9`z!rAn zwhRUQ91xrP5%ZbVG8>Ojxt&IxCe3*jVDH*H|10bs|10&ohbGzalef6=s?`R4)V|h5}pW^w`|S$oN^j_4U%l_ivP+t z`S(1iR|gOg5Q{teJ`DXguddo&bs@9w1@wQg$+E;UXG-Mhi3x^4TfqC>@ujbxd_+HhU)3BG~w2sM%+$CshZ3k7cLu(@Ozb8D!#v&Xr ze=$G!IUz+*1BjI~00v(WwFVPlVycl4^(AgH+{=VkaSLP-I!y{q!f0*C6-`wMpk4lP zTjP8{V(Iuu4LVu%AdU~TTA|!8O*f`~6l#_wcvAff5Y!{FWu-rDNXAynoOx5K8uHs! z0pMQzJagc8k5HFv2X6q(Isgbrocy-EYNgEm?HmWl4^*GQO(KC(3sO+x4A?En!AO!t--nW1vw_2Ag}*h>9ZGk;F%{5g#HNBI9YJlTz(&_vWD z|8G3mG25=Zr$LkdyVmmm)3Yi2AENTV#Abg_GsZvaLg7CBFt(yEX&W&I^C@G z?OhWNbMt{Wv3Aq$(c&H6d1ZUwrId)UY+}r)Ks4gkA|sTCq+G!dR4!&LJd5ytO)kiN zs?~c6+c0#dcfx?Of1VgaFnBadkRw53*hh{wM-MK=_jI-%x#KX&{i!43#Xt(LYv=KP zMOgLKOEiBkCmORNS$vk8V_^QcegAq>q~tRm^A~4JNG-<(B#%{o^0cn>{=(FcV@Dw< z9HeZ-HyS@_T7$qa#p)N`wk1}^qWqyq@(Am49@m_4Y5Xfcsrrhi-Eu8N@+%U!B+L?OMaLY48BIgCp9(}x53nlR(hWnfsM#YqC z^znmlq-Y%>JTWh0F80iuR6U8eIlMb2B!zDuvW-lVvt%zop-?SI zyuor1CJz}kFphboYLH`JRFr7lce=<`Lm;DXDbkfkVz+jiL427kS?d~if6GSQ22tT- zsI=pa@bj>Ds^RZ7M)xxF3;IVNJ;X{qQ>&LB`vZ2lB)GGmqf{p&=4KSrg}f3LrtV%i zkc-e8dq!pJ=gFWvS`5Ka*05^SRGck_1=R(y!N)Qp3fRtG$R|5gzTs+1ocZ{kNdD?6 z89Fm_E|MjtmwxYQdCH2f2{lrccMLJ0SdIHQ9UxD=e7T^f_o9RO*6a=PRcybNnWJi2 z)K1h=Gq+)}-_&&Y0eH6+CeyCJAk{ngsXN2s`>N;DMKLyERU!g8kFu^u-r~PnbDCFm zhZQSXk=CBHpPEp4upZx1-MbZ?cB?3Eq}e62DfU9wAOm~;`IzMM3T*Fqx?^=jwnid+ za!%FDUU}!D zwZCOa+*KHR`mmawcSoD1c~?0!YI&2Wrl>_Y66g0oN&RX?!J3@jVOU%NM~fmX?qMhH zC?9RtS3J_CZvwlYp}9)pwl@8Sx^{Ep<%et7SYIA80{C3t0TIJ<-%}*y*sF`HS3gA7 zdP_S6Fc)3xv*f<~J?I)+xr@$2D%@v_hQN9Q0+9NX%di~T>2XBufJB&-jH*G3MLX;M z*rV>OZf-ZK8O%>>Fcr#KI@ECtSu{IHFUAQAJKTIvx0_$~u}0&WUBYkWDb2JIc+ zIEpt;pmLwDAoUGmG|ikMc#@QvJxH=2a|$Umvm=;i?&U7J6fB_5q$22$va#XnSS#>a zVMGd{0nG0_i8{(>W+58_Q~%B&pjVwqzP$HDG4>hJH>vzA`mXLMDum=zFL;m;AHyE1 zDx76H?`>K2*`(CH&eLP*1SVcP;W3S|C|Apz=Da?#n*s`?0!&a}ycvs9?RnG>ldQ)} zTwLF$pDfRhs!C!WWBcHg&C#Q6bB(E~fh#oqJXlGk1rlpFH*Ejr-W^IW8cSGm(nujiQ=RPeQ7a5Hy zb3v4Di^cDA8na!PCY)&;FAN+<@15&UPhk6OoNKAdVF9Jp;gz1=3^TtV9Q)2x{2o6i z<6d}jzMXe|PMj>xfPT8%Mci}#(T zkW60-O*<{lt5*dCX{=T7H90VdlHf2fz04KW$%LqLkWyZ= z?-zxD>mF2pLf4%#1vO6L2`>DD3kU2Ik^A?)w=qUS8hK9eoVHGh; zzFxd9zt!(dIEYmcx@Twh8&dD2yfp}Syod7J>BNzl6U=j3_H z?+^%ZmqW}cA4q^qAl43Y1HJl)A2978KSdS@r?oZbavM=)JFGU7Qo%*`QI`h*gf__9 z{^DEDG@Y>sQrCy!Oi-`XS)lP3fHMZ>8@QtgN5tkXk_xTlE_`c0*H#ft{+GNBE+-@} z_)oI4tIpdK!0RLx8vIlEl&akXd=EtpACH~Da1TWY@SVv^q-_EHyl3<*W=-c921lLW zF^l={xkHDC8j(OJ2O^0zF4B$5L?Rg6n0-y~^L248Qgz3xHZEnq@62!LB-~)M_bhbv zec`Xb)nK~hH9w>Z!T^S+Boo&#cr*>}6{1}XmrS{k)N6G0Mlbcg*-N?sM@>{JMVM4F zY7i|*pG%6tPf@XJ`sY5y=!rPcXNm0T&_?fnXvu44aA5Mrvtt^{!=fZ7{A$C)#z9(lV({Mg79vX`s`4DM%j*r>*s>@he!Z#tUoNul6f)kDHE(hZK zPtdwPz4q?yM(nQS^5w_d&=4mM4o0WEoo&0Vuh}>G^p?r)+5G&r+Ljv1 zppWkW!Gy+KOFrs*v1=;2x5mZmtkLyh<2PdsWahBY(HA#fm|U9(3Qr20U6i`H!=@;FQHn8zt$WwzN>KgB7|GKUpM_&hB>k!52jJ5c zs5?-#NjWnpe6n3gyFY#)We5?tUV*qe$Y^?2MLsf+IyfW&-?-n81FYuuv6i?uL8%q9KGSQB z*G1VeW%88IvqhL;+t)`b`=~)UI}wrvnUP{ynKUY$hNrFAxz$^5*!13vmY|oIaf(0V zHH*3EgC>cwFSJ-sAo_&I71G9w{W0VC^3K=APaJQ3{HSv%*xBH4{Q4AX^Tgq4E(r%1 zRhgQAlGG&NMim1pk8B3$Wh3=M@A5$*mkK}gSPS?UM-gak5-S-M&J~G-9$%5kZwI^Mku%1Lx~Tn|Ky^pBzfJgy&Ye4HuUn$Z9FrF}s&|(v*iP#1tNphMJ+a7`;9=C*MkEX8Ct^15Q z2Bmn}jui#1!P)yXGG>Y9nom54Ju|}L@+(h9VJfjYYR%2fQ)Po&F3Tfe1i982fSbJV z1+l;bj*)CsdiOdC3=h?}9I^*S*#of`tlJ|RIL@Jmj4W7dM&akhOZeBYo!EeT$kAT^ zgc7mZgGwSR23!1=_lI$ch|!Pm6-OEepi=b={DA3itZ!-JwP@On{?LMH2W~C;7!2rA z-37ez5fVGmp7eA)``B5wMNEiHPyZ$DI~m2Hwfz3kGi|#zxCrbNPWV`5%-C|@##K_J z(D|k28nTg{8`nq07b2fKwR`Zjm!VY z1mi0Viz-%{5OltJ^Cgwbmo&UA_?=9w{)8`;8G;|Ds_}gk*z3-gq}D~ z4Vg$FnsDjLfmNrIjyZh34p6;a?M|cxvqAD0{3V&FEtz`kfJ_Yv^qWssb}0I? zuCm|34lQljs3kn)cNZ>ZAA2 znjF%iw;5j8PI;V#BQu)HpnN6W2E|3#8L#(+yU3@wYpP7jsc>{vN9MmT{OC~h4Jt0%r6oXo5z&e8>xyTM* zpN03*9Ydb z*{p(rauaT6N%8plOOm$tE(ISBQVd275vaA~fmp~rr{kCV^GtKaO_y{MAK#xbF-vFBG~ePYdxb37hSx=2y1awOl4(-;(~yyV=3R zO=m?jrOvTZn&M1N_SN%w?Mpu}Ho`o+@?2U~!}glj3`_$3`N0m6OsACa5?1+U!-qY6{vLaI|Yw%3mYjN9t0T@Rf06@IczW&b82# zb8)%_<%!yx`>qY0``B{C`&C;b6S-J`kqP965BK5(<_mL_y5fQkWXVWfu+~ekGPpd6 ze2C0Hf*VKfyG9WqRisDlYgAy-g;iej{1j3Axa9iBd(_cmy2>`sU^grCN=l0Ii{h7- z&V}#dNR8K0xyr$47N!P+O%l2A&|*-=0O@`Mw7XJtR`;>J!dABjS_r>-E;?4INZ2)V z7^kyKBwAt^cUSGq>ID+rgv1LWW8;s}gE8HWE+?Hosjc$mZW(2t;S#-=CT}D3Mv+Ur z#m#pDQEw29$PWpZSwlXI!v;~{>7TA+tP(t0RQ8}Yjol@W8=dMtZp2zV2XCi61hucFo9J}pvV`KhL!}Rro$4A#=ml{asLxx{Pm_Ij<0H+_q)V?&R=k=x zU|U=)`dv~>G*IB>3as(8#8B9BS7!U>G(YO;)en_zDH*%6yjf1>V2_~8Ew)Ws1u9Qa zbiR}`jH;bSFx-v()^4BKKRBQ%`f*O-_LSL6-s?$jY@9+1j)uWX4O3Khl0zD4<2?Rp z0lKc@=7?o)%y&Di)Q!CjO`mmPT*CD42#+H$XIu>$59UOq*};o?0;QkFG;BpDsD1B0 z)F5sCX-Pqnk#WlOYuJ*7>J&}`@ygidRKczq1^sJR_I+(BAs`!&Xm#aE!Z(sIp0h*7 zS2smD`t{sL&6~$rk8NT~*$&*O7(8y|;g4JzL-(x`F&5CGAt82jZcwo=;+kKC=QYQn zJl+Ya)d9R((e9HG5-<6s=cif|hthC{;2$1^TE59=F*$_oZ5&h=Q>YG4HCmO7ia z;DaEo2GUA0R=8}L3XJoBn8PW=d?Iw%*go1rKT$g5p)ZQGnC815zs8w{BVt13jRm)R`Jg(v= zShWCjTY}KNM&fx-9)Ey?Z@OYp2kbgi;J2RkR}4j8bU(70<5GDjkcg!w-B3T~heCuV z@f1*}-f(@2PdpV&r{eUv2{tn;{BGT?Ux}GcR{@5T!K)G_O*lR1p*C-NU4% z-a0|vZdJLI5i1S9bhF`xncRef&P|bXFFs{FNe$xd-^1uETW@s#^>^b>y6t**!yjeK zJD^L&Q#K8)csu{$L612lo9JCh4=#S2F#0^~zdLU8%By)55Zyl3oLwt=_5*fWp6phJ z;j=H>uc|hVWAiF(C!eiVewCBK#A|P6Y?(^Dp88b1ktuve0*}!9TA;s&ATPkZ;=}ru zHc9L}Y4n!peu%h^O{Z{?t$g+IU-X>z`eEuk0A~_$>~Klr>%V;tA!`Nc}r0xuyywbV;(pN zw!AQ_Hgyy!kX?+P5@@1(?SAx-2!FgW^~o39XbSv8W!cSVnFJPA#$#sL%kP~WrqJ-3 zv!}1b&{~eKVbk0ZfjH&@G-Ew}*$96-5D~Okz4uOQ`ar}kMb5hVoei9F#j(6QA7AwD z{j}9c*{4O6?U7DgAhEq4K0jE~ezp5XBvqJ4bH9(c;b}o9f;Ek$h%DzNc0S%9eyMe#4YnqAq7aO^~kd=ukZW z#V==WisO!GQRE~wy8m-N#|JSVuEWn$4pJHMiVIw1VTu|KedUWfzg-cJbFSO7tFaTt zEE6famTi*cg#&h7(wH>q4dZtas^@%k?$Wyyf7k)oo~k|Fu;nVlZge)N-yo0)Ej7a@ z@H~y^Fk~J!$hZDuFU4lJ^DJRE-)pgiwN&9Qo0&sygIZ~jDV(`d&<@9<&g+F7OMkMX z06+Z9K7+{+Ek7D%tfNg^!9A1iC;(o*Ho$+>2y@bRvm zTJF_ggMyQ{9SFz7ql&)o%u!}pOL}6;J|#?JQ5u8q^<|=Fsv3^7v#5NV#q3`@Ds8*c zxb)p(Z1V2$qy!mNbswLm0l~zV zS4I=CHJG3g&ZIVj(BZvb%8mM+ADa~xqz~L>9K3L)Nr-&T^&a~NPlg7M$X?rwZ>F;f z-2KMS9N1nxeR-6jqM&rwn_%%L$FvTLvxJ84eCH3NgBfYFy05Y?3X?4;qSSaPHzgXd zfwXIu2~C_dwU~`h9@pYVnY{dLrJZuA($(GfC4SEy^`soR2567EAmw~P(FaoCm>*9a zu_wCIqW1kPaqE$D*=}yl;;5R~QzF;9K&={0aFr~9-V7n(02*01LV1CFf!K?<2L-8% zQY$E84tHk^t_TD?LskTiQ4Jsf=QKTb8Dbjl{5*6tpO+jfvQE37qT_BN;ROyO9 zR6ta~&^v?5+W&{<@-(9^UnNc_MGoKXV2{U{s{b7AuDUG=XvhuF4uM4 zhr70@FilpH6v0!deV$o^_nrR(!%DiR$4YNp3o3e4srni`cR&Z|TNTZdIArVrB#Lr& zjO4ZGoXIHMb{yPa5G?34q-H&(Gt_;DmHh$REzmdN7>YM);r)CSqLq0nu?5D4U2QWA zc2Un}wy0^S4Zbxd?ms0Q-dRs?EGn4OE)7nD>-(jrXU6B@xx-~=re<|;#;3aZLTeU=a7JY*5!p&rT;WjG|Kz?%QdC0!w)-W&v)Pys*!gf1u zf+{Aua$5SF&3dZ}hiO@iicoUrNUs>(rJN@+3BvbZQBB7!zkpwd7Y8JU1G*I4Senn| z>IGvee}}frgwDk6%v*_$4xXhU)Ir_+IxW09o_5)tvI$op=xWwxiVu7t7gB|4fltX} z`ZKUg7$m--`WXCj*d%jfug`5;D3r(g6K8v;xv0<&8`^mPe$Qq|9=sH_U5vF}l1z+* zo$dTXRC=VOimx&YpVoONh8c_?X&frffW z?L2gTT!Uz<^G@y+$SSX|td;m4APD5?yuPhB@L=H>>9)deKH#W1I_z$w)N10l^d+64 z;wM7M5|I<=Q+nU)U#JMi#efc6NS@>}__QfcloUK6Dv zRgvK2~I*{lPeesWVmcRD5<)5-?P1S#f2b+nWgZ&x#3o!EjoN_zj^uXv2@-af=fy#|F z7x3dM_5Z!%zJD{+!=F(Qe~Z8W2TCRWy}5;RStavy;i)H{CL+k8#WTo?c8)?=y0vl z$lCmEceL}yxQzHKJ!Z9&oc*$G7x-!}j2q(M&7wF6rmB7+@==Vf!8Dm$m)6CmwO2yI z_~=IT`w}%rT=4=p6af_BRS+#Xe3fN&Q@3ZU)^|!~WX^xLyUP6Zw3)g$(u@Kht1VFT z{FJY2=(pjNn(5-$3N43s^@5q5aY5$@C=u+@OARG>d9fYwY}=Iv8*Q#v*|Gf0Y0s{A zzcok~MwBWdcnIok$JVZDbJh1BJrIz4`J*~E?*8g$wteRkx8+wJ zUM%!_Go_$y+`!MUe8OOSo=+BAmA&La?=p98)bEU~)sU+`{a&}A+57P-6HLa;$)N)5 zcm(On!Zsi8$=2f_?#BpsnRNWOQaR7`E0eFuKU5uN#*T(jKi6#tS(X~PTcfGIQmmQA zZ+&4NL1KiqLfH4}JrXNn$<31~!&RZo>3GDnVSt=HQBD8l9_F!7>L+J`$6`Hd()EOT z{5Jv^Gs|bV4YqWH5k77P@`yaPOiDD`(~G@e4{p$(X?T@~gX;Q+weelRJ$gArGR~je z7zrH7rA;$yb$C$kdW5p1f|hD@9*-{$LLI}ns)Y-(%KIDki6g%W@@gGhXSL< z#U2{BxO4Go{6A4AR2_NG50Ewqx}Hm9M|>R?6$j&=(!c-7Kd1i}=yqjghSA<6Y2doebruS@(C?$S_aWUWrXsjQfg+4z>bpV-bqK;X3r^@W6{(Cx>>IhAL1M zKxN(Xgg&2n0$0yf}uE`V|_EU}b>ZCAW8{2(z zgvJjVF9(=^*Fz#NRr%gbsO@+Ux_Rb8A;6^G{3`LR+)ISf>4e9>~@K93Br6r z;OezeHytKg=p4?rKdIR1m>lEsobj+K-|^BT!&v=f|GUUjv~guwd`!%2`vc@exT7Y8 zg#@pt1XB!%B;QGXRuj3(~;~hq~GAcVyxb9|awJr{4_dO;EN1PSK>9 zqBBgp?|Y78j-zx272r(k18c{O@l9_X+-2D+iwqg`uB4qv#C`fyf(wgR|JKxa&M>>t z$auYj)zn5=;otSo0C^Q4n7u*r{6m=&-2-TKE^ELsaDq_-GtytHpQ!Gt=F^wl7Z*L{ z)KhqF=EOCDn#HQNZ(^k$_l+^m;1>v{%2;M5(lu;XwBkJm3oG}^`vFfE*u@ze)&;{w zmS4pHfhKYSOmJhKJfehELkQ9UaAV2mCpwVG2OFsJdp50&NvqSF_=2V;BhoJNa%p`} zOgu_6F8PAOcB3kE$@J2IMBUgG7|ID*)@k1Ip!Sj3^W5(rH-_u<$bh&;~pfR}=9xXh8PI$MCrkweTB8;RrfYOc@!2vnp&(g4+fv-(G3E#;L z-xXjm78_7zgnLV~;I4Bd~)+c|8bI|p6D5*JgW=g9{v z7XsyyZ1VX=mV`O{>*+d)h$jSb{18qDu`)?m)eo}_e>$!dZZ)$sQXngfHwkU3$69Wm z!4`B`Um8Aqz2za;DRFoXf6r@}{_g7;qChFK%au{{7wAr1Lfg%%^t~VERVwyc5(&X4 zJ_#aPn^LfrTW@g29oN;f?Km6MAI|JH3HAfZ)V{NF(~Vi3t`n^erIJ(Pua}FjBP<<8 zQSSUq?-v%C;69(=YbKT(tAz1IkL`2VuaF4#9M-|5G2~(573sU=&$v@U3@6WOr>vYr zy#1ltd;nlha9<@_zKy#Ze4l1Y4lM_kbxnNeZ|uf@_EihvBV?|&*wNsa<0KC1v!4Ys z8#atQ7?$XCm$n;XPqUA2Kb2L!)Jt~EE#XTwwf}c5+J81`{0YVblH&gh)_$CA53*hP2iBe!UQtxKc@(cc z;k@AwX+Z(mB+IZSt~E`r@k%ZXsw8B{e`w74L}}UtV^1F6Y2+jAwcV4C@s8A zCg}I>ZU5U`0CobLOW_JzDj=Vs{cYw@1Tu8I6!nd8X2N7AcnPR}{fmzSO;R#iAjkAT z4RL|>7l>pO#0waT7Tho;BJ8*Mg_2;2gvZPYhyw{QiKz@Q8VA9FJS4=6Kzd$u0~}M- z1Rxg&ELH*O=mNkDxTfOfx36H~Hdx(gZ(DWqn!rXagT{&wqpS_?dkfxI^=%kZM#j4! z*zaIo$l6^9ffvB6b!{YkCaRDe2P>u<9nG!31Y)MvGNv>{8&*ZK+*FEg$+WHwny#J%^h+@pqZu=ye1G zrk*kX4-M7FyFi)=P&{=5hE^Dp=>a%v7$fkslf@TG{TWy{YDcpXpLfg)?`Vq@GY_H(Zqk#04rZ7# zoFEMt!zDm2)cFt5RIYkp{ruKC39Y?GQ2?7v1%&+^{ZYj`c}wlLF>*asgD zlazU8pmuJ`Q)w+Uiz^u_7oH}C-Wsu^dFH2dm&mpJBSt*4SpRm0!tA7rsJK81fQVhR z^=h?BPgx+_I9YXkcd4oiiN1N!zPWV5Up}5b!#l+vh-0-Vj!BbHBP z@=AK#aWF7iNOQ=eSlV1_`$zVHY}ds%k<_q`Io9EZdgKL{ludc&H^pw(Dl5_NpS-aN zj7(@6U&S4LXmsJS<$m6HOYQaN-tHBW`~s5BUv7NMj(x~Yp*xx??i{sWm(gx-?a|}Q zbqVr0l*XSQVh%o}-uY1ERW-NzPbh|`v^$kdh+RN73{aFwMO1@H;lEu8n@VOfJw4eP zaNB<}43mFA$F(Nf;D0E(2mEeI{5KSyB-Q znm^Zp6y&5Qfv}|`74X|v#{jSIV9EeLlZpE?B{R66hhTc}TNQ@ma$Kf?cwiazx7^Fg zF;dMonG2MEREP2TH`QUv3$ca+pMv!E!2hfm282Dxe_u%QP;-f4`#15+&S$a_kS$}i zjhF~_0-7kJO#X{vf`Rq?@8gyKM@m2bUC8*a+-Ly|wO?00$3M(2x|78mJ5<`de?-fG zs6hqD^y-IyG7ZeglVfp-ra#BCNM=!sK3x%Ua5^b(qOITdx#Z(lm!-@1e^9s9FlX1y zb65!8v=*^0{^N7N7)vo1VDytF!UzMv!2CAOZ&*PU zrj+1621NKmCUE1wK%<*|z)o;&2?=jam;~|~YJ=c(3~oIfd@s&wKIvjN`gmVK-0wksyIc z_b15ze!$ZO{)kg`4U4s-W8;i z(?YRwdph5rsy)PA1*f%9&WK`F4zR{C`v*V-y_`w*9Y&g)4R8B!rX@+ePw=)NwmdXx zzTlY?fNX~lBxplPyntv0idh)jAMw$d#kgo*5P9E`u~4tjJ~KOM9u53RIg13H*E z=yj0@*6_9bJeotmzdWVV$pqmhrH;cFO5i6H;vXLwhP6;6YYkPGtM@Z`R19Cg{;bZu z`YcrEsyz?yRn?P+6_#{<*m}&zTt7+tdyFLgj~~8rh8lHl<=+IVh2CV!=?i~`pg+<6 zm=A+56a%uvLC%Y0=9V!&Mw|wR8b06o<28wShrOlby*m;2@H6aFXZBy*l5bgu7S5rp zNSA>8PzV9qrpZn&fjjoX8P?gkZsth+Ifw#v(g1n$C?Y7{N9cJ01i`NlHFYYB%KWR?q1q_v#D98iX{pd7Q7%>h1Rw%s1qsRrmeWrAlnN z`yod;=HWd7AF;J&wue`)@wObS4zo>1r?W)p8puA|uT2fk%TPpX5L|H%&A&kG73ReR zX%p+b=!lx?R{?%XThHkngauSo1jHuP^;^1fEmxrlBw1IYDr_)^5r+tUQHuQqir=~Q z=CgANsR~!Fp|{MiAi8gM+eFjSqLXzYn3rfm(i(wrlXyof<5?`i%p08!rd3lh9|E(Y zl8jHuwST>x5J$CrceJHrBs3q}ixpFp&%dx3E)5vq5R!= z4MmOfmlE{yN8Il5T8DDo>%O>Jvu?{$V34wM`>ieU_-wwY_-6q)X15(l6J$1!(XL59 z!g4$f&k(cE8!-F@()bbI^w8rbR#!Z!&o3Cxm-aK(qmXb0!@MnvnKj4IG#1SJJ9f!4 zLd=J~r$6o7uSj=hm)+~^D?ODgkrXx%5QCCFd9Ybvu+)jU!=44>_)?oMI;(J`sfL4W z7h-o?>we_Fcj4p1$z~YVrjI#m=ZW(uNST!EOR;VXK6Iz|j0>^*_BqI#;P;-SHblAX zA9GmIr+%+8VWWTQX>p)(W=Oh1q*CzSGdb2Yo8?yxW76AN2!aVr?j!}!Qy?F}5UW#7 zP;xfp@p^-6-WrsJB4^9%G9=F9f56DCGw;Th>Y|bUMz{NR;_DkUOn&+`<&wVU?<2CQ z@69Pa|9Q;S#v>I-goYoTXZ&;^sEkg zWQrc{Gz`cOy(;z(E$VRScCRK-b-r1EtPlstzmYZ`?Y&H7!Cem(7wtbtgRb>qGJ zi4CtIujNT^W8GcW!5^i2o$KD+hi7$9o$Cu4#mTpW%Pl(+8POONn}2`yViP~NI?d9@)?lo$Q`*Iy;rEQ~&h3Y#0BdtO zr?p7|r@M{7sJlIbGLclUI|WOzpLkq*?ei}_P$5sBO4sGuU7;38lVEZN8g#&8e0rg$ zoxn^%s-ls*UECkm_tcWlSiiqIi0kLmcVOJ8PYq=Zrp1wQIco?ra z>9-P*xo5BG{OAdbzThjl>j^Z}+9Ia;+II>I{mKqDlvYHab-mv|ihw*ppSImB_4is- z3i;yCz2`fX`04BBQ)6(0uU?L(|BSF*sf{U{ z$PFC>Wr&ufl-b@GPtE9{W4z$)Bm=c5E~?bMBK5HDLe>}d_P#)wf7xt2HgLl`;y-e= z{^9+-bXZ6SiY+hxGU7(*??IzXq|Iz%qRFh zexad^FCjO;SSh`(zd)zSJ&>0qX9c^5R%~&F;K|Vpk)!fgt+O^~@Ax*voxY@$-L^1o zJcXpt!*S1~w|66<^q9c|=jK2QO1D#c65pLMHv^x0Wsn5L(}4_Q)ui)|_=mSm&v@V*Z(C9*hyCR1LH7{vlu=(`#IURfXl~ginL(`+TQs^m!MjGM) zp59$h@AyoD6Yen1h5RV;vg!MXE?7>c8EL8xa5H_Y!jtK~>I_jg&hQTkmLLu}cLu7ftlqR_ zsG9QWYkJSs7%unu+%;~IH(I=(;;yz9Fq=T$@AhJINyh_MYS0EGAW0dDpbQ?PTa3dj z?C7wMM$+vB31N~QaegLMlf~ZCKF}(CE?RNH$h#QxxEDJ;T4I@?Rg^P=AVwQPVJAew zBY|j7Ap}R;;rU(ia<(93(&FgU(l?zb?+h=RpZEBuUStJCgqSX{&x3)|adDGGM37c) zkaFU!GWeWi;o6{8a@4y$Br)lCPd1D{VhiD3|%evG(>On|GpZGCk6I4Fk8#-tZ zmCKa7^5pYHia6|B-F!U!f%LSpDLGZ+5nSjfJP7)%bbVO)+nJe}%iEgALf@wLBiPIN zv$$mFJVc#Ch=-J?!EivK3GM=)9$zYGHhwvE6rlhPtL9FO^w!&6h5{;#3zc;Vcg=L( zJdBhU70~tK`X1*eI&+&8cIe8voj6R|rv#4oK&ypGnUD^td7Lr&fcULz1yC_rT7xVU z^3e=ZKu+`LH16bSdoIoT8WOgH#Pe;^ZzoLoy%es?)V@3?Jl%O`w)^MV7vGyM-6!4# ziqED^;y{k0)fT&o$x?HVP~I)R?nJb3dU{&qI2^OeP_WwxNSf0=ktSTG-Ll3=^Q^yu z4MEQHSC2{BH>5K&JMAIgfO1Ch`hMPVO0~Mw_v2QsQBMm$hQMk&<&)L|01K9s{|Ouo zW7|BKpiFdb&HloRBIj z-`s*t?%=P;ycz8PhhPRj_Hh{*pfyLDmM*^&Xfne*Fs`G>}gU06b){V(OQ$D%Z3x(L)YObqWbKMb00hWUeq0JKKxE1@}dShQ> z8$&iU8C(cpvfdh~>tk{JIx%J+!>nzhMs*eZ0gS9JhDj696nc50`I@Hqn1VX<Yfa0sEYS?-f;$$x%rs(CKC#VC3_I-l+$)85#c)0U!EP#qQ zMDV#ln40(ums}An-yR&NnqKo=?AV@Lf8|!CD<&vkLxnq1S##Y%69S^P9e;szhdIQo0COig3jX^6Oug;MQ5y(S`~pMQ#oTjw z9$#7fy$U~-`b>*qh&n*4mn!~-i(xXs=48#MZ{RX-(}VS^w6~r+9D6}uBPzk$#l)*Y z=LzKj3(QnO>`geOL}xcQ3AMo({9TWmIEna`;7pbneqX0(iMwSf%>s~uVAWkc{{=@d z(zy3v^C~zQUJfR)8ZIVwCQfna6S$U8QB_TB>6A0y93_Q@?5y9qs!9!epZ}7j_eCuv z?MWOCdW|v)uO4rOOoo5MbTKZXxLFzM*ur~4Cse4dj+dCKFd^M0NYPWgA$l$(7`e2; z4JY3W#hL=CAy+7EdsipNIp@sBZ}3i zEEkMhnIo+5jf;sDYMa{bO05b2A?zLKM!Ay|n;sYl>OtWP^^_RWd2&+I8JAz6>hUgSR?09O+%`|JzBzJ= zz0SOx$2B&B@1YX?HO`8%h+H{o8VjGZ%g--zWl+Mem1?m%$$W}_CkF6CK~xE&5A;4{UJiX|2{eV% z0Tqg$I4$s=RwJxa1+XrcV7(B4z34HOYn0B+(2yw|Bk^G0qu~l{%{@tl#@f$L>LP<@ zAza$T5~1p|?txjLzU|$yrp`Ev4f;*Uxt+zfK39ne=;-snXR` zl>t?d*GiONr>B`zLT+=kNXMu-cA~-oXRsizYq@3dikf(J7~rPy!_54v;T&ml4G)jR zr}IJ2(}4Uda|fCraYRZ<1U64R4+>BQdxV^T(gQsfO7r035!IAfD-uv|4n@PisSrE> zc~t-(M80fAj=&;GvD~_3e;}1x`HpepHOr0BWE>2ST29JN|(Nf%o(N866z>V~ezp%|{#=8P86?3l-#Y^m_n0IgZ_g z#>3A;7QW0$;yhv>Vwtz%v6Q8bYV8~qpEE@3x1ZgsvbZD!Bsy z3(#ujrSxfnDzKKJ5{s@VQKrJe27~I%?Cw()DJs2B7`_W6`c908%%sw;gpr;A52$|n zy3eF0_{P}lIZ2un7xZSks3*P%-v#Zgmkt9ORo{6#&CCucu1!_9m=T1{Sc+ISEMD1M z<1LEwq`YzPsas^-vE}WiEN}_ny*)S4RzE%PpUG(&CyAzn6RT}a7pp^i+bss=oig`Y z8ApNjKZb=R^kDePbu8jHdj8pr0y0t-Bv9S#QU%@2shjj&FTaL6CPo6jylKG(h>M? zl@Aj(to;l2AI43ExSd(NeaBMbyPTj2ElraZ0f?@sl?i=|#_@La1jD8Ii1axwO|j7@ z3V3DX01qGD#)CyFIbAiW1s)ZZDTAb(N}@5^U3PeS{Q$iVMT1Ff(j9Y`u*};C>}qEd z3%ySxV(uE`jotNj+zT>UfrT3pO!-8uh67k{~W^+6Bhnkodg> zdl+KTRAYBr|FYiQi-Hc{VKwUP*H0tA0}3D_e%tf7>*|S|K|BO`H&2YUrK3fx?nq^D zPqyjT#q?8eGHN0f?A2nne}Nt`6ND2Qm$LmR+~@HH;Y(}UlNvPcykG6zjHE;%(5G^XDa~M zX5N#FkKf}GwXt6jkCr4Y*hBX%BDfx>L3#RT=kEGVDR-X**5P?Rug%;43b^p!pG5lS zQp$g)zyC*efBAc_u)n7GU)6f?tInbkgjMQ8SufK>mkjGRw$&Y|4M1cbCoZ5pQq)k^iOTP ziC68@z8nXR%@HgoY!kHz=P{_z8R!H-=U_vvaf^YEs&X;;4uf1xJU?C5zF>q}3?4Pj z(P~MNAn<&tLY&JC=3Zp9>@`hy+TJTmqAcI)4^AD=3lboRF2KXMH8MRSBxiTrtKRlq zUyiD)eRP4w9(0>a-Sp~7)s>gRW7#Y>obpV%7YfCnoz^%T+^BnNG!Ew(uO|kG2J;nF z8r3wp7qkK5BAN`8J}8?e&pMxQ1-7H;D0EIe*hqVHYz_HA`@A?a77B5$o^v ziwZekUoD@Y^g%!ej0Rnn71+k&%9YCRW>eiqmZ!)clxF!(8b#V)y=Z^1<~rZluX=3R zPB~A06Xdrj&EebxArP0i6p7@^7^$LzX_jx!tVt!_KdaimoD>mqcqt!}&fnBG!v1qh z%KT=s3X+?Py1pl`vn=fr*QlP5mcvE+#Tr?cJwwDB3Qfg<@vMeA{yhMyrd^W#1-d2r z3zVC?X*~~8B?vD(Q(yCi9*YJ;`dxn@I7pYtWeuLcSsC<%s7}rE2*VK*T@8^$9yuDu z7n=n%c30QnVt!Eog>fo}ZD317^@IOXYt=FA?J3`}LC(0h{LyZvwFg6e%^UiP6Q9hF z>k78nc8|IC4d1>^CH5q`A1=U8dxNKV^hP}%5xN$QIIKznpH?L~mux2q&oTYD@A^b( zySrsJCC=djadoJnuHq+Ha(B&J)Yi=&Nc3L>P#;{ILob*J$XG!3grZ4jy-ESXDL^0W z01;~kCg=IM!KUEhe3u6f+<4vYJPtFB^6v9$j8$=P^-2@FO_kO{8`crDxda5jsLJtn zGF_1J5|q>5ifDXqXj$hA_MC)EPjQ{3D$k46xWz^rYLV-CF8$6z1D!>Ai;GFe=KwAN z-&6RwAmw_|GE*=lqc}(>=QO!CiH)Nxhn4EK2)SAKpzi6Q&p%k}4k7Gj(q zJwCT18_A+a^sHIp><>V5{*2i*BG+noe{9{`yoS{-3S;SY+ITeOuWrjY6H*^q6b0$9 zo5U(FD80o#X1sNH=vwS&H_oj*QpuBreC;rE^|r+Fvn@k;d0ExI`?lZAD>i2FR+-m6 z9wbDiz@{?U%W`R z#Y<@;%W@?u7eh}YUsggVc8;!%yZfL+?Nmn^IHjh&tHg%%=~@Iu{8!>*PWazrzb-%a zF?D@3ms|1CtUZ zGvedlx<__u3HmOn2pMX8ou)e}&Y394kTVL!8z%H=3X$Bo9|-yyE-D!Myu5xxz&e%; z#KR{dIzdak;vZ#mjn7!f_&v8JeQU_RTU8YN4e0A0?ft)t8TqeNEFg6NfnJqS0LNC2 z05Huhm0uoI)U1N*>7Fia5<3jYYRF8;6Xq}u2pHlB=L}LF8nw2ptF-PD_Txg8`qV@y z^KtZvJdk)!d-;VBIic9Q7cyy$xuK?aC!#?puLtAL7c{mmxVrJ!5#1E{qbV8Li6RK0 zw~cbYVF0};ioguqfl$z9sVwW{IS<3^Z0A@c8*1o>;R~HJjc2oD<6h(*xg}2CBJAov zq0$eFgCF9i3#yz0A2-pF3sDR2;B>!0kM(IIw-@>3a4F|dH%ja7nhio41H8&iPl7RV z0($;Jck~`K6Xz31`-iKFg!@3WcF`~pJ#C1Gm5jG$)9ZUjAil2{=og92Ec3~(M4&5S zLj<1oWPfyvCKwk!72KJ2xgH?+yWRJuML3N=E&9kM1DfY@E8by*IRR$D0!HNuXMwS- zgV{B}9)ibRZEqZF>Jn!4-y9SoCD3Bq%Wo}T3U+GVC3SXpT?Bt22P^?vc8kUn8TbY) zYFiyU*CRgN?M4dzFxAD5`Y2DGZW%|dJRr>TE{oLVL>@*+0Gjk3RRBK=94}NtJA^s| zU&woT3S0$m7M~Rn8Dq#anL%vQ>lU4K%ONlgxqaJ2ctI=duHb;oY!e5;+yvK^=wlts zabsvvZf16-YShO24me=hxAlXF#P{o;1jjL!TfacScL;B<5(5m0*EhI>s&Z(sr^b$y zMAbt14cQ&?r*@zj=;UYaE1(h^6KGPiP#^yfqFNb|FGhXrL zch}LR##-dyP4GDDMa@8RF|Z9Y)Z<(s2SS^uV{OSGpqzIqS(Tg$rF6!d1I@mt$H&2y zNK)o*2e56M*);-c@8*`>^H_Z;$Rk=bnUTAI5?lR_d3Z|wH=L3e-f|JL>`MS*U8t2b zC2>^zh#hqr$OWck{y<<*@$=kGe6DiEU#sCl4JFok(+}ZWg@xTacWy6~U#hu&l?!x! zz;b7y3xHU-J4?P0$rGeXY2HM*ECos8z?h>1X&)oymYmB&ikporH=@kKjG7{M3{?gD zN3$RJ%BD{>yLXA{nq0N__2x_Ux<<>(2!ioV#sTxk#fK@&N|XzLmWP{(kz0=~F^7qy zj|D)w6{-CTGy)uJ`3qoHcbG&`Frn?5uU^h5g>@m$&ozUUiDE)e9LeUk*M-&rPxpv> z-QFv*J(a!7e7VRb$1`C9SxFJ}=P@L_1@a{AaHhke zSZNk#zf7C{!rENxPni%|-J@5pde^RMrV+e|)Fhu;@+*qCKN7D;e)o`@Ev^6S&|Mb} z;oi#15rd+@OxVZ6C)&~ApoHzlwLKoWIIj`XY!q8$SrwYSqKrO+m1wahaL$3zr zK+vlEh$G z&id*6Y4gMkUyf;GYL?gVcWJ_prmKL-N}&v&!FibtLmcKqA{ul*Z>Z(hZ59`t6Vvx& zMXVh^c_LTzO-U%bY3oUJewpBzV>D4CNT`ayg*9)5&==?F&tDxL694>xGr@K8&ByvQ zul`BlqzT6?Zo{Wna)9mvw2P}G_CSh$R~wwjIR6W@4v;aVBjC$-haj7+)4=2_hFyWT zIKr2+f`IyF$t=JeOp%1O5-cg&@dA_vNz{SWz;7_Ytf^DKY>rq^X@9l1VgI$ku%J&5s>NjrtTiEv5P7% zAe#RM!2B4;Q2?6|nn|bz+e*SaigYg-?TlApOLi|`opg=HRx zQ_x_nMZ!E=vFC0Pf}&LbZ!w^75tc9&?>pcUAnKtE|@^2k%KC4 zIF|%yePG^EfKa9UD25_k(2P1ms2jh7bIor%Es?Ch9hd%TsP}ZeHc>TAK(s_%x4xiNn3<_L}SAR z4-g@+#Sg(8Wa{Ucf3L$?u*536Ob%;616ms3CNoyO-DV${d6F!xq>$2^>gGL1)yDK) zzWX!bV9jg5mn14y>Vvs6CtJ>@VxXo3BzvE&-3@j+=wmgnxuQi{J_JaYOc>x6FaCz_ z{pq!CPp=9 zMf37s7)V{a^0EsTEC*NveYb7dN}Y$joppLYpUvCtyA0f^C-;A`fGH|0vB)Zl53m8n1bq0p=`u-W#Jr_R z^O;Z$!hwg;;9+N1mM*dTGA9@nCws+~x1?>wR{FQ!(na32?E?|stX+Qv(9So z?B!^L8vKzH@Nr`ta`tPW8I~EmY*qpeSBq+sCWu#eV!fdpo4pH-Vm^DbDJH`Q?IJTW z4!J+8pPXJOe0UaCd2sYw3inhq;U3oYb|tQ>y|)EO->^;V3BRz>T5(oNIa#COyVXD3 zU63SL09q(=X;y?G91^XpBu?Z!KRi7As3sUa*nLu*F<-Cy;$e3IP($s4PMxICg*=~= z^N59(Sw@dH*B$ra-{-ygSY8$Bm5jdcM3zjAc95LPY_E7G-9_%HybLA&;2BQlE3K~Nt;IJxaiSc$W@fINlZA(Tr_YjGvg`Al6}3Uki#(ej zD+iH2wgy8&!}+foEQY46Cwgi4jXpi?t9M`ewuHBc0g*%qP~va@;2MlWx4_Bn908r{ z?{~GLo@hLAK!)B)pX1-+*0EMDNuX2ayT|#ZR@f8Z6OC~-qXj(?ZG5Q}CbTQa?LeXg zY!b!O5Ll#-MJ=Wy@`50v2Wv&vZPj%VhvE0Rsn|xIX*)Y>c;#)^#_CPBrFIU8w`)?t zT2R%NEpG7ZOlrzfjzpTaQTW`3t3i^F-;!TT&W_Z3bh((z5FDIqs=##s1N&9`` zR0N0@Q2^dz2zT;PLhx$x7epSo#ud+oXU52BxOL8#tkX+g#@`b%-5o>epdP{}P|c9C zTWMdw%o~=O6x7!uy3ZTcE+vIRwGWb7+#|wGS6*JMujl)E6%-s#fguba87}r9rlsj| z6yT^e!juT*cmM+&`qm{!cvO)Wywv}?ibL5;{|RcUEK7>DGo})k6~k6JI#&4zb@8fX$zyJ(CjlVc@tru!cL2?d z3wUBCfkCix0FH&Q{smfrD-uJr#i@Qq5#=cT;A&_aI_B8%Ws?%gp$aD*Ui_fmx{v>g zvB}8Xc0ok4Y;65qcG(N{f=rxA6`wdA5W~RNLsx;eQ|b=IL9RqASO=5=Xx25$FCPEs z?RA_lf+MYf5IQC+SjcA>z;TY{!y;pQnpw|avVqJ@OH7Z4f+NGKG02R`}n5+*Ui zYMD<4JNgmh#$q=yXRS?-NHgPw_SA$sAf(QhT-fu!Z0m?Ylh{y8hxPsrotde2X9kdG zyVQfLjfXG!Pwz@Z8OcM{s;?K(mk6E6 z&>B`#dk6y1$bq*2!IMW~jBiysgasx}2yDmWSrn>DUFvp_zOT9$#O3G|hFD*L1bx5m zfG4Uc^Z_0WzIfn+61fS2cLy!ok0|= zr;IrsoKSpILB5O0mCBXukq38$Bd=8^4c0umc!2DLyhLDcdb~t2HaJVSqb5*Y^8U}C z?eed4_@!7GpOBroAG#;AxXACn_m!3Lok!9pzCT8S7E`2o5qQ*nPJ@?YrDAE`3(pu< zL7DaRcy{597H3rD`Y~=!zK!N=Kw0Gt4P`7J;L`I2eAtFX4Ye+~-!#_|JFnKtbOdLa1B z5~S@22#IRQ&zJhgEIPxa9%IDLh%9?lea$ann-c2|M8lwmuX(|A*ZkAC6Nxc-zbFT2UKBm~4FQvX z8+0uRDoN;Q=FdTFiOV5T8Z!nSe$jqPG1pxBMt&7A@DVlx$o@afYcm7sv= znqL4&oZ9blHU)nuXOo&+A#*ULSS6IcW)WyBVylrv0R-hZN5D98HM# zJ-!ELl>7Xbz`=iS8ULrj$W_r_sl?Du2sq8u_MxfCYT%f3Mh@`Pw{y>RiPLHD@rSQ( z0V(}tA5!XX$}s>*+xEM8u^oI`wJxYe)oC`|DN&1foJ_ehneUFcQZTugcHmm8{!^Ka z(Mir}xNCw(E^#W{L&f-c=cN247>x6freVAou*_S zsL5m#f=3PJS#4MkE~|RnJDgmMXd3vQusIm7 zLn~bf|C-7dpX|Pui#R2q`(Q_4w$h%b>tH7(`v-Y=?29JE#U<0c!(SH{G`O$iu4 zvf2u?6P&aalC~FZ8q?qAbX*$BI^;c}J-YSc_>S|+E(mc}4MKlEX9C`-JV9x0BGxhC zK+fFbgYI_466arg#BDX{qU~RBXNRDaX|Z&HG55C*s5S)4*fUxt7vtY%4QZLcJxRN? zx4xrF`m(C>y@a#*Xw@PMv|?b@$zg)Fg&{fcx)83e>m_b4G;^M+Omx#<92>Yd`)Z0F z-T}ZZGYwn&ja9C$e6P72QuH>kavN%?L&^mtKfODzd$;3#?`y1%`}Xs)fWguz=4760Ma?3-K6mqDhMFLlz+>Go-iGz0;9!JQt$AOT7*2JRPyqZ@S}J4pJ2U52)M zf%I94?{D7N_u47{(Q}s=wQYU?qy3}(iQC<03q~@Y|o{cb8S@TRZ9@1zsZr| z-lGFQ%aLhea<~`W2r0|@3FYZe4yALG!&22k`(EuVzB0=d#4ZPmbPYe|a+o>h;C`XV zaB}QoZ*8sarH*|1cJkiG=8nD|`$na3OqrenoBa;6D&qIAyHsc{VLTE5k6EBO#cjHj zf%LL-K2h>;!ru~y?yMmlOIQ@`OTLmBIJ0?;T*o%z1-jfAbt4yxe zFt10*a}&N9^^xzZ#s|W*#?R1S;bhp!soS7oo)J=dkjjWxK0}@KQ7_?u1FR*FNT945 z+NUzW>e3DUrR_m&oIcI&&enOwfiqjI!%fxMd9M@kLkpAhZi^bmUh273XTzzz^1 z<_KL>MSu8t2||_z+@b+r90GTf&Wip396~buB4A{Jvr&jK8Q{kUflu8VFbsgn2PRS$ zBe_r1!ARqtf^bGIWlImhzOWc-45*C&p8z}`4Q24+54 zZ5B{q!PqWq=;uzV6*0d8<55LR!i?CXsXV}ApHYP`yZ@6-%f=^WSwr(2NeAZN2=sh4 z*kJu#cJK4a_;+Ar5FCg(jttDVc&2%VXKLof#!K^JeFT`?#F$Xm+ zzns6X+H2J^6*PWL8ME9L{*3j09*||$o3^+)*Avb#w%?4IVQgQ#91LUoa?xb0Y=6H| zF;+IlHu@jmMm^C#>9&uo(h5sgt2zOkw0`clPRWI$70!G1DOrsbzv>@YZ+i7)vUg&? zkS`u}QycYp!)Ib4UwlKteBSZr8_yx0lPVIqtK(5zdEORU9fjSIi(wt=XbD7~V~j&#g* zypm>+ZT1x&V8o$kM|)kJI|nvnN1!DO2d{mt4GSRk&DcFED2w z_RoKQX#(J9&B`~x_N6x;(B#rP{|u}T5y960o@Kr(5PTPBvm(Acu?sW<Ar>&VNVQrB|X&aZll+n3HD7yBdj0!9hto|6;L47u?CE&dFJJBVM*Wf z9)CfIluhZ%Z!Ot<>M;}~`WmT)xG^c%)MWOdBV~_2Fih2m{cAAPV zmBjUQ)ZwNI@Q?fUB`zND*^H3jzk5UJlDfBsKP$VMlBVZvqxpb#MK`38zbfHV1OZ+d zkCOb*BWs>1a`k%IC$A-l$)?2=Rdm?-ZnoU6{T_QmBssWS;P6|P-AW00ouDYwoM;kQ z$5yP1v8-*XN>OapOmUZ>=Gftogf+BuK!&~Rd5J%U!^f?qyKK(cHmhvPH&EJz6Y3sA zulFTQ9wh|(^Wa|K4_`)5bqm_U6(gy{7cSnveO-weh3Wu3W&T#l9 zpIFw+A7wbdXy;#2Z-*iF|7TaZ@BBShnX6RgG@n9^QatvmRP3zoM@t9MV9K7t6#8c9 z>eKEyfr?w;ai&qBQA-eOWLOUWu8yoA`LMnG(VK_3N3rYzU69^rW=_<&8%V%1&y7;q zgiF3^v9%aq81YjqkZ37B$+xdJ4OUEeIw;^9VsVf7My*Wm?x_kx{pg4H+9FjPUuP8! zqPPflm;0SLJF8KAua4I7U$1&N$m^wL@J?yYRwcTW!_#n~y>B`M&Wo_=_C;^@;kzi0 zVLR5I7-`!-gDLV`>mFHDetUOT%LOikw!aK5T@6mvj^-D4;n8fpCs7bQ5YAjQ$xz&nkgYn|!ueN^# z!8RAfEAH3F{_^d!yoO@~YwRjkTS2ofsK^{NuAzg92Hq!+`ODzL+Y53`z1L@uZZxo6 zkNzMO!Jp-yv}ctkVt?NYIu!NRwB~uXO!ah3)XvHI>cAl>k-?H$Zy|2KN{`xO>ie0Q z@J!KV_KJPG)HZTxb|=Ndn3Q5)0ZKdwk|~j*{k1@)py|Gjx9-jL#8Qcl5z8mGy%}{6 z;lg^CRBqPpUk5P+U`R&ht*h7XYk!n@P;Ll;K-D3AiO6Vcw*p!DGdj=59GXt`e?FzS z-3k7alHb5ZU%3@x{%V9}h6vktUhMxgilTKs04#C5gxc-A1BPCf1verCVJ;pE#~UYZI~s9*}T(SLx$~`uSi5r6*0g`x8UP;W`5}uodo#QOG~7|mHw?~ zq;@_WZh1FaXFXffNyL)vw-1eLW4C*J6gHZ|+KP7`Li zmwQ-qx0cYM_yy62XZC&CgL-w+ejEU+ICcMx)4c%zT!o~5uGZaRegQE^jdqgWDZx5&S5y;Kox@pBIb5DpvkLwfDoqEvd_9S zzvLOz0a_I2Fi=D3K(0lP2;`!B n{^xr0P!HUklM!vGJExWe2ULu2cJ z)0u$gNHqu^FS|f5ZCF4E(Q86I23(hQ^fL#diEOY0QJ(}v0w#cpE=ZIWfwVg&ycYe6 zGwiocI{eWUi(zW=HMF%x(Tu{fPM-RD9FQQds`3(f2Vh(53k8FthbG9Ozq*j?LDzkQ z$V=&3;HUE+#p%+RL6RjMh%<=J#zR1fTGvR&_!aFf1aO0zg>V5<&=}ZiT!9%NQePy&?28e z!*$H^K?4MjFNc*fOy`1Dz$qK@5!6+H3>lWT{4>KG8RqzJEN2XJWUP*V+gcc_M?Op{$ zbnMwt3alL4q0tMg*w$Q5;rZ3WZ~ZwDABsC1+Xq6M#T+F;>DNbJ;FciMxiS~V_0*If zwA?sg(^xh3!>i)A_cTCoOg_~z^@TW}I3=)mM%eA407+ahwLlKj?newIS6tYf zK?p@U3)Y=?b5)6O+Y|Ij@-$oF)&6J`ZTjdC#y}{L-65XcCsyo(r5?nP`2%FPgsUUL zt;9IuNs)D`vcq6LuBZ>b7Hy9SL9%T#@mI(SNINC@;MY=JHLs8T+qHHsAQLe_fsE#ehhsYZJs>iPJNwJ?~)1}VELJz?scIP-`Nn8(~57mpSrfJxytH{FQq|Oos;*{62!s(LQR`C z0_jV^QfUE?XW_)3KTe~z`J3R870#;*e-@P4&8c4eao}`6Ct~#85jd?~vgw_J(#r?A zx1+av2dTBwVpMk1H`9{*CD)C=2spgOONUeTrNxn^L+I(ZktpuDZaar!!=&JJ6NfwQ z7rpOz)KrD5mfJ^g$81GUz;ZH5WG z-p3pC$zT+j!o3i)c-+Uyh?WSZUkcuz6)c2kR~meqG$gESFll2&WF5ck#=qs%J?h{a zxKM6m4+k04d+@%TMZT+%=psiu!BSLs&HBbQm*FH{PusCnRre$a|QOT>M(0EVbp%8BA z2~;=-%ANkkS0s&amw1_=P#d%UV2@q1aJ-oz>fo7A%v>9o8-q)qT26TLjV(c(8^RMd zoNI-zR@r6IZ-`9~F(dcZX$wiSZ0?nIpMA&FiFLdjxYfA5=Q+00&ov0mE|<*atnuI( z?YZGi#aWprkUbtE}+QUAb|6uHoYn zLc7RB^tfU+jiOjSAUUGriSIoIw=L#eaOc|WVhCy2rf1gr?%Al7 z{d+ohQT^5I6n??DMFD?tEK1C0_9QJsZKwFlCCJg6a~ao9wC8#hWS#U_e0+AFW*g$* zI)8fBWOhC5P*aIQx~T&nceb}FDtWCLa9np^*W|5yK;ayY`#3Ob+CtJ1&VHd1(%E(3 z=n9v9{A@i--#N+RGt8fPP4|cw7ZV;nskbQdwm)ouoQ8jhs_I*`5-lpYTyp(^oOzhl zS!3IdUdv}Jx3+96QgNLiEt+a&*TbulBVB26eMgNKg^jV21GOF!0-2JR+Gbo1^k3s{ zfJ>f*H#O~zIkK>q7)pyP5g+4|g+B%fhe(M5{M;9dYShEW(kjBTkSJhX?;^KqhqhHh-D9eR&puuu0n_w#Wz ztO)M`ZeH`ueb^EEs-Ez&Rphix4ucBQe1&pIvsv6=x4P~*%b%1y%7xGNP6~SV|qBR|LXgcQUpJJF44bdGF}uUca|BL%c#2MrnW{eT>k17Tz;IyfVBt%Ue3`3p zeaOi*0T(SZj%ZX_i%#W=hALli(`agfxhoW&#O$LG@mr*he40PA-QDPQjnbh3sh{Y( zP+du?TXf`Pm_|rYzq19U4^*x(mA@?UL>z*WPesz7`y=qMU^<_VQC$Un{c|%_rMEtC zUmY7)%&wf8g{?F1(d!_PRy;O%4h9|ZPTGopeTC2EuGM9!$sDYs(Dam!;;!0V)v-Fl zt$5ztysQ&keJQJLF2>%Cdj(N$YSc8@wla?pUxc%v-la^ zn}m&cjA1N<C1_iE@o-fgO!Hp5v(OrzaLv0G>Xzc$)}`|ioB z0ugR*@U|%%=0N>Ec|X5Pst50p{ISgzoU~_ZP;!C3a=no&tQ$eiYe|(ATY|iJV{-*Y zO4Ka~$ar|p*Co$hB=K>_fq-+nJB4{l4aJg{eMwtCDtJI^*ME_^icp$M&O=SEn|? zPqzm#>wf(n`hBg!gOpB{GE?SpM;7e zNngNK?^5z3xdR9Ti&JDbS{QBkV6F56n&@lpg->*4q` zP+6%F8d&&?GLvKw^;1Zzh%fBhc~BG6<_d4i;FU4qPm0AcX9MIbBm0V_l2 zL{q>)q2*oj&q3pj6Q~<{$U7hfDIM|m_lqIx!wZvX9H976@9+{NM~hNqu<#+kS2d<7 zTyhpk=L($!mo>~WWW^=OI7mNRyZm{^5@;n@u2vpJPZQ+?a=fn5Nc^UjA^ZIIOdQ9#VwHgRHjJG@AKC>WEtD zpY1F9@l8Y`6r0vY6HCR&gG9YAAHBTi^X^%*_bGFJ@C+{FA$I3h4y zMuyACa2XjcBg186xQq;!@gISE440ANGBR97hRevn(-}dGl^DbTK`RaO^E+(SP#u0d}CB^s|R_U+6MAC^9paOXCq4=pM>=G0mO zBp6vH$tD?lj`!8O8e(nCU7``vHQlx64G+c6PKxD>;s=ZgBFFN&uUGo?5Et;JDb5I7 zO^{c1x8fRsdJ;vdtp7vy(J~Y0qG+9HYsm~eq^DqbQdQz@zv2KM6JmFkZrD)}m3Jb| z_Ri47pB0S~Vzjs^_PxkJAY`k?7wpPHwyQdR`>@)_yoJI;f;D~mvl}Lm+@o!X;qZBU zyNh7RQ{#C>2`f?6hIslq)LS?^3MQwN?LCYnu&Bc)k85&A9>?y(&saXC zT&vq|k>sqqni|#5FfK7hf?*SkSAnr8e3P~ChJK@ZV5D8R7!%~R)Q^|#0bTmeIu(Dv zg)x5r&*_6O#`=dCYv!fzs}`}M>tr%)_=m9J|7IIv{@!&<8Sen&9bnkN|7iovOYQ#y DG;p6n literal 0 HcmV?d00001 From d9d765ec3f9afb464003f7ca61696072665f6eb4 Mon Sep 17 00:00:00 2001 From: Florian Golemo Date: Tue, 4 Aug 2020 00:29:21 -0400 Subject: [PATCH 03/49] refactor into package --- .idea/.gitignore | 8 + .idea/StanfordQuadruped.iml | 15 + .idea/inspectionProfiles/Project_Default.xml | 41 +++ .../inspectionProfiles/profiles_settings.xml | 6 + .idea/misc.xml | 4 + .idea/modules.xml | 8 + .idea/vcs.xml | 6 + RunPyBulletSim.py | 96 ------ common/Controller.py | 171 ---------- common/Tests.py | 311 ------------------ run_robot.py | 79 ----- scripts/RunPyBulletSim.py | 93 ++++++ .../calibrate_servos.py | 54 +-- install.sh => scripts/install.sh | 2 +- robot.service => scripts/robot.service | 0 scripts/run_robot.py | 70 ++++ setup.py | 16 + sim/test.py | 1 - stanford_quad.egg-info/PKG-INFO | 10 + stanford_quad.egg-info/SOURCES.txt | 7 + stanford_quad.egg-info/dependency_links.txt | 1 + stanford_quad.egg-info/requires.txt | 8 + stanford_quad.egg-info/top_level.txt | 1 + {common => stanford_quad}/__init__.py | 0 stanford_quad/assets/__init__.py | 4 + .../assets}/pupper_pybullet_out.xml | 0 {common => stanford_quad/common}/Command.py | 0 stanford_quad/common/Controller.py | 132 ++++++++ {common => stanford_quad/common}/Gaits.py | 0 {common => stanford_quad/common}/IMU.py | 0 .../common}/JoystickInterface.py | 8 +- .../common}/StanceController.py | 1 + {common => stanford_quad/common}/State.py | 2 +- .../common}/SwingLegController.py | 27 +- stanford_quad/common/Tests.py | 304 +++++++++++++++++ {common => stanford_quad/common}/Utilities.py | 0 {pupper => stanford_quad/common}/__init__.py | 0 {pupper => stanford_quad/pupper}/Config.py | 58 +--- .../pupper}/HardwareConfig.py | 0 .../pupper}/HardwareInterface.py | 2 +- .../pupper}/Kinematics.py | 0 {sim => stanford_quad/pupper}/__init__.py | 0 .../sim}/HardwareInterface.py | 0 {sim => stanford_quad/sim}/IMU.py | 0 {woofer => stanford_quad/sim}/__init__.py | 0 sim/Sim.py => stanford_quad/sim/simulator.py | 11 +- stanford_quad/sim/test.py | 0 {woofer => stanford_quad/woofer}/Config.py | 0 .../woofer}/HardwareConfig.py | 0 .../woofer}/HardwareInterface.py | 4 +- .../woofer}/Kinematics.py | 0 stanford_quad/woofer/__init__.py | 0 52 files changed, 797 insertions(+), 764 deletions(-) create mode 100644 .idea/.gitignore create mode 100644 .idea/StanfordQuadruped.iml create mode 100644 .idea/inspectionProfiles/Project_Default.xml create mode 100644 .idea/inspectionProfiles/profiles_settings.xml create mode 100644 .idea/misc.xml create mode 100644 .idea/modules.xml create mode 100644 .idea/vcs.xml delete mode 100644 RunPyBulletSim.py delete mode 100644 common/Controller.py delete mode 100644 common/Tests.py delete mode 100644 run_robot.py create mode 100644 scripts/RunPyBulletSim.py rename calibrate_servos.py => scripts/calibrate_servos.py (72%) rename install.sh => scripts/install.sh (96%) rename robot.service => scripts/robot.service (100%) create mode 100644 scripts/run_robot.py create mode 100644 setup.py delete mode 100644 sim/test.py create mode 100644 stanford_quad.egg-info/PKG-INFO create mode 100644 stanford_quad.egg-info/SOURCES.txt create mode 100644 stanford_quad.egg-info/dependency_links.txt create mode 100644 stanford_quad.egg-info/requires.txt create mode 100644 stanford_quad.egg-info/top_level.txt rename {common => stanford_quad}/__init__.py (100%) create mode 100644 stanford_quad/assets/__init__.py rename {sim => stanford_quad/assets}/pupper_pybullet_out.xml (100%) rename {common => stanford_quad/common}/Command.py (100%) create mode 100644 stanford_quad/common/Controller.py rename {common => stanford_quad/common}/Gaits.py (100%) rename {common => stanford_quad/common}/IMU.py (100%) rename {common => stanford_quad/common}/JoystickInterface.py (94%) rename {common => stanford_quad/common}/StanceController.py (99%) rename {common => stanford_quad/common}/State.py (97%) rename {common => stanford_quad/common}/SwingLegController.py (72%) create mode 100644 stanford_quad/common/Tests.py rename {common => stanford_quad/common}/Utilities.py (100%) rename {pupper => stanford_quad/common}/__init__.py (100%) rename {pupper => stanford_quad/pupper}/Config.py (80%) rename {pupper => stanford_quad/pupper}/HardwareConfig.py (100%) rename {pupper => stanford_quad/pupper}/HardwareInterface.py (98%) rename {pupper => stanford_quad/pupper}/Kinematics.py (100%) rename {sim => stanford_quad/pupper}/__init__.py (100%) rename {sim => stanford_quad/sim}/HardwareInterface.py (100%) rename {sim => stanford_quad/sim}/IMU.py (100%) rename {woofer => stanford_quad/sim}/__init__.py (100%) rename sim/Sim.py => stanford_quad/sim/simulator.py (84%) create mode 100644 stanford_quad/sim/test.py rename {woofer => stanford_quad/woofer}/Config.py (100%) rename {woofer => stanford_quad/woofer}/HardwareConfig.py (100%) rename {woofer => stanford_quad/woofer}/HardwareInterface.py (96%) rename {woofer => stanford_quad/woofer}/Kinematics.py (100%) create mode 100644 stanford_quad/woofer/__init__.py diff --git a/.idea/.gitignore b/.idea/.gitignore new file mode 100644 index 00000000..73f69e09 --- /dev/null +++ b/.idea/.gitignore @@ -0,0 +1,8 @@ +# Default ignored files +/shelf/ +/workspace.xml +# Datasource local storage ignored files +/dataSources/ +/dataSources.local.xml +# Editor-based HTTP Client requests +/httpRequests/ diff --git a/.idea/StanfordQuadruped.iml b/.idea/StanfordQuadruped.iml new file mode 100644 index 00000000..4f2c9af6 --- /dev/null +++ b/.idea/StanfordQuadruped.iml @@ -0,0 +1,15 @@ + + + + + + + + + + + + \ No newline at end of file diff --git a/.idea/inspectionProfiles/Project_Default.xml b/.idea/inspectionProfiles/Project_Default.xml new file mode 100644 index 00000000..c4850975 --- /dev/null +++ b/.idea/inspectionProfiles/Project_Default.xml @@ -0,0 +1,41 @@ + + + + \ No newline at end of file diff --git a/.idea/inspectionProfiles/profiles_settings.xml b/.idea/inspectionProfiles/profiles_settings.xml new file mode 100644 index 00000000..105ce2da --- /dev/null +++ b/.idea/inspectionProfiles/profiles_settings.xml @@ -0,0 +1,6 @@ + + + + \ No newline at end of file diff --git a/.idea/misc.xml b/.idea/misc.xml new file mode 100644 index 00000000..65531ca9 --- /dev/null +++ b/.idea/misc.xml @@ -0,0 +1,4 @@ + + + + \ No newline at end of file diff --git a/.idea/modules.xml b/.idea/modules.xml new file mode 100644 index 00000000..5cfc3383 --- /dev/null +++ b/.idea/modules.xml @@ -0,0 +1,8 @@ + + + + + + + + \ No newline at end of file diff --git a/.idea/vcs.xml b/.idea/vcs.xml new file mode 100644 index 00000000..94a25f7f --- /dev/null +++ b/.idea/vcs.xml @@ -0,0 +1,6 @@ + + + + + + \ No newline at end of file diff --git a/RunPyBulletSim.py b/RunPyBulletSim.py deleted file mode 100644 index 2c908557..00000000 --- a/RunPyBulletSim.py +++ /dev/null @@ -1,96 +0,0 @@ -import pybullet as p -import pybullet_data -import time -import numpy as np - -from sim.IMU import IMU -from sim.Sim import Sim -from common.Controller import Controller -from common.Command import Command -from common.JoystickInterface import JoystickInterface -from common.State import State -from sim.HardwareInterface import HardwareInterface -from pupper.Config import Configuration -from pupper.Kinematics import four_legs_inverse_kinematics - - -def main(use_imu=False, default_velocity=np.zeros(2), default_yaw_rate=0.0): - # Create config - config = Configuration() - config.z_clearance = 0.02 - sim = Sim(xml_path="sim/pupper_pybullet_out.xml") - hardware_interface = HardwareInterface(sim.model, sim.joint_indices) - - # Create imu handle - if use_imu: - imu = IMU() - - # Create controller and user input handles - controller = Controller(config, four_legs_inverse_kinematics,) - state = State() - command = Command() - - # Emulate the joystick inputs required to activate the robot - command.activate_event = 1 - controller.run(state, command) - command.activate_event = 0 - command.trot_event = 1 - controller.run(state, command) - command = Command() # zero it out - - # Apply a constant command. # TODO Add support for user input or an external commander - command.horizontal_velocity = default_velocity - command.yaw_rate = default_yaw_rate - - # The joystick service is linux-only, so commenting out for mac - # print("Creating joystick listener...") - # joystick_interface = JoystickInterface(config) - # print("Done.") - - print("Summary of gait parameters:") - print("overlap time: ", config.overlap_time) - print("swing time: ", config.swing_time) - print("z clearance: ", config.z_clearance) - print("x shift: ", config.x_shift) - - # Run the simulation - timesteps = 240 * 60 * 10 # simulate for a max of 10 minutes - - # Sim seconds per sim step - sim_steps_per_sim_second = 240 - sim_dt = 1.0 / sim_steps_per_sim_second - last_control_update = 0 - start = time.time() - - for steps in range(timesteps): - sim_time_elapsed = sim_dt * steps - if sim_time_elapsed - last_control_update > config.dt: - last_control_update = sim_time_elapsed - - # Get IMU measurement if enabled - state.quat_orientation = ( - imu.read_orientation() if use_imu else np.array([1, 0, 0, 0]) - ) - - # Step the controller forward by dt - controller.run(state, command) - - # Update the pwm widths going to the servos - hardware_interface.set_actuator_postions(state.joint_angles) - - # Simulate physics for 1/240 seconds (the default timestep) - sim.step() - - # Performance testing - elapsed = time.time() - start - if (steps % 60) == 0: - print( - "Sim seconds elapsed: {}, Real seconds elapsed: {}".format( - round(sim_time_elapsed, 3), round(elapsed, 3) - ) - ) - # print("Average steps per second: {0}, elapsed: {1}, i:{2}".format(steps / elapsed, elapsed, i)) - - -if __name__ == "__main__": - main(default_velocity=np.array([0.15, 0])) diff --git a/common/Controller.py b/common/Controller.py deleted file mode 100644 index 28351ba5..00000000 --- a/common/Controller.py +++ /dev/null @@ -1,171 +0,0 @@ -from common.Gaits import GaitController -from common.StanceController import StanceController -from common.SwingLegController import SwingController -from common.Utilities import clipped_first_order_filter -from common.State import BehaviorState, State - -import numpy as np -from collections import defaultdict -from transforms3d.euler import euler2mat, quat2euler -from transforms3d.quaternions import qconjugate, quat2axangle -from transforms3d.axangles import axangle2mat - - -class Controller: - """Controller and planner object - """ - - def __init__( - self, - config, - inverse_kinematics, - ): - self.config = config - - self.smoothed_yaw = 0.0 # for REST mode only - self.inverse_kinematics = inverse_kinematics - - self.contact_modes = np.zeros(4) - self.gait_controller = GaitController(self.config) - self.swing_controller = SwingController(self.config) - self.stance_controller = StanceController(self.config) - - self.hop_transition_mapping = {BehaviorState.REST: BehaviorState.HOP, BehaviorState.HOP: BehaviorState.FINISHHOP, BehaviorState.FINISHHOP: BehaviorState.REST, BehaviorState.TROT: BehaviorState.HOP} - self.trot_transition_mapping = {BehaviorState.REST: BehaviorState.TROT, BehaviorState.TROT: BehaviorState.REST, BehaviorState.HOP: BehaviorState.TROT, BehaviorState.FINISHHOP: BehaviorState.TROT} - self.activate_transition_mapping = defaultdict(lambda: BehaviorState.DEACTIVATED, {BehaviorState.DEACTIVATED: BehaviorState.REST}) - - - def step_gait(self, state, command): - """Calculate the desired foot locations for the next timestep - - Returns - ------- - Numpy array (3, 4) - Matrix of new foot locations. - """ - contact_modes = self.gait_controller.contacts(state.ticks) - new_foot_locations = np.zeros((3, 4)) - for leg_index in range(4): - contact_mode = contact_modes[leg_index] - foot_location = state.foot_locations[:, leg_index] - if contact_mode == 1: - new_location = self.stance_controller.next_foot_location(leg_index, state, command) - else: - swing_proportion = ( - self.gait_controller.subphase_ticks(state.ticks) / self.config.swing_ticks - ) - new_location = self.swing_controller.next_foot_location( - swing_proportion, - leg_index, - state, - command - ) - new_foot_locations[:, leg_index] = new_location - return new_foot_locations, contact_modes - - - def run(self, state, command): - """Steps the controller forward one timestep - - Parameters - ---------- - controller : Controller - Robot controller object. - """ - - ########## Update operating state based on command ###### - if command.activate_event: - state.behavior_state = self.activate_transition_mapping[state.behavior_state] - elif command.trot_event: - state.behavior_state = self.trot_transition_mapping[state.behavior_state] - elif command.hop_event: - state.behavior_state = self.hop_transition_mapping[state.behavior_state] - - if state.behavior_state == BehaviorState.TROT: - state.foot_locations, contact_modes = self.step_gait( - state, - command, - ) - - # Apply the desired body rotation - rotated_foot_locations = ( - euler2mat( - command.roll, command.pitch, 0.0 - ) - @ state.foot_locations - ) - - # Construct foot rotation matrix to compensate for body tilt - (roll, pitch, yaw) = quat2euler(state.quat_orientation) - correction_factor = 0.8 - max_tilt = 0.4 - roll_compensation = correction_factor * np.clip(roll, -max_tilt, max_tilt) - pitch_compensation = correction_factor * np.clip(pitch, -max_tilt, max_tilt) - rmat = euler2mat(roll_compensation, pitch_compensation, 0) - - rotated_foot_locations = rmat.T @ rotated_foot_locations - - state.joint_angles = self.inverse_kinematics( - rotated_foot_locations, self.config - ) - - elif state.behavior_state == BehaviorState.HOP: - state.foot_locations = ( - self.config.default_stance - + np.array([0, 0, -0.09])[:, np.newaxis] - ) - state.joint_angles = self.inverse_kinematics( - state.foot_locations, self.config - ) - - elif state.behavior_state == BehaviorState.FINISHHOP: - state.foot_locations = ( - self.config.default_stance - + np.array([0, 0, -0.22])[:, np.newaxis] - ) - state.joint_angles = self.inverse_kinematics( - state.foot_locations, self.config - ) - - elif state.behavior_state == BehaviorState.REST: - yaw_proportion = command.yaw_rate / self.config.max_yaw_rate - self.smoothed_yaw += ( - self.config.dt - * clipped_first_order_filter( - self.smoothed_yaw, - yaw_proportion * -self.config.max_stance_yaw, - self.config.max_stance_yaw_rate, - self.config.yaw_time_constant, - ) - ) - # Set the foot locations to the default stance plus the standard height - state.foot_locations = ( - self.config.default_stance - + np.array([0, 0, command.height])[:, np.newaxis] - ) - # Apply the desired body rotation - rotated_foot_locations = ( - euler2mat( - command.roll, - command.pitch, - self.smoothed_yaw, - ) - @ state.foot_locations - ) - state.joint_angles = self.inverse_kinematics( - rotated_foot_locations, self.config - ) - - state.ticks += 1 - state.pitch = command.pitch - state.roll = command.roll - state.height = command.height - - def set_pose_to_default(self): - state.foot_locations = ( - self.config.default_stance - + np.array([0, 0, self.config.default_z_ref])[:, np.newaxis] - ) - state.joint_angles = controller.inverse_kinematics( - state.foot_locations, self.config - ) diff --git a/common/Tests.py b/common/Tests.py deleted file mode 100644 index 83a5afb1..00000000 --- a/common/Tests.py +++ /dev/null @@ -1,311 +0,0 @@ -# using LinearAlgebra -# using Profile -# using StaticArrays -# using Plots -# using BenchmarkTools - -# include("Kinematics.jl") -# include("PupperConfig.jl") -# include("Gait.jl") -# include("StanceController.jl") -# include("SwingLegController.jl") -# include("Types.jl") -# include("Controller.jl") - -import numpy as np -import matplotlib.pyplot as plt - -from Kinematics import leg_explicit_inverse_kinematics -from PupperConfig import * -from Gaits import * -from StanceController import position_delta, stance_foot_location -from SwingLegController import * -from Types import MovementReference, GaitParams, StanceParams, SwingParams -from Controller import * - -# function round_(a, dec) -# return map(x -> round(x, digits=dec), a) -# end - -# function testInverseKinematicsExplicit!() -# println("\n-------------- Testing Inverse Kinematics -----------") -# config = PupperConfig() -# println("\nTesting Inverse Kinematics") -# function testHelper(r, alpha_true, i; do_assert=true) -# eps = 1e-6 -# @time α = leg_explicitinversekinematics_prismatic(r, i, config) -# println("Leg ", i, ": r: ", r, " -> α: ", α) -# if do_assert -# @assert norm(α - alpha_true) < eps -# end -# end - -# c = config.LEG_L/sqrt(2) -# offset = config.ABDUCTION_OFFSET -# testHelper(SVector(0, offset, -0.125), SVector(0, 0, 0), 2) -# testHelper(SVector(c, offset, -c), SVector(0, -pi/4, 0), 2) -# testHelper(SVector(-c, offset, -c), SVector(0, pi/4, 0), 2) -# testHelper(SVector(0, c, -c), missing, 2, do_assert=false) - -# testHelper(SVector(-c, -offset, -c), [0, pi/4, 0], 1) -# testHelper(SVector(config.LEG_L * sqrt(3)/2, offset, -config.LEG_L / 2), SVector(0, -pi/3, 0), 2) -# end - - -def test_inverse_kinematics_linkage(): - print("\n-------------- Testing Five-bar Linkage Inverse Kinematics -----------") - config = PupperConfig() - print("\nTesting Inverse Kinematics") - - def testHelper(r, alpha_true, i, do_assert=True): - eps = 1e-6 - alpha = leg_explicit_inverse_kinematics(r, i, config) - print("Leg ", i, ": r: ", r, " -> α: ", alpha) - if do_assert: - assert np.linalg.norm(alpha - alpha_true) < eps - - c = config.LEG_L / (2 ** 0.5) - offset = config.ABDUCTION_OFFSET - testHelper(np.array([0, offset, -0.125]), None, 1, do_assert=False) - testHelper(np.array([c, offset, -c]), None, 1, do_assert=False) - testHelper(np.array([-c, offset, -c]), None, 1, do_assert=False) - testHelper(np.array([0, c, -c]), None, 1, do_assert=False) - - testHelper(np.array([-c, -offset, -c]), None, 0, do_assert=False) - testHelper( - np.array([config.LEG_L * (3 ** 0.5) / 2, offset, -config.LEG_L / 2]), - None, - 1, - do_assert=False, - ) - - -# function testForwardKinematics!() -# println("\n-------------- Testing Forward Kinematics -----------") -# config = PupperConfig() -# println("\nTesting Forward Kinematics") -# function testHelper(alpha, r_true, i; do_assert=true) -# eps = 1e-6 -# r = zeros(3) -# println("Vectors") -# a = [alpha.data...] -# @time legForwardKinematics!(r, a, i, config) -# println("SVectors") -# @time r = legForwardKinematics(alpha, i, config) -# println("Leg ", i, ": α: ", alpha, " -> r: ", r) -# if do_assert -# @assert norm(r_true - r) < eps -# end -# end - -# l = config.LEG_L -# offset = config.ABDUCTION_OFFSET -# testHelper(SVector{3}([0.0, 0.0, 0.0]), SVector{3}([0, offset, -l]), 2) -# testHelper(SVector{3}([0.0, pi/4, 0.0]), missing, 2, do_assert=false) -# # testHelper([0.0, 0.0, 0.0], [0, offset, -l], 2) -# # testHelper([0.0, pi/4, 0.0], missing, 2, do_assert=false) -# end - -# function testForwardInverseAgreeance() -# println("\n-------------- Testing Forward/Inverse Consistency -----------") -# config = PupperConfig() -# println("\nTest forward/inverse consistency") -# eps = 1e-6 -# for i in 1:10 -# alpha = SVector(rand()-0.5, rand()-0.5, (rand()-0.5)*0.05) -# leg = rand(1:4) -# @time r = legForwardKinematics(alpha, leg, config) -# # @code_warntype legForwardKinematics!(r, alpha, leg, config) -# @time alpha_prime = leg_explicitinversekinematics_prismatic(r, leg, config) -# # @code_warntype inverseKinematicsExplicit!(alpha_prime, r, leg, config) -# println("Leg ", leg, ": α: ", round_(alpha, 3), " -> r_body_foot: ", round_(r, 3), " -> α': ", round_(alpha_prime, 3)) -# @assert norm(alpha_prime - alpha) < eps -# end -# end - -# function testAllInverseKinematics() -# println("\n-------------- Testing Four Leg Inverse Kinematics -----------") -# function helper(r_body, alpha_true; do_assert=true) -# println("Timing for fourlegs_inversekinematics") -# config = PupperConfig() -# @time alpha = fourlegs_inversekinematics(SMatrix(r_body), config) -# @code_warntype fourlegs_inversekinematics(SMatrix(r_body), config) -# println("r: ", r_body, " -> α: ", alpha) - -# if do_assert -# @assert norm(alpha - alpha_true) < 1e-10 -# end -# end -# config = PupperConfig() -# f = config.LEG_FB -# l = config.LEG_LR -# s = -0.125 -# o = config.ABDUCTION_OFFSET -# r_body = MMatrix{3,4}(zeros(3,4)) -# r_body[:,1] = [f, -l-o, s] -# r_body[:,2] = [f, l+o, s] -# r_body[:,3] = [-f, -l-o, s] -# r_body[:,4] = [-f, l+o, s] - -# helper(r_body, zeros(3,4)) -# helper(SMatrix{3,4}(zeros(3,4)), missing, do_assert=false) -# end - -# function testKinematics() -# testInverseKinematicsExplicit!() -# testForwardKinematics!() -# testForwardInverseAgreeance() -# testAllInverseKinematics() -# end - -# function testGait() -# println("\n-------------- Testing Gait -----------") -# p = GaitParams() -# # println("Gait params=",p) -# t = 680 -# println("Timing for phaseindex") -# @time ph = phaseindex(t, p) -# # @code_warntype phaseindex(t, p) -# println("t=",t," phase=",ph) -# @assert ph == 4 -# @assert phaseindex(0, p) == 1 - -# println("Timing for contacts") -# @time c = contacts(t, p) -# # @code_warntype contacts(t, p) -# @assert typeof(c) == SArray{Tuple{4},Int64,1,4} -# println("t=", t, " contacts=", c) -# end - - -def test_stance_controller(): - print("\n-------------- Testing Stance Controller -----------") - stanceparams = StanceParams() - gaitparams = GaitParams() - - zmeas = -0.20 - mvref = MovementReference() - dp, dR = position_delta(zmeas, stanceparams, mvref, gaitparams) - assert np.linalg.norm(dR - np.eye(3)) < 1e-10 - assert np.linalg.norm(dp - np.array([0, 0, gaitparams.dt * 0.04])) < 1e-10 - - zmeas = -0.18 - mvref = MovementReference() - mvref.v_xy_ref = np.array([1.0, 0.0]) - mvref.z_ref = -0.18 - dp, dR = position_delta(zmeas, stanceparams, mvref, gaitparams) - - zmeas = -0.20 - mvref = MovementReference() - mvref.wz_ref = 1.0 - mvref.z_ref = -0.20 - dp, dR = position_delta(zmeas, stanceparams, mvref, gaitparams) - assert np.linalg.norm(dp - np.array([0, 0, 0])) < 1e-10 - assert np.linalg.norm(dR[0, 1] - (gaitparams.dt)) < 1e-6 - - stancefootloc = np.zeros(3) - sloc = stance_foot_location(stancefootloc, stanceparams, gaitparams, mvref) - - -# function typeswinglegcontroller() -# println("\n--------------- Code warn type for raibert_tdlocation[s] ----------") -# swp = SwingParams() -# stp = StanceParams() -# gp = GaitParams() -# mvref = MovementReference(SVector(1.0, 0.0), 0, -0.18) -# raibert_tdlocations(swp, stp, gp, mvref) - -# mvref = MovementReference(SVector(1.0, 0.0), 0, -0.18) -# raibert_tdlocation(1, swp, stp, gp, mvref) -# end - -# function TestSwingLegController() -# println("\n-------------- Testing Swing Leg Controller -----------") -# swp = SwingParams() -# stp = StanceParams() -# gp = GaitParams() -# p = ControllerParams() -# println("Timing for swingheight:") -# @time z = swingheight(0.5, swp) -# println("z clearance at t=1/2swingtime =>",z) -# @assert abs(z - swp.zclearance) < 1e-10 - -# println("Timing for swingheight:") -# @time z = swingheight(0, swp) -# println("Z clearance at t=0 =>",z) -# @assert abs(z) < 1e-10 - -# mvref = MovementReference(SVector(1.0, 0.0), 0, -0.18) -# println("Timing for raibert tdlocation*s*:") -# @time l = raibert_tdlocations(swp, stp, gp, mvref) -# target = stp.defaultstance .+ [gp.stanceticks*gp.dt*0.5*1, 0, 0] -# println("Touchdown locations =>", l, " ", target) -# @assert norm(l - target) <= 1e-10 - -# mvref = MovementReference(SVector(1.0, 0.0), 0, -0.18) -# println("Timing for raibert tdlocation:") -# @time l = raibert_tdlocation(1, swp, stp, gp, mvref) - -# fcurrent = SMatrix{3, 4, Float64}(stp.defaultstance) -# mvref = MovementReference() -# tswing = 0.125 -# println("Timing for swingfootlocation*s* increment") -# @time l = swingfootlocations(tswing, fcurrent, swp, stp, gp, mvref) -# println(l) - -# fcurrent = SVector{3, Float64}(0.0, 0.0, 0.0) -# println("Timing for swingfootlocation") -# @time swingfootlocation(tswing, fcurrent, 1, swp, stp, gp, mvref) - -# typeswinglegcontroller() -# return nothing -# end - - -def test_run(): - print("Run timing") - foot_loc_history, joint_angle_history = run() - plt.subplot(211) - x = plt.plot(foot_loc_history[0, :, :].T, label="x") - y = plt.plot(foot_loc_history[1, :, :].T, label="y") - z = plt.plot(foot_loc_history[2, :, :].T, label="z") - - plt.subplot(212) - alpha = plt.plot(joint_angle_history[0, :, :].T, label="alpha") - beta = plt.plot(joint_angle_history[1, :, :].T, label="beta") - gamma = plt.plot(joint_angle_history[2, :, :].T, label="gamma") - plt.show() - - # plot(x, β, y, α, z, γ, layout=(3,2), legend=false)) - - -# function teststep() -# swingparams = SwingParams() -# stanceparams = StanceParams() -# gaitparams = GaitParams() -# mvref = MovementReference(vxyref=SVector{2}(0.2, 0.0), wzref=0.0) -# conparams = ControllerParams() -# robotconfig = PupperConfig() - - -# footlocations::SMatrix{3, 4, Float64, 12} = stanceparams.defaultstance .+ SVector{3, Float64}(0, 0, mvref.zref) - -# ticks = 1 -# println("Timing for step!") -# @btime step($ticks, $footlocations, $swingparams, $stanceparams, $gaitparams, $mvref, $conparams) -# @code_warntype step(ticks, footlocations, swingparams, stanceparams, gaitparams, mvref, conparams) -# end - -# # testGait() -# # testKinematics() -# # TestStanceController() -# # testStaticArrays() -# # TestSwingLegController() -# test_inversekinematics_linkage() - -# # teststep() -# # testrun() - -test_inverse_kinematics_linkage() -test_stance_controller() -test_run() diff --git a/run_robot.py b/run_robot.py deleted file mode 100644 index 591b4ee8..00000000 --- a/run_robot.py +++ /dev/null @@ -1,79 +0,0 @@ -import numpy as np -import time -from common.IMU import IMU -from common.Controller import Controller -from common.JoystickInterface import JoystickInterface -from common.State import State -from pupper.HardwareInterface import HardwareInterface -from pupper.Config import Configuration -from pupper.Kinematics import four_legs_inverse_kinematics - -def main(use_imu=False): - """Main program - """ - - # Create config - config = Configuration() - hardware_interface = HardwareInterface() - - # Create imu handle - if use_imu: - imu = IMU(port="/dev/ttyACM0") - imu.flush_buffer() - - # Create controller and user input handles - controller = Controller( - config, - four_legs_inverse_kinematics, - ) - state = State() - print("Creating joystick listener...") - joystick_interface = JoystickInterface(config) - print("Done.") - - last_loop = time.time() - - print("Summary of gait parameters:") - print("overlap time: ", config.overlap_time) - print("swing time: ", config.swing_time) - print("z clearance: ", config.z_clearance) - print("x shift: ", config.x_shift) - - # Wait until the activate button has been pressed - while True: - print("Waiting for L1 to activate robot.") - while True: - command = joystick_interface.get_command(state) - joystick_interface.set_color(config.ps4_deactivated_color) - if command.activate_event == 1: - break - time.sleep(0.1) - print("Robot activated.") - joystick_interface.set_color(config.ps4_color) - - while True: - now = time.time() - if now - last_loop < config.dt: - continue - last_loop = time.time() - - # Parse the udp joystick commands and then update the robot controller's parameters - command = joystick_interface.get_command(state) - if command.activate_event == 1: - print("Deactivating Robot") - break - - # Read imu data. Orientation will be None if no data was available - quat_orientation = ( - imu.read_orientation() if use_imu else np.array([1, 0, 0, 0]) - ) - state.quat_orientation = quat_orientation - - # Step the controller forward by dt - controller.run(state, command) - - # Update the pwm widths going to the servos - hardware_interface.set_actuator_postions(state.joint_angles) - -if __name__ == "__main__": - main() diff --git a/scripts/RunPyBulletSim.py b/scripts/RunPyBulletSim.py new file mode 100644 index 00000000..81f01f59 --- /dev/null +++ b/scripts/RunPyBulletSim.py @@ -0,0 +1,93 @@ +import os +import time +import numpy as np + +from stanford_quad.assets import ASSET_DIR +from stanford_quad.common.Command import Command +from stanford_quad.common.Controller import Controller +from stanford_quad.common.State import State +from stanford_quad.pupper.Config import Configuration +from stanford_quad.pupper.Kinematics import four_legs_inverse_kinematics +from stanford_quad.sim.IMU import IMU +from stanford_quad.sim.HardwareInterface import HardwareInterface +from stanford_quad.sim.simulator import PySim + +USE_IMU = False +DEFAULT_VEL = np.array([0.15, 0]) +DEFAULT_YAW_RATE=0.0 + +# Create config +config = Configuration() +config.z_clearance = 0.02 + +sim = PySim(xml_path=os.path.join(ASSET_DIR, "pupper_pybullet_out.xml")) +hardware_interface = HardwareInterface(sim.model, sim.joint_indices) + +# Create imu handle +if USE_IMU: + imu = IMU() + +# Create controller and user input handles +controller = Controller(config, four_legs_inverse_kinematics,) +state = State() +command = Command() + +# Emulate the joystick inputs required to activate the robot +command.activate_event = 1 +controller.run(state, command) +command.activate_event = 0 +command.trot_event = 1 +controller.run(state, command) +command = Command() # zero it out + +# Apply a constant command. # TODO Add support for user input or an external commander +command.horizontal_velocity = DEFAULT_VEL +command.yaw_rate = DEFAULT_YAW_RATE + +# The joystick service is linux-only, so commenting out for mac +# print("Creating joystick listener...") +# joystick_interface = JoystickInterface(config) +# print("Done.") + +print("Summary of gait parameters:") +print("overlap time: ", config.overlap_time) +print("swing time: ", config.swing_time) +print("z clearance: ", config.z_clearance) +print("x shift: ", config.x_shift) + +# Run the simulation +timesteps = 240 * 60 * 10 # simulate for a max of 10 minutes + +# Sim seconds per sim step +sim_steps_per_sim_second = 240 +sim_dt = 1.0 / sim_steps_per_sim_second +last_control_update = 0 +start = time.time() + +for steps in range(timesteps): + sim_time_elapsed = sim_dt * steps + if sim_time_elapsed - last_control_update > config.dt: + last_control_update = sim_time_elapsed + + # Get IMU measurement if enabled + state.quat_orientation = IMU.read_orientation() if USE_IMU else np.array([1, 0, 0, 0]) + + # Step the controller forward by dt + controller.run(state, command) + + # Update the pwm widths going to the servos + hardware_interface.set_actuator_postions(state.joint_angles) + + # Simulate physics for 1/240 seconds (the default timestep) + sim.step() + + # Performance testing + elapsed = time.time() - start + if (steps % 60) == 0: + print( + "Sim seconds elapsed: {}, Real seconds elapsed: {}".format( + round(sim_time_elapsed, 3), round(elapsed, 3) + ) + ) + # print("Average steps per second: {0}, elapsed: {1}, i:{2}".format(steps / elapsed, elapsed, i)) + diff --git a/calibrate_servos.py b/scripts/calibrate_servos.py similarity index 72% rename from calibrate_servos.py rename to scripts/calibrate_servos.py index 6013f95b..0e48abe8 100644 --- a/calibrate_servos.py +++ b/scripts/calibrate_servos.py @@ -1,6 +1,4 @@ -import pigpio -from pupper.HardwareInterface import HardwareInterface -from pupper.Config import PWMParams, ServoParams +from stanford_quad.pupper import HardwareInterface import numpy as np @@ -45,22 +43,21 @@ def step_until(hardware_interface, axis, leg, set_point): offset = 0 while not found_position: move_input = str( - input("Enter 'a' or 'b' to move the link until it is **" + set_names[axis] + "**. Enter 'd' when done. Input: " + input( + "Enter 'a' or 'b' to move the link until it is **" + + set_names[axis] + + "**. Enter 'd' when done. Input: " ) ) if move_input == "a": offset += 1.0 hardware_interface.set_actuator_position( - degrees_to_radians(set_point + offset), - axis, - leg, + degrees_to_radians(set_point + offset), axis, leg, ) elif move_input == "b": offset -= 1.0 hardware_interface.set_actuator_position( - degrees_to_radians(set_point + offset), - axis, - leg, + degrees_to_radians(set_point + offset), axis, leg, ) elif move_input == "d": found_position = True @@ -83,7 +80,11 @@ def calibrate_angle_offset(hardware_interface): # Found K value of (11.4) k = float( - input("Enter the scaling constant for your servo. This constant is how much you have to increase the pwm pulse width (in microseconds) to rotate the servo output 1 degree. (It is 11.333 for the newer CLS6336 and CLS6327 servos). Input: ") + input( + "Enter the scaling constant for your servo. This constant is how much you have to increase the pwm pulse " + "width (in microseconds) to rotate the servo output 1 degree. (It is 11.333 for the newer CLS6336 and " + "CLS6327 servos). Input: " + ) ) hardware_interface.servo_params.micros_per_rad = k * 180 / np.pi @@ -103,15 +104,11 @@ def calibrate_angle_offset(hardware_interface): # Move servo to set_point angle hardware_interface.set_actuator_position( - degrees_to_radians(set_point), - axis, - leg_index, + degrees_to_radians(set_point), axis, leg_index, ) # Adjust the angle using keyboard input until it matches the reference angle - offset = step_until( - hardware_interface, axis, leg_index, set_point - ) + offset = step_until(hardware_interface, axis, leg_index, set_point) print("Final offset: ", offset) # The upper leg link has a different equation because we're calibrating to make it horizontal, not vertical @@ -119,20 +116,22 @@ def calibrate_angle_offset(hardware_interface): hardware_interface.servo_params.neutral_angle_degrees[axis, leg_index] = set_point - offset else: hardware_interface.servo_params.neutral_angle_degrees[axis, leg_index] = -(set_point + offset) - print("Calibrated neutral angle: ", hardware_interface.servo_params.neutral_angle_degrees[axis, leg_index]) + print( + "Calibrated neutral angle: ", hardware_interface.servo_params.neutral_angle_degrees[axis, leg_index] + ) # Send the servo command using the new beta value and check that it's ok hardware_interface.set_actuator_position( - degrees_to_radians([0, 45, -45][axis]), - axis, - leg_index, + degrees_to_radians([0, 45, -45][axis]), axis, leg_index, ) okay = "" - prompt = "The leg should be at exactly **" + ["horizontal", "45 degrees", "45 degrees"][axis] + "**. Are you satisfied? Enter 'yes' or 'no': " + prompt = ( + "The leg should be at exactly **" + + ["horizontal", "45 degrees", "45 degrees"][axis] + + "**. Are you satisfied? Enter 'yes' or 'no': " + ) while okay not in ["yes", "no"]: - okay = str( - input(prompt) - ) + okay = str(input(prompt)) completed = okay == "yes" @@ -146,7 +145,10 @@ def main(): print("Calibrated neutral angles:") print(hardware_interface.servo_params.neutral_angle_degrees) print("Copy these values into the NEUTRAL_ANGLE_DEGREES matrix defined pupper/HardwareConfig.py") - print("Set the MICROS_PER_RAD value in pupper/HardwareConfig.py to whatever you defined in the beginning of this program as well.") + print( + "Set the MICROS_PER_RAD value in pupper/HardwareConfig.py to whatever you defined in the beginning of " + "this program as well." + ) main() diff --git a/install.sh b/scripts/install.sh similarity index 96% rename from install.sh rename to scripts/install.sh index 2aeff727..e9428e0c 100644 --- a/install.sh +++ b/scripts/install.sh @@ -22,7 +22,7 @@ make sudo make install cd .. -cd StanfordQuadruped +cd StanfordQuadruped/scripts sudo ln -s $(realpath .)/robot.service /etc/systemd/system/ sudo systemctl daemon-reload sudo systemctl enable robot diff --git a/robot.service b/scripts/robot.service similarity index 100% rename from robot.service rename to scripts/robot.service diff --git a/scripts/run_robot.py b/scripts/run_robot.py new file mode 100644 index 00000000..b7f3fd2d --- /dev/null +++ b/scripts/run_robot.py @@ -0,0 +1,70 @@ +import numpy as np +import time + +from stanford_quad.common.Controller import Controller +from stanford_quad.common.IMU import IMU +from stanford_quad.common.JoystickInterface import JoystickInterface +from stanford_quad.common.State import State +from stanford_quad.pupper.HardwareInterface import HardwareInterface +from stanford_quad.pupper.Config import Configuration +from stanford_quad.pupper.Kinematics import four_legs_inverse_kinematics + +USE_IMU = False + +# Create config +config = Configuration() +hardware_interface = HardwareInterface() + +# Create imu handle +if USE_IMU: + imu = IMU(port="/dev/ttyACM0") + imu.flush_buffer() + +# Create controller and user input handles +controller = Controller(config, four_legs_inverse_kinematics,) +state = State() +print("Creating joystick listener...") +joystick_interface = JoystickInterface(config) +print("Done.") + +last_loop = time.time() + +print("Summary of gait parameters:") +print("overlap time: ", config.overlap_time) +print("swing time: ", config.swing_time) +print("z clearance: ", config.z_clearance) +print("x shift: ", config.x_shift) + +# Wait until the activate button has been pressed +while True: + print("Waiting for L1 to activate robot.") + while True: + command = joystick_interface.get_command(state) + joystick_interface.set_color(config.ps4_deactivated_color) + if command.activate_event == 1: + break + time.sleep(0.1) + print("Robot activated.") + joystick_interface.set_color(config.ps4_color) + + while True: + now = time.time() + if now - last_loop < config.dt: + continue + last_loop = time.time() + + # Parse the udp joystick commands and then update the robot controller's parameters + command = joystick_interface.get_command(state) + if command.activate_event == 1: + print("Deactivating Robot") + break + + # Read imu data. Orientation will be None if no data was available + quat_orientation = IMU.read_orientation() if USE_IMU else np.array([1, 0, 0, 0]) + state.quat_orientation = quat_orientation + + # Step the controller forward by dt + controller.run(state, command) + + # Update the pwm widths going to the servos + hardware_interface.set_actuator_postions(state.joint_angles) diff --git a/setup.py b/setup.py new file mode 100644 index 00000000..a7b08ef6 --- /dev/null +++ b/setup.py @@ -0,0 +1,16 @@ +from setuptools import setup + +setup( + name="stanford_quad", + version="1.0", + install_requires=[ + "tqdm", + "numpy", + "matplotlib", + "pybullet", + "gym", + "opencv-python", + "transforms3d", + "UDPComms @ git+ssh://git@github.com/stanfordroboticsclub/UDPComms@master#egg=UDPComms", + ], +) diff --git a/sim/test.py b/sim/test.py deleted file mode 100644 index 384c4794..00000000 --- a/sim/test.py +++ /dev/null @@ -1 +0,0 @@ -from ..pupper import Config \ No newline at end of file diff --git a/stanford_quad.egg-info/PKG-INFO b/stanford_quad.egg-info/PKG-INFO new file mode 100644 index 00000000..ae45e17c --- /dev/null +++ b/stanford_quad.egg-info/PKG-INFO @@ -0,0 +1,10 @@ +Metadata-Version: 1.0 +Name: stanford-quad +Version: 1.0 +Summary: UNKNOWN +Home-page: UNKNOWN +Author: UNKNOWN +Author-email: UNKNOWN +License: UNKNOWN +Description: UNKNOWN +Platform: UNKNOWN diff --git a/stanford_quad.egg-info/SOURCES.txt b/stanford_quad.egg-info/SOURCES.txt new file mode 100644 index 00000000..9cdebdc2 --- /dev/null +++ b/stanford_quad.egg-info/SOURCES.txt @@ -0,0 +1,7 @@ +README.md +setup.py +stanford_quad.egg-info/PKG-INFO +stanford_quad.egg-info/SOURCES.txt +stanford_quad.egg-info/dependency_links.txt +stanford_quad.egg-info/requires.txt +stanford_quad.egg-info/top_level.txt \ No newline at end of file diff --git a/stanford_quad.egg-info/dependency_links.txt b/stanford_quad.egg-info/dependency_links.txt new file mode 100644 index 00000000..8b137891 --- /dev/null +++ b/stanford_quad.egg-info/dependency_links.txt @@ -0,0 +1 @@ + diff --git a/stanford_quad.egg-info/requires.txt b/stanford_quad.egg-info/requires.txt new file mode 100644 index 00000000..ae045828 --- /dev/null +++ b/stanford_quad.egg-info/requires.txt @@ -0,0 +1,8 @@ +tqdm +numpy +matplotlib +pybullet +gym +opencv-python +transforms3d +UDPComms@ git+ssh://git@github.com/stanfordroboticsclub/UDPComms@master#egg=UDPComms diff --git a/stanford_quad.egg-info/top_level.txt b/stanford_quad.egg-info/top_level.txt new file mode 100644 index 00000000..8b137891 --- /dev/null +++ b/stanford_quad.egg-info/top_level.txt @@ -0,0 +1 @@ + diff --git a/common/__init__.py b/stanford_quad/__init__.py similarity index 100% rename from common/__init__.py rename to stanford_quad/__init__.py diff --git a/stanford_quad/assets/__init__.py b/stanford_quad/assets/__init__.py new file mode 100644 index 00000000..2e377da4 --- /dev/null +++ b/stanford_quad/assets/__init__.py @@ -0,0 +1,4 @@ +import os + +ASSET_DIR = os.path.dirname(os.path.realpath(__file__)) + diff --git a/sim/pupper_pybullet_out.xml b/stanford_quad/assets/pupper_pybullet_out.xml similarity index 100% rename from sim/pupper_pybullet_out.xml rename to stanford_quad/assets/pupper_pybullet_out.xml diff --git a/common/Command.py b/stanford_quad/common/Command.py similarity index 100% rename from common/Command.py rename to stanford_quad/common/Command.py diff --git a/stanford_quad/common/Controller.py b/stanford_quad/common/Controller.py new file mode 100644 index 00000000..d857d70d --- /dev/null +++ b/stanford_quad/common/Controller.py @@ -0,0 +1,132 @@ +from transforms3d.euler import euler2mat, quat2euler + +from stanford_quad.common.Gaits import GaitController +from stanford_quad.common.StanceController import StanceController + +import numpy as np +from collections import defaultdict + +from stanford_quad.common.State import BehaviorState +from stanford_quad.common.SwingLegController import SwingController +from stanford_quad.common.Utilities import clipped_first_order_filter + + +class Controller: + """Controller and planner object + """ + + def __init__( + self, config, inverse_kinematics, + ): + self.config = config + + self.smoothed_yaw = 0.0 # for REST mode only + self.inverse_kinematics = inverse_kinematics + + self.contact_modes = np.zeros(4) + self.gait_controller = GaitController(self.config) + self.swing_controller = SwingController(self.config) + self.stance_controller = StanceController(self.config) + + self.hop_transition_mapping = { + BehaviorState.REST: BehaviorState.HOP, + BehaviorState.HOP: BehaviorState.FINISHHOP, + BehaviorState.FINISHHOP: BehaviorState.REST, + BehaviorState.TROT: BehaviorState.HOP, + } + self.trot_transition_mapping = { + BehaviorState.REST: BehaviorState.TROT, + BehaviorState.TROT: BehaviorState.REST, + BehaviorState.HOP: BehaviorState.TROT, + BehaviorState.FINISHHOP: BehaviorState.TROT, + } + self.activate_transition_mapping = defaultdict( + lambda: BehaviorState.DEACTIVATED, {BehaviorState.DEACTIVATED: BehaviorState.REST} + ) + + def step_gait(self, state, command): + """Calculate the desired foot locations for the next timestep + + Returns + ------- + Numpy array (3, 4) + Matrix of new foot locations. + """ + contact_modes = self.gait_controller.contacts(state.ticks) + new_foot_locations = np.zeros((3, 4)) + for leg_index in range(4): + contact_mode = contact_modes[leg_index] + foot_location = state.foot_locations[:, leg_index] + if contact_mode == 1: + new_location = self.stance_controller.next_foot_location(leg_index, state, command) + else: + swing_proportion = self.gait_controller.subphase_ticks(state.ticks) / self.config.swing_ticks + new_location = self.swing_controller.next_foot_location(swing_proportion, leg_index, state, command) + new_foot_locations[:, leg_index] = new_location + return new_foot_locations, contact_modes + + def run(self, state, command): + """Steps the controller forward one timestep + + Parameters + ---------- + controller : Controller + Robot controller object. + """ + + ########## Update operating state based on command ###### + if command.activate_event: + state.behavior_state = self.activate_transition_mapping[state.behavior_state] + elif command.trot_event: + state.behavior_state = self.trot_transition_mapping[state.behavior_state] + elif command.hop_event: + state.behavior_state = self.hop_transition_mapping[state.behavior_state] + + if state.behavior_state == BehaviorState.TROT: + state.foot_locations, contact_modes = self.step_gait(state, command,) + + # Apply the desired body rotation + rotated_foot_locations = euler2mat(command.roll, command.pitch, 0.0) @ state.foot_locations + + # Construct foot rotation matrix to compensate for body tilt + (roll, pitch, yaw) = quat2euler(state.quat_orientation) + correction_factor = 0.8 + max_tilt = 0.4 + roll_compensation = correction_factor * np.clip(roll, -max_tilt, max_tilt) + pitch_compensation = correction_factor * np.clip(pitch, -max_tilt, max_tilt) + rmat = euler2mat(roll_compensation, pitch_compensation, 0) + + rotated_foot_locations = rmat.T @ rotated_foot_locations + + state.joint_angles = self.inverse_kinematics(rotated_foot_locations, self.config) + + elif state.behavior_state == BehaviorState.HOP: + state.foot_locations = self.config.default_stance + np.array([0, 0, -0.09])[:, np.newaxis] + state.joint_angles = self.inverse_kinematics(state.foot_locations, self.config) + + elif state.behavior_state == BehaviorState.FINISHHOP: + state.foot_locations = self.config.default_stance + np.array([0, 0, -0.22])[:, np.newaxis] + state.joint_angles = self.inverse_kinematics(state.foot_locations, self.config) + + elif state.behavior_state == BehaviorState.REST: + yaw_proportion = command.yaw_rate / self.config.max_yaw_rate + self.smoothed_yaw += self.config.dt * clipped_first_order_filter( + self.smoothed_yaw, + yaw_proportion * -self.config.max_stance_yaw, + self.config.max_stance_yaw_rate, + self.config.yaw_time_constant, + ) + # Set the foot locations to the default stance plus the standard height + state.foot_locations = self.config.default_stance + np.array([0, 0, command.height])[:, np.newaxis] + # Apply the desired body rotation + rotated_foot_locations = euler2mat(command.roll, command.pitch, self.smoothed_yaw,) @ state.foot_locations + state.joint_angles = self.inverse_kinematics(rotated_foot_locations, self.config) + + state.ticks += 1 + state.pitch = command.pitch + state.roll = command.roll + state.height = command.height + + def set_pose_to_default(self, state, controller): + state.foot_locations = self.config.default_stance + np.array([0, 0, self.config.default_z_ref])[:, np.newaxis] + state.joint_angles = controller.inverse_kinematics(state.foot_locations, self.config) diff --git a/common/Gaits.py b/stanford_quad/common/Gaits.py similarity index 100% rename from common/Gaits.py rename to stanford_quad/common/Gaits.py diff --git a/common/IMU.py b/stanford_quad/common/IMU.py similarity index 100% rename from common/IMU.py rename to stanford_quad/common/IMU.py diff --git a/common/JoystickInterface.py b/stanford_quad/common/JoystickInterface.py similarity index 94% rename from common/JoystickInterface.py rename to stanford_quad/common/JoystickInterface.py index 4922dc4a..5211515b 100644 --- a/common/JoystickInterface.py +++ b/stanford_quad/common/JoystickInterface.py @@ -1,9 +1,9 @@ import UDPComms import numpy as np -import time -from common.State import BehaviorState, State -from common.Command import Command -from common.Utilities import deadband, clipped_first_order_filter + +from stanford_quad.common.Command import Command +from stanford_quad.common.State import BehaviorState +from stanford_quad.common.Utilities import deadband, clipped_first_order_filter class JoystickInterface: diff --git a/common/StanceController.py b/stanford_quad/common/StanceController.py similarity index 99% rename from common/StanceController.py rename to stanford_quad/common/StanceController.py index dfd925d3..63f2a55b 100644 --- a/common/StanceController.py +++ b/stanford_quad/common/StanceController.py @@ -1,6 +1,7 @@ import numpy as np from transforms3d.euler import euler2mat + class StanceController: def __init__(self, config): self.config = config diff --git a/common/State.py b/stanford_quad/common/State.py similarity index 97% rename from common/State.py rename to stanford_quad/common/State.py index 3af64bfe..acb148f8 100644 --- a/common/State.py +++ b/stanford_quad/common/State.py @@ -24,4 +24,4 @@ class BehaviorState(Enum): REST = 0 TROT = 1 HOP = 2 - FINISHHOP = 3 \ No newline at end of file + FINISHHOP = 3 diff --git a/common/SwingLegController.py b/stanford_quad/common/SwingLegController.py similarity index 72% rename from common/SwingLegController.py rename to stanford_quad/common/SwingLegController.py index ac3b670b..063b44b1 100644 --- a/common/SwingLegController.py +++ b/stanford_quad/common/SwingLegController.py @@ -1,30 +1,18 @@ import numpy as np from transforms3d.euler import euler2mat + class SwingController: def __init__(self, config): self.config = config - def raibert_touchdown_location( - self, leg_index, command - ): - delta_p_2d = ( - self.config.alpha - * self.config.stance_ticks - * self.config.dt - * command.horizontal_velocity - ) + def raibert_touchdown_location(self, leg_index, command): + delta_p_2d = self.config.alpha * self.config.stance_ticks * self.config.dt * command.horizontal_velocity delta_p = np.array([delta_p_2d[0], delta_p_2d[1], 0]) - theta = ( - self.config.beta - * self.config.stance_ticks - * self.config.dt - * command.yaw_rate - ) + theta = self.config.beta * self.config.stance_ticks * self.config.dt * command.yaw_rate R = euler2mat(0, 0, theta) return R @ self.config.default_stance[:, leg_index] + delta_p - def swing_height(self, swing_phase, triangular=True): if triangular: if swing_phase < 0.5: @@ -33,13 +21,8 @@ def swing_height(self, swing_phase, triangular=True): swing_height_ = self.config.z_clearance * (1 - (swing_phase - 0.5) / 0.5) return swing_height_ - def next_foot_location( - self, - swing_prop, - leg_index, - state, - command, + self, swing_prop, leg_index, state, command, ): assert swing_prop >= 0 and swing_prop <= 1 foot_location = state.foot_locations[:, leg_index] diff --git a/stanford_quad/common/Tests.py b/stanford_quad/common/Tests.py new file mode 100644 index 00000000..ffa55b22 --- /dev/null +++ b/stanford_quad/common/Tests.py @@ -0,0 +1,304 @@ +# # using LinearAlgebra +# # using Profile +# # using StaticArrays +# # using Plots +# # using BenchmarkTools +# +# # include("Kinematics.jl") +# # include("PupperConfig.jl") +# # include("Gait.jl") +# # include("StanceController.jl") +# # include("SwingLegController.jl") +# # include("Types.jl") +# # include("Controller.jl") +# +# import numpy as np +# import matplotlib.pyplot as plt +# +# # function round_(a, dec) +# # return map(x -> round(x, digits=dec), a) +# # end +# +# # function testInverseKinematicsExplicit!() +# # println("\n-------------- Testing Inverse Kinematics -----------") +# # config = PupperConfig() +# # println("\nTesting Inverse Kinematics") +# # function testHelper(r, alpha_true, i; do_assert=true) +# # eps = 1e-6 +# # @time α = leg_explicitinversekinematics_prismatic(r, i, config) +# # println("Leg ", i, ": r: ", r, " -> α: ", α) +# # if do_assert +# # @assert norm(α - alpha_true) < eps +# # end +# # end +# +# # c = config.LEG_L/sqrt(2) +# # offset = config.ABDUCTION_OFFSET +# # testHelper(SVector(0, offset, -0.125), SVector(0, 0, 0), 2) +# # testHelper(SVector(c, offset, -c), SVector(0, -pi/4, 0), 2) +# # testHelper(SVector(-c, offset, -c), SVector(0, pi/4, 0), 2) +# # testHelper(SVector(0, c, -c), missing, 2, do_assert=false) +# +# # testHelper(SVector(-c, -offset, -c), [0, pi/4, 0], 1) +# # testHelper(SVector(config.LEG_L * sqrt(3)/2, offset, -config.LEG_L / 2), SVector(0, -pi/3, 0), 2) +# # end +# from stanford_quad.pupper.Kinematics import leg_explicit_inverse_kinematics +# +# +# def test_inverse_kinematics_linkage(): +# print("\n-------------- Testing Five-bar Linkage Inverse Kinematics -----------") +# config = PupperConfig() +# print("\nTesting Inverse Kinematics") +# +# def testHelper(r, alpha_true, i, do_assert=True): +# eps = 1e-6 +# alpha = leg_explicit_inverse_kinematics(r, i, config) +# print("Leg ", i, ": r: ", r, " -> α: ", alpha) +# if do_assert: +# assert np.linalg.norm(alpha - alpha_true) < eps +# +# c = config.LEG_L / (2 ** 0.5) +# offset = config.ABDUCTION_OFFSET +# testHelper(np.array([0, offset, -0.125]), None, 1, do_assert=False) +# testHelper(np.array([c, offset, -c]), None, 1, do_assert=False) +# testHelper(np.array([-c, offset, -c]), None, 1, do_assert=False) +# testHelper(np.array([0, c, -c]), None, 1, do_assert=False) +# +# testHelper(np.array([-c, -offset, -c]), None, 0, do_assert=False) +# testHelper( +# np.array([config.LEG_L * (3 ** 0.5) / 2, offset, -config.LEG_L / 2]), +# None, +# 1, +# do_assert=False, +# ) +# +# +# # function testForwardKinematics!() +# # println("\n-------------- Testing Forward Kinematics -----------") +# # config = PupperConfig() +# # println("\nTesting Forward Kinematics") +# # function testHelper(alpha, r_true, i; do_assert=true) +# # eps = 1e-6 +# # r = zeros(3) +# # println("Vectors") +# # a = [alpha.data...] +# # @time legForwardKinematics!(r, a, i, config) +# # println("SVectors") +# # @time r = legForwardKinematics(alpha, i, config) +# # println("Leg ", i, ": α: ", alpha, " -> r: ", r) +# # if do_assert +# # @assert norm(r_true - r) < eps +# # end +# # end +# +# # l = config.LEG_L +# # offset = config.ABDUCTION_OFFSET +# # testHelper(SVector{3}([0.0, 0.0, 0.0]), SVector{3}([0, offset, -l]), 2) +# # testHelper(SVector{3}([0.0, pi/4, 0.0]), missing, 2, do_assert=false) +# # # testHelper([0.0, 0.0, 0.0], [0, offset, -l], 2) +# # # testHelper([0.0, pi/4, 0.0], missing, 2, do_assert=false) +# # end +# +# # function testForwardInverseAgreeance() +# # println("\n-------------- Testing Forward/Inverse Consistency -----------") +# # config = PupperConfig() +# # println("\nTest forward/inverse consistency") +# # eps = 1e-6 +# # for i in 1:10 +# # alpha = SVector(rand()-0.5, rand()-0.5, (rand()-0.5)*0.05) +# # leg = rand(1:4) +# # @time r = legForwardKinematics(alpha, leg, config) +# # # @code_warntype legForwardKinematics!(r, alpha, leg, config) +# # @time alpha_prime = leg_explicitinversekinematics_prismatic(r, leg, config) +# # # @code_warntype inverseKinematicsExplicit!(alpha_prime, r, leg, config) +# # println("Leg ", leg, ": α: ", round_(alpha, 3), " -> r_body_foot: ", round_(r, 3), " -> α': ", round_(alpha_prime, 3)) +# # @assert norm(alpha_prime - alpha) < eps +# # end +# # end +# +# # function testAllInverseKinematics() +# # println("\n-------------- Testing Four Leg Inverse Kinematics -----------") +# # function helper(r_body, alpha_true; do_assert=true) +# # println("Timing for fourlegs_inversekinematics") +# # config = PupperConfig() +# # @time alpha = fourlegs_inversekinematics(SMatrix(r_body), config) +# # @code_warntype fourlegs_inversekinematics(SMatrix(r_body), config) +# # println("r: ", r_body, " -> α: ", alpha) +# +# # if do_assert +# # @assert norm(alpha - alpha_true) < 1e-10 +# # end +# # end +# # config = PupperConfig() +# # f = config.LEG_FB +# # l = config.LEG_LR +# # s = -0.125 +# # o = config.ABDUCTION_OFFSET +# # r_body = MMatrix{3,4}(zeros(3,4)) +# # r_body[:,1] = [f, -l-o, s] +# # r_body[:,2] = [f, l+o, s] +# # r_body[:,3] = [-f, -l-o, s] +# # r_body[:,4] = [-f, l+o, s] +# +# # helper(r_body, zeros(3,4)) +# # helper(SMatrix{3,4}(zeros(3,4)), missing, do_assert=false) +# # end +# +# # function testKinematics() +# # testInverseKinematicsExplicit!() +# # testForwardKinematics!() +# # testForwardInverseAgreeance() +# # testAllInverseKinematics() +# # end +# +# # function testGait() +# # println("\n-------------- Testing Gait -----------") +# # p = GaitParams() +# # # println("Gait params=",p) +# # t = 680 +# # println("Timing for phaseindex") +# # @time ph = phaseindex(t, p) +# # # @code_warntype phaseindex(t, p) +# # println("t=",t," phase=",ph) +# # @assert ph == 4 +# # @assert phaseindex(0, p) == 1 +# +# # println("Timing for contacts") +# # @time c = contacts(t, p) +# # # @code_warntype contacts(t, p) +# # @assert typeof(c) == SArray{Tuple{4},Int64,1,4} +# # println("t=", t, " contacts=", c) +# # end +# +# +# def test_stance_controller(): +# print("\n-------------- Testing Stance Controller -----------") +# stanceparams = StanceParams() +# gaitparams = GaitParams() +# +# zmeas = -0.20 +# mvref = MovementReference() +# dp, dR = position_delta(zmeas, stanceparams, mvref, gaitparams) +# assert np.linalg.norm(dR - np.eye(3)) < 1e-10 +# assert np.linalg.norm(dp - np.array([0, 0, gaitparams.dt * 0.04])) < 1e-10 +# +# zmeas = -0.18 +# mvref = MovementReference() +# mvref.v_xy_ref = np.array([1.0, 0.0]) +# mvref.z_ref = -0.18 +# dp, dR = position_delta(zmeas, stanceparams, mvref, gaitparams) +# +# zmeas = -0.20 +# mvref = MovementReference() +# mvref.wz_ref = 1.0 +# mvref.z_ref = -0.20 +# dp, dR = position_delta(zmeas, stanceparams, mvref, gaitparams) +# assert np.linalg.norm(dp - np.array([0, 0, 0])) < 1e-10 +# assert np.linalg.norm(dR[0, 1] - (gaitparams.dt)) < 1e-6 +# +# stancefootloc = np.zeros(3) +# sloc = stance_foot_location(stancefootloc, stanceparams, gaitparams, mvref) +# +# +# # function typeswinglegcontroller() +# # println("\n--------------- Code warn type for raibert_tdlocation[s] ----------") +# # swp = SwingParams() +# # stp = StanceParams() +# # gp = GaitParams() +# # mvref = MovementReference(SVector(1.0, 0.0), 0, -0.18) +# # raibert_tdlocations(swp, stp, gp, mvref) +# +# # mvref = MovementReference(SVector(1.0, 0.0), 0, -0.18) +# # raibert_tdlocation(1, swp, stp, gp, mvref) +# # end +# +# # function TestSwingLegController() +# # println("\n-------------- Testing Swing Leg Controller -----------") +# # swp = SwingParams() +# # stp = StanceParams() +# # gp = GaitParams() +# # p = ControllerParams() +# # println("Timing for swingheight:") +# # @time z = swingheight(0.5, swp) +# # println("z clearance at t=1/2swingtime =>",z) +# # @assert abs(z - swp.zclearance) < 1e-10 +# +# # println("Timing for swingheight:") +# # @time z = swingheight(0, swp) +# # println("Z clearance at t=0 =>",z) +# # @assert abs(z) < 1e-10 +# +# # mvref = MovementReference(SVector(1.0, 0.0), 0, -0.18) +# # println("Timing for raibert tdlocation*s*:") +# # @time l = raibert_tdlocations(swp, stp, gp, mvref) +# # target = stp.defaultstance .+ [gp.stanceticks*gp.dt*0.5*1, 0, 0] +# # println("Touchdown locations =>", l, " ", target) +# # @assert norm(l - target) <= 1e-10 +# +# # mvref = MovementReference(SVector(1.0, 0.0), 0, -0.18) +# # println("Timing for raibert tdlocation:") +# # @time l = raibert_tdlocation(1, swp, stp, gp, mvref) +# +# # fcurrent = SMatrix{3, 4, Float64}(stp.defaultstance) +# # mvref = MovementReference() +# # tswing = 0.125 +# # println("Timing for swingfootlocation*s* increment") +# # @time l = swingfootlocations(tswing, fcurrent, swp, stp, gp, mvref) +# # println(l) +# +# # fcurrent = SVector{3, Float64}(0.0, 0.0, 0.0) +# # println("Timing for swingfootlocation") +# # @time swingfootlocation(tswing, fcurrent, 1, swp, stp, gp, mvref) +# +# # typeswinglegcontroller() +# # return nothing +# # end +# +# +# def test_run(): +# print("Run timing") +# foot_loc_history, joint_angle_history = run() +# plt.subplot(211) +# x = plt.plot(foot_loc_history[0, :, :].T, label="x") +# y = plt.plot(foot_loc_history[1, :, :].T, label="y") +# z = plt.plot(foot_loc_history[2, :, :].T, label="z") +# +# plt.subplot(212) +# alpha = plt.plot(joint_angle_history[0, :, :].T, label="alpha") +# beta = plt.plot(joint_angle_history[1, :, :].T, label="beta") +# gamma = plt.plot(joint_angle_history[2, :, :].T, label="gamma") +# plt.show() +# +# # plot(x, β, y, α, z, γ, layout=(3,2), legend=false)) +# +# +# # function teststep() +# # swingparams = SwingParams() +# # stanceparams = StanceParams() +# # gaitparams = GaitParams() +# # mvref = MovementReference(vxyref=SVector{2}(0.2, 0.0), wzref=0.0) +# # conparams = ControllerParams() +# # robotconfig = PupperConfig() +# +# +# # footlocations::SMatrix{3, 4, Float64, 12} = stanceparams.defaultstance .+ SVector{3, Float64}(0, 0, mvref.zref) +# +# # ticks = 1 +# # println("Timing for step!") +# # @btime step($ticks, $footlocations, $swingparams, $stanceparams, $gaitparams, $mvref, $conparams) +# # @code_warntype step(ticks, footlocations, swingparams, stanceparams, gaitparams, mvref, conparams) +# # end +# +# # # testGait() +# # # testKinematics() +# # # TestStanceController() +# # # testStaticArrays() +# # # TestSwingLegController() +# # test_inversekinematics_linkage() +# +# # # teststep() +# # # testrun() +# +# test_inverse_kinematics_linkage() +# test_stance_controller() +# test_run() diff --git a/common/Utilities.py b/stanford_quad/common/Utilities.py similarity index 100% rename from common/Utilities.py rename to stanford_quad/common/Utilities.py diff --git a/pupper/__init__.py b/stanford_quad/common/__init__.py similarity index 100% rename from pupper/__init__.py rename to stanford_quad/common/__init__.py diff --git a/pupper/Config.py b/stanford_quad/pupper/Config.py similarity index 80% rename from pupper/Config.py rename to stanford_quad/pupper/Config.py index df1c98ca..33fbdc37 100644 --- a/pupper/Config.py +++ b/stanford_quad/pupper/Config.py @@ -1,8 +1,9 @@ import numpy as np -from pupper.HardwareConfig import MICROS_PER_RAD, NEUTRAL_ANGLE_DEGREES, PS4_COLOR, PS4_DEACTIVATED_COLOR -from enum import Enum # TODO: put these somewhere else +from stanford_quad.pupper.HardwareConfig import MICROS_PER_RAD, NEUTRAL_ANGLE_DEGREES, PS4_COLOR, PS4_DEACTIVATED_COLOR + + class PWMParams: def __init__(self): self.pins = np.array([[2, 14, 18, 23], [3, 15, 27, 24], [4, 17, 22, 25]]) @@ -18,9 +19,7 @@ def __init__(self): # The neutral angle of the joint relative to the modeled zero-angle in degrees, for each joint self.neutral_angle_degrees = NEUTRAL_ANGLE_DEGREES - self.servo_multipliers = np.array( - [[1, 1, 1, 1], [-1, 1, -1, 1], [1, -1, 1, -1]] - ) + self.servo_multipliers = np.array([[1, 1, 1, 1], [-1, 1, -1, 1], [1, -1, 1, -1]]) @property def neutral_angles(self): @@ -30,15 +29,15 @@ def neutral_angles(self): class Configuration: def __init__(self): ################# CONTROLLER BASE COLOR ############## - self.ps4_color = PS4_COLOR - self.ps4_deactivated_color = PS4_DEACTIVATED_COLOR + self.ps4_color = PS4_COLOR + self.ps4_deactivated_color = PS4_DEACTIVATED_COLOR #################### COMMANDS #################### self.max_x_velocity = 0.4 self.max_y_velocity = 0.3 self.max_yaw_rate = 2.0 self.max_pitch = 30.0 * np.pi / 180.0 - + #################### MOVEMENT PARAMS #################### self.z_time_constant = 0.02 self.z_speed = 0.03 # maximum speed [m/s] @@ -59,25 +58,15 @@ def __init__(self): #################### SWING ###################### self.z_coeffs = None self.z_clearance = 0.07 - self.alpha = ( - 0.5 # Ratio between touchdown distance and total horizontal stance movement - ) - self.beta = ( - 0.5 # Ratio between touchdown distance and total horizontal stance movement - ) + self.alpha = 0.5 # Ratio between touchdown distance and total horizontal stance movement + self.beta = 0.5 # Ratio between touchdown distance and total horizontal stance movement #################### GAIT ####################### self.dt = 0.01 self.num_phases = 4 - self.contact_phases = np.array( - [[1, 1, 1, 0], [1, 0, 1, 1], [1, 0, 1, 1], [1, 1, 1, 0]] - ) - self.overlap_time = ( - 0.10 # duration of the phase where all four feet are on the ground - ) - self.swing_time = ( - 0.15 # duration of the phase when only two feet are on the ground - ) + self.contact_phases = np.array([[1, 1, 1, 0], [1, 0, 1, 1], [1, 0, 1, 1], [1, 1, 1, 0]]) + self.overlap_time = 0.10 # duration of the phase where all four feet are on the ground + self.swing_time = 0.15 # duration of the phase when only two feet are on the ground ######################## GEOMETRY ###################### self.LEG_FB = 0.10 # front-back distance from center line to leg axis @@ -105,12 +94,7 @@ def __init__(self): ) self.ABDUCTION_OFFSETS = np.array( - [ - -self.ABDUCTION_OFFSET, - self.ABDUCTION_OFFSET, - -self.ABDUCTION_OFFSET, - self.ABDUCTION_OFFSET, - ] + [-self.ABDUCTION_OFFSET, self.ABDUCTION_OFFSET, -self.ABDUCTION_OFFSET, self.ABDUCTION_OFFSET,] ) ################### INERTIAL #################### @@ -122,9 +106,7 @@ def __init__(self): # Compensation factor of 3 because the inertia measurement was just # of the carbon fiber and plastic parts of the frame and did not # include the hip servos and electronics - self.FRAME_INERTIA = tuple( - map(lambda x: 3.0 * x, (1.844e-4, 1.254e-3, 1.337e-3)) - ) + self.FRAME_INERTIA = tuple(map(lambda x: 3.0 * x, (1.844e-4, 1.254e-3, 1.337e-3))) self.MODULE_INERTIA = (3.698e-5, 7.127e-6, 4.075e-5) leg_z = 1e-6 @@ -183,15 +165,13 @@ def stance_ticks(self): @property def phase_ticks(self): - return np.array( - [self.overlap_ticks, self.swing_ticks, self.overlap_ticks, self.swing_ticks] - ) + return np.array([self.overlap_ticks, self.swing_ticks, self.overlap_ticks, self.swing_ticks]) @property def phase_length(self): return 2 * self.overlap_ticks + 2 * self.swing_ticks - + class SimulationConfig: def __init__(self): self.XML_IN = "pupper.xml" @@ -204,7 +184,7 @@ def __init__(self): self.JOINT_SOLIMP = "0.9 0.95 0.001" # joint constraint parameters self.GEOM_SOLREF = "0.01 1" # time constant and damping ratio for geom contacts self.GEOM_SOLIMP = "0.9 0.95 0.001" # geometry contact parameters - + # Joint params G = 220 # Servo gear ratio m_rotor = 0.016 # Servo rotor mass @@ -215,9 +195,7 @@ def __init__(self): NATURAL_DAMPING = 1.0 # Damping resulting from friction ELECTRICAL_DAMPING = 0.049 # Damping resulting from back-EMF - self.REV_DAMPING = ( - NATURAL_DAMPING + ELECTRICAL_DAMPING - ) # Damping torque on the revolute joints + self.REV_DAMPING = NATURAL_DAMPING + ELECTRICAL_DAMPING # Damping torque on the revolute joints # Servo params self.SERVO_REV_KP = 300 # Position gain [Nm/rad] diff --git a/pupper/HardwareConfig.py b/stanford_quad/pupper/HardwareConfig.py similarity index 100% rename from pupper/HardwareConfig.py rename to stanford_quad/pupper/HardwareConfig.py diff --git a/pupper/HardwareInterface.py b/stanford_quad/pupper/HardwareInterface.py similarity index 98% rename from pupper/HardwareInterface.py rename to stanford_quad/pupper/HardwareInterface.py index 0c2bbfc7..0a3a4978 100644 --- a/pupper/HardwareInterface.py +++ b/stanford_quad/pupper/HardwareInterface.py @@ -1,5 +1,5 @@ import pigpio -from pupper.Config import ServoParams, PWMParams +from stanford_quad.pupper.Config import ServoParams, PWMParams class HardwareInterface: diff --git a/pupper/Kinematics.py b/stanford_quad/pupper/Kinematics.py similarity index 100% rename from pupper/Kinematics.py rename to stanford_quad/pupper/Kinematics.py diff --git a/sim/__init__.py b/stanford_quad/pupper/__init__.py similarity index 100% rename from sim/__init__.py rename to stanford_quad/pupper/__init__.py diff --git a/sim/HardwareInterface.py b/stanford_quad/sim/HardwareInterface.py similarity index 100% rename from sim/HardwareInterface.py rename to stanford_quad/sim/HardwareInterface.py diff --git a/sim/IMU.py b/stanford_quad/sim/IMU.py similarity index 100% rename from sim/IMU.py rename to stanford_quad/sim/IMU.py diff --git a/woofer/__init__.py b/stanford_quad/sim/__init__.py similarity index 100% rename from woofer/__init__.py rename to stanford_quad/sim/__init__.py diff --git a/sim/Sim.py b/stanford_quad/sim/simulator.py similarity index 84% rename from sim/Sim.py rename to stanford_quad/sim/simulator.py index 3fdebf37..e806b661 100644 --- a/sim/Sim.py +++ b/stanford_quad/sim/simulator.py @@ -2,15 +2,8 @@ import pybullet_data -class Sim: - def __init__( - self, - xml_path, - kp=0.25, - kv=0.5, - max_torque=10, - g=-9.81, - ): +class PySim: + def __init__(self, xml_path, kp=0.25, kv=0.5, max_torque=10, g=-9.81): # Set up PyBullet Simulator pybullet.connect(pybullet.GUI) # or p.DIRECT for non-graphical version pybullet.setAdditionalSearchPath(pybullet_data.getDataPath()) # optionally diff --git a/stanford_quad/sim/test.py b/stanford_quad/sim/test.py new file mode 100644 index 00000000..e69de29b diff --git a/woofer/Config.py b/stanford_quad/woofer/Config.py similarity index 100% rename from woofer/Config.py rename to stanford_quad/woofer/Config.py diff --git a/woofer/HardwareConfig.py b/stanford_quad/woofer/HardwareConfig.py similarity index 100% rename from woofer/HardwareConfig.py rename to stanford_quad/woofer/HardwareConfig.py diff --git a/woofer/HardwareInterface.py b/stanford_quad/woofer/HardwareInterface.py similarity index 96% rename from woofer/HardwareInterface.py rename to stanford_quad/woofer/HardwareInterface.py index 3f4be8be..3ad83b1b 100644 --- a/woofer/HardwareInterface.py +++ b/stanford_quad/woofer/HardwareInterface.py @@ -1,7 +1,7 @@ import odrive from odrive.enums import * -from woofer.Config import RobotConfig -from woofer.HardwareConfig import ( +from stanford_quad.woofer import RobotConfig +from stanford_quad.woofer.HardwareConfig import ( ODRIVE_SERIAL_NUMBERS, ACTUATOR_DIRECTIONS, ANGLE_OFFSETS, diff --git a/woofer/Kinematics.py b/stanford_quad/woofer/Kinematics.py similarity index 100% rename from woofer/Kinematics.py rename to stanford_quad/woofer/Kinematics.py diff --git a/stanford_quad/woofer/__init__.py b/stanford_quad/woofer/__init__.py new file mode 100644 index 00000000..e69de29b From cd8c48982dd3de9561b83a424186e8ef078180fb Mon Sep 17 00:00:00 2001 From: Florian Golemo Date: Tue, 4 Aug 2020 00:31:13 -0400 Subject: [PATCH 04/49] updated gi --- .gitignore | 137 ++++++++++++++++++++++++++++++++++++++++++++++++++++- 1 file changed, 135 insertions(+), 2 deletions(-) diff --git a/.gitignore b/.gitignore index 33bc90c7..b34a5878 100644 --- a/.gitignore +++ b/.gitignore @@ -1,3 +1,136 @@ +# Created by .ignore support plugin (hsz.mobi) +### Python template +# Byte-compiled / optimized / DLL files +__pycache__/ +*.py[cod] +*$py.class + +# C extensions +*.so + +# Distribution / packaging +.Python +build/ +develop-eggs/ +dist/ +downloads/ +eggs/ +.eggs/ +lib/ +lib64/ +parts/ +sdist/ +var/ +wheels/ +pip-wheel-metadata/ +share/python-wheels/ +*.egg-info/ +.installed.cfg +*.egg +MANIFEST + +# PyInstaller +# Usually these files are written by a python script from a template +# before PyInstaller builds the exe, so as to inject date/other infos into it. +*.manifest +*.spec + +# Installer logs +pip-log.txt +pip-delete-this-directory.txt + +# Unit test / coverage reports +htmlcov/ +.tox/ +.nox/ +.coverage +.coverage.* +.cache +nosetests.xml +coverage.xml +*.cover +*.py,cover +.hypothesis/ +.pytest_cache/ + +# Translations +*.mo +*.pot + +# Django stuff: +*.log +local_settings.py +db.sqlite3 +db.sqlite3-journal + +# Flask stuff: +instance/ +.webassets-cache + +# Scrapy stuff: +.scrapy + +# Sphinx documentation +docs/_build/ + +# PyBuilder +target/ + +# Jupyter Notebook +.ipynb_checkpoints + +# IPython +profile_default/ +ipython_config.py + +# pyenv +.python-version + +# pipenv +# According to pypa/pipenv#598, it is recommended to include Pipfile.lock in version control. +# However, in case of collaboration, if having platform-specific dependencies or dependencies +# having no cross-platform support, pipenv may install dependencies that don't work, or not +# install all needed dependencies. +#Pipfile.lock + +# PEP 582; used by e.g. github.com/David-OConnor/pyflow +__pypackages__/ + +# Celery stuff +celerybeat-schedule +celerybeat.pid + +# SageMath parsed files +*.sage.py + +# Environments +.env +.venv +env/ +venv/ +ENV/ +env.bak/ +venv.bak/ + +# Spyder project settings +.spyderproject +.spyproject + +# Rope project settings +.ropeproject + +# mkdocs documentation +/site + +# mypy +.mypy_cache/ +.dmypy.json +dmypy.json + +# Pyre type checker +.pyre/ +.idea/ +wandb/ +.DS_Store *.DS_Store -*.pyc -**/__pycache__ +*.hdf5 From 49ba3c908e5660a5ed050e99d6241ad9f88628ac Mon Sep 17 00:00:00 2001 From: Florian Golemo Date: Tue, 4 Aug 2020 00:31:34 -0400 Subject: [PATCH 05/49] cleanup --- .idea/.gitignore | 8 ---- .idea/StanfordQuadruped.iml | 15 ------- .idea/inspectionProfiles/Project_Default.xml | 41 ------------------- .../inspectionProfiles/profiles_settings.xml | 6 --- .idea/misc.xml | 4 -- .idea/modules.xml | 8 ---- .idea/vcs.xml | 6 --- 7 files changed, 88 deletions(-) delete mode 100644 .idea/.gitignore delete mode 100644 .idea/StanfordQuadruped.iml delete mode 100644 .idea/inspectionProfiles/Project_Default.xml delete mode 100644 .idea/inspectionProfiles/profiles_settings.xml delete mode 100644 .idea/misc.xml delete mode 100644 .idea/modules.xml delete mode 100644 .idea/vcs.xml diff --git a/.idea/.gitignore b/.idea/.gitignore deleted file mode 100644 index 73f69e09..00000000 --- a/.idea/.gitignore +++ /dev/null @@ -1,8 +0,0 @@ -# Default ignored files -/shelf/ -/workspace.xml -# Datasource local storage ignored files -/dataSources/ -/dataSources.local.xml -# Editor-based HTTP Client requests -/httpRequests/ diff --git a/.idea/StanfordQuadruped.iml b/.idea/StanfordQuadruped.iml deleted file mode 100644 index 4f2c9af6..00000000 --- a/.idea/StanfordQuadruped.iml +++ /dev/null @@ -1,15 +0,0 @@ - - - - - - - - - - - - \ No newline at end of file diff --git a/.idea/inspectionProfiles/Project_Default.xml b/.idea/inspectionProfiles/Project_Default.xml deleted file mode 100644 index c4850975..00000000 --- a/.idea/inspectionProfiles/Project_Default.xml +++ /dev/null @@ -1,41 +0,0 @@ - - - - \ No newline at end of file diff --git a/.idea/inspectionProfiles/profiles_settings.xml b/.idea/inspectionProfiles/profiles_settings.xml deleted file mode 100644 index 105ce2da..00000000 --- a/.idea/inspectionProfiles/profiles_settings.xml +++ /dev/null @@ -1,6 +0,0 @@ - - - - \ No newline at end of file diff --git a/.idea/misc.xml b/.idea/misc.xml deleted file mode 100644 index 65531ca9..00000000 --- a/.idea/misc.xml +++ /dev/null @@ -1,4 +0,0 @@ - - - - \ No newline at end of file diff --git a/.idea/modules.xml b/.idea/modules.xml deleted file mode 100644 index 5cfc3383..00000000 --- a/.idea/modules.xml +++ /dev/null @@ -1,8 +0,0 @@ - - - - - - - - \ No newline at end of file diff --git a/.idea/vcs.xml b/.idea/vcs.xml deleted file mode 100644 index 94a25f7f..00000000 --- a/.idea/vcs.xml +++ /dev/null @@ -1,6 +0,0 @@ - - - - - - \ No newline at end of file From 0f3986dbd3f3941d1f655a9085d944e51fd87a31 Mon Sep 17 00:00:00 2001 From: Florian Golemo Date: Tue, 4 Aug 2020 01:07:03 -0400 Subject: [PATCH 06/49] small fixes --- scripts/RunPyBulletSim.py | 25 ++++++++++++------------- stanford_quad/common/Controller.py | 4 +--- stanford_quad/sim/simulator.py | 7 +++++-- 3 files changed, 18 insertions(+), 18 deletions(-) diff --git a/scripts/RunPyBulletSim.py b/scripts/RunPyBulletSim.py index 81f01f59..ce79322f 100644 --- a/scripts/RunPyBulletSim.py +++ b/scripts/RunPyBulletSim.py @@ -14,13 +14,13 @@ USE_IMU = False DEFAULT_VEL = np.array([0.15, 0]) -DEFAULT_YAW_RATE=0.0 +DEFAULT_YAW_RATE = 0.0 # Create config config = Configuration() config.z_clearance = 0.02 -sim = PySim(xml_path=os.path.join(ASSET_DIR, "pupper_pybullet_out.xml")) +sim = PySim(xml_path=os.path.join(ASSET_DIR, "pupper_pybullet_out.xml"), headless=False) hardware_interface = HardwareInterface(sim.model, sim.joint_indices) # Create imu handle @@ -28,7 +28,7 @@ imu = IMU() # Create controller and user input handles -controller = Controller(config, four_legs_inverse_kinematics,) +controller = Controller(config, four_legs_inverse_kinematics) state = State() command = Command() @@ -55,11 +55,13 @@ print("z clearance: ", config.z_clearance) print("x shift: ", config.x_shift) +SIM_FPS = 240 + # Run the simulation -timesteps = 240 * 60 * 10 # simulate for a max of 10 minutes +timesteps = 120 * 60 * 10 # simulate for a max of 10 minutes # Sim seconds per sim step -sim_steps_per_sim_second = 240 +sim_steps_per_sim_second = 120 sim_dt = 1.0 / sim_steps_per_sim_second last_control_update = 0 start = time.time() @@ -82,12 +84,9 @@ sim.step() # Performance testing - elapsed = time.time() - start - if (steps % 60) == 0: - print( - "Sim seconds elapsed: {}, Real seconds elapsed: {}".format( - round(sim_time_elapsed, 3), round(elapsed, 3) - ) - ) - # print("Average steps per second: {0}, elapsed: {1}, i:{2}".format(steps / elapsed, elapsed, i)) + if ((steps+1) % 100) == 0: + elapsed = (time.time() - start) / 100 + # print("Sim seconds elapsed: {}, Real seconds elapsed: {}".format(round(sim_time_elapsed, 3), round(elapsed, 3))) + print (f"Sim running at {1/elapsed} Hz") + start = time.time() diff --git a/stanford_quad/common/Controller.py b/stanford_quad/common/Controller.py index d857d70d..9aaab64c 100644 --- a/stanford_quad/common/Controller.py +++ b/stanford_quad/common/Controller.py @@ -15,9 +15,7 @@ class Controller: """Controller and planner object """ - def __init__( - self, config, inverse_kinematics, - ): + def __init__(self, config, inverse_kinematics): self.config = config self.smoothed_yaw = 0.0 # for REST mode only diff --git a/stanford_quad/sim/simulator.py b/stanford_quad/sim/simulator.py index e806b661..e9e053c1 100644 --- a/stanford_quad/sim/simulator.py +++ b/stanford_quad/sim/simulator.py @@ -3,9 +3,12 @@ class PySim: - def __init__(self, xml_path, kp=0.25, kv=0.5, max_torque=10, g=-9.81): + def __init__(self, xml_path, headless=False, kp=0.25, kv=0.5, max_torque=10, g=-9.81): # Set up PyBullet Simulator - pybullet.connect(pybullet.GUI) # or p.DIRECT for non-graphical version + if not headless: + pybullet.connect(pybullet.GUI) # or p.DIRECT for non-graphical version + else: + pybullet.connect(pybullet.DIRECT) # or p.DIRECT for non-graphical version pybullet.setAdditionalSearchPath(pybullet_data.getDataPath()) # optionally pybullet.setGravity(0, 0, g) self.model = pybullet.loadMJCF(xml_path) From 6aaf8558a1c58a20e01bf0d4557962d5e3d9a40f Mon Sep 17 00:00:00 2001 From: Florian Golemo Date: Sun, 9 Aug 2020 10:48:52 -0400 Subject: [PATCH 07/49] added new pybullet sim --- .gitignore | 2 + scripts/03-pybullet-quadruped-example.py | 469 ++++++++++++++++++ scripts/04-testing-pybullet-multithreading.py | 64 +++ scripts/05-plot-joint-positions.py | 38 ++ scripts/06-run-controller-live.py | 145 ++++++ scripts/07-debug-new-simulator.py | 23 + scripts/RunPyBulletSim.py | 13 +- stanford_quad/envs/__init__.py | 0 stanford_quad/envs/walking_env.py | 23 + stanford_quad/sim/HardwareInterface.py | 3 +- stanford_quad/sim/simulator2.py | 79 +++ 11 files changed, 856 insertions(+), 3 deletions(-) create mode 100644 scripts/03-pybullet-quadruped-example.py create mode 100644 scripts/04-testing-pybullet-multithreading.py create mode 100644 scripts/05-plot-joint-positions.py create mode 100644 scripts/06-run-controller-live.py create mode 100644 scripts/07-debug-new-simulator.py create mode 100644 stanford_quad/envs/__init__.py create mode 100644 stanford_quad/envs/walking_env.py create mode 100644 stanford_quad/sim/simulator2.py diff --git a/.gitignore b/.gitignore index b34a5878..258144fe 100644 --- a/.gitignore +++ b/.gitignore @@ -134,3 +134,5 @@ wandb/ .DS_Store *.DS_Store *.hdf5 +scripts/*.npz +scripts/*.pkl \ No newline at end of file diff --git a/scripts/03-pybullet-quadruped-example.py b/scripts/03-pybullet-quadruped-example.py new file mode 100644 index 00000000..356bb777 --- /dev/null +++ b/scripts/03-pybullet-quadruped-example.py @@ -0,0 +1,469 @@ +import pybullet as p +import time +import math +import pybullet_data + + + + +def drawInertiaBox(parentUid, parentLinkIndex, color): + dyn = p.getDynamicsInfo(parentUid, parentLinkIndex) + mass = dyn[0] + frictionCoeff = dyn[1] + inertia = dyn[2] + if (mass > 0): + Ixx = inertia[0] + Iyy = inertia[1] + Izz = inertia[2] + boxScaleX = 0.5 * math.sqrt(6 * (Izz + Iyy - Ixx) / mass) + boxScaleY = 0.5 * math.sqrt(6 * (Izz + Ixx - Iyy) / mass) + boxScaleZ = 0.5 * math.sqrt(6 * (Ixx + Iyy - Izz) / mass) + + halfExtents = [boxScaleX, boxScaleY, boxScaleZ] + pts = [[halfExtents[0], halfExtents[1], halfExtents[2]], + [-halfExtents[0], halfExtents[1], halfExtents[2]], + [halfExtents[0], -halfExtents[1], halfExtents[2]], + [-halfExtents[0], -halfExtents[1], halfExtents[2]], + [halfExtents[0], halfExtents[1], -halfExtents[2]], + [-halfExtents[0], halfExtents[1], -halfExtents[2]], + [halfExtents[0], -halfExtents[1], -halfExtents[2]], + [-halfExtents[0], -halfExtents[1], -halfExtents[2]]] + + p.addUserDebugLine(pts[0], + pts[1], + color, + 1, + parentObjectUniqueId=parentUid, + parentLinkIndex=parentLinkIndex) + p.addUserDebugLine(pts[1], + pts[3], + color, + 1, + parentObjectUniqueId=parentUid, + parentLinkIndex=parentLinkIndex) + p.addUserDebugLine(pts[3], + pts[2], + color, + 1, + parentObjectUniqueId=parentUid, + parentLinkIndex=parentLinkIndex) + p.addUserDebugLine(pts[2], + pts[0], + color, + 1, + parentObjectUniqueId=parentUid, + parentLinkIndex=parentLinkIndex) + + p.addUserDebugLine(pts[0], + pts[4], + color, + 1, + parentObjectUniqueId=parentUid, + parentLinkIndex=parentLinkIndex) + p.addUserDebugLine(pts[1], + pts[5], + color, + 1, + parentObjectUniqueId=parentUid, + parentLinkIndex=parentLinkIndex) + p.addUserDebugLine(pts[2], + pts[6], + color, + 1, + parentObjectUniqueId=parentUid, + parentLinkIndex=parentLinkIndex) + p.addUserDebugLine(pts[3], + pts[7], + color, + 1, + parentObjectUniqueId=parentUid, + parentLinkIndex=parentLinkIndex) + + p.addUserDebugLine(pts[4 + 0], + pts[4 + 1], + color, + 1, + parentObjectUniqueId=parentUid, + parentLinkIndex=parentLinkIndex) + p.addUserDebugLine(pts[4 + 1], + pts[4 + 3], + color, + 1, + parentObjectUniqueId=parentUid, + parentLinkIndex=parentLinkIndex) + p.addUserDebugLine(pts[4 + 3], + pts[4 + 2], + color, + 1, + parentObjectUniqueId=parentUid, + parentLinkIndex=parentLinkIndex) + p.addUserDebugLine(pts[4 + 2], + pts[4 + 0], + color, + 1, + parentObjectUniqueId=parentUid, + parentLinkIndex=parentLinkIndex) + + +toeConstraint = True +useMaximalCoordinates = False +useRealTime = 0 + +#the fixedTimeStep and numSolverIterations are the most important parameters to trade-off quality versus performance +fixedTimeStep = 1. / 100 +numSolverIterations = 50 + +if (useMaximalCoordinates): + fixedTimeStep = 1. / 500 + numSolverIterations = 200 + +speed = 10 +amplitude = 0.8 +jump_amp = 0.5 +maxForce = 3.5 +kneeFrictionForce = 0 +kp = 1 +kd = .5 +maxKneeForce = 1000 + +physId = p.connect(p.SHARED_MEMORY_GUI) +if (physId < 0): + p.connect(p.GUI) +#p.resetSimulation() + +p.setAdditionalSearchPath(pybullet_data.getDataPath()) +angle = 0 # pick in range 0..0.2 radians +orn = p.getQuaternionFromEuler([0, angle, 0]) +p.loadURDF("plane.urdf", [0, 0, 0], orn) +p.setPhysicsEngineParameter(numSolverIterations=numSolverIterations) +p.startStateLogging(p.STATE_LOGGING_GENERIC_ROBOT, + "genericlogdata.bin", + maxLogDof=16, + logFlags=p.STATE_LOG_JOINT_TORQUES) +p.setTimeOut(4000000) + +p.setGravity(0, 0, 0) +p.setTimeStep(fixedTimeStep) + +orn = p.getQuaternionFromEuler([0, 0, 0.4]) +p.setRealTimeSimulation(0) +quadruped = p.loadURDF("quadruped/minitaur_v1.urdf", [1, -1, .3], + orn, + useFixedBase=False, + useMaximalCoordinates=useMaximalCoordinates, + flags=p.URDF_USE_IMPLICIT_CYLINDER) +nJoints = p.getNumJoints(quadruped) + +jointNameToId = {} +for i in range(nJoints): + jointInfo = p.getJointInfo(quadruped, i) + jointNameToId[jointInfo[1].decode('UTF-8')] = jointInfo[0] + +motor_front_rightR_joint = jointNameToId['motor_front_rightR_joint'] +motor_front_rightL_joint = jointNameToId['motor_front_rightL_joint'] +knee_front_rightL_link = jointNameToId['knee_front_rightL_link'] +hip_front_rightR_link = jointNameToId['hip_front_rightR_link'] +knee_front_rightR_link = jointNameToId['knee_front_rightR_link'] +motor_front_rightL_link = jointNameToId['motor_front_rightL_link'] +motor_front_leftR_joint = jointNameToId['motor_front_leftR_joint'] +hip_front_leftR_link = jointNameToId['hip_front_leftR_link'] +knee_front_leftR_link = jointNameToId['knee_front_leftR_link'] +motor_front_leftL_joint = jointNameToId['motor_front_leftL_joint'] +motor_front_leftL_link = jointNameToId['motor_front_leftL_link'] +knee_front_leftL_link = jointNameToId['knee_front_leftL_link'] +motor_back_rightR_joint = jointNameToId['motor_back_rightR_joint'] +hip_rightR_link = jointNameToId['hip_rightR_link'] +knee_back_rightR_link = jointNameToId['knee_back_rightR_link'] +motor_back_rightL_joint = jointNameToId['motor_back_rightL_joint'] +motor_back_rightL_link = jointNameToId['motor_back_rightL_link'] +knee_back_rightL_link = jointNameToId['knee_back_rightL_link'] +motor_back_leftR_joint = jointNameToId['motor_back_leftR_joint'] +hip_leftR_link = jointNameToId['hip_leftR_link'] +knee_back_leftR_link = jointNameToId['knee_back_leftR_link'] +motor_back_leftL_joint = jointNameToId['motor_back_leftL_joint'] +motor_back_leftL_link = jointNameToId['motor_back_leftL_link'] +knee_back_leftL_link = jointNameToId['knee_back_leftL_link'] + +#fixtorso = p.createConstraint(-1,-1,quadruped,-1,p.JOINT_FIXED,[0,0,0],[0,0,0],[0,0,0]) + +motordir = [-1, -1, -1, -1, 1, 1, 1, 1] +halfpi = 1.57079632679 +twopi = 4 * halfpi +kneeangle = -2.1834 + +dyn = p.getDynamicsInfo(quadruped, -1) +mass = dyn[0] +friction = dyn[1] +localInertiaDiagonal = dyn[2] + +print("localInertiaDiagonal", localInertiaDiagonal) + +#this is a no-op, just to show the API +p.changeDynamics(quadruped, -1, localInertiaDiagonal=localInertiaDiagonal) + +#for i in range (nJoints): +# p.changeDynamics(quadruped,i,localInertiaDiagonal=[0.000001,0.000001,0.000001]) + +drawInertiaBox(quadruped, -1, [1, 0, 0]) +#drawInertiaBox(quadruped,motor_front_rightR_joint, [1,0,0]) + +for i in range(nJoints): + drawInertiaBox(quadruped, i, [0, 1, 0]) + +if (useMaximalCoordinates): + steps = 400 + for aa in range(steps): + p.setJointMotorControl2(quadruped, motor_front_leftL_joint, p.POSITION_CONTROL, + motordir[0] * halfpi * float(aa) / steps) + p.setJointMotorControl2(quadruped, motor_front_leftR_joint, p.POSITION_CONTROL, + motordir[1] * halfpi * float(aa) / steps) + p.setJointMotorControl2(quadruped, motor_back_leftL_joint, p.POSITION_CONTROL, + motordir[2] * halfpi * float(aa) / steps) + p.setJointMotorControl2(quadruped, motor_back_leftR_joint, p.POSITION_CONTROL, + motordir[3] * halfpi * float(aa) / steps) + p.setJointMotorControl2(quadruped, motor_front_rightL_joint, p.POSITION_CONTROL, + motordir[4] * halfpi * float(aa) / steps) + p.setJointMotorControl2(quadruped, motor_front_rightR_joint, p.POSITION_CONTROL, + motordir[5] * halfpi * float(aa) / steps) + p.setJointMotorControl2(quadruped, motor_back_rightL_joint, p.POSITION_CONTROL, + motordir[6] * halfpi * float(aa) / steps) + p.setJointMotorControl2(quadruped, motor_back_rightR_joint, p.POSITION_CONTROL, + motordir[7] * halfpi * float(aa) / steps) + + p.setJointMotorControl2(quadruped, knee_front_leftL_link, p.POSITION_CONTROL, + motordir[0] * (kneeangle + twopi) * float(aa) / steps) + p.setJointMotorControl2(quadruped, knee_front_leftR_link, p.POSITION_CONTROL, + motordir[1] * kneeangle * float(aa) / steps) + p.setJointMotorControl2(quadruped, knee_back_leftL_link, p.POSITION_CONTROL, + motordir[2] * kneeangle * float(aa) / steps) + p.setJointMotorControl2(quadruped, knee_back_leftR_link, p.POSITION_CONTROL, + motordir[3] * (kneeangle + twopi) * float(aa) / steps) + p.setJointMotorControl2(quadruped, knee_front_rightL_link, p.POSITION_CONTROL, + motordir[4] * (kneeangle) * float(aa) / steps) + p.setJointMotorControl2(quadruped, knee_front_rightR_link, p.POSITION_CONTROL, + motordir[5] * (kneeangle + twopi) * float(aa) / steps) + p.setJointMotorControl2(quadruped, knee_back_rightL_link, p.POSITION_CONTROL, + motordir[6] * (kneeangle + twopi) * float(aa) / steps) + p.setJointMotorControl2(quadruped, knee_back_rightR_link, p.POSITION_CONTROL, + motordir[7] * kneeangle * float(aa) / steps) + + p.stepSimulation() + #time.sleep(fixedTimeStep) +else: + + p.resetJointState(quadruped, motor_front_leftL_joint, motordir[0] * halfpi) + p.resetJointState(quadruped, knee_front_leftL_link, motordir[0] * kneeangle) + p.resetJointState(quadruped, motor_front_leftR_joint, motordir[1] * halfpi) + p.resetJointState(quadruped, knee_front_leftR_link, motordir[1] * kneeangle) + + p.resetJointState(quadruped, motor_back_leftL_joint, motordir[2] * halfpi) + p.resetJointState(quadruped, knee_back_leftL_link, motordir[2] * kneeangle) + p.resetJointState(quadruped, motor_back_leftR_joint, motordir[3] * halfpi) + p.resetJointState(quadruped, knee_back_leftR_link, motordir[3] * kneeangle) + + p.resetJointState(quadruped, motor_front_rightL_joint, motordir[4] * halfpi) + p.resetJointState(quadruped, knee_front_rightL_link, motordir[4] * kneeangle) + p.resetJointState(quadruped, motor_front_rightR_joint, motordir[5] * halfpi) + p.resetJointState(quadruped, knee_front_rightR_link, motordir[5] * kneeangle) + + p.resetJointState(quadruped, motor_back_rightL_joint, motordir[6] * halfpi) + p.resetJointState(quadruped, knee_back_rightL_link, motordir[6] * kneeangle) + p.resetJointState(quadruped, motor_back_rightR_joint, motordir[7] * halfpi) + p.resetJointState(quadruped, knee_back_rightR_link, motordir[7] * kneeangle) + +#p.getNumJoints(1) + +if (toeConstraint): + cid = p.createConstraint(quadruped, knee_front_leftR_link, quadruped, knee_front_leftL_link, + p.JOINT_POINT2POINT, [0, 0, 0], [0, 0.005, 0.1], [0, 0.01, 0.1]) + p.changeConstraint(cid, maxForce=maxKneeForce) + cid = p.createConstraint(quadruped, knee_front_rightR_link, quadruped, knee_front_rightL_link, + p.JOINT_POINT2POINT, [0, 0, 0], [0, 0.005, 0.1], [0, 0.01, 0.1]) + p.changeConstraint(cid, maxForce=maxKneeForce) + cid = p.createConstraint(quadruped, knee_back_leftR_link, quadruped, knee_back_leftL_link, + p.JOINT_POINT2POINT, [0, 0, 0], [0, 0.005, 0.1], [0, 0.01, 0.1]) + p.changeConstraint(cid, maxForce=maxKneeForce) + cid = p.createConstraint(quadruped, knee_back_rightR_link, quadruped, knee_back_rightL_link, + p.JOINT_POINT2POINT, [0, 0, 0], [0, 0.005, 0.1], [0, 0.01, 0.1]) + p.changeConstraint(cid, maxForce=maxKneeForce) + +if (1): + p.setJointMotorControl(quadruped, knee_front_leftL_link, p.VELOCITY_CONTROL, 0, + kneeFrictionForce) + p.setJointMotorControl(quadruped, knee_front_leftR_link, p.VELOCITY_CONTROL, 0, + kneeFrictionForce) + p.setJointMotorControl(quadruped, knee_front_rightL_link, p.VELOCITY_CONTROL, 0, + kneeFrictionForce) + p.setJointMotorControl(quadruped, knee_front_rightR_link, p.VELOCITY_CONTROL, 0, + kneeFrictionForce) + p.setJointMotorControl(quadruped, knee_back_leftL_link, p.VELOCITY_CONTROL, 0, kneeFrictionForce) + p.setJointMotorControl(quadruped, knee_back_leftR_link, p.VELOCITY_CONTROL, 0, kneeFrictionForce) + p.setJointMotorControl(quadruped, knee_back_leftL_link, p.VELOCITY_CONTROL, 0, kneeFrictionForce) + p.setJointMotorControl(quadruped, knee_back_leftR_link, p.VELOCITY_CONTROL, 0, kneeFrictionForce) + p.setJointMotorControl(quadruped, knee_back_rightL_link, p.VELOCITY_CONTROL, 0, + kneeFrictionForce) + p.setJointMotorControl(quadruped, knee_back_rightR_link, p.VELOCITY_CONTROL, 0, + kneeFrictionForce) + +p.setGravity(0, 0, -10) + +legnumbering = [ + motor_front_leftL_joint, motor_front_leftR_joint, motor_back_leftL_joint, + motor_back_leftR_joint, motor_front_rightL_joint, motor_front_rightR_joint, + motor_back_rightL_joint, motor_back_rightR_joint +] + +for i in range(8): + print(legnumbering[i]) +#use the Minitaur leg numbering +p.setJointMotorControl2(bodyIndex=quadruped, + jointIndex=legnumbering[0], + controlMode=p.POSITION_CONTROL, + targetPosition=motordir[0] * 1.57, + positionGain=kp, + velocityGain=kd, + force=maxForce) +p.setJointMotorControl2(bodyIndex=quadruped, + jointIndex=legnumbering[1], + controlMode=p.POSITION_CONTROL, + targetPosition=motordir[1] * 1.57, + positionGain=kp, + velocityGain=kd, + force=maxForce) +p.setJointMotorControl2(bodyIndex=quadruped, + jointIndex=legnumbering[2], + controlMode=p.POSITION_CONTROL, + targetPosition=motordir[2] * 1.57, + positionGain=kp, + velocityGain=kd, + force=maxForce) +p.setJointMotorControl2(bodyIndex=quadruped, + jointIndex=legnumbering[3], + controlMode=p.POSITION_CONTROL, + targetPosition=motordir[3] * 1.57, + positionGain=kp, + velocityGain=kd, + force=maxForce) +p.setJointMotorControl2(bodyIndex=quadruped, + jointIndex=legnumbering[4], + controlMode=p.POSITION_CONTROL, + targetPosition=motordir[4] * 1.57, + positionGain=kp, + velocityGain=kd, + force=maxForce) +p.setJointMotorControl2(bodyIndex=quadruped, + jointIndex=legnumbering[5], + controlMode=p.POSITION_CONTROL, + targetPosition=motordir[5] * 1.57, + positionGain=kp, + velocityGain=kd, + force=maxForce) +p.setJointMotorControl2(bodyIndex=quadruped, + jointIndex=legnumbering[6], + controlMode=p.POSITION_CONTROL, + targetPosition=motordir[6] * 1.57, + positionGain=kp, + velocityGain=kd, + force=maxForce) +p.setJointMotorControl2(bodyIndex=quadruped, + jointIndex=legnumbering[7], + controlMode=p.POSITION_CONTROL, + targetPosition=motordir[7] * 1.57, + positionGain=kp, + velocityGain=kd, + force=maxForce) +#stand still +p.setRealTimeSimulation(useRealTime) + +t = 0.0 +t_end = t + 15 +ref_time = time.time() +while (t < t_end): + p.setGravity(0, 0, -10) + if (useRealTime): + t = time.time() - ref_time + else: + t = t + fixedTimeStep + if (useRealTime == 0): + p.stepSimulation() + time.sleep(fixedTimeStep) + +print("quadruped Id = ") +print(quadruped) +p.saveWorld("quadru.py") +logId = p.startStateLogging(p.STATE_LOGGING_MINITAUR, "quadrupedLog.bin", [quadruped]) + +#jump +t = 0.0 +t_end = t + 100 +i = 0 +ref_time = time.time() + +while (1): + if (useRealTime): + t = time.time() - ref_time + else: + t = t + fixedTimeStep + if (True): + + target = math.sin(t * speed) * jump_amp + 1.57 + p.setJointMotorControl2(bodyIndex=quadruped, + jointIndex=legnumbering[0], + controlMode=p.POSITION_CONTROL, + targetPosition=motordir[0] * target, + positionGain=kp, + velocityGain=kd, + force=maxForce) + p.setJointMotorControl2(bodyIndex=quadruped, + jointIndex=legnumbering[1], + controlMode=p.POSITION_CONTROL, + targetPosition=motordir[1] * target, + positionGain=kp, + velocityGain=kd, + force=maxForce) + p.setJointMotorControl2(bodyIndex=quadruped, + jointIndex=legnumbering[2], + controlMode=p.POSITION_CONTROL, + targetPosition=motordir[2] * target, + positionGain=kp, + velocityGain=kd, + force=maxForce) + p.setJointMotorControl2(bodyIndex=quadruped, + jointIndex=legnumbering[3], + controlMode=p.POSITION_CONTROL, + targetPosition=motordir[3] * target, + positionGain=kp, + velocityGain=kd, + force=maxForce) + p.setJointMotorControl2(bodyIndex=quadruped, + jointIndex=legnumbering[4], + controlMode=p.POSITION_CONTROL, + targetPosition=motordir[4] * target, + positionGain=kp, + velocityGain=kd, + force=maxForce) + p.setJointMotorControl2(bodyIndex=quadruped, + jointIndex=legnumbering[5], + controlMode=p.POSITION_CONTROL, + targetPosition=motordir[5] * target, + positionGain=kp, + velocityGain=kd, + force=maxForce) + p.setJointMotorControl2(bodyIndex=quadruped, + jointIndex=legnumbering[6], + controlMode=p.POSITION_CONTROL, + targetPosition=motordir[6] * target, + positionGain=kp, + velocityGain=kd, + force=maxForce) + p.setJointMotorControl2(bodyIndex=quadruped, + jointIndex=legnumbering[7], + controlMode=p.POSITION_CONTROL, + targetPosition=motordir[7] * target, + positionGain=kp, + velocityGain=kd, + force=maxForce) + + if (useRealTime == 0): + p.stepSimulation() + time.sleep(fixedTimeStep) diff --git a/scripts/04-testing-pybullet-multithreading.py b/scripts/04-testing-pybullet-multithreading.py new file mode 100644 index 00000000..d4093504 --- /dev/null +++ b/scripts/04-testing-pybullet-multithreading.py @@ -0,0 +1,64 @@ +import threading +import time +import numpy as np + + +def make_sim(): + import pybullet_data + + + # OPTION 1 - NOT THREAD-SAFE + # import pybullet as p + # p.connect(p.DIRECT) + + # OPTION 2 - SEEMINGLY THREAD-SAFE + import pybullet + import pybullet_utils.bullet_client as bc + p = bc.BulletClient(connection_mode=pybullet.DIRECT) + + + p.setAdditionalSearchPath(pybullet_data.getDataPath()) + + plane = p.loadURDF("plane.urdf") + sphereRadius = 0.05 + colSphereId = p.createCollisionShape(p.GEOM_SPHERE, radius=sphereRadius) + visualShapeId = p.createVisualShape(shapeType=p.GEOM_SPHERE, rgbaColor=[1, 0, 1, 1], radius=sphereRadius) + sphere = p.createMultiBody(0.1, colSphereId, visualShapeId, basePosition=[0, 0, sphereRadius + 0.00001]) + p.setGravity(0, 0, -10) + p.setRealTimeSimulation(0) + p.applyExternalForce(sphere, -1, [100, 0, 0], posObj=[0, 0, 0], flags=p.LINK_FRAME) + positions = [] + for _ in range(240): + p.stepSimulation() + positions.append(list(p.getBasePositionAndOrientation(sphere)[0])) + + return np.array(positions) + + +def worker(inst): + pos = make_sim() + np.savez(f"inst-{inst}.npz", positions=pos) + + +w1 = threading.Thread(target=worker, kwargs={"inst":0}) +w2 = threading.Thread(target=worker, kwargs={"inst":1}) +w3 = threading.Thread(target=worker, kwargs={"inst":2}) + +w1.start() +w2.start() +w3.start() + +w1.join() +w2.join() +w3.join() + +import matplotlib.pyplot as plt + +x = np.arange(0,240) +data = [] +for i in range(3): + trajectory = np.load(f"inst-{i}.npz")["positions"] + plt.plot(x, trajectory[:,0]) + +plt.show() + diff --git a/scripts/05-plot-joint-positions.py b/scripts/05-plot-joint-positions.py new file mode 100644 index 00000000..9f0b12b1 --- /dev/null +++ b/scripts/05-plot-joint-positions.py @@ -0,0 +1,38 @@ +import pickle +import numpy as np +import matplotlib.pyplot as plt +from matplotlib import colors + +saved_states = pickle.load(open("saved-states.pkl", "rb")) +foot_locations = np.array([s.foot_locations for s in saved_states]) +joint_angles = np.array([s.joint_angles for s in saved_states]) + +# print (foot_locations[0,[0,2],:]) +# +# print (foot_locations.shape) +# +# foot_locations_x = foot_locations[50:,0,:] +# foot_locations_y = foot_locations[50:,2,:] +# +# print (foot_locations_x[:10]) +# print (foot_locations_y[:10]) +# +# norm = colors.Normalize(vmin=0, vmax=239) +# +# for i in range(4): +# plt.scatter(foot_locations_x,foot_locations_y,label=f"foot {i}") +# +# plt.legend() +# plt.show() + + +x = np.arange(0,len(joint_angles)) +for i in range(3): + plt.plot(x, joint_angles[:,i,0], label=f"joint {i}") + +plt.legend() +plt.tight_layout() +plt.show() + + + diff --git a/scripts/06-run-controller-live.py b/scripts/06-run-controller-live.py new file mode 100644 index 00000000..24abad8d --- /dev/null +++ b/scripts/06-run-controller-live.py @@ -0,0 +1,145 @@ +from collections import deque +import matplotlib.pyplot as plt +import numpy as np +from drawnow import drawnow +import cv2 +from stanford_quad.common.Command import Command +from stanford_quad.common.Controller import Controller +from stanford_quad.common.State import State +from stanford_quad.pupper.Config import Configuration +from stanford_quad.pupper.Kinematics import four_legs_inverse_kinematics +from stanford_quad.sim.IMU import IMU + +USE_IMU = False +DEFAULT_VEL = np.array([0.15, 0]) +DEFAULT_YAW_RATE = 0.0 + +# Create config +config = Configuration() +config.z_clearance = 0.02 + +# Create imu handle +if USE_IMU: + imu = IMU() + +# Create controller and user input handles +controller = Controller(config, four_legs_inverse_kinematics) +state = State() +command = Command() + +# Emulate the joystick inputs required to activate the robot +command.activate_event = 1 +controller.run(state, command) +command.activate_event = 0 +command.trot_event = 1 +controller.run(state, command) +command = Command() # zero it out + +print("resting pos:", state.joint_angles) + +# Apply a constant command. # TODO Add support for user input or an external commander +command.horizontal_velocity = DEFAULT_VEL +command.yaw_rate = DEFAULT_YAW_RATE + +# The joystick service is linux-only, so commenting out for mac +# print("Creating joystick listener...") +# joystick_interface = JoystickInterface(config) +# print("Done.") + +print("Summary of gait parameters:") +print("overlap time: ", config.overlap_time) +print("swing time: ", config.swing_time) +print("z clearance: ", config.z_clearance) +print("x shift: ", config.x_shift) + +SIM_FPS = 240 + +steps = 1000 + +# these values are from plotting foot locations and getting matplotlib recommendations for canvas +x_min = -0.14 +x_max = 0.14 + +y_min = -0.162 +y_max = -0.138 + +img_width = 800 +img_height = 400 + + +def coords_to_pix(coords): + x_norm = (coords[0] - x_min) / (x_max - x_min) + y_norm = (coords[1] - y_min) / (y_max - y_min) + x_pix = int(round(img_width * x_norm)) + y_pix = img_height - int(round(img_height * y_norm)) + return x_pix, y_pix + + +no_points = 20 +# I tried `foot_pts = [deque(maxlen=no_points)] * 4` but that didn't work +foot_pts = [deque(maxlen=no_points), deque(maxlen=no_points), deque(maxlen=no_points), deque(maxlen=no_points)] + +img_feet = np.zeros((img_height, img_width, 3), dtype=np.uint8) +joints_left = [] +joints_right = [] +joints = [joints_right, joints_left] +plt.plot([], [], label="right - joint 0") +plt.plot([], [], label="right - joint 1") +plt.plot([], [], label="right - joint 2") +plt.plot([], [], label="left - joint 0") +plt.plot([], [], label="left - joint 1") +plt.plot([], [], label="left - joint 2") +plt.legend(loc='center left') + +for steps in range(steps): + img_feet.fill(0) + + # Get IMU measurement if enabled + state.quat_orientation = IMU.read_orientation() if USE_IMU else np.array([1, 0, 0, 0]) + + # Step the controller forward by dt + controller.run(state, command) + + for foot_idx, color, name in zip( + range(4), + [[0, 0, 255], [0, 255, 0], [255, 0, 0], [255, 255, 0]], + ["front-right", "front-left", "back-right", "back-left"], + ): + + cv2.putText( + img_feet, + name, + (int(round(img_width / 2 - 70)), int(round(img_height - 100 + (foot_idx * 25)))), + cv2.FONT_HERSHEY_SIMPLEX, + fontScale=1, + color=color, + thickness=2, + ) + + foot_xy = state.foot_locations[[0, 2], foot_idx] + foot_pix = coords_to_pix(foot_xy) + cv2.circle(img_feet, foot_pix, 5, (255, 255, 255), -1) + foot_pts[foot_idx].appendleft(foot_pix) + + for i in range(1, len(foot_pts[foot_idx])): + thickness = int(np.sqrt(no_points / float(i + 1)) * 2.5) + cv2.line(img_feet, foot_pts[foot_idx][i - 1], foot_pts[foot_idx][i], color, thickness) + + cv2.imshow("feet", img_feet[:, :, ::-1]) + cv2.waitKey(1) + + for foot_idx, color, name in zip(range(2), [[0, 0, 255], [0, 255, 0]], ["front-right", "front-left"],): + + joints[foot_idx].append(np.rad2deg(state.joint_angles[:, foot_idx])) + joint_np = np.array(joints[foot_idx]) + + for joint_idx in range(3): + plot_id = joint_idx + (foot_idx * 3) + print ("plot id",plot_id) + print (joint_np[:,joint_idx]) + plt.gca().lines[plot_id].set_xdata(np.arange(len(joint_np))) + plt.gca().lines[plot_id].set_ydata(joint_np[:,joint_idx]) + + plt.gca().relim() + plt.gca().autoscale_view() + plt.pause(0.001) diff --git a/scripts/07-debug-new-simulator.py b/scripts/07-debug-new-simulator.py new file mode 100644 index 00000000..4a204932 --- /dev/null +++ b/scripts/07-debug-new-simulator.py @@ -0,0 +1,23 @@ +import time +import numpy as np +from stanford_quad.sim.simulator2 import PupperSim2, REST_POS + +sim = PupperSim2(debug=True) + +debugParams = [] + +rest_pos = REST_POS.T.flatten() +for i in range(len(sim.joint_indices)): + motor = sim.p.addUserDebugParameter("motor{}".format(i + 1), -np.pi, np.pi, rest_pos[i]) + debugParams.append(motor) + + +for step in range(100000): + motorPos = [] + for i in range(len(sim.joint_indices)): + pos = sim.p.readUserDebugParameter(debugParams[i]) + motorPos.append(pos) + sim.action(motorPos) + sim.step() + + diff --git a/scripts/RunPyBulletSim.py b/scripts/RunPyBulletSim.py index ce79322f..352bc6e1 100644 --- a/scripts/RunPyBulletSim.py +++ b/scripts/RunPyBulletSim.py @@ -1,6 +1,8 @@ import os +import pickle import time import numpy as np +import copy from stanford_quad.assets import ASSET_DIR from stanford_quad.common.Command import Command @@ -61,11 +63,13 @@ timesteps = 120 * 60 * 10 # simulate for a max of 10 minutes # Sim seconds per sim step -sim_steps_per_sim_second = 120 +sim_steps_per_sim_second = 240 sim_dt = 1.0 / sim_steps_per_sim_second last_control_update = 0 start = time.time() +saved_states = [] + for steps in range(timesteps): sim_time_elapsed = sim_dt * steps if sim_time_elapsed - last_control_update > config.dt: @@ -77,6 +81,8 @@ # Step the controller forward by dt controller.run(state, command) + saved_states.append(copy.copy(state)) + # Update the pwm widths going to the servos hardware_interface.set_actuator_postions(state.joint_angles) @@ -85,8 +91,11 @@ # Performance testing - if ((steps+1) % 100) == 0: + if ((steps+1) % 240) == 0: elapsed = (time.time() - start) / 100 # print("Sim seconds elapsed: {}, Real seconds elapsed: {}".format(round(sim_time_elapsed, 3), round(elapsed, 3))) print (f"Sim running at {1/elapsed} Hz") + pickle.dump(saved_states, open("saved-states.pkl", "wb")) + quit() start = time.time() + diff --git a/stanford_quad/envs/__init__.py b/stanford_quad/envs/__init__.py new file mode 100644 index 00000000..e69de29b diff --git a/stanford_quad/envs/walking_env.py b/stanford_quad/envs/walking_env.py new file mode 100644 index 00000000..2c9feaf9 --- /dev/null +++ b/stanford_quad/envs/walking_env.py @@ -0,0 +1,23 @@ +from gym import register + +for headlessness in ["Headless", "Graphical"]: + register( + id=f'Splearn-Poke-Single-{headlessness}-v0', + entry_point='splearn.envs:PokeSingleEnv', + kwargs={ + "headless": (True if headlessness == "Headless" else False), + "steps": 10 + }, + max_episode_steps=10, + ) + + register( + id=f'Splearn-Poke-RandomSand-{headlessness}-v0', + entry_point='splearn.envs:PokeSingleEnv', + kwargs={ + "headless": (True if headlessness == "Headless" else False), + "steps": 10, + "random_sand": True + }, + max_episode_steps=10, + ) \ No newline at end of file diff --git a/stanford_quad/sim/HardwareInterface.py b/stanford_quad/sim/HardwareInterface.py index fe27a3ba..e8cc4220 100644 --- a/stanford_quad/sim/HardwareInterface.py +++ b/stanford_quad/sim/HardwareInterface.py @@ -22,7 +22,8 @@ def set_actuator_postions(self, joint_angles): forces=[self.max_torque] * 12, ) - def parallel_to_serial_joint_angles(self, joint_matrix): + @staticmethod + def parallel_to_serial_joint_angles(joint_matrix): """Convert from joint angles meant for the parallel linkage in Pupper to the joint angles in the serial linkage approximation implemented in the simulation diff --git a/stanford_quad/sim/simulator2.py b/stanford_quad/sim/simulator2.py new file mode 100644 index 00000000..c8bcf3c5 --- /dev/null +++ b/stanford_quad/sim/simulator2.py @@ -0,0 +1,79 @@ +import os + +import pybullet +import pybullet_data +import pybullet_utils.bullet_client as bc +import numpy as np + +from stanford_quad.assets import ASSET_DIR +from stanford_quad.sim.HardwareInterface import HardwareInterface + +FREQ_SIM = 240 + +REST_POS = HardwareInterface.parallel_to_serial_joint_angles( + np.array([ + [-0.12295051, 0.12295051, -0.12295051, 0.12295051], + [0.77062617, 0.77062617, 0.77062617, 0.77062617], + [-0.845151, -0.845151, -0.845151, -0.845151], + ]) +) + + +class PupperSim2: + def __init__( + self, xml_path=None, debug=False, gain_pos=0.25, gain_vel=0.5, max_torque=10, g=-9.81, start_standing=True + ): + """ + + :param str xml_path: Path to Mujoco robot XML definition file + :param bool debug: Set to True to enable visual inspection + :param float gain_pos: Gain position value for low-level controller + :param float gain_vel: Gain velocity value for low-level controller + :param float max_torque: Max torque for PID controller + :param float g: Gravity value + """ + if xml_path is None: + xml_path = os.path.join(ASSET_DIR, "pupper_pybullet_out.xml") + + self.gain_pos = gain_pos + self.gain_vel = gain_vel + self.max_torque = max_torque + + if debug: + startup_flag = pybullet.GUI + else: + startup_flag = pybullet.DIRECT + self.p = bc.BulletClient(connection_mode=startup_flag) + self.p.setTimeStep(1 / FREQ_SIM) + self.p.setAdditionalSearchPath(pybullet_data.getDataPath()) + self.p.setGravity(0, 0, g) + + # self.p.loadURDF("plane.urdf") + + self.model = self.p.loadMJCF(xml_path)[1] # [0] is the floor + if debug: + numjoints = self.p.getNumJoints(self.model) + for i in range(numjoints): + print(self.p.getJointInfo(self.model, i)) + self.joint_indices = list(range(0, 24, 2)) + + if start_standing: + self.action(REST_POS.T.flatten()) + + def step(self): + self.p.stepSimulation() + + def action(self, joint_angles): + assert len(joint_angles) == 12 + assert np.min(np.rad2deg(joint_angles)) > -180 + assert np.max(np.rad2deg(joint_angles)) < 180 + + self.p.setJointMotorControlArray( + bodyUniqueId=self.model, + jointIndices=self.joint_indices, + controlMode=self.p.POSITION_CONTROL, + targetPositions=list(joint_angles), + positionGains=[self.gain_pos] * 12, + velocityGains=[self.gain_vel] * 12, + forces=[self.max_torque] * 12, + ) From 16246ae746e94067e37cdba51a1bad5243ad148f Mon Sep 17 00:00:00 2001 From: Florian Golemo Date: Sun, 9 Aug 2020 13:34:53 -0400 Subject: [PATCH 08/49] added halfcheetah-like walking environment --- README.md | 230 ++++++------------------------ scripts/07-debug-new-simulator.py | 3 + scripts/08-run-walker-gym-env.py | 19 +++ stanford_quad/__init__.py | 15 ++ stanford_quad/envs/__init__.py | 1 + stanford_quad/envs/walking_env.py | 125 +++++++++++++--- stanford_quad/sim/simulator2.py | 47 ++++-- 7 files changed, 222 insertions(+), 218 deletions(-) create mode 100644 scripts/08-run-walker-gym-env.py diff --git a/README.md b/README.md index 64b8168f..d718763a 100644 --- a/README.md +++ b/README.md @@ -1,200 +1,60 @@ -# Stanford Quadruped - -## Overview -This repository hosts the code for Stanford Pupper and Stanford Woofer, Raspberry Pi-based quadruped robots that can trot, walk, and jump. +# Stanford Quadruped Gym +This repo is adapted from the original Standford Quadruped repo at https://github.com/stanfordroboticsclub/StanfordQuadruped and we've added an additional simulator and gym-compatible environments + ![Pupper CC Max Morse](https://live.staticflickr.com/65535/49614690753_78edca83bc_4k.jpg) -Video of pupper in action: https://youtu.be/NIjodHA78UE -Link to project page: https://stanfordstudentrobotics.org/pupper +## Installation -## How it works -![Overview diagram](imgs/diagram1.jpg) -The main program is ```run_robot.py``` which is located in this directory. The robot code is run as a loop, with a joystick interface, a controller, and a hardware interface orchestrating the behavior. +We assume you got an environment where `pip` and `python` point to the Python 3 binaries. This repo was tested on Python 3.6. -The joystick interface is responsible for reading joystick inputs from a UDP socket and converting them into a generic robot ```command``` type. A separate program, ```joystick.py```, publishes these UDP messages, and is responsible for reading inputs from the PS4 controller over bluetooth. The controller does the bulk of the work, switching between states (trot, walk, rest, etc) and generating servo position targets. A detailed model of the controller is shown below. The third component of the code, the hardware interface, converts the position targets from the controller into PWM duty cycles, which it then passes to a Python binding to ```pigpiod```, which then generates PWM signals in software and sends these signals to the motors attached to the Raspberry Pi. -![Controller diagram](imgs/diagram2.jpg) -This diagram shows a breakdown of the robot controller. Inside, you can see four primary components: a gait scheduler (also called gait controller), a stance controller, a swing controller, and an inverse kinematics model. +```bash +git clone https://github.com/fgolemo/StanfordQuadruped.git +cd StanfordQuadruped +pip install -e . +``` -The gait scheduler is responsible for planning which feet should be on the ground (stance) and which should be moving forward to the next step (swing) at any given time. In a trot for example, the diagonal pairs of legs move in sync and take turns between stance and swing. As shown in the diagram, the gait scheduler can be thought of as a conductor for each leg, switching it between stance and swing as time progresses. +## Getting Started -The stance controller controls the feet on the ground, and is actually quite simple. It looks at the desired robot velocity, and then generates a body-relative target velocity for these stance feet that is in the opposite direction as the desired velocity. It also incorporates turning, in which case it rotates the feet relative to the body in the opposite direction as the desired body rotation. +The new simulator lives in `stanford_quad/sim/simulator2.py` in the `PupperSim2` class. You can run the simulator in dev mode by running the script -The swing controller picks up the feet that just finished their stance phase, and brings them to their next touchdown location. The touchdown locations are selected so that the foot moves the same distance forward in swing as it does backwards in stance. For example, if in stance phase the feet move backwards at -0.4m/s (to achieve a body velocity of +0.4m/s) and the stance phase is 0.5 seconds long, then we know the feet will have moved backwards -0.20m. The swing controller will then move the feet forwards 0.20m to put the foot back in its starting place. You can imagine that if the swing controller only put the leg forward 0.15m, then every step the foot would lag more and more behind the body by -0.05m. + python scripts/07-debug-new-simulator.py + +## Gym Environments -Both the stance and swing controllers generate target positions for the feet in cartesian coordinates relative the body center of mass. It's convenient to work in cartesian coordinates for the stance and swing planning, but we now need to convert them to motor angles. This is done by using an inverse kinematics model, which maps between cartesian body coordinates and motor angles. These motor angles, also called joint angles, are then populated into the ```state``` variable and returned by the model. +There are currently 2 environments. Both come in 2 variants: `Headless` and `Graphical`. `Headless` is meant for training and launches the PyBullet sim without any GUI, `Graphical` is meant for local debugging, offers a GUI to inspect the robot and is significantly slower. +You can try out one of the walking environments, by running: + python scripts/08-run-walker-gym-env.py -## Installation -### Materials -- Raspberry Pi 4 -- SD Card (32GB recommended) -- Raspberry Pi 4 power supply (USB-C, 5V, >=3A) -- Ethernet cable - -### Steps -1. Set up the Raspberry Pi - - Follow the instructions on this repo to put the self-setup code on the Pi: https://github.com/stanfordroboticsclub/RPI-Setup - - If you're not on Stanford campus, use - ```bash - sudo raspi-config - ``` - to connect the Raspberry Pi to your home wifi network. It's important to connect to the internet over wifi and leave your ethernet port unused. This is because our UDPComms library checks that the ethernet adapter has a certain ip and subnet mask so it can do inter-process and inter-device communication. - - Note: The robot code won't work without following the RPI-Setup instructions linked above because the robot's inter-process communication layer (UDPComms) needs the Pi to have a certain ethernet configuration. If you're having problems with the networking, specifically with UDPComms failing, check out this issue: https://groups.google.com/forum/#!topic/stanford-quadrupeds/GO5GPiBUcnc -2. Test that the Pi works and connects to the internet - ```bash - ping www.google.com - ``` - - If that doesn't work, do - ```bash - ifconfig - ``` - and check the wlan0 portion to check if you have an IP address and other debugging info. -3. (Optional) Install the PREEMPT-RT kernel onto the Pi - - Download the kernel patch https://github.com/lemariva/RT-Tools-RPi/tree/master/preempt-rt/kernel_4_19_59-rt23-v7l%2B - - Follow these instructions starting from “Transfer the Kernel” https://lemariva.com/blog/2019/09/raspberry-pi-4b-preempt-rt-kernel-419y-performance-test - - Test by running in the shell: - ```bash - uname -r - ``` - - We haven't yet characterized the benefits of using the preempt-rt kernel on the Pi so skipping it is totally fine. -4. Clone this code - ```bash - git clone https://github.com/stanfordroboticsclub/StanfordQuadruped.git - ``` -5. Install requirements - ```bash - cd StanfordQuadruped - sudo bash install.sh - ``` -6. Power-cycle the robot -7. Reconnect to the robot (over ethernet) and check that everything is running correctly. (If your computer can't connect to the Pi, check that you correctly changed your computer's ethernet adapter's IP and subnet mask as described in step 1). - - SSH into the robot - ```bash - ssh pi@10.0.0.xx - ``` - where xx is the address you chose. - - Check the status for the joystick service - ```bash - sudo systemctl status joystick - ``` - - If you haven't yet connected the PS4 controller, it should say something like: - ```shell - pi@pupper(rw):~/StanfordQuadruped$ sudo systemctl status joystick - ● joystick.service - Pupper Joystick service - Loaded: loaded (/home/pi/PupperCommand/joystick.service; enabled; vendor preset: enabled) - Active: active (running) since Sun 2020-03-01 06:57:20 GMT; 1s ago - Main PID: 5692 (python3) - Tasks: 3 (limit: 4035) - Memory: 7.1M - CGroup: /system.slice/joystick.service - ├─5692 /usr/bin/python3 /home/pi/PupperCommand/joystick.py - └─5708 hcitool scan --flush - - Mar 01 06:57:20 pupper systemd[1]: Started Pupper Joystick service. - Mar 01 06:57:21 pupper python3[5692]: [info][controller 1] Created devices /dev/input/js0 (joystick) /dev/input/event0 (evdev) - Mar 01 06:57:21 pupper python3[5692]: [info][bluetooth] Scanning for devices - ``` - - Connect the PS4 controller to the Pi by putting it pairing mode. - - To put it into pairing mode, hold the share button and circular Playstation button at the same time until it starts making quick double flashes. - - If it starts making slow single flashes, hold the Playstation button down until it stops blinking and try again. - - Once the controller is connected, check the status again - ```bash - sudo systemctl status joystick - ``` - - It should now look something like - ```shell - pi@pupper(rw):~/StanfordQuadruped$ sudo systemctl status joystick - ● joystick.service - Pupper Joystick service - Loaded: loaded (/home/pi/PupperCommand/joystick.service; enabled; vendor preset: enabled) - Active: active (running) since Sun 2020-03-01 06:57:20 GMT; 55s ago - Main PID: 5692 (python3) - Tasks: 2 (limit: 4035) - Memory: 7.3M - CGroup: /system.slice/joystick.service - └─5692 /usr/bin/python3 /home/pi/PupperCommand/joystick.py - - Mar 01 06:57:20 pupper systemd[1]: Started Pupper Joystick service. - Mar 01 06:57:21 pupper python3[5692]: [info][controller 1] Created devices /dev/input/js0 (joystick) /dev/input/event0 (evdev) - Mar 01 06:57:21 pupper python3[5692]: [info][bluetooth] Scanning for devices - Mar 01 06:58:12 pupper python3[5692]: [info][bluetooth] Found device A0:AB:51:33:B5:A0 - Mar 01 06:58:13 pupper python3[5692]: [info][controller 1] Connected to Bluetooth Controller (A0:AB:51:33:B5:A0) - Mar 01 06:58:14 pupper python3[5692]: running - Mar 01 06:58:14 pupper python3[5692]: [info][controller 1] Battery: 50% - ```shell - - Check the status of the robot service - ```bash - sudo systemctl status robot - ``` - - The output varies depending on the order of you running various programs, but just check that it doesn't have any red text saying that it failed. - - If it did fail, usually this fixes it - ```bash - sudo systemctl restart robot - ``` -## Calibration -Calibration is a necessary step before running the robot because that we don't yet have a precise measurement of how the servos arms are fixed relative to the servo output shafts. Running the calibration script will help you determine this rotational offset by prompting you to align each of the 12 degrees of freedom with a known angle, such as the horizontal or the vertical. -### Materials -1. Finished robot -2. Some sort of stand to hold the robot up so that its legs can extend without touching the ground/table. -### Steps -1. Plug in your 2S Lipo battery -2. SSH into the robot as done in the installation section -3. Stop the robot script from taking over the PWM outputs - ```bash - rw - sudo systemctl stop robot - ``` -4. Run the calibration script - ```bash - cd StanfordQudruped - sudo pigpiod - python3 calibrate_servos.py - ``` - - The calibration script will prompt you through calibrating each of pupper's 12 servo motors. When it asks you to move a link to the horizontal position, you might be wondering what exactly counts as making the link horizontal. The answer is to align the *joint centers* of each link. For example, when aligning the upper link to the horizontal, you'll want to the line between the servo spline and bolt that connects the upper link to the lower link to be as horizontal as possible. -5. Re-enable the robot script - ```bash - sudo systemctl start robot - ``` - -## Running the robot -1. Plug in your 2S Lipo battery. - - If you followed the instructions above, the code will automatically start running on boot. If you want to turn this feature off, ssh into the robot, go into rw mode, and then do - ```bash - sudo systemctl disable robot - ``` -2. Connect the PS4 controller to the Pi by putting it pairing mode. - - To put it into pairing mode, hold the share button and circular Playstation button at the same time until it starts making quick double flashes. - - If it starts making slow single flashes, hold the Playstation button down until it stops blinking and try again. -3. Wait until the controller binds to the robot, at which point the controller should turn a dim green (or whatever color you chose in pupper/HardwareConfig.py for the deactivated color). -4. Press L1 on the controller to "activate" the robot. The controller should turn bright green (or again, whatever you chose in HardwareConfig). -5. You're good to go! Check out the controls section below for operating instructions. - -## Robot controls -- L1: toggles activating and deactivate the robot - - Note: the PS4 controller's front light will change colors to indicate if the robot is deactivated or activated. -- R1: pressing it transitions the robot between Rest mode and Trot mode -- "x" button: Press it three times to complete a full hop -- Right joystick - - Forward/back: pitches the robot forward and backward - - Left/right: turns the robot left and right -- Left joystick - - Forward/back: moves the robot forward/backwards when in Trot mode - - Left/right: moves the robot left/right when in Trot mode - -## Notes -- PS4 controller pairing instructions (repeat of instructions above) - - To put it into pairing mode, hold the share button and circular Playstation button at the same time until it starts making quick double flashes. - - If it starts making slow single flashes, hold the Playstation button down until it stops blinking and try again. -- Battery voltage - - If you power the robot with anything higher than 8.4V (aka >2S) you'll almost certainly fry all your expensive servos! - - Also note that you should attach a lipo battery alarm to your battery when running the robot so that you are know when the battery is depleted. Discharging your battery too much runs the risk of starting a fire, especially if you try to charge it again after it's been completely discharged. A good rule-of-thumb for know when a lipo is discharged is checking whether the individual cell voltages are below 3.6V. -- Feet! - - Using the bare carbon fiber as feet works well for grippy surfaces, including carpet. If you want to use the robot on a more slippery surface, we recommend buying rubber grommets (McMaster #90131A101) and fastening them to the pre-drilled holes in the feet. - -## Help -- Feel free to raise an issue (https://github.com/stanfordroboticsclub/StanfordQuadruped/issues/new/choose) or email me at nathankau [at] stanford [dot] edu -- We also have a Google group set up here: https://groups.google.com/forum/#!forum/stanford-quadrupeds +### Walking + +In both environments, the observations are the same: + +Observation space: +- 12 leg joints in the order + - front right hip + - front right upper leg + - front right lower leg + - front left hip/upper/lower leg + - back right hip/upper/lower leg + - back left hip/upper/lower leg +- 3 body orientation in euler angles +- 2 linear velocity (only along the plane, we don't care about z velocity + +The joints are normalized to be in [-1,1] but the orientation and velocity can be arbitrarily large. + +The action space in both environments is also 12-dimensional (corresponding to the same 12 joints as above in that order) and also normalized in [-1,1] but the effects are different between both environments (see below). + +In both environments, the goal is to walk/run as fast as possible straight forward. This means the reward is calculated as relative increase of x position with respect to the previous timestep (minus a small penalty term for high action values, same as in HalfCheetah-v2) + +#### Pupper-Walk-Absolute-[Headless|Graphical]-v0 + +In this environment, you have full absolute control over all joints and their resting position is set to 0 (which looks unnatural - the robot is standing fully straight, legs extended). Any action command is sent directly to the joints. + +#### Pupper-Walk-Relative-[Headless|Graphical]-v0 +In this env, your actions are relative to the resting position (see image at the top - roughly that). Meaning an action of `[0]*12` will put the Pupper to a stable rest. Action clipping is done after summing the current action and the action corresponding to the resting position, which means the action space is asymmetric - e.g. if a given joint's resting position is at `0.7`, then the action space for that joint is `[-1.7,.3]`. This is intentional because it allows the Pupper to start with a stable position. diff --git a/scripts/07-debug-new-simulator.py b/scripts/07-debug-new-simulator.py index 4a204932..14c637a8 100644 --- a/scripts/07-debug-new-simulator.py +++ b/scripts/07-debug-new-simulator.py @@ -11,6 +11,8 @@ motor = sim.p.addUserDebugParameter("motor{}".format(i + 1), -np.pi, np.pi, rest_pos[i]) debugParams.append(motor) +print (sim.get_pos_orn_vel()) +print (sim.get_joint_states()) for step in range(100000): motorPos = [] @@ -19,5 +21,6 @@ motorPos.append(pos) sim.action(motorPos) sim.step() + print (sim.get_pos_orn_vel()[0][0]) diff --git a/scripts/08-run-walker-gym-env.py b/scripts/08-run-walker-gym-env.py new file mode 100644 index 00000000..3fc47757 --- /dev/null +++ b/scripts/08-run-walker-gym-env.py @@ -0,0 +1,19 @@ +import time + +import gym +import stanford_quad +import numpy as np +env = gym.make("Pupper-Walk-Graphical-v0") + +for run in range(5): + env.reset() + for step in range(121): + action = env.action_space.sample() + obs, rew, done, misc = env.step(action) + print (f"action: {np.around(action,2)}, " + f"obs: {np.around(obs,2)}, " + f"rew: {np.around(rew,2)}, " + f"done: {done}") + + time.sleep(.01) + quit() diff --git a/stanford_quad/__init__.py b/stanford_quad/__init__.py index e69de29b..90937548 100644 --- a/stanford_quad/__init__.py +++ b/stanford_quad/__init__.py @@ -0,0 +1,15 @@ +from gym import register + +for headlessness in ["Headless", "Graphical"]: + register( + id=f"Pupper-Walk-Absolute-{headlessness}-v0", + entry_point="stanford_quad.envs:WalkingEnv", + kwargs={"debug": (False if headlessness == "Headless" else True), "steps": 120, "relative_action": False}, + max_episode_steps=120, + ) + register( + id=f"Pupper-Walk-Relative-{headlessness}-v0", + entry_point="stanford_quad.envs:WalkingEnv", + kwargs={"debug": (False if headlessness == "Headless" else True), "steps": 120, "relative_action": True}, + max_episode_steps=120, + ) diff --git a/stanford_quad/envs/__init__.py b/stanford_quad/envs/__init__.py index e69de29b..cf7271d2 100644 --- a/stanford_quad/envs/__init__.py +++ b/stanford_quad/envs/__init__.py @@ -0,0 +1 @@ +from stanford_quad.envs.walking_env import WalkingEnv \ No newline at end of file diff --git a/stanford_quad/envs/walking_env.py b/stanford_quad/envs/walking_env.py index 2c9feaf9..2cbbada8 100644 --- a/stanford_quad/envs/walking_env.py +++ b/stanford_quad/envs/walking_env.py @@ -1,23 +1,102 @@ -from gym import register - -for headlessness in ["Headless", "Graphical"]: - register( - id=f'Splearn-Poke-Single-{headlessness}-v0', - entry_point='splearn.envs:PokeSingleEnv', - kwargs={ - "headless": (True if headlessness == "Headless" else False), - "steps": 10 - }, - max_episode_steps=10, - ) - - register( - id=f'Splearn-Poke-RandomSand-{headlessness}-v0', - entry_point='splearn.envs:PokeSingleEnv', - kwargs={ - "headless": (True if headlessness == "Headless" else False), - "steps": 10, - "random_sand": True - }, - max_episode_steps=10, - ) \ No newline at end of file +import gym +from gym import spaces +import numpy as np + +from stanford_quad.sim.simulator2 import PupperSim2, FREQ_SIM + +CONTROL_FREQUENCY = 60 # Hz, the simulation runs at 240Hz by default and doing a multiple of that is easier + + +class WalkingEnv(gym.Env): + def __init__(self, debug=False, steps=120, control_freq=CONTROL_FREQUENCY, relative_action=True): + """ Gym-compatible environment to teach the pupper how to walk + + :param bool debug: If True, shows PyBullet in GUI mode. Set to False when training. + :param int steps: How long is the episode? Each step = one call to WalkingEnv.step() + :param int control_freq: How many simulation steps are there in a second of Pybullet sim. Pybullet always runs + at 240Hz but that's not optimal for RL control. + :param bool relative_action: If set to True, then all actions are added to the resting position. + This give the robot a more stable starting position. + """ + + super().__init__() + + ## observation space: + ## - 12 lef joints in the order + ## - front right hip + ## - front right upper leg + ## - front right lower leg + ## - front left hip/upper/lower leg + ## - back right hip/upper/lower leg + ## - back left hip/upper/lower leg + ## - 3 body orientation in euler angles + ## - 2 linear velocity (only along the plane, we don't care about z velocity + + self.observation_space = spaces.Box(low=-1, high=1, shape=(12 + 3 + 2,), dtype=np.float32) + + # action = 12 joint angles in the same order as above (fr/fl/br/bl and each with hip/upper/lower) + self.action_space = spaces.Box(low=-1, high=1, shape=(12,), dtype=np.float32) + + # turning off start_standing because the that's done in self.reset() + self.sim = PupperSim2(debug=debug, start_standing=False) + self.episode_steps = 0 + self.episode_steps_max = steps + self.control_freq = control_freq + self.dt = 1 / self.control_freq + self.sim_steps = int(round(FREQ_SIM / control_freq)) + self.relative_action = relative_action + + def reset(self): + self.episode_steps = 0 + self.sim.reset(rest=self.relative_action) # also stand up the robot + + def seed(self, seed=None): + np.random.seed(seed) + return super().seed(seed) + + def close(self): + self.sim.p.disconnect() + super().close() + + def sanitize_actions(self, actions): + assert len(actions) == 12 + scaled = actions * np.pi # because 1/-1 corresponds to pi/-pi radians rotation + + if self.relative_action: + scaled += self.sim.get_rest_pos() + + # this enforces an action range of -1/1, except if it's relative action - then the action space is asymmetric + clipped = np.clip(scaled, -np.pi+0.001, np.pi-0.001) + return clipped + + def step(self, action): + action_clean = self.sanitize_actions(action) + + pos_before, _, _ = self.sim.get_pos_orn_vel() + + # The action command only sets the goals of the motors. It doesn't actually step the simulation forward in time + self.sim.action(action_clean) + for _ in range(self.sim_steps): + self.sim.step() + + pos_after, orn_after, vel_after = self.sim.get_pos_orn_vel() + + joint_states = self.sim.get_joint_states() / np.pi # to normalize to [-1,1] + obs = list(joint_states) + list(orn_after) + list(vel_after)[:2] + + # this reward calculation is taken verbatim from halfcheetah-v2 + reward_ctrl = -0.1 * np.square(action).sum() + reward_run = (pos_after[0] - pos_before[0]) / self.dt + reward = reward_ctrl + reward_run + + done = False + self.episode_steps += 1 + if self.episode_steps == self.episode_steps_max: + done = True + + return obs, reward, done, dict(reward_run=reward_run, reward_ctrl=reward_ctrl) + + def render(self, mode="human"): + # unused - use debug flag via "Headless"/"Graphical" environment instead + # FIXME: in the future we could add an external camera here + pass diff --git a/stanford_quad/sim/simulator2.py b/stanford_quad/sim/simulator2.py index c8bcf3c5..217e5587 100644 --- a/stanford_quad/sim/simulator2.py +++ b/stanford_quad/sim/simulator2.py @@ -11,17 +11,19 @@ FREQ_SIM = 240 REST_POS = HardwareInterface.parallel_to_serial_joint_angles( - np.array([ - [-0.12295051, 0.12295051, -0.12295051, 0.12295051], - [0.77062617, 0.77062617, 0.77062617, 0.77062617], - [-0.845151, -0.845151, -0.845151, -0.845151], - ]) + np.array( + [ + [-0.12295051, 0.12295051, -0.12295051, 0.12295051], + [0.77062617, 0.77062617, 0.77062617, 0.77062617], + [-0.845151, -0.845151, -0.845151, -0.845151], + ] + ) ) class PupperSim2: def __init__( - self, xml_path=None, debug=False, gain_pos=0.25, gain_vel=0.5, max_torque=10, g=-9.81, start_standing=True + self, xml_path=None, debug=False, gain_pos=0.125, gain_vel=0.25, max_torque=1, g=-9.81, start_standing=True ): """ @@ -50,7 +52,7 @@ def __init__( # self.p.loadURDF("plane.urdf") - self.model = self.p.loadMJCF(xml_path)[1] # [0] is the floor + self.model = self.p.loadMJCF(xml_path)[1] # [0] is the floor if debug: numjoints = self.p.getNumJoints(self.model) for i in range(numjoints): @@ -58,15 +60,40 @@ def __init__( self.joint_indices = list(range(0, 24, 2)) if start_standing: - self.action(REST_POS.T.flatten()) + self.reset() + self.step() def step(self): self.p.stepSimulation() + def reset(self, rest=True): + self.p.resetBasePositionAndOrientation(self.model, [0, 0, .3], self.p.getQuaternionFromEuler([0, 0, 0])) + if rest: + action = self.get_rest_pos() + else: + action = [0] * 12 + self.action(action) + + def get_rest_pos(self): + return REST_POS.T.flatten() + + def get_pos_orn_vel(self): + posorn = self.p.getBasePositionAndOrientation(self.model) + pos = posorn[0] + orn = self.p.getEulerFromQuaternion(posorn[1]) + vel = self.p.getBaseVelocity(self.model)[0] + + return pos, orn, vel + + def get_joint_states(self): + joint_states = self.p.getJointStates(self.model, self.joint_indices) + joint_states = [joint[0] for joint in joint_states] + return joint_states + def action(self, joint_angles): assert len(joint_angles) == 12 - assert np.min(np.rad2deg(joint_angles)) > -180 - assert np.max(np.rad2deg(joint_angles)) < 180 + assert np.min(np.rad2deg(joint_angles)) >= -180 + assert np.max(np.rad2deg(joint_angles)) <= 180 self.p.setJointMotorControlArray( bodyUniqueId=self.model, From 63d41ed15fad2f75340d8fb163628f2a2ccbfc04 Mon Sep 17 00:00:00 2001 From: Florian Golemo Date: Sun, 9 Aug 2020 13:37:07 -0400 Subject: [PATCH 09/49] highlights --- README.md | 6 +++--- scripts/08-run-walker-gym-env.py | 2 +- 2 files changed, 4 insertions(+), 4 deletions(-) diff --git a/README.md b/README.md index d718763a..3fcb4922 100644 --- a/README.md +++ b/README.md @@ -33,7 +33,7 @@ You can try out one of the walking environments, by running: In both environments, the observations are the same: -Observation space: +**Observation space**: - 12 leg joints in the order - front right hip - front right upper leg @@ -46,9 +46,9 @@ Observation space: The joints are normalized to be in [-1,1] but the orientation and velocity can be arbitrarily large. -The action space in both environments is also 12-dimensional (corresponding to the same 12 joints as above in that order) and also normalized in [-1,1] but the effects are different between both environments (see below). +The **action space** in both environments is also 12-dimensional (corresponding to the same 12 joints as above in that order) and also normalized in [-1,1] but the effects are different between both environments (see below). -In both environments, the goal is to walk/run as fast as possible straight forward. This means the reward is calculated as relative increase of x position with respect to the previous timestep (minus a small penalty term for high action values, same as in HalfCheetah-v2) +In both environments, the goal is to walk/run as fast as possible straight forward. This means the **reward** is calculated as relative increase of x position with respect to the previous timestep (minus a small penalty term for high action values, same as in HalfCheetah-v2) #### Pupper-Walk-Absolute-[Headless|Graphical]-v0 diff --git a/scripts/08-run-walker-gym-env.py b/scripts/08-run-walker-gym-env.py index 3fc47757..c56a88b8 100644 --- a/scripts/08-run-walker-gym-env.py +++ b/scripts/08-run-walker-gym-env.py @@ -1,7 +1,7 @@ import time import gym -import stanford_quad +import stanford_quad # need this unused import to get our custom environments import numpy as np env = gym.make("Pupper-Walk-Graphical-v0") From fc1b060d1cb094f472ddf8213ac4cd30ce398b29 Mon Sep 17 00:00:00 2001 From: Florian Golemo Date: Sun, 9 Aug 2020 19:04:03 -0400 Subject: [PATCH 10/49] bugfix and improved example --- scripts/08-run-walker-gym-env.py | 7 +++---- stanford_quad/envs/walking_env.py | 2 +- 2 files changed, 4 insertions(+), 5 deletions(-) diff --git a/scripts/08-run-walker-gym-env.py b/scripts/08-run-walker-gym-env.py index c56a88b8..f0942b54 100644 --- a/scripts/08-run-walker-gym-env.py +++ b/scripts/08-run-walker-gym-env.py @@ -3,17 +3,16 @@ import gym import stanford_quad # need this unused import to get our custom environments import numpy as np -env = gym.make("Pupper-Walk-Graphical-v0") +env = gym.make("Pupper-Walk-Relative-Graphical-v0") for run in range(5): env.reset() for step in range(121): - action = env.action_space.sample() + action = env.action_space.sample() * 0.2 obs, rew, done, misc = env.step(action) print (f"action: {np.around(action,2)}, " f"obs: {np.around(obs,2)}, " f"rew: {np.around(rew,2)}, " f"done: {done}") - time.sleep(.01) - quit() + time.sleep(.02) diff --git a/stanford_quad/envs/walking_env.py b/stanford_quad/envs/walking_env.py index 2cbbada8..1ef9efed 100644 --- a/stanford_quad/envs/walking_env.py +++ b/stanford_quad/envs/walking_env.py @@ -81,7 +81,7 @@ def step(self, action): pos_after, orn_after, vel_after = self.sim.get_pos_orn_vel() - joint_states = self.sim.get_joint_states() / np.pi # to normalize to [-1,1] + joint_states = np.array(self.sim.get_joint_states()) / np.pi # to normalize to [-1,1] obs = list(joint_states) + list(orn_after) + list(vel_after)[:2] # this reward calculation is taken verbatim from halfcheetah-v2 From 63eb854c0f286a71fbf45d1114192f7cff8da4c3 Mon Sep 17 00:00:00 2001 From: Florian Golemo Date: Thu, 13 Aug 2020 13:25:27 -0400 Subject: [PATCH 11/49] bugfix: reset now returns observation --- scripts/08-run-walker-gym-env.py | 4 ++-- stanford_quad/envs/walking_env.py | 14 ++++++++++---- stanford_quad/sim/simulator2.py | 1 + 3 files changed, 13 insertions(+), 6 deletions(-) diff --git a/scripts/08-run-walker-gym-env.py b/scripts/08-run-walker-gym-env.py index f0942b54..f0037345 100644 --- a/scripts/08-run-walker-gym-env.py +++ b/scripts/08-run-walker-gym-env.py @@ -3,7 +3,7 @@ import gym import stanford_quad # need this unused import to get our custom environments import numpy as np -env = gym.make("Pupper-Walk-Relative-Graphical-v0") +env = gym.make("Pupper-Walk-Relative-Headless-v0") for run in range(5): env.reset() @@ -15,4 +15,4 @@ f"rew: {np.around(rew,2)}, " f"done: {done}") - time.sleep(.02) + # time.sleep(.02) diff --git a/stanford_quad/envs/walking_env.py b/stanford_quad/envs/walking_env.py index 1ef9efed..081f6509 100644 --- a/stanford_quad/envs/walking_env.py +++ b/stanford_quad/envs/walking_env.py @@ -49,6 +49,7 @@ def __init__(self, debug=False, steps=120, control_freq=CONTROL_FREQUENCY, relat def reset(self): self.episode_steps = 0 self.sim.reset(rest=self.relative_action) # also stand up the robot + return self.get_obs() def seed(self, seed=None): np.random.seed(seed) @@ -69,6 +70,13 @@ def sanitize_actions(self, actions): clipped = np.clip(scaled, -np.pi+0.001, np.pi-0.001) return clipped + def get_obs(self): + pos, orn, vel = self.sim.get_pos_orn_vel() + + joint_states = np.array(self.sim.get_joint_states()) / np.pi # to normalize to [-1,1] + obs = list(joint_states) + list(orn) + list(vel)[:2] + return obs + def step(self, action): action_clean = self.sanitize_actions(action) @@ -78,11 +86,9 @@ def step(self, action): self.sim.action(action_clean) for _ in range(self.sim_steps): self.sim.step() + pos_after, _, _ = self.sim.get_pos_orn_vel() - pos_after, orn_after, vel_after = self.sim.get_pos_orn_vel() - - joint_states = np.array(self.sim.get_joint_states()) / np.pi # to normalize to [-1,1] - obs = list(joint_states) + list(orn_after) + list(vel_after)[:2] + obs = self.get_obs() # this reward calculation is taken verbatim from halfcheetah-v2 reward_ctrl = -0.1 * np.square(action).sum() diff --git a/stanford_quad/sim/simulator2.py b/stanford_quad/sim/simulator2.py index 217e5587..8b5e904c 100644 --- a/stanford_quad/sim/simulator2.py +++ b/stanford_quad/sim/simulator2.py @@ -73,6 +73,7 @@ def reset(self, rest=True): else: action = [0] * 12 self.action(action) + self.step() # one step to move joints into place def get_rest_pos(self): return REST_POS.T.flatten() From b1dff9403ce7d37205620a00539f29c51556a712 Mon Sep 17 00:00:00 2001 From: Florian Golemo Date: Thu, 13 Aug 2020 15:16:07 -0400 Subject: [PATCH 12/49] scaled down action amount and torque --- scripts/08-run-walker-gym-env.py | 7 ++++--- stanford_quad/__init__.py | 10 ++++++++-- stanford_quad/envs/walking_env.py | 7 ++++--- stanford_quad/sim/simulator2.py | 28 +++++++++++++++++++++++++--- 4 files changed, 41 insertions(+), 11 deletions(-) diff --git a/scripts/08-run-walker-gym-env.py b/scripts/08-run-walker-gym-env.py index f0037345..1dd38983 100644 --- a/scripts/08-run-walker-gym-env.py +++ b/scripts/08-run-walker-gym-env.py @@ -3,16 +3,17 @@ import gym import stanford_quad # need this unused import to get our custom environments import numpy as np -env = gym.make("Pupper-Walk-Relative-Headless-v0") +env = gym.make("Pupper-Walk-Relative-Graphical-v0") for run in range(5): env.reset() + time.sleep(2) for step in range(121): - action = env.action_space.sample() * 0.2 + action = env.action_space.sample() * 0.3 obs, rew, done, misc = env.step(action) print (f"action: {np.around(action,2)}, " f"obs: {np.around(obs,2)}, " f"rew: {np.around(rew,2)}, " f"done: {done}") - # time.sleep(.02) + time.sleep(.02) diff --git a/stanford_quad/__init__.py b/stanford_quad/__init__.py index 90937548..46338dfd 100644 --- a/stanford_quad/__init__.py +++ b/stanford_quad/__init__.py @@ -4,12 +4,18 @@ register( id=f"Pupper-Walk-Absolute-{headlessness}-v0", entry_point="stanford_quad.envs:WalkingEnv", - kwargs={"debug": (False if headlessness == "Headless" else True), "steps": 120, "relative_action": False}, + kwargs={"debug": (False if headlessness == "Headless" else True), "steps": 120, "relative_action": False, "action_scaling": 1}, max_episode_steps=120, ) register( id=f"Pupper-Walk-Relative-{headlessness}-v0", entry_point="stanford_quad.envs:WalkingEnv", - kwargs={"debug": (False if headlessness == "Headless" else True), "steps": 120, "relative_action": True}, + kwargs={"debug": (False if headlessness == "Headless" else True), "steps": 120, "relative_action": True, "action_scaling": 1}, + max_episode_steps=120, + ) + register( + id=f"Pupper-Walk-Relative-ScaledDown-{headlessness}-v0", + entry_point="stanford_quad.envs:WalkingEnv", + kwargs={"debug": (False if headlessness == "Headless" else True), "steps": 120, "relative_action": True, "action_scaling": .3}, max_episode_steps=120, ) diff --git a/stanford_quad/envs/walking_env.py b/stanford_quad/envs/walking_env.py index 081f6509..7cd27fc9 100644 --- a/stanford_quad/envs/walking_env.py +++ b/stanford_quad/envs/walking_env.py @@ -8,7 +8,7 @@ class WalkingEnv(gym.Env): - def __init__(self, debug=False, steps=120, control_freq=CONTROL_FREQUENCY, relative_action=True): + def __init__(self, debug=False, steps=120, control_freq=CONTROL_FREQUENCY, relative_action=True, action_scaling=1.0): """ Gym-compatible environment to teach the pupper how to walk :param bool debug: If True, shows PyBullet in GUI mode. Set to False when training. @@ -38,13 +38,14 @@ def __init__(self, debug=False, steps=120, control_freq=CONTROL_FREQUENCY, relat self.action_space = spaces.Box(low=-1, high=1, shape=(12,), dtype=np.float32) # turning off start_standing because the that's done in self.reset() - self.sim = PupperSim2(debug=debug, start_standing=False) + self.sim = PupperSim2(debug=debug, start_standing=False, gain_pos=1/16, gain_vel=1/8, max_torque=1/2) self.episode_steps = 0 self.episode_steps_max = steps self.control_freq = control_freq self.dt = 1 / self.control_freq self.sim_steps = int(round(FREQ_SIM / control_freq)) self.relative_action = relative_action + self.action_scaling = action_scaling def reset(self): self.episode_steps = 0 @@ -61,7 +62,7 @@ def close(self): def sanitize_actions(self, actions): assert len(actions) == 12 - scaled = actions * np.pi # because 1/-1 corresponds to pi/-pi radians rotation + scaled = actions * np.pi * self.action_scaling # because 1/-1 corresponds to pi/-pi radians rotation if self.relative_action: scaled += self.sim.get_rest_pos() diff --git a/stanford_quad/sim/simulator2.py b/stanford_quad/sim/simulator2.py index 8b5e904c..edbccdc3 100644 --- a/stanford_quad/sim/simulator2.py +++ b/stanford_quad/sim/simulator2.py @@ -1,4 +1,5 @@ import os +import time import pybullet import pybullet_data @@ -67,13 +68,20 @@ def step(self): self.p.stepSimulation() def reset(self, rest=True): - self.p.resetBasePositionAndOrientation(self.model, [0, 0, .3], self.p.getQuaternionFromEuler([0, 0, 0])) + height = .3 + if rest: + height = .182 + self.p.resetBasePositionAndOrientation(self.model, [0, 0, height], self.p.getQuaternionFromEuler([0, 0, 0])) if rest: action = self.get_rest_pos() else: action = [0] * 12 self.action(action) - self.step() # one step to move joints into place + self.set(action) + # self.step() # one step to move joints into place + + for _ in range(10): + self.step() def get_rest_pos(self): return REST_POS.T.flatten() @@ -91,11 +99,14 @@ def get_joint_states(self): joint_states = [joint[0] for joint in joint_states] return joint_states - def action(self, joint_angles): + def joint_sanity_check(self, joint_angles): assert len(joint_angles) == 12 assert np.min(np.rad2deg(joint_angles)) >= -180 assert np.max(np.rad2deg(joint_angles)) <= 180 + def action(self, joint_angles): + self.joint_sanity_check(joint_angles) + self.p.setJointMotorControlArray( bodyUniqueId=self.model, jointIndices=self.joint_indices, @@ -105,3 +116,14 @@ def action(self, joint_angles): velocityGains=[self.gain_vel] * 12, forces=[self.max_torque] * 12, ) + + def set(self, joint_angles): + self.joint_sanity_check(joint_angles) + + for joint_idx in range(12): + self.p.resetJointState( + bodyUniqueId=self.model, + jointIndex=self.joint_indices[joint_idx], + targetValue=joint_angles[joint_idx], + targetVelocity=0, + ) From 3e4e3ae26102bb69c0c3850fb27ac049fb574cfb Mon Sep 17 00:00:00 2001 From: Florian Golemo Date: Fri, 28 Aug 2020 19:06:04 -0400 Subject: [PATCH 13/49] cleanup - we don't need the woofer for what we're doing here and in case we have it in the git hostory --- scripts/09-test-random-steps.py | 6 + stanford_quad/woofer/Config.py | 240 ---------------------- stanford_quad/woofer/HardwareConfig.py | 44 ---- stanford_quad/woofer/HardwareInterface.py | 97 --------- stanford_quad/woofer/Kinematics.py | 98 --------- stanford_quad/woofer/__init__.py | 0 6 files changed, 6 insertions(+), 479 deletions(-) create mode 100644 scripts/09-test-random-steps.py delete mode 100644 stanford_quad/woofer/Config.py delete mode 100644 stanford_quad/woofer/HardwareConfig.py delete mode 100644 stanford_quad/woofer/HardwareInterface.py delete mode 100644 stanford_quad/woofer/Kinematics.py delete mode 100644 stanford_quad/woofer/__init__.py diff --git a/scripts/09-test-random-steps.py b/scripts/09-test-random-steps.py new file mode 100644 index 00000000..134f575d --- /dev/null +++ b/scripts/09-test-random-steps.py @@ -0,0 +1,6 @@ +STAIRS_STEP_WIDTH = 1 # if you're standing in front of a staircase and looking up, what's the left-right distance? +STAIRS_STEP_DEPTH = 0.1 # if you're stepping onto one step, how much of your foot can fit on the step? +STAIRS_STEP_HEIGHT = 0.2 # how far for you have to go up between each step? + +sim = + diff --git a/stanford_quad/woofer/Config.py b/stanford_quad/woofer/Config.py deleted file mode 100644 index 11225c5f..00000000 --- a/stanford_quad/woofer/Config.py +++ /dev/null @@ -1,240 +0,0 @@ -import numpy as np -from scipy.linalg import solve - - -class BehaviorState(Enum): - REST = 0 - TROT = 1 - HOP = 2 - FINISHHOP = 3 - - -class UserInputParams: - def __init__(self): - self.max_x_velocity = 0.5 - self.max_y_velocity = 0.24 - self.max_yaw_rate = 0.2 - self.max_pitch = 30.0 * np.pi / 180.0 - - -class MovementReference: - """Stores movement reference - """ - - def __init__(self): - self.v_xy_ref = np.array([0, 0]) - self.wz_ref = 0.0 - self.z_ref = -0.265 - self.pitch = 0.0 - self.roll = 0.0 - - -class SwingParams: - """Swing Parameters - """ - - def __init__(self): - self.z_coeffs = None - self.z_clearance = 0.05 - self.alpha = ( - 0.5 - ) # Ratio between touchdown distance and total horizontal stance movement - self.beta = ( - 0.5 - ) # Ratio between touchdown distance and total horizontal stance movement - - @property - def z_clearance(self): - return self.__z_clearance - - @z_clearance.setter - def z_clearance(self, z): - self.__z_clearance = z - b_z = np.array([0, 0, 0, 0, self.__z_clearance]) - A_z = np.array( - [ - [0, 0, 0, 0, 1], - [1, 1, 1, 1, 1], - [0, 0, 0, 1, 0], - [4, 3, 2, 1, 0], - [0.5 ** 4, 0.5 ** 3, 0.5 ** 2, 0.5 ** 1, 0.5 ** 0], - ] - ) - self.z_coeffs = solve(A_z, b_z) - - -class StanceParams: - """Stance parameters - """ - - def __init__(self): - self.z_time_constant = 0.02 - self.z_speed = 0.03 # maximum speed [m/s] - self.pitch_deadband = 0.02 - self.pitch_time_constant = 0.25 - self.max_pitch_rate = 0.15 - self.roll_speed = 0.16 # maximum roll rate [rad/s] - self.delta_x = 0.23 - self.delta_y = 0.173 - self.x_shift = -0.01 - - @property - def default_stance(self): - return np.array( - [ - [ - self.delta_x + self.x_shift, - self.delta_x + self.x_shift, - -self.delta_x + self.x_shift, - -self.delta_x + self.x_shift, - ], - [-self.delta_y, self.delta_y, -self.delta_y, self.delta_y], - [0, 0, 0, 0], - ] - ) - - -class GaitParams: - """Gait Parameters - """ - - def __init__(self): - self.dt = 0.01 - self.num_phases = 4 - self.contact_phases = np.array( - [[1, 1, 1, 1], [1, 1, 1, 1], [1, 1, 1, 1], [1, 1, 1, 1]] - ) - self.overlap_time = ( - 0.5 # duration of the phase where all four feet are on the ground - ) - self.swing_time = ( - 0.5 # duration of the phase when only two feet are on the ground - ) - - @property - def overlap_ticks(self): - return int(self.overlap_time / self.dt) - - @property - def swing_ticks(self): - return int(self.swing_time / self.dt) - - @property - def stance_ticks(self): - return 2 * self.overlap_ticks + self.swing_ticks - - @property - def phase_times(self): - return np.array( - [self.overlap_ticks, self.swing_ticks, self.overlap_ticks, self.swing_ticks] - ) - - @property - def phase_length(self): - return 2 * self.overlap_ticks + 2 * self.swing_ticks - - -class RobotConfig: - """Woofer hardware parameters - """ - - def __init__(self): - - # Robot geometry - self.LEG_FB = 0.23 # front-back distance from center line to leg axis - self.LEG_LR = 0.109 # left-right distance from center line to leg plane - self.ABDUCTION_OFFSET = 0.064 # distance from abduction axis to leg - self.FOOT_RADIUS = 0.02 - - self.UPPER_LEG = 0.18 - self.LOWER_LEG = 0.32 - - # Update hip geometry - self.HIP_L = 0.0394 - self.HIP_W = 0.0744 - self.HIP_T = 0.0214 - self.HIP_OFFSET = 0.0132 - - self.L = 0.66 - self.W = 0.176 - self.T = 0.092 - - self.LEG_ORIGINS = np.array( - [ - [self.LEG_FB, self.LEG_FB, -self.LEG_FB, -self.LEG_FB], - [-self.LEG_LR, self.LEG_LR, -self.LEG_LR, self.LEG_LR], - [0, 0, 0, 0], - ] - ) - - self.ABDUCTION_OFFSETS = np.array( - [ - -self.ABDUCTION_OFFSET, - self.ABDUCTION_OFFSET, - -self.ABDUCTION_OFFSET, - self.ABDUCTION_OFFSET, - ] - ) - - self.START_HEIGHT = 0.3 - - # Robot inertia params - self.FRAME_MASS = 3.0 # kg - self.MODULE_MASS = 1.033 # kg - self.LEG_MASS = 0.15 # kg - self.MASS = self.FRAME_MASS + (self.MODULE_MASS + self.LEG_MASS) * 4 - - # Compensation factor of 3 because the inertia measurement was just - # of the carbon fiber and plastic parts of the frame and did not - # include the hip servos and electronics - self.FRAME_INERTIA = tuple( - map(lambda x: 3.0 * x, (1.844e-4, 1.254e-3, 1.337e-3)) - ) - self.MODULE_INERTIA = (3.698e-5, 7.127e-6, 4.075e-5) - - leg_z = 1e-6 - leg_mass = 0.010 - leg_x = 1 / 12 * self.LOWER_LEG ** 2 * leg_mass - leg_y = leg_x - self.LEG_INERTIA = (leg_x, leg_y, leg_z) - - # Joint params - G = 220 # Servo gear ratio - m_rotor = 0.016 # Servo rotor mass - r_rotor = 0.005 # Rotor radius - self.ARMATURE = G ** 2 * m_rotor * r_rotor ** 2 # Inertia of rotational joints - # print("Servo armature", self.ARMATURE) - - NATURAL_DAMPING = 1.0 # Damping resulting from friction - ELECTRICAL_DAMPING = 0.049 # Damping resulting from back-EMF - - self.REV_DAMPING = ( - NATURAL_DAMPING + ELECTRICAL_DAMPING - ) # Damping torque on the revolute joints - - # Force limits - self.MAX_JOINT_TORQUE = 12.0 - self.REVOLUTE_RANGE = 3 - self.NUM_ODRIVES = 6 - self.ENCODER_CPR = 2000 - self.MOTOR_REDUCTION = 4 - - -class EnvironmentConfig: - """Environmental parameters - """ - - def __init__(self): - self.MU = 1.5 # coeff friction - self.DT = 0.001 # seconds between simulation steps - - -class SolverConfig: - """MuJoCo solver parameters - """ - - def __init__(self): - self.JOINT_SOLREF = "0.001 1" # time constant and damping ratio for joints - self.JOINT_SOLIMP = "0.9 0.95 0.001" # joint constraint parameters - self.GEOM_SOLREF = "0.01 1" # time constant and damping ratio for geom contacts - self.GEOM_SOLIMP = "0.9 0.95 0.001" # geometry contact parameters diff --git a/stanford_quad/woofer/HardwareConfig.py b/stanford_quad/woofer/HardwareConfig.py deleted file mode 100644 index 02f4c8e8..00000000 --- a/stanford_quad/woofer/HardwareConfig.py +++ /dev/null @@ -1,44 +0,0 @@ -""" -Per-robot configuration file that is particular to each individual robot, not just the type of robot. -""" - -import numpy as np - -ODRIVE_SERIAL_NUMBERS = [ - "2065339F304B", - "208F3384304B", - "365833753037", - "207E35753748", - "208F3385304B", - "208E3387304B", -] - -ACTUATOR_DIRECTIONS = np.array([[1, 1, -1, -1], [-1, -1, -1, -1], [1, 1, 1, 1]]) - -ANGLE_OFFSETS = np.array( - [ - [0, 0, 0, 0], - [np.pi / 2, np.pi / 2, np.pi / 2, np.pi / 2], - [-np.pi / 2, -np.pi / 2, -np.pi / 2, -np.pi / 2], - ] -) - - -def map_actuators_to_axes(odrives): - axes = [[None for _ in range(4)] for _ in range(3)] - axes[0][0] = odrives[1].axis1 - axes[1][0] = odrives[0].axis0 - axes[2][0] = odrives[0].axis1 - - axes[0][1] = odrives[1].axis0 - axes[1][1] = odrives[2].axis1 - axes[2][1] = odrives[2].axis0 - - axes[0][2] = odrives[4].axis1 - axes[1][2] = odrives[5].axis0 - axes[2][2] = odrives[5].axis1 - - axes[0][3] = odrives[4].axis0 - axes[1][3] = odrives[3].axis1 - axes[2][3] = odrives[3].axis0 - return axes diff --git a/stanford_quad/woofer/HardwareInterface.py b/stanford_quad/woofer/HardwareInterface.py deleted file mode 100644 index 3ad83b1b..00000000 --- a/stanford_quad/woofer/HardwareInterface.py +++ /dev/null @@ -1,97 +0,0 @@ -import odrive -from odrive.enums import * -from stanford_quad.woofer import RobotConfig -from stanford_quad.woofer.HardwareConfig import ( - ODRIVE_SERIAL_NUMBERS, - ACTUATOR_DIRECTIONS, - ANGLE_OFFSETS, - map_actuators_to_axes, -) -import time -import threading -import numpy as np - - -class HardwareInterface: - def __init__(self): - self.config = RobotConfig() - assert len(ODRIVE_SERIAL_NUMBERS) == self.config.NUM_ODRIVES - self.odrives = [None for _ in range(self.config.NUM_ODRIVES)] - threads = [] - for i in range(self.config.NUM_ODRIVES): - t = threading.Thread(target=find_odrive, args=(i, self.odrives)) - threads.append(t) - t.start() - for t in threads: - t.join() - input("Press enter to calibrate odrives...") - calibrate_odrives(self.odrives) - set_position_control(self.odrives) - - self.axes = assign_axes(self.odrives) - - def set_actuator_postions(self, joint_angles): - set_all_odrive_positions(self.axes, joint_angles, self.config) - - def deactivate_actuators(self): - set_odrives_idle(self.odrives) - - -def find_odrive(i, odrives): - o = odrive.find_any(serial_number=ODRIVE_SERIAL_NUMBERS[i]) - print("Found odrive: ", i) - odrives[i] = o - - -def calibrate_odrives(odrives): - for odrv in odrives: - odrv.axis0.requested_state = AXIS_STATE_FULL_CALIBRATION_SEQUENCE - odrv.axis1.requested_state = AXIS_STATE_FULL_CALIBRATION_SEQUENCE - for odrv in odrives: - while ( - odrv.axis0.current_state != AXIS_STATE_IDLE - or odrv.axis1.current_state != AXIS_STATE_IDLE - ): - time.sleep(0.1) # busy waiting - not ideal - - -def set_position_control(odrives): - for odrv in odrives: - for axis in [odrv.axis0, odrv.axis1]: - axis.controller.config.pos_gain = 60 - axis.controller.config.vel_gain = 0.002 - axis.controller.config.vel_limit_tolerance = 0 - axis.controller.config.vel_integrator_gain = 0 - axis.motor.config.current_lim = 15 - print("Updated gains") - - odrv.axis0.requested_state = AXIS_STATE_CLOSED_LOOP_CONTROL - odrv.axis1.requested_state = AXIS_STATE_CLOSED_LOOP_CONTROL - - -def set_odrives_idle(odrives): - for odrv in odrives: - odrv.axis0.requested_state = AXIS_STATE_IDLE - odrv.axis1.requested_state = AXIS_STATE_IDLE - - -def assign_axes(odrives): - return map_actuators_to_axes(odrives) - - -def set_all_odrive_positions(axes, joint_angles, config): - for i in range(joint_angles.shape[0]): - for j in range(joint_angles.shape[1]): - axes[i][j].controller.pos_setpoint = actuator_angle_to_odrive( - joint_angles, i, j, config - ) - - -def radians_to_encoder_count(angle, config): - return (angle / (2 * np.pi)) * config.ENCODER_CPR * config.MOTOR_REDUCTION - - -def actuator_angle_to_odrive(joint_angles, i, j, config): - offset_angle = joint_angles[i][j] + ANGLE_OFFSETS[i][j] - odrive_radians = offset_angle * ACTUATOR_DIRECTIONS[i][j] - return radians_to_encoder_count(odrive_radians, config) diff --git a/stanford_quad/woofer/Kinematics.py b/stanford_quad/woofer/Kinematics.py deleted file mode 100644 index 57e176b6..00000000 --- a/stanford_quad/woofer/Kinematics.py +++ /dev/null @@ -1,98 +0,0 @@ -import numpy as np - - -def leg_forward_kinematics(alpha, leg_index, config): - """Find the body-centric coordinates of a given foot given the joint angles. - Parameters - ---------- - alpha : Numpy array (3) - Joint angles ordered as (abduction, hip, knee) - leg_index : int - Leg index. - config : Config object - Robot parameters object - Returns - ------- - Numpy array (3) - Body-centric coordinates of the specified foot - """ - pass - - -def leg_explicit_inverse_kinematics(r_body_foot, leg_index, config): - """Find the joint angles corresponding to the given body-relative foot position for a given leg and configuration - Parameters - ---------- - r_body_foot : [type] - [description] - leg_index : [type] - [description] - config : [type] - [description] - Returns - ------- - numpy array (3) - Array of corresponding joint angles. - """ - (x, y, z) = r_body_foot - - # Distance from the leg origin to the foot, projected into the y-z plane - R_body_foot_yz = (y ** 2 + z ** 2) ** 0.5 - - # Distance from the leg's forward/back point of rotation to the foot - R_hip_foot_yz = (R_body_foot_yz ** 2 - config.ABDUCTION_OFFSET ** 2) ** 0.5 - - # Interior angle of the right triangle formed in the y-z plane by the leg that is coincident to the ab/adduction axis - # For feet 2 (front left) and 4 (back left), the abduction offset is positive, for the right feet, the abduction offset is negative. - cos_param = config.ABDUCTION_OFFSETS[leg_index] / R_body_foot_yz - if abs(cos_param) > 0.9: - print("Clipping 1st cos param") - cos_param = np.clip(cos_param, -0.9, 0.9) - phi = np.arccos(cos_param) - - # Angle of the y-z projection of the hip-to-foot vector, relative to the positive y-axis - hip_foot_angle = np.arctan2(z, y) - - # Ab/adduction angle, relative to the positive y-axis - abduction_angle = phi + hip_foot_angle - - # theta: Angle between the tilted negative z-axis and the hip-to-foot vector - theta = np.arctan2(-x, R_hip_foot_yz) - - # Distance between the hip and foot - R_hip_foot = (R_hip_foot_yz ** 2 + x ** 2) ** 0.5 - - # Using law of cosines to determine the angle between upper leg links - cos_param = (config.UPPER_LEG ** 2 + R_hip_foot ** 2 - config.LOWER_LEG ** 2) / (2.0*config.UPPER_LEG*R_hip_foot) - - # Ensure that the leg isn't over or under extending - cos_param = np.clip(cos_param, -0.9, 0.9) - if abs(cos_param) > 0.9: - print("Clipping 2nd cos param") - - # gamma: Angle between upper leg links and the center of the leg - gamma = np.arccos(cos_param) - - return np.array([abduction_angle, theta - gamma, theta + gamma]) - - -def four_legs_inverse_kinematics(r_body_foot, config): - """Find the joint angles for all twelve DOF correspoinding to the given matrix of body-relative foot positions. - Parameters - ---------- - r_body_foot : numpy array (3,4) - Matrix of the body-frame foot positions. Each column corresponds to a separate foot. - config : Config object - Object of robot configuration parameters. - Returns - ------- - numpy array (3,4) - Matrix of corresponding joint angles. - """ - alpha = np.zeros((3, 4)) - for i in range(4): - body_offset = config.LEG_ORIGINS[:, i] - alpha[:, i] = leg_explicit_inverse_kinematics( - r_body_foot[:, i] - body_offset, i, config - ) - return alpha \ No newline at end of file diff --git a/stanford_quad/woofer/__init__.py b/stanford_quad/woofer/__init__.py deleted file mode 100644 index e69de29b..00000000 From 551bc11b1866b78ca105bfebb21a60a892b534f8 Mon Sep 17 00:00:00 2001 From: Florian Golemo Date: Sat, 29 Aug 2020 16:02:38 -0400 Subject: [PATCH 14/49] added chair generation --- scripts/09-test-random-steps.py | 12 ++++++-- stanford_quad/sim/simulator2.py | 53 +++++++++++++++++++++++++++++++-- stanford_quad/sim/test.py | 0 3 files changed, 61 insertions(+), 4 deletions(-) delete mode 100644 stanford_quad/sim/test.py diff --git a/scripts/09-test-random-steps.py b/scripts/09-test-random-steps.py index 134f575d..77b0a827 100644 --- a/scripts/09-test-random-steps.py +++ b/scripts/09-test-random-steps.py @@ -1,6 +1,14 @@ +from stanford_quad.sim.simulator2 import PupperSim2 + STAIRS_STEP_WIDTH = 1 # if you're standing in front of a staircase and looking up, what's the left-right distance? -STAIRS_STEP_DEPTH = 0.1 # if you're stepping onto one step, how much of your foot can fit on the step? +STAIRS_STEP_DEPTH = 0.2 # if you're stepping onto one step, how much of your foot can fit on the step? STAIRS_STEP_HEIGHT = 0.2 # how far for you have to go up between each step? -sim = +sim = PupperSim2(debug=True) +sim.reset() +sim.add_stairs(step_width=STAIRS_STEP_WIDTH, step_depth=STAIRS_STEP_DEPTH, step_height=STAIRS_STEP_HEIGHT) +for step in range(100000): + # sim.action(motorPo) + sim.step() + print(sim.get_pos_orn_vel()[0][0]) diff --git a/stanford_quad/sim/simulator2.py b/stanford_quad/sim/simulator2.py index edbccdc3..b27928e6 100644 --- a/stanford_quad/sim/simulator2.py +++ b/stanford_quad/sim/simulator2.py @@ -68,9 +68,9 @@ def step(self): self.p.stepSimulation() def reset(self, rest=True): - height = .3 + height = 0.3 if rest: - height = .182 + height = 0.182 self.p.resetBasePositionAndOrientation(self.model, [0, 0, height], self.p.getQuaternionFromEuler([0, 0, 0])) if rest: action = self.get_rest_pos() @@ -127,3 +127,52 @@ def set(self, joint_angles): targetValue=joint_angles[joint_idx], targetVelocity=0, ) + + def create_box(self, pos, orn, size, color): + # we need to round or small float errors will explode the simulation + pos = np.around(pos, 4) + size = np.around(size, 4) + orn = np.around(orn, 4) + + obj_visual = self.p.createVisualShape(shapeType=self.p.GEOM_BOX, rgbaColor=list(color) + [1], halfExtents=size) + obj_collision = self.p.createCollisionShape(shapeType=self.p.GEOM_BOX, halfExtents=size) + + obj = self.p.createMultiBody( + baseMass=1, # doesn't matter + baseCollisionShapeIndex=obj_collision, + baseVisualShapeIndex=obj_visual, + basePosition=pos, + baseOrientation=orn, + useMaximalCoordinates=False, + ) + return obj + + def add_stairs( + self, no_steps=8, step_width=1, step_height=0.1, step_depth=0.1, offset=None, color=(0.5, 0, 0.5) + ) -> None: + pos_x = 0 + pos_y = 0 + pos_z = 0 + if offset is not None: + assert len(offset) == 2 or len(offset) == 3 + pos_x += offset[0] + pos_y += offset[1] + if len(offset) == 3: + pos_z += offset[2] + + steps = [] + orientation = self.p.getQuaternionFromEuler([0, 0, 0]) + size = (step_depth / 2, step_width / 2, step_height / 2) + for step_idx in range(no_steps): + pos = (pos_x + step_depth / 2, pos_y, pos_z + size[2]) + step = self.create_box(pos, orientation, size, color) + steps.append(step) + + pos_x += step_depth + size = (size[0], size[1], size[2] + step_height / 2) + + +# depth = 0.2, height = 0.2 +# pos 0.1, 0.1, size 0.1, 0.1, total height 0.2 +# pos 0.2, 0.2, size 0.1, 0.2, total height 0.4 +# diff --git a/stanford_quad/sim/test.py b/stanford_quad/sim/test.py deleted file mode 100644 index e69de29b..00000000 From 3a79bdd133fae12eb688ef47926824b3f6f739a6 Mon Sep 17 00:00:00 2001 From: Florian Golemo Date: Sat, 29 Aug 2020 16:36:15 -0400 Subject: [PATCH 15/49] stairs are now fixed to each other and to the ground --- scripts/09-test-random-steps.py | 9 +++--- stanford_quad/sim/simulator2.py | 57 ++++++++++++++++++++++++++++++--- 2 files changed, 57 insertions(+), 9 deletions(-) diff --git a/scripts/09-test-random-steps.py b/scripts/09-test-random-steps.py index 77b0a827..464dfb29 100644 --- a/scripts/09-test-random-steps.py +++ b/scripts/09-test-random-steps.py @@ -1,12 +1,13 @@ from stanford_quad.sim.simulator2 import PupperSim2 -STAIRS_STEP_WIDTH = 1 # if you're standing in front of a staircase and looking up, what's the left-right distance? -STAIRS_STEP_DEPTH = 0.2 # if you're stepping onto one step, how much of your foot can fit on the step? -STAIRS_STEP_HEIGHT = 0.2 # how far for you have to go up between each step? +STEP_WIDTH = 2 # if you're standing in front of a staircase and looking up, what's the left-right distance? +STEP_DEPTH = 0.3 # if you're stepping onto one step, how much of your foot can fit on the step? +STEP_HEIGHT = 0.05 # how far for you have to go up between each step? +OFFSET = (0.3, 0, 0) sim = PupperSim2(debug=True) sim.reset() -sim.add_stairs(step_width=STAIRS_STEP_WIDTH, step_depth=STAIRS_STEP_DEPTH, step_height=STAIRS_STEP_HEIGHT) +sim.add_stairs(step_width=STEP_WIDTH, step_depth=STEP_DEPTH, step_height=STEP_HEIGHT, offset=OFFSET) for step in range(100000): # sim.action(motorPo) diff --git a/stanford_quad/sim/simulator2.py b/stanford_quad/sim/simulator2.py index b27928e6..5eb1fb54 100644 --- a/stanford_quad/sim/simulator2.py +++ b/stanford_quad/sim/simulator2.py @@ -1,5 +1,4 @@ import os -import time import pybullet import pybullet_data @@ -83,7 +82,8 @@ def reset(self, rest=True): for _ in range(10): self.step() - def get_rest_pos(self): + @staticmethod + def get_rest_pos(): return REST_POS.T.flatten() def get_pos_orn_vel(self): @@ -99,7 +99,8 @@ def get_joint_states(self): joint_states = [joint[0] for joint in joint_states] return joint_states - def joint_sanity_check(self, joint_angles): + @staticmethod + def joint_sanity_check(joint_angles): assert len(joint_angles) == 12 assert np.min(np.rad2deg(joint_angles)) >= -180 assert np.max(np.rad2deg(joint_angles)) <= 180 @@ -138,7 +139,7 @@ def create_box(self, pos, orn, size, color): obj_collision = self.p.createCollisionShape(shapeType=self.p.GEOM_BOX, halfExtents=size) obj = self.p.createMultiBody( - baseMass=1, # doesn't matter + baseMass=0.1, # doesn't matter baseCollisionShapeIndex=obj_collision, baseVisualShapeIndex=obj_visual, basePosition=pos, @@ -149,7 +150,7 @@ def create_box(self, pos, orn, size, color): def add_stairs( self, no_steps=8, step_width=1, step_height=0.1, step_depth=0.1, offset=None, color=(0.5, 0, 0.5) - ) -> None: + ) -> list: pos_x = 0 pos_y = 0 pos_z = 0 @@ -161,16 +162,62 @@ def add_stairs( pos_z += offset[2] steps = [] + positions = [] + orientation = self.p.getQuaternionFromEuler([0, 0, 0]) size = (step_depth / 2, step_width / 2, step_height / 2) + + # create steps boxes for step_idx in range(no_steps): pos = (pos_x + step_depth / 2, pos_y, pos_z + size[2]) + + positions.append(np.array(pos)) + step = self.create_box(pos, orientation, size, color) steps.append(step) pos_x += step_depth size = (size[0], size[1], size[2] + step_height / 2) + # connect the steps to each other + for step_idx in range(no_steps - 1): + step_1 = steps[step_idx] + step_2 = steps[step_idx + 1] + + pos_1 = positions[step_idx] + pos_2 = positions[step_idx + 1] + + # in order to create a fixing constraint between parent and child step, + # you need to find a point where they touch. + center = (pos_1 + pos_2) / 2 + parent_frame = center - pos_1 + child_frame = center - pos_2 + + self.p.createConstraint( + parentBodyUniqueId=step_1, + parentLinkIndex=-1, + childBodyUniqueId=step_2, + childLinkIndex=-1, + jointType=self.p.JOINT_FIXED, + jointAxis=(1, 1, 1), + parentFramePosition=parent_frame, + childFramePosition=child_frame, + ) + + # and fix the chairs to the ground/world + self.p.createConstraint( + parentBodyUniqueId=steps[0], + parentLinkIndex=-1, + childBodyUniqueId=-1, + childLinkIndex=-1, + jointType=self.p.JOINT_FIXED, + jointAxis=(1, 1, 1), + parentFramePosition=-positions[0], + childFramePosition=(0, 0, 0), + ) + + return steps + # depth = 0.2, height = 0.2 # pos 0.1, 0.1, size 0.1, 0.1, total height 0.2 From 46d249d297886d709a59b5a4594801319bf26068 Mon Sep 17 00:00:00 2001 From: Florian Golemo Date: Sat, 29 Aug 2020 16:50:07 -0400 Subject: [PATCH 16/49] added random colors for better visbility --- scripts/09-test-random-steps.py | 2 +- stanford_quad/sim/simulator2.py | 17 ++++++++++++++--- stanford_quad/sim/utils.py | 14 ++++++++++++++ 3 files changed, 29 insertions(+), 4 deletions(-) create mode 100644 stanford_quad/sim/utils.py diff --git a/scripts/09-test-random-steps.py b/scripts/09-test-random-steps.py index 464dfb29..9a1b1b2d 100644 --- a/scripts/09-test-random-steps.py +++ b/scripts/09-test-random-steps.py @@ -7,7 +7,7 @@ sim = PupperSim2(debug=True) sim.reset() -sim.add_stairs(step_width=STEP_WIDTH, step_depth=STEP_DEPTH, step_height=STEP_HEIGHT, offset=OFFSET) +sim.add_stairs(step_width=STEP_WIDTH, step_depth=STEP_DEPTH, step_height=STEP_HEIGHT, offset=OFFSET, random_color=True) for step in range(100000): # sim.action(motorPo) diff --git a/stanford_quad/sim/simulator2.py b/stanford_quad/sim/simulator2.py index 5eb1fb54..0feb91f9 100644 --- a/stanford_quad/sim/simulator2.py +++ b/stanford_quad/sim/simulator2.py @@ -7,6 +7,7 @@ from stanford_quad.assets import ASSET_DIR from stanford_quad.sim.HardwareInterface import HardwareInterface +from stanford_quad.sim.utils import random_bright_color FREQ_SIM = 240 @@ -129,12 +130,15 @@ def set(self, joint_angles): targetVelocity=0, ) - def create_box(self, pos, orn, size, color): + def create_box(self, pos, orn, size, color, random_color): # we need to round or small float errors will explode the simulation pos = np.around(pos, 4) size = np.around(size, 4) orn = np.around(orn, 4) + if random_color: + color = random_bright_color(uint=False) + obj_visual = self.p.createVisualShape(shapeType=self.p.GEOM_BOX, rgbaColor=list(color) + [1], halfExtents=size) obj_collision = self.p.createCollisionShape(shapeType=self.p.GEOM_BOX, halfExtents=size) @@ -149,7 +153,14 @@ def create_box(self, pos, orn, size, color): return obj def add_stairs( - self, no_steps=8, step_width=1, step_height=0.1, step_depth=0.1, offset=None, color=(0.5, 0, 0.5) + self, + no_steps=8, + step_width=1, + step_height=0.1, + step_depth=0.1, + offset=None, + color=(0.5, 0, 0.5), + random_color=False, ) -> list: pos_x = 0 pos_y = 0 @@ -173,7 +184,7 @@ def add_stairs( positions.append(np.array(pos)) - step = self.create_box(pos, orientation, size, color) + step = self.create_box(pos, orientation, size, color, random_color) steps.append(step) pos_x += step_depth diff --git a/stanford_quad/sim/utils.py b/stanford_quad/sim/utils.py new file mode 100644 index 00000000..e584249e --- /dev/null +++ b/stanford_quad/sim/utils.py @@ -0,0 +1,14 @@ +import colorsys + +import numpy as np + + +def random_bright_color(uint=False): + base = np.random.rand(3) + h, s, l = base[0], 0.5 + base[1] / 2.0, 0.4 + base[2] / 5.0 + r, g, b = [int(256 * i) for i in colorsys.hls_to_rgb(h, l, s)] + + if uint: + return r, g, b + else: + return [x / 255 for x in (r, g, b)] From fe0a59b16b9246ef09f0e457cdf53964470c9409 Mon Sep 17 00:00:00 2001 From: Florian Golemo Date: Sat, 29 Aug 2020 16:54:55 -0400 Subject: [PATCH 17/49] typo --- stanford_quad/sim/simulator2.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/stanford_quad/sim/simulator2.py b/stanford_quad/sim/simulator2.py index 0feb91f9..683dc5c8 100644 --- a/stanford_quad/sim/simulator2.py +++ b/stanford_quad/sim/simulator2.py @@ -215,7 +215,7 @@ def add_stairs( childFramePosition=child_frame, ) - # and fix the chairs to the ground/world + # and fix the first step to the ground/world self.p.createConstraint( parentBodyUniqueId=steps[0], parentLinkIndex=-1, From e01f0ca26ca6866d8c6364a10c5ca8b05384fb5b Mon Sep 17 00:00:00 2001 From: Florian Golemo Date: Sat, 29 Aug 2020 17:47:39 -0400 Subject: [PATCH 18/49] added black settings file --- pyproject.toml | 3 +++ 1 file changed, 3 insertions(+) create mode 100644 pyproject.toml diff --git a/pyproject.toml b/pyproject.toml new file mode 100644 index 00000000..2f7cc3f4 --- /dev/null +++ b/pyproject.toml @@ -0,0 +1,3 @@ +[tool.black] +line-length = 120 +target-version = ['py37'] From f36281291e23693053ddcae505c67a66243060bb Mon Sep 17 00:00:00 2001 From: Florian Golemo Date: Sat, 29 Aug 2020 18:03:54 -0400 Subject: [PATCH 19/49] added photo utility --- scripts/10-test-camera.py | 20 +++++++++++++++++ stanford_quad/sim/simulator2.py | 38 ++++++++++++++++++++++++++++++--- stanford_quad/sim/utils.py | 7 ++++++ 3 files changed, 62 insertions(+), 3 deletions(-) create mode 100644 scripts/10-test-camera.py diff --git a/scripts/10-test-camera.py b/scripts/10-test-camera.py new file mode 100644 index 00000000..4696c92d --- /dev/null +++ b/scripts/10-test-camera.py @@ -0,0 +1,20 @@ +import cv2 +import numpy as np +from stanford_quad.sim.simulator2 import PupperSim2 + +sim = PupperSim2(debug=True) +sim.reset() +sim.add_stairs(step_width=2, step_depth=0.3, step_height=0.05, offset=(0.3, 0, 0), random_color=True) + +for step in range(100000): + # sim.action(motorPo) + action = np.random.uniform(-0.3, 0.3, 12) + sim.action(action) + sim.step() + + # render an image + img = sim.take_photo() + + # display the image (converting from RGB to BGR because OpenCV is weird) + cv2.imshow("rendered img", img[:, :, ::-1]) + cv2.waitKey(10) diff --git a/stanford_quad/sim/simulator2.py b/stanford_quad/sim/simulator2.py index 683dc5c8..fe7bdf6d 100644 --- a/stanford_quad/sim/simulator2.py +++ b/stanford_quad/sim/simulator2.py @@ -7,7 +7,7 @@ from stanford_quad.assets import ASSET_DIR from stanford_quad.sim.HardwareInterface import HardwareInterface -from stanford_quad.sim.utils import random_bright_color +from stanford_quad.sim.utils import random_bright_color, pybulletimage2numpy FREQ_SIM = 240 @@ -24,7 +24,15 @@ class PupperSim2: def __init__( - self, xml_path=None, debug=False, gain_pos=0.125, gain_vel=0.25, max_torque=1, g=-9.81, start_standing=True + self, + xml_path=None, + debug=False, + gain_pos=0.125, + gain_vel=0.25, + max_torque=1, + g=-9.81, + start_standing=True, + img_size=(84, 84), ): """ @@ -41,6 +49,7 @@ def __init__( self.gain_pos = gain_pos self.gain_vel = gain_vel self.max_torque = max_torque + self.img_size = img_size if debug: startup_flag = pybullet.GUI @@ -64,6 +73,10 @@ def __init__( self.reset() self.step() + self.cam_proj = self.p.computeProjectionMatrixFOV( + fov=90, aspect=self.img_size[0] / self.img_size[1], nearVal=0.001, farVal=10 + ) + def step(self): self.p.stepSimulation() @@ -89,7 +102,7 @@ def get_rest_pos(): def get_pos_orn_vel(self): posorn = self.p.getBasePositionAndOrientation(self.model) - pos = posorn[0] + pos = np.array(posorn[0]) orn = self.p.getEulerFromQuaternion(posorn[1]) vel = self.p.getBaseVelocity(self.model)[0] @@ -229,6 +242,25 @@ def add_stairs( return steps + def take_photo(self): + pos, _, _ = self.get_pos_orn_vel() + cam_pos = pos + [0, -0.3, 0.3] + cam_view = self.p.computeViewMatrix( + cameraEyePosition=cam_pos, cameraTargetPosition=pos, cameraUpVector=[0, 0, 1] + ) + img = self.p.getCameraImage( + self.img_size[0], + self.img_size[1], + cam_view, + self.cam_proj, + renderer=self.p.ER_BULLET_HARDWARE_OPENGL, + flags=0 + # lightDirection=[-.5, -1, .5], lightDistance=1, + # renderer=self.p0.ER_TINY_RENDERER + ) + output_img = pybulletimage2numpy(img, self.img_size[0], self.img_size[1]) + return output_img + # depth = 0.2, height = 0.2 # pos 0.1, 0.1, size 0.1, 0.1, total height 0.2 diff --git a/stanford_quad/sim/utils.py b/stanford_quad/sim/utils.py index e584249e..44bd8642 100644 --- a/stanford_quad/sim/utils.py +++ b/stanford_quad/sim/utils.py @@ -12,3 +12,10 @@ def random_bright_color(uint=False): return r, g, b else: return [x / 255 for x in (r, g, b)] + + +def pybulletimage2numpy(img, height, width): + rgb = img[2] + rgb = np.reshape(rgb, (height, width, 4)) + rgb = rgb[:, :, :3] + return rgb From 1d4a4b16738d6e16a0d3ed558f272c3d9fdec34b Mon Sep 17 00:00:00 2001 From: Florian Golemo Date: Sat, 29 Aug 2020 18:06:06 -0400 Subject: [PATCH 20/49] added renderer to env --- stanford_quad/envs/walking_env.py | 35 ++++++++++++++++--------------- 1 file changed, 18 insertions(+), 17 deletions(-) diff --git a/stanford_quad/envs/walking_env.py b/stanford_quad/envs/walking_env.py index 7cd27fc9..14f0e97f 100644 --- a/stanford_quad/envs/walking_env.py +++ b/stanford_quad/envs/walking_env.py @@ -8,7 +8,9 @@ class WalkingEnv(gym.Env): - def __init__(self, debug=False, steps=120, control_freq=CONTROL_FREQUENCY, relative_action=True, action_scaling=1.0): + def __init__( + self, debug=False, steps=120, control_freq=CONTROL_FREQUENCY, relative_action=True, action_scaling=1.0 + ): """ Gym-compatible environment to teach the pupper how to walk :param bool debug: If True, shows PyBullet in GUI mode. Set to False when training. @@ -21,16 +23,16 @@ def __init__(self, debug=False, steps=120, control_freq=CONTROL_FREQUENCY, relat super().__init__() - ## observation space: - ## - 12 lef joints in the order - ## - front right hip - ## - front right upper leg - ## - front right lower leg - ## - front left hip/upper/lower leg - ## - back right hip/upper/lower leg - ## - back left hip/upper/lower leg - ## - 3 body orientation in euler angles - ## - 2 linear velocity (only along the plane, we don't care about z velocity + # observation space: + # - 12 lef joints in the order + # - front right hip + # - front right upper leg + # - front right lower leg + # - front left hip/upper/lower leg + # - back right hip/upper/lower leg + # - back left hip/upper/lower leg + # - 3 body orientation in euler angles + # - 2 linear velocity (only along the plane, we don't care about z velocity self.observation_space = spaces.Box(low=-1, high=1, shape=(12 + 3 + 2,), dtype=np.float32) @@ -38,7 +40,7 @@ def __init__(self, debug=False, steps=120, control_freq=CONTROL_FREQUENCY, relat self.action_space = spaces.Box(low=-1, high=1, shape=(12,), dtype=np.float32) # turning off start_standing because the that's done in self.reset() - self.sim = PupperSim2(debug=debug, start_standing=False, gain_pos=1/16, gain_vel=1/8, max_torque=1/2) + self.sim = PupperSim2(debug=debug, start_standing=False, gain_pos=1 / 16, gain_vel=1 / 8, max_torque=1 / 2) self.episode_steps = 0 self.episode_steps_max = steps self.control_freq = control_freq @@ -68,13 +70,13 @@ def sanitize_actions(self, actions): scaled += self.sim.get_rest_pos() # this enforces an action range of -1/1, except if it's relative action - then the action space is asymmetric - clipped = np.clip(scaled, -np.pi+0.001, np.pi-0.001) + clipped = np.clip(scaled, -np.pi + 0.001, np.pi - 0.001) return clipped def get_obs(self): pos, orn, vel = self.sim.get_pos_orn_vel() - joint_states = np.array(self.sim.get_joint_states()) / np.pi # to normalize to [-1,1] + joint_states = np.array(self.sim.get_joint_states()) / np.pi # to normalize to [-1,1] obs = list(joint_states) + list(orn) + list(vel)[:2] return obs @@ -104,6 +106,5 @@ def step(self, action): return obs, reward, done, dict(reward_run=reward_run, reward_ctrl=reward_ctrl) def render(self, mode="human"): - # unused - use debug flag via "Headless"/"Graphical" environment instead - # FIXME: in the future we could add an external camera here - pass + img = self.sim.take_photo() + return img From c69486f84daf0631af97fd4192638dbc5c7daae0 Mon Sep 17 00:00:00 2001 From: Florian Golemo Date: Sat, 29 Aug 2020 18:07:31 -0400 Subject: [PATCH 21/49] added note --- stanford_quad/envs/walking_env.py | 3 +++ 1 file changed, 3 insertions(+) diff --git a/stanford_quad/envs/walking_env.py b/stanford_quad/envs/walking_env.py index 14f0e97f..9763fff8 100644 --- a/stanford_quad/envs/walking_env.py +++ b/stanford_quad/envs/walking_env.py @@ -106,5 +106,8 @@ def step(self, action): return obs, reward, done, dict(reward_run=reward_run, reward_ctrl=reward_ctrl) def render(self, mode="human"): + # todo: if the mode=="human" then this should open and display a + # window a la "cv2.imshow('xxx',img), cv2.waitkey(10)" + img = self.sim.take_photo() return img From 1e9948b510ba0c9afdc9e17f50d097096cc2505d Mon Sep 17 00:00:00 2001 From: Massimo Caccia Date: Tue, 1 Sep 2020 15:07:26 +0000 Subject: [PATCH 22/49] added new envs and random position init --- setup.py | 1 + stanford_quad/__init__.py | 16 ++++++++++------ stanford_quad/sim/simulator2.py | 9 ++++++++- 3 files changed, 19 insertions(+), 7 deletions(-) diff --git a/setup.py b/setup.py index a7b08ef6..8da68dbc 100644 --- a/setup.py +++ b/setup.py @@ -11,6 +11,7 @@ "gym", "opencv-python", "transforms3d", + "torchvision", "UDPComms @ git+ssh://git@github.com/stanfordroboticsclub/UDPComms@master#egg=UDPComms", ], ) diff --git a/stanford_quad/__init__.py b/stanford_quad/__init__.py index 46338dfd..a574a47b 100644 --- a/stanford_quad/__init__.py +++ b/stanford_quad/__init__.py @@ -1,4 +1,6 @@ from gym import register +import numpy as np +import pdb for headlessness in ["Headless", "Graphical"]: register( @@ -13,9 +15,11 @@ kwargs={"debug": (False if headlessness == "Headless" else True), "steps": 120, "relative_action": True, "action_scaling": 1}, max_episode_steps=120, ) - register( - id=f"Pupper-Walk-Relative-ScaledDown-{headlessness}-v0", - entry_point="stanford_quad.envs:WalkingEnv", - kwargs={"debug": (False if headlessness == "Headless" else True), "steps": 120, "relative_action": True, "action_scaling": .3}, - max_episode_steps=120, - ) + for scale_down in list(np.arange(0.05,0.5,0.05)): + register( + id=f"Pupper-Walk-Relative-ScaledDown_{scale_down:.2}-{headlessness}-v0", + entry_point="stanford_quad.envs:WalkingEnv", + kwargs={"debug": (False if headlessness == "Headless" else True), "steps": 120, "relative_action": True, "action_scaling": scale_down}, + max_episode_steps=120, + ) + print(f"Pupper-Walk-Relative-ScaledDown_{scale_down:.2}-{headlessness}-v0") \ No newline at end of file diff --git a/stanford_quad/sim/simulator2.py b/stanford_quad/sim/simulator2.py index fe7bdf6d..9f3c20e1 100644 --- a/stanford_quad/sim/simulator2.py +++ b/stanford_quad/sim/simulator2.py @@ -84,7 +84,14 @@ def reset(self, rest=True): height = 0.3 if rest: height = 0.182 - self.p.resetBasePositionAndOrientation(self.model, [0, 0, height], self.p.getQuaternionFromEuler([0, 0, 0])) + # self.p.resetBasePositionAndOrientation(self.model, [0, 0, height], self.p.getQuaternionFromEuler([0, 0, 0])) + rand_init_x = np.random.uniform(-30, 30, 1)[0] + rand_init_y = np.random.uniform(-30, 30, 1)[0] + rand_init_angle1 = np.deg2rad(np.random.uniform(-30, 30, 1))[0] + rand_init_angle2 = np.deg2rad(np.random.uniform(-30, 30, 1))[0] + self.p.resetBasePositionAndOrientation(self.model, + [rand_init_x, rand_init_y, height], + self.p.getQuaternionFromEuler([0, rand_init_angle1, rand_init_angle2])) if rest: action = self.get_rest_pos() else: From 641c5afefb0e851b5d23b67632480609092e3bef Mon Sep 17 00:00:00 2001 From: Florian Golemo Date: Wed, 2 Sep 2020 22:19:08 -0400 Subject: [PATCH 23/49] added handful new environments, added action smoothing, modularized rotation/pos --- stanford_quad/__init__.py | 76 +++++++++++++++++++++++++++++-- stanford_quad/envs/walking_env.py | 24 ++++++++-- stanford_quad/sim/simulator2.py | 23 ++++++---- 3 files changed, 106 insertions(+), 17 deletions(-) diff --git a/stanford_quad/__init__.py b/stanford_quad/__init__.py index a574a47b..cb4cd945 100644 --- a/stanford_quad/__init__.py +++ b/stanford_quad/__init__.py @@ -6,20 +6,86 @@ register( id=f"Pupper-Walk-Absolute-{headlessness}-v0", entry_point="stanford_quad.envs:WalkingEnv", - kwargs={"debug": (False if headlessness == "Headless" else True), "steps": 120, "relative_action": False, "action_scaling": 1}, + kwargs={ + "debug": (False if headlessness == "Headless" else True), + "steps": 120, + "relative_action": False, + "action_scaling": 1, + }, max_episode_steps=120, ) register( id=f"Pupper-Walk-Relative-{headlessness}-v0", entry_point="stanford_quad.envs:WalkingEnv", - kwargs={"debug": (False if headlessness == "Headless" else True), "steps": 120, "relative_action": True, "action_scaling": 1}, + kwargs={ + "debug": (False if headlessness == "Headless" else True), + "steps": 120, + "relative_action": True, + "action_scaling": 1, + }, max_episode_steps=120, ) - for scale_down in list(np.arange(0.05,0.5,0.05)): + for scale_down in list(np.arange(0.05, 0.5, 0.05)): register( id=f"Pupper-Walk-Relative-ScaledDown_{scale_down:.2}-{headlessness}-v0", entry_point="stanford_quad.envs:WalkingEnv", - kwargs={"debug": (False if headlessness == "Headless" else True), "steps": 120, "relative_action": True, "action_scaling": scale_down}, + kwargs={ + "debug": (False if headlessness == "Headless" else True), + "steps": 120, + "relative_action": True, + "action_scaling": scale_down, + }, max_episode_steps=120, ) - print(f"Pupper-Walk-Relative-ScaledDown_{scale_down:.2}-{headlessness}-v0") \ No newline at end of file + # print(f"Pupper-Walk-Relative-ScaledDown_{scale_down:.2}-{headlessness}-v0") + register( + id=f"Pupper-Walk-Relative-ScaledDown-RandomZRot-{headlessness}-v0", + entry_point="stanford_quad.envs:WalkingEnv", + kwargs={ + "debug": (False if headlessness == "Headless" else True), + "steps": 120, + "relative_action": True, + "action_scaling": 0.3, + "random_rot": (0, 0, 15), + }, + max_episode_steps=120, + ) + register( + id=f"Pupper-Walk-Relative-ScaledNSmoothed3-RandomZRot-{headlessness}-v0", + entry_point="stanford_quad.envs:WalkingEnv", + kwargs={ + "debug": (False if headlessness == "Headless" else True), + "steps": 120, + "relative_action": True, + "action_scaling": 0.3, + "action_smoothing": 3, + "random_rot": (0, 0, 15), + }, + max_episode_steps=120, + ) + register( + id=f"Pupper-Walk-Relative-ScaledNSmoothed5-RandomZRot-{headlessness}-v0", + entry_point="stanford_quad.envs:WalkingEnv", + kwargs={ + "debug": (False if headlessness == "Headless" else True), + "steps": 120, + "relative_action": True, + "action_scaling": 0.3, + "action_smoothing": 5, + "random_rot": (0, 0, 15), + }, + max_episode_steps=120, + ) + register( + id=f"Pupper-Walk-Relative-Smoothed5-RandomZRot-{headlessness}-v0", + entry_point="stanford_quad.envs:WalkingEnv", + kwargs={ + "debug": (False if headlessness == "Headless" else True), + "steps": 120, + "relative_action": True, + "action_scaling": 1, + "action_smoothing": 5, + "random_rot": (0, 0, 15), + }, + max_episode_steps=120, + ) diff --git a/stanford_quad/envs/walking_env.py b/stanford_quad/envs/walking_env.py index 9763fff8..8cd2a9d8 100644 --- a/stanford_quad/envs/walking_env.py +++ b/stanford_quad/envs/walking_env.py @@ -1,3 +1,5 @@ +from collections import deque + import gym from gym import spaces import numpy as np @@ -9,7 +11,14 @@ class WalkingEnv(gym.Env): def __init__( - self, debug=False, steps=120, control_freq=CONTROL_FREQUENCY, relative_action=True, action_scaling=1.0 + self, + debug=False, + steps=120, + control_freq=CONTROL_FREQUENCY, + relative_action=True, + action_scaling=1.0, + action_smoothing=1, + random_rot=(0, 0, 0), ): """ Gym-compatible environment to teach the pupper how to walk @@ -48,10 +57,12 @@ def __init__( self.sim_steps = int(round(FREQ_SIM / control_freq)) self.relative_action = relative_action self.action_scaling = action_scaling + self.action_smoothing = deque(maxlen=action_smoothing) + self.random_rot = random_rot def reset(self): self.episode_steps = 0 - self.sim.reset(rest=self.relative_action) # also stand up the robot + self.sim.reset(rest=self.relative_action, random_rot=self.random_rot) # also stand up the robot return self.get_obs() def seed(self, seed=None): @@ -85,8 +96,13 @@ def step(self, action): pos_before, _, _ = self.sim.get_pos_orn_vel() - # The action command only sets the goals of the motors. It doesn't actually step the simulation forward in time - self.sim.action(action_clean) + # The action command only sets the goals of the motors. It doesn't actually step the simulation forward in + # time. Instead of feeding the simulator the action directly, we take the mean of the last N actions, + # where N comes from the action_smoothing hyper-parameter + self.action_smoothing.append(action_clean) + self.sim.action(np.mean(self.action_smoothing)) + + # this steps the simulation forward for _ in range(self.sim_steps): self.sim.step() pos_after, _, _ = self.sim.get_pos_orn_vel() diff --git a/stanford_quad/sim/simulator2.py b/stanford_quad/sim/simulator2.py index 9f3c20e1..f9931894 100644 --- a/stanford_quad/sim/simulator2.py +++ b/stanford_quad/sim/simulator2.py @@ -80,18 +80,25 @@ def __init__( def step(self): self.p.stepSimulation() - def reset(self, rest=True): + def reset(self, rest=True, random_rot=(0, 0, 0), random_pos=(0, 0, 0)): height = 0.3 if rest: height = 0.182 # self.p.resetBasePositionAndOrientation(self.model, [0, 0, height], self.p.getQuaternionFromEuler([0, 0, 0])) - rand_init_x = np.random.uniform(-30, 30, 1)[0] - rand_init_y = np.random.uniform(-30, 30, 1)[0] - rand_init_angle1 = np.deg2rad(np.random.uniform(-30, 30, 1))[0] - rand_init_angle2 = np.deg2rad(np.random.uniform(-30, 30, 1))[0] - self.p.resetBasePositionAndOrientation(self.model, - [rand_init_x, rand_init_y, height], - self.p.getQuaternionFromEuler([0, rand_init_angle1, rand_init_angle2])) + rand_pos = ( + np.random.uniform(-random_pos[0], random_pos[0], 1)[0], + np.random.uniform(-random_pos[1], random_pos[1], 1)[0], + np.random.uniform(-random_pos[2], random_pos[2], 1)[0] + height, + ) + rand_rot = ( + np.random.normal(0, random_rot[0], 1)[0], + np.random.normal(0, random_rot[1], 1)[0], + np.random.normal(0, random_rot[2], 1)[0], + ) + + self.p.resetBasePositionAndOrientation( + self.model, rand_pos, self.p.getQuaternionFromEuler(rand_rot), + ) if rest: action = self.get_rest_pos() else: From e1fa1dae07c3641766d1c18151141cdd40510bdc Mon Sep 17 00:00:00 2001 From: Florian Golemo Date: Wed, 2 Sep 2020 22:22:02 -0400 Subject: [PATCH 24/49] bugfix --- stanford_quad/envs/walking_env.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/stanford_quad/envs/walking_env.py b/stanford_quad/envs/walking_env.py index 8cd2a9d8..f8a2c913 100644 --- a/stanford_quad/envs/walking_env.py +++ b/stanford_quad/envs/walking_env.py @@ -100,7 +100,7 @@ def step(self, action): # time. Instead of feeding the simulator the action directly, we take the mean of the last N actions, # where N comes from the action_smoothing hyper-parameter self.action_smoothing.append(action_clean) - self.sim.action(np.mean(self.action_smoothing)) + self.sim.action(np.mean(self.action_smoothing, axis=0)) # this steps the simulation forward for _ in range(self.sim_steps): From 803e8027d492abf59a18f8923107a96f5363f599 Mon Sep 17 00:00:00 2001 From: Florian Golemo Date: Wed, 2 Sep 2020 22:45:40 -0400 Subject: [PATCH 25/49] added reward for stability --- scripts/08-run-walker-gym-env.py | 17 +++++++------- stanford_quad/__init__.py | 37 +++++++++++++++++++++++++++++++ stanford_quad/envs/walking_env.py | 13 ++++++----- stanford_quad/sim/simulator2.py | 1 + 4 files changed, 55 insertions(+), 13 deletions(-) diff --git a/scripts/08-run-walker-gym-env.py b/scripts/08-run-walker-gym-env.py index 1dd38983..69d02c8c 100644 --- a/scripts/08-run-walker-gym-env.py +++ b/scripts/08-run-walker-gym-env.py @@ -1,19 +1,20 @@ import time import gym -import stanford_quad # need this unused import to get our custom environments +import stanford_quad # need this unused import to get our custom environments import numpy as np -env = gym.make("Pupper-Walk-Relative-Graphical-v0") + +env = gym.make("Pupper-Walk-Relative-ScaledDown-RandomZRot-Graphical-v0") for run in range(5): env.reset() time.sleep(2) for step in range(121): - action = env.action_space.sample() * 0.3 + # action = env.action_space.sample() * 0.3 + action = np.array([0] * 12) obs, rew, done, misc = env.step(action) - print (f"action: {np.around(action,2)}, " - f"obs: {np.around(obs,2)}, " - f"rew: {np.around(rew,2)}, " - f"done: {done}") + print( + f"action: {np.around(action,2)}, " f"obs: {np.around(obs,2)}, " f"rew: {np.around(rew,2)}, " f"done: {done}" + ) - time.sleep(.02) + time.sleep(0.02) diff --git a/stanford_quad/__init__.py b/stanford_quad/__init__.py index cb4cd945..9ebefe2b 100644 --- a/stanford_quad/__init__.py +++ b/stanford_quad/__init__.py @@ -89,3 +89,40 @@ }, max_episode_steps=120, ) + register( + id=f"Pupper-Walk-Relative-RewardStable0.5-{headlessness}-v0", + entry_point="stanford_quad.envs:WalkingEnv", + kwargs={ + "debug": (False if headlessness == "Headless" else True), + "steps": 120, + "relative_action": True, + "action_scaling": 1, + "reward_stable": 0.5, + }, + max_episode_steps=120, + ) + register( + id=f"Pupper-Walk-Relative-RewardStable0.5-ScaledDown3-{headlessness}-v0", + entry_point="stanford_quad.envs:WalkingEnv", + kwargs={ + "debug": (False if headlessness == "Headless" else True), + "steps": 120, + "relative_action": True, + "action_scaling": 0.3, + "reward_stable": 0.5, + }, + max_episode_steps=120, + ) + register( + id=f"Pupper-Walk-Relative-RewardStable0.5-ScaledDown-RandomZRot-{headlessness}-v0", + entry_point="stanford_quad.envs:WalkingEnv", + kwargs={ + "debug": (False if headlessness == "Headless" else True), + "steps": 120, + "relative_action": True, + "action_scaling": 0.3, + "random_rot": (0, 0, 15), + "reward_stable": 0.5, + }, + max_episode_steps=120, + ) diff --git a/stanford_quad/envs/walking_env.py b/stanford_quad/envs/walking_env.py index f8a2c913..ac8de36b 100644 --- a/stanford_quad/envs/walking_env.py +++ b/stanford_quad/envs/walking_env.py @@ -19,6 +19,7 @@ def __init__( action_scaling=1.0, action_smoothing=1, random_rot=(0, 0, 0), + reward_stability=0, ): """ Gym-compatible environment to teach the pupper how to walk @@ -59,6 +60,7 @@ def __init__( self.action_scaling = action_scaling self.action_smoothing = deque(maxlen=action_smoothing) self.random_rot = random_rot + self.reward_stability = reward_stability def reset(self): self.episode_steps = 0 @@ -76,10 +78,8 @@ def close(self): def sanitize_actions(self, actions): assert len(actions) == 12 scaled = actions * np.pi * self.action_scaling # because 1/-1 corresponds to pi/-pi radians rotation - if self.relative_action: scaled += self.sim.get_rest_pos() - # this enforces an action range of -1/1, except if it's relative action - then the action space is asymmetric clipped = np.clip(scaled, -np.pi + 0.001, np.pi - 0.001) return clipped @@ -105,14 +105,17 @@ def step(self, action): # this steps the simulation forward for _ in range(self.sim_steps): self.sim.step() - pos_after, _, _ = self.sim.get_pos_orn_vel() + pos_after, orn_after, _ = self.sim.get_pos_orn_vel() obs = self.get_obs() - # this reward calculation is taken verbatim from halfcheetah-v2 + # this reward calculation is taken verbatim from halfcheetah-v2, save reward_ctrl = -0.1 * np.square(action).sum() reward_run = (pos_after[0] - pos_before[0]) / self.dt - reward = reward_ctrl + reward_run + reward_stable = 0 + if self.reward_stability > 0: + reward_stable += self.reward_stability * np.square(orn_after).sum() + reward = reward_ctrl + reward_run + reward_stable done = False self.episode_steps += 1 diff --git a/stanford_quad/sim/simulator2.py b/stanford_quad/sim/simulator2.py index f9931894..9b4a7b76 100644 --- a/stanford_quad/sim/simulator2.py +++ b/stanford_quad/sim/simulator2.py @@ -95,6 +95,7 @@ def reset(self, rest=True, random_rot=(0, 0, 0), random_pos=(0, 0, 0)): np.random.normal(0, random_rot[1], 1)[0], np.random.normal(0, random_rot[2], 1)[0], ) + rand_rot = [np.deg2rad(x) for x in rand_rot] self.p.resetBasePositionAndOrientation( self.model, rand_pos, self.p.getQuaternionFromEuler(rand_rot), From bc43e8d9a7709303318954accbc5310782588793 Mon Sep 17 00:00:00 2001 From: Florian Golemo Date: Wed, 2 Sep 2020 23:05:42 -0400 Subject: [PATCH 26/49] bugfix --- stanford_quad/envs/walking_env.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/stanford_quad/envs/walking_env.py b/stanford_quad/envs/walking_env.py index ac8de36b..7a3e23b6 100644 --- a/stanford_quad/envs/walking_env.py +++ b/stanford_quad/envs/walking_env.py @@ -114,7 +114,7 @@ def step(self, action): reward_run = (pos_after[0] - pos_before[0]) / self.dt reward_stable = 0 if self.reward_stability > 0: - reward_stable += self.reward_stability * np.square(orn_after).sum() + reward_stable -= self.reward_stability * np.square(orn_after).sum() reward = reward_ctrl + reward_run + reward_stable done = False From c23511d5c99b7adc139f064ada659ce648c754db Mon Sep 17 00:00:00 2001 From: Florian Golemo Date: Thu, 3 Sep 2020 10:06:13 -0400 Subject: [PATCH 27/49] bugfixes --- stanford_quad/__init__.py | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/stanford_quad/__init__.py b/stanford_quad/__init__.py index 9ebefe2b..69f931ae 100644 --- a/stanford_quad/__init__.py +++ b/stanford_quad/__init__.py @@ -97,7 +97,7 @@ "steps": 120, "relative_action": True, "action_scaling": 1, - "reward_stable": 0.5, + "reward_stability": 0.5, }, max_episode_steps=120, ) @@ -109,7 +109,7 @@ "steps": 120, "relative_action": True, "action_scaling": 0.3, - "reward_stable": 0.5, + "reward_stability": 0.5, }, max_episode_steps=120, ) @@ -122,7 +122,7 @@ "relative_action": True, "action_scaling": 0.3, "random_rot": (0, 0, 15), - "reward_stable": 0.5, + "reward_stability": 0.5, }, max_episode_steps=120, ) From a4066639b34eb5553dc97d492dc99ad9560eb144 Mon Sep 17 00:00:00 2001 From: Florian Golemo Date: Thu, 3 Sep 2020 10:11:54 -0400 Subject: [PATCH 28/49] added new scaled-n-smoothed variant environment --- stanford_quad/__init__.py | 14 ++++++++++++++ 1 file changed, 14 insertions(+) diff --git a/stanford_quad/__init__.py b/stanford_quad/__init__.py index 69f931ae..df13c811 100644 --- a/stanford_quad/__init__.py +++ b/stanford_quad/__init__.py @@ -126,3 +126,17 @@ }, max_episode_steps=120, ) + register( + id=f"Pupper-Walk-Relative-RewardStable0.5-ScaledNSmoothed-RandomZRot-{headlessness}-v0", + entry_point="stanford_quad.envs:WalkingEnv", + kwargs={ + "debug": (False if headlessness == "Headless" else True), + "steps": 120, + "relative_action": True, + "action_scaling": 0.3, + "action_smoothing": 3, + "random_rot": (0, 0, 15), + "reward_stability": 0.5, + }, + max_episode_steps=120, + ) From c4c3ad0ee0131c282d98feb7a90d1bb559701c21 Mon Sep 17 00:00:00 2001 From: Florian Golemo Date: Wed, 9 Sep 2020 00:07:18 -0400 Subject: [PATCH 29/49] added support for reward monitoring --- stanford_quad/envs/walking_env.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/stanford_quad/envs/walking_env.py b/stanford_quad/envs/walking_env.py index 7a3e23b6..723b69ff 100644 --- a/stanford_quad/envs/walking_env.py +++ b/stanford_quad/envs/walking_env.py @@ -122,7 +122,7 @@ def step(self, action): if self.episode_steps == self.episode_steps_max: done = True - return obs, reward, done, dict(reward_run=reward_run, reward_ctrl=reward_ctrl) + return obs, reward, done, dict(reward_run=reward_run, reward_ctrl=reward_ctrl, reward_stable=reward_stable) def render(self, mode="human"): # todo: if the mode=="human" then this should open and display a From 0fd8667faf58cdb73eb50ff06d68fd0dc2315452 Mon Sep 17 00:00:00 2001 From: Florian Golemo Date: Wed, 9 Sep 2020 10:53:39 -0400 Subject: [PATCH 30/49] added readme for the new environments --- README.md | 68 +++++++++++++++++++++++++++++++++++++++++++++++++++++-- 1 file changed, 66 insertions(+), 2 deletions(-) diff --git a/README.md b/README.md index 3fcb4922..43e46279 100644 --- a/README.md +++ b/README.md @@ -23,7 +23,7 @@ The new simulator lives in `stanford_quad/sim/simulator2.py` in the `PupperSim2` ## Gym Environments -There are currently 2 environments. Both come in 2 variants: `Headless` and `Graphical`. `Headless` is meant for training and launches the PyBullet sim without any GUI, `Graphical` is meant for local debugging, offers a GUI to inspect the robot and is significantly slower. +There are currently 11 environments. All come in 2 variants: `Headless` and `Graphical`. `Headless` is meant for training and launches the PyBullet sim without any GUI, `Graphical` is meant for local debugging, offers a GUI to inspect the robot and is significantly slower. You can try out one of the walking environments, by running: @@ -31,7 +31,7 @@ You can try out one of the walking environments, by running: ### Walking -In both environments, the observations are the same: +In all environments, the observations are the same: **Observation space**: - 12 leg joints in the order @@ -50,6 +50,32 @@ The **action space** in both environments is also 12-dimensional (corresponding In both environments, the goal is to walk/run as fast as possible straight forward. This means the **reward** is calculated as relative increase of x position with respect to the previous timestep (minus a small penalty term for high action values, same as in HalfCheetah-v2) +#### Parameters + +There are several settings for the walking environment and a handful of combinations of these parameters have been given dedicated names. Here's the list of parameters and their meaning: + +- `debug` (bool): If True, this will turn ON the GUI. Usually the `[Headless|Graphical]` name in the environment specifies that this is False/True respectively. +- `steps` (int): default 120, Length of an episode. This corresponds to 2 seconds at 60Hz. +- `relative_action` (bool): If False, action commands correspond directly to the joint positions. If True, then at each step, the actions are added to the stable resting position, i.e. instead of `robot.move(action)`, it's `robot.move(REST_POSE+action)`. +- `action_scaling` (float): By default, the robot has a large movement range and very responsive joints, meaning the policy can pick the maximum negative joint position in one step and the maximum positive joint position in the next step. This causes a lot of jitter. In order to reduce this, this setting allows to restrict the movement range. Best used in combination with `relative_action`. +- `action_smoothing` (int): Another method to reduce jitter. If this is larger than 1, actions aren't applied to the robot directly anymore but instead go into a queue of this length. At each step, the mean of this queue is applied to the robot. +- `random_rot` (3-tuple of floats): This allows to specify the initial random rotation. The 3 elements in the triple correspond to rotation around the x/y/z axes respectively. The rotations are drawn from a normal distribution centered at 0 and this value specifies the variance on each axis. Values are in degrees. +- `reward_stability` (float): Specifies the coefficient of the IMU reward term that encourages stability. By default, it's 0. + +Based on our previous experiments, the following set of parameters seem to perform best (corresponding to the environment **`Pupper-Walk-Relative-ScaledNSmoothed3-RandomZRot-Headless-v0`**): + +```python +params = { + "debug": False, + "steps": 120, + "relative_action": True, + "action_scaling": 0.3, + "action_smoothing": 3, + "random_rot": (0,0,15), + "reward_stability": 0 +} +``` + #### Pupper-Walk-Absolute-[Headless|Graphical]-v0 In this environment, you have full absolute control over all joints and their resting position is set to 0 (which looks unnatural - the robot is standing fully straight, legs extended). Any action command is sent directly to the joints. @@ -58,3 +84,41 @@ In this environment, you have full absolute control over all joints and their re In this env, your actions are relative to the resting position (see image at the top - roughly that). Meaning an action of `[0]*12` will put the Pupper to a stable rest. Action clipping is done after summing the current action and the action corresponding to the resting position, which means the action space is asymmetric - e.g. if a given joint's resting position is at `0.7`, then the action space for that joint is `[-1.7,.3]`. This is intentional because it allows the Pupper to start with a stable position. +#### Pupper-Walk-Relative-ScaledDown_[0.05|0.1|0.15|...|0.5]-[Headless|Graphical]-v0 + +Similar to the `Pupper-Walk-Relative` but here the actions are multiplied with a factor (in the environment name) to reduce the range of motion. + +#### Pupper-Walk-Relative-ScaledDown-RandomZRot-[Headless|Graphical]-v0 + +Like the `Pupper-Walk-Relative-ScaledDown_0.3` but with random initial z rotation (rotation is drawn from a normal distribution, centered at 0, variance of 15 degrees). + +#### Pupper-Walk-Relative-ScaledNSmoothed3-RandomZRot-[Headless|Graphical]-v0 + +Like `Pupper-Walk-Relative-ScaledDown-RandomZRot` but with an additional action smoothing of **3**. + +#### Pupper-Walk-Relative-ScaledNSmoothed5-RandomZRot-[Headless|Graphical]-v0 + +Like `Pupper-Walk-Relative-ScaledDown-RandomZRot` but with an additional action smoothing of **5**. + +#### Pupper-Walk-Relative-Smoothed5-RandomZRot-[Headless|Graphical]-v0 + +Like `Pupper-Walk-Relative-ScaledNSmoothed5-RandomZRot` but with the actions only averaged in a list of 5, not scaled. + +#### Pupper-Walk-Relative-RewardStable0.5-[Headless|Graphical]-v0 + +Like `Pupper-Walk-Relative` but with the additional reward term for body orientation close to zero. Coefficient for the reward term is 0.5 + +#### Pupper-Walk-Relative-RewardStable0.5-ScaledDown3-[Headless|Graphical]-v0 + +Like `Pupper-Walk-Relative-RewardStable0.5` but additionally with the actions scaled by 0.3 + +#### Pupper-Walk-Relative-RewardStable0.5-ScaledDown-RandomZRot-[Headless|Graphical]-v0 + +Like `Pupper-Walk-Relative-RewardStable0.5-ScaledDown3` but with additional random initial rotation around the z axis + +#### Pupper-Walk-Relative-RewardStable0.5-ScaledNSmoothed-RandomZRot-[Headless|Graphical]-v0 + +Like `Pupper-Walk-Relative-RewardStable0.5-ScaledDown-RandomZRot` but additionally with the actions smoothed with queue length 3. + + + From b43fdf82f8a327e4e1c9a5281699ed31ea4c23c6 Mon Sep 17 00:00:00 2001 From: Anqi Xu Date: Wed, 9 Sep 2020 23:54:31 -0400 Subject: [PATCH 31/49] remove pip editable install files --- stanford_quad.egg-info/PKG-INFO | 10 ---------- stanford_quad.egg-info/SOURCES.txt | 7 ------- stanford_quad.egg-info/dependency_links.txt | 1 - stanford_quad.egg-info/requires.txt | 8 -------- stanford_quad.egg-info/top_level.txt | 1 - 5 files changed, 27 deletions(-) delete mode 100644 stanford_quad.egg-info/PKG-INFO delete mode 100644 stanford_quad.egg-info/SOURCES.txt delete mode 100644 stanford_quad.egg-info/dependency_links.txt delete mode 100644 stanford_quad.egg-info/requires.txt delete mode 100644 stanford_quad.egg-info/top_level.txt diff --git a/stanford_quad.egg-info/PKG-INFO b/stanford_quad.egg-info/PKG-INFO deleted file mode 100644 index ae45e17c..00000000 --- a/stanford_quad.egg-info/PKG-INFO +++ /dev/null @@ -1,10 +0,0 @@ -Metadata-Version: 1.0 -Name: stanford-quad -Version: 1.0 -Summary: UNKNOWN -Home-page: UNKNOWN -Author: UNKNOWN -Author-email: UNKNOWN -License: UNKNOWN -Description: UNKNOWN -Platform: UNKNOWN diff --git a/stanford_quad.egg-info/SOURCES.txt b/stanford_quad.egg-info/SOURCES.txt deleted file mode 100644 index 9cdebdc2..00000000 --- a/stanford_quad.egg-info/SOURCES.txt +++ /dev/null @@ -1,7 +0,0 @@ -README.md -setup.py -stanford_quad.egg-info/PKG-INFO -stanford_quad.egg-info/SOURCES.txt -stanford_quad.egg-info/dependency_links.txt -stanford_quad.egg-info/requires.txt -stanford_quad.egg-info/top_level.txt \ No newline at end of file diff --git a/stanford_quad.egg-info/dependency_links.txt b/stanford_quad.egg-info/dependency_links.txt deleted file mode 100644 index 8b137891..00000000 --- a/stanford_quad.egg-info/dependency_links.txt +++ /dev/null @@ -1 +0,0 @@ - diff --git a/stanford_quad.egg-info/requires.txt b/stanford_quad.egg-info/requires.txt deleted file mode 100644 index ae045828..00000000 --- a/stanford_quad.egg-info/requires.txt +++ /dev/null @@ -1,8 +0,0 @@ -tqdm -numpy -matplotlib -pybullet -gym -opencv-python -transforms3d -UDPComms@ git+ssh://git@github.com/stanfordroboticsclub/UDPComms@master#egg=UDPComms diff --git a/stanford_quad.egg-info/top_level.txt b/stanford_quad.egg-info/top_level.txt deleted file mode 100644 index 8b137891..00000000 --- a/stanford_quad.egg-info/top_level.txt +++ /dev/null @@ -1 +0,0 @@ - From a11b87be75be41a2d1a28376c7f850cfab0cf4c9 Mon Sep 17 00:00:00 2001 From: Anqi Xu Date: Thu, 10 Sep 2020 12:07:56 -0400 Subject: [PATCH 32/49] switched from ssh to https in installation to prevent Docker ssh from asking for confirmation --- setup.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/setup.py b/setup.py index 8da68dbc..08084463 100644 --- a/setup.py +++ b/setup.py @@ -12,6 +12,6 @@ "opencv-python", "transforms3d", "torchvision", - "UDPComms @ git+ssh://git@github.com/stanfordroboticsclub/UDPComms@master#egg=UDPComms", + "UDPComms @ git+https://github.com/stanfordroboticsclub/UDPComms@master#egg=UDPComms", ], ) From 74b04a9a12f3e7bfe5e159bdf69b996c2c24f0eb Mon Sep 17 00:00:00 2001 From: Massimo Caccia Date: Tue, 15 Sep 2020 21:15:02 +0000 Subject: [PATCH 33/49] added control over action_smoothing and RandomZRot --- stanford_quad/__init__.py | 164 +++++------------------------- stanford_quad/envs/walking_env.py | 8 +- 2 files changed, 28 insertions(+), 144 deletions(-) diff --git a/stanford_quad/__init__.py b/stanford_quad/__init__.py index df13c811..c9a6c944 100644 --- a/stanford_quad/__init__.py +++ b/stanford_quad/__init__.py @@ -2,141 +2,29 @@ import numpy as np import pdb -for headlessness in ["Headless", "Graphical"]: - register( - id=f"Pupper-Walk-Absolute-{headlessness}-v0", - entry_point="stanford_quad.envs:WalkingEnv", - kwargs={ - "debug": (False if headlessness == "Headless" else True), - "steps": 120, - "relative_action": False, - "action_scaling": 1, - }, - max_episode_steps=120, - ) - register( - id=f"Pupper-Walk-Relative-{headlessness}-v0", - entry_point="stanford_quad.envs:WalkingEnv", - kwargs={ - "debug": (False if headlessness == "Headless" else True), - "steps": 120, - "relative_action": True, - "action_scaling": 1, - }, - max_episode_steps=120, - ) - for scale_down in list(np.arange(0.05, 0.5, 0.05)): - register( - id=f"Pupper-Walk-Relative-ScaledDown_{scale_down:.2}-{headlessness}-v0", - entry_point="stanford_quad.envs:WalkingEnv", - kwargs={ - "debug": (False if headlessness == "Headless" else True), - "steps": 120, - "relative_action": True, - "action_scaling": scale_down, - }, - max_episode_steps=120, - ) - # print(f"Pupper-Walk-Relative-ScaledDown_{scale_down:.2}-{headlessness}-v0") - register( - id=f"Pupper-Walk-Relative-ScaledDown-RandomZRot-{headlessness}-v0", - entry_point="stanford_quad.envs:WalkingEnv", - kwargs={ - "debug": (False if headlessness == "Headless" else True), - "steps": 120, - "relative_action": True, - "action_scaling": 0.3, - "random_rot": (0, 0, 15), - }, - max_episode_steps=120, - ) - register( - id=f"Pupper-Walk-Relative-ScaledNSmoothed3-RandomZRot-{headlessness}-v0", - entry_point="stanford_quad.envs:WalkingEnv", - kwargs={ - "debug": (False if headlessness == "Headless" else True), - "steps": 120, - "relative_action": True, - "action_scaling": 0.3, - "action_smoothing": 3, - "random_rot": (0, 0, 15), - }, - max_episode_steps=120, - ) - register( - id=f"Pupper-Walk-Relative-ScaledNSmoothed5-RandomZRot-{headlessness}-v0", - entry_point="stanford_quad.envs:WalkingEnv", - kwargs={ - "debug": (False if headlessness == "Headless" else True), - "steps": 120, - "relative_action": True, - "action_scaling": 0.3, - "action_smoothing": 5, - "random_rot": (0, 0, 15), - }, - max_episode_steps=120, - ) - register( - id=f"Pupper-Walk-Relative-Smoothed5-RandomZRot-{headlessness}-v0", - entry_point="stanford_quad.envs:WalkingEnv", - kwargs={ - "debug": (False if headlessness == "Headless" else True), - "steps": 120, - "relative_action": True, - "action_scaling": 1, - "action_smoothing": 5, - "random_rot": (0, 0, 15), - }, - max_episode_steps=120, - ) - register( - id=f"Pupper-Walk-Relative-RewardStable0.5-{headlessness}-v0", - entry_point="stanford_quad.envs:WalkingEnv", - kwargs={ - "debug": (False if headlessness == "Headless" else True), - "steps": 120, - "relative_action": True, - "action_scaling": 1, - "reward_stability": 0.5, - }, - max_episode_steps=120, - ) - register( - id=f"Pupper-Walk-Relative-RewardStable0.5-ScaledDown3-{headlessness}-v0", - entry_point="stanford_quad.envs:WalkingEnv", - kwargs={ - "debug": (False if headlessness == "Headless" else True), - "steps": 120, - "relative_action": True, - "action_scaling": 0.3, - "reward_stability": 0.5, - }, - max_episode_steps=120, - ) - register( - id=f"Pupper-Walk-Relative-RewardStable0.5-ScaledDown-RandomZRot-{headlessness}-v0", - entry_point="stanford_quad.envs:WalkingEnv", - kwargs={ - "debug": (False if headlessness == "Headless" else True), - "steps": 120, - "relative_action": True, - "action_scaling": 0.3, - "random_rot": (0, 0, 15), - "reward_stability": 0.5, - }, - max_episode_steps=120, - ) - register( - id=f"Pupper-Walk-Relative-RewardStable0.5-ScaledNSmoothed-RandomZRot-{headlessness}-v0", - entry_point="stanford_quad.envs:WalkingEnv", - kwargs={ - "debug": (False if headlessness == "Headless" else True), - "steps": 120, - "relative_action": True, - "action_scaling": 0.3, - "action_smoothing": 3, - "random_rot": (0, 0, 15), - "reward_stability": 0.5, - }, - max_episode_steps=120, - ) + +HEADLESSNESS = ["Headless", "Graphical"] +RELATIVE_ACTION = [True, False] +ACTION_SMOOTHING = [1, 2, 3, 4] +RANDOM_ROT = [0, 1, 10, 100] +ACTION_SCALING = [1.] + list(np.arange(0.05, 0.5, 0.05)) + +for headlessness in HEADLESSNESS: + for relative_action in RELATIVE_ACTION: + for action_smoothing in ACTION_SMOOTHING: + for action_scaling in ACTION_SCALING: + for random_rot in RANDOM_ROT: + action = 'Relative' if relative_action else 'Absolute' + register( + id=f"Pupper-Walk-{action}_aScale_{action_scaling:.2}-aSmooth_{action_smoothing}-RandomZRot_{random_rot}-{headlessness}-v0", + entry_point="stanford_quad.envs:WalkingEnv", + kwargs={ + "debug": (False if headlessness == "Headless" else True), + "steps": 120, + "relative_action": relative_action, + "action_scaling": action_scaling, + "action_smoothing": action_smoothing, + "random_rot": (0, 0, random_rot), + }, + max_episode_steps=120, + ) \ No newline at end of file diff --git a/stanford_quad/envs/walking_env.py b/stanford_quad/envs/walking_env.py index 723b69ff..566227de 100644 --- a/stanford_quad/envs/walking_env.py +++ b/stanford_quad/envs/walking_env.py @@ -19,7 +19,6 @@ def __init__( action_scaling=1.0, action_smoothing=1, random_rot=(0, 0, 0), - reward_stability=0, ): """ Gym-compatible environment to teach the pupper how to walk @@ -60,7 +59,6 @@ def __init__( self.action_scaling = action_scaling self.action_smoothing = deque(maxlen=action_smoothing) self.random_rot = random_rot - self.reward_stability = reward_stability def reset(self): self.episode_steps = 0 @@ -110,11 +108,9 @@ def step(self, action): obs = self.get_obs() # this reward calculation is taken verbatim from halfcheetah-v2, save - reward_ctrl = -0.1 * np.square(action).sum() + reward_ctrl = -np.square(action).sum() reward_run = (pos_after[0] - pos_before[0]) / self.dt - reward_stable = 0 - if self.reward_stability > 0: - reward_stable -= self.reward_stability * np.square(orn_after).sum() + reward_stable = -np.square(orn_after).sum() reward = reward_ctrl + reward_run + reward_stable done = False From 9f4feefea362376260d4042afedb64694f55d109 Mon Sep 17 00:00:00 2001 From: Florian Golemo Date: Thu, 17 Sep 2020 00:40:02 -0400 Subject: [PATCH 34/49] merged & updated from @optimass PR --- scripts/08-run-walker-gym-env.py | 3 +- stanford_quad/__init__.py | 153 ++++++++++++++++++++++++++++-- stanford_quad/envs/walking_env.py | 6 +- 3 files changed, 154 insertions(+), 8 deletions(-) diff --git a/scripts/08-run-walker-gym-env.py b/scripts/08-run-walker-gym-env.py index 69d02c8c..4e3e7e4d 100644 --- a/scripts/08-run-walker-gym-env.py +++ b/scripts/08-run-walker-gym-env.py @@ -4,7 +4,8 @@ import stanford_quad # need this unused import to get our custom environments import numpy as np -env = gym.make("Pupper-Walk-Relative-ScaledDown-RandomZRot-Graphical-v0") +# env = gym.make("Pupper-Walk-Relative-ScaledDown-RandomZRot-Graphical-v0") +env = gym.make("Pupper-Walk-Relative-RewardStable0.5-Graphical-v0") for run in range(5): env.reset() diff --git a/stanford_quad/__init__.py b/stanford_quad/__init__.py index c9a6c944..5e1b813a 100644 --- a/stanford_quad/__init__.py +++ b/stanford_quad/__init__.py @@ -1,22 +1,163 @@ from gym import register import numpy as np -import pdb +HEADLESSNESS = ["Headless", "Graphical"] + +for headlessness in HEADLESSNESS: + register( + id=f"Pupper-Walk-Absolute-{headlessness}-v0", + entry_point="stanford_quad.envs:WalkingEnv", + kwargs={ + "debug": (False if headlessness == "Headless" else True), + "steps": 120, + "relative_action": False, + "action_scaling": 1, + }, + max_episode_steps=120, + ) + register( + id=f"Pupper-Walk-Relative-{headlessness}-v0", + entry_point="stanford_quad.envs:WalkingEnv", + kwargs={ + "debug": (False if headlessness == "Headless" else True), + "steps": 120, + "relative_action": True, + "action_scaling": 1, + }, + max_episode_steps=120, + ) + for scale_down in list(np.arange(0.05, 0.5, 0.05)): + register( + id=f"Pupper-Walk-Relative-ScaledDown_{scale_down:.2}-{headlessness}-v0", + entry_point="stanford_quad.envs:WalkingEnv", + kwargs={ + "debug": (False if headlessness == "Headless" else True), + "steps": 120, + "relative_action": True, + "action_scaling": scale_down, + }, + max_episode_steps=120, + ) + # print(f"Pupper-Walk-Relative-ScaledDown_{scale_down:.2}-{headlessness}-v0") + register( + id=f"Pupper-Walk-Relative-ScaledDown-RandomZRot-{headlessness}-v0", + entry_point="stanford_quad.envs:WalkingEnv", + kwargs={ + "debug": (False if headlessness == "Headless" else True), + "steps": 120, + "relative_action": True, + "action_scaling": 0.3, + "random_rot": (0, 0, 15), + }, + max_episode_steps=120, + ) + register( + id=f"Pupper-Walk-Relative-ScaledNSmoothed3-RandomZRot-{headlessness}-v0", + entry_point="stanford_quad.envs:WalkingEnv", + kwargs={ + "debug": (False if headlessness == "Headless" else True), + "steps": 120, + "relative_action": True, + "action_scaling": 0.3, + "action_smoothing": 3, + "random_rot": (0, 0, 15), + }, + max_episode_steps=120, + ) + register( + id=f"Pupper-Walk-Relative-ScaledNSmoothed5-RandomZRot-{headlessness}-v0", + entry_point="stanford_quad.envs:WalkingEnv", + kwargs={ + "debug": (False if headlessness == "Headless" else True), + "steps": 120, + "relative_action": True, + "action_scaling": 0.3, + "action_smoothing": 5, + "random_rot": (0, 0, 15), + }, + max_episode_steps=120, + ) + register( + id=f"Pupper-Walk-Relative-Smoothed5-RandomZRot-{headlessness}-v0", + entry_point="stanford_quad.envs:WalkingEnv", + kwargs={ + "debug": (False if headlessness == "Headless" else True), + "steps": 120, + "relative_action": True, + "action_scaling": 1, + "action_smoothing": 5, + "random_rot": (0, 0, 15), + }, + max_episode_steps=120, + ) + register( + id=f"Pupper-Walk-Relative-RewardStable0.5-{headlessness}-v0", + entry_point="stanford_quad.envs:WalkingEnv", + kwargs={ + "debug": (False if headlessness == "Headless" else True), + "steps": 120, + "relative_action": True, + "action_scaling": 1, + "reward_coefficients": (0.1, 1, 0.5), + }, + max_episode_steps=120, + ) + register( + id=f"Pupper-Walk-Relative-RewardStable0.5-ScaledDown3-{headlessness}-v0", + entry_point="stanford_quad.envs:WalkingEnv", + kwargs={ + "debug": (False if headlessness == "Headless" else True), + "steps": 120, + "relative_action": True, + "action_scaling": 0.3, + "reward_coefficients": (0.1, 1, 0.5), + }, + max_episode_steps=120, + ) + register( + id=f"Pupper-Walk-Relative-RewardStable0.5-ScaledDown-RandomZRot-{headlessness}-v0", + entry_point="stanford_quad.envs:WalkingEnv", + kwargs={ + "debug": (False if headlessness == "Headless" else True), + "steps": 120, + "relative_action": True, + "action_scaling": 0.3, + "random_rot": (0, 0, 15), + "reward_coefficients": (0.1, 1, 0.5), + }, + max_episode_steps=120, + ) + register( + id=f"Pupper-Walk-Relative-RewardStable0.5-ScaledNSmoothed-RandomZRot-{headlessness}-v0", + entry_point="stanford_quad.envs:WalkingEnv", + kwargs={ + "debug": (False if headlessness == "Headless" else True), + "steps": 120, + "relative_action": True, + "action_scaling": 0.3, + "action_smoothing": 3, + "random_rot": (0, 0, 15), + "reward_coefficients": (0.1, 1, 0.5), + }, + max_episode_steps=120, + ) -HEADLESSNESS = ["Headless", "Graphical"] RELATIVE_ACTION = [True, False] ACTION_SMOOTHING = [1, 2, 3, 4] RANDOM_ROT = [0, 1, 10, 100] -ACTION_SCALING = [1.] + list(np.arange(0.05, 0.5, 0.05)) +ACTION_SCALING = [1.0] + list(np.arange(0.05, 0.5, 0.05)) for headlessness in HEADLESSNESS: for relative_action in RELATIVE_ACTION: for action_smoothing in ACTION_SMOOTHING: for action_scaling in ACTION_SCALING: for random_rot in RANDOM_ROT: - action = 'Relative' if relative_action else 'Absolute' + action = "Relative" if relative_action else "Absolute" register( - id=f"Pupper-Walk-{action}_aScale_{action_scaling:.2}-aSmooth_{action_smoothing}-RandomZRot_{random_rot}-{headlessness}-v0", + id=f"Pupper-Walk-{action}-" + f"aScale_{action_scaling:.2}-" + f"aSmooth_{action_smoothing}-" + f"RandomZRot_{random_rot}-{headlessness}-v0", entry_point="stanford_quad.envs:WalkingEnv", kwargs={ "debug": (False if headlessness == "Headless" else True), @@ -27,4 +168,4 @@ "random_rot": (0, 0, random_rot), }, max_episode_steps=120, - ) \ No newline at end of file + ) diff --git a/stanford_quad/envs/walking_env.py b/stanford_quad/envs/walking_env.py index 566227de..2d8b264d 100644 --- a/stanford_quad/envs/walking_env.py +++ b/stanford_quad/envs/walking_env.py @@ -19,6 +19,7 @@ def __init__( action_scaling=1.0, action_smoothing=1, random_rot=(0, 0, 0), + reward_coefficients=(0, 1, 0), ): """ Gym-compatible environment to teach the pupper how to walk @@ -60,6 +61,9 @@ def __init__( self.action_smoothing = deque(maxlen=action_smoothing) self.random_rot = random_rot + # new reward coefficients + self.rcoeff_ctrl, self.rcoeff_run, self.rcoeff_stable = reward_coefficients + def reset(self): self.episode_steps = 0 self.sim.reset(rest=self.relative_action, random_rot=self.random_rot) # also stand up the robot @@ -111,7 +115,7 @@ def step(self, action): reward_ctrl = -np.square(action).sum() reward_run = (pos_after[0] - pos_before[0]) / self.dt reward_stable = -np.square(orn_after).sum() - reward = reward_ctrl + reward_run + reward_stable + reward = self.rcoeff_ctrl * reward_ctrl + self.rcoeff_run * reward_run + self.rcoeff_stable * reward_stable done = False self.episode_steps += 1 From 4dd2dc23daf1f80c4b277977a711b86e7004eec1 Mon Sep 17 00:00:00 2001 From: Florian Golemo Date: Thu, 17 Sep 2020 13:09:09 -0400 Subject: [PATCH 35/49] made it so that the penalty for rotation is in range 0-3 not 0-(3*pi^2) --- scripts/07-debug-new-simulator.py | 9 ++++----- stanford_quad/envs/walking_env.py | 3 ++- 2 files changed, 6 insertions(+), 6 deletions(-) diff --git a/scripts/07-debug-new-simulator.py b/scripts/07-debug-new-simulator.py index 14c637a8..32b15865 100644 --- a/scripts/07-debug-new-simulator.py +++ b/scripts/07-debug-new-simulator.py @@ -11,8 +11,8 @@ motor = sim.p.addUserDebugParameter("motor{}".format(i + 1), -np.pi, np.pi, rest_pos[i]) debugParams.append(motor) -print (sim.get_pos_orn_vel()) -print (sim.get_joint_states()) +print(sim.get_pos_orn_vel()) +print(sim.get_joint_states()) for step in range(100000): motorPos = [] @@ -21,6 +21,5 @@ motorPos.append(pos) sim.action(motorPos) sim.step() - print (sim.get_pos_orn_vel()[0][0]) - - + pos, orn, vel = sim.get_pos_orn_vel() + print(pos, orn, vel) diff --git a/stanford_quad/envs/walking_env.py b/stanford_quad/envs/walking_env.py index 2d8b264d..d990764b 100644 --- a/stanford_quad/envs/walking_env.py +++ b/stanford_quad/envs/walking_env.py @@ -114,7 +114,8 @@ def step(self, action): # this reward calculation is taken verbatim from halfcheetah-v2, save reward_ctrl = -np.square(action).sum() reward_run = (pos_after[0] - pos_before[0]) / self.dt - reward_stable = -np.square(orn_after).sum() + # technically we should divide the next line by (3*pi^2) but that's really hard to reach + reward_stable = -np.square(orn_after).sum() / np.square(np.pi) reward = self.rcoeff_ctrl * reward_ctrl + self.rcoeff_run * reward_run + self.rcoeff_stable * reward_stable done = False From 93c79042a250968ffe67f26571b887ec6b489738 Mon Sep 17 00:00:00 2001 From: Florian Golemo Date: Thu, 17 Sep 2020 15:01:06 -0400 Subject: [PATCH 36/49] added stop_on_flip --- scripts/07-debug-new-simulator.py | 6 ++- stanford_quad/envs/walking_env.py | 11 +++++- stanford_quad/sim/simulator2.py | 62 ++++++++++++++++++++++++++----- 3 files changed, 67 insertions(+), 12 deletions(-) diff --git a/scripts/07-debug-new-simulator.py b/scripts/07-debug-new-simulator.py index 32b15865..648a7954 100644 --- a/scripts/07-debug-new-simulator.py +++ b/scripts/07-debug-new-simulator.py @@ -22,4 +22,8 @@ sim.action(motorPos) sim.step() pos, orn, vel = sim.get_pos_orn_vel() - print(pos, orn, vel) + # print(pos, orn, vel) + # for i in range(40): + # print(sim.p.getLinkState(bodyUniqueId=sim.model, linkIndex=i)) + # quit() + sim.check_collision() diff --git a/stanford_quad/envs/walking_env.py b/stanford_quad/envs/walking_env.py index d990764b..0dbca969 100644 --- a/stanford_quad/envs/walking_env.py +++ b/stanford_quad/envs/walking_env.py @@ -19,7 +19,8 @@ def __init__( action_scaling=1.0, action_smoothing=1, random_rot=(0, 0, 0), - reward_coefficients=(0, 1, 0), + reward_coefficients=(0.1, 1, 0), + stop_on_flip=False, ): """ Gym-compatible environment to teach the pupper how to walk @@ -60,6 +61,7 @@ def __init__( self.action_scaling = action_scaling self.action_smoothing = deque(maxlen=action_smoothing) self.random_rot = random_rot + self.stop_on_flip = stop_on_flip # new reward coefficients self.rcoeff_ctrl, self.rcoeff_run, self.rcoeff_stable = reward_coefficients @@ -107,6 +109,7 @@ def step(self, action): # this steps the simulation forward for _ in range(self.sim_steps): self.sim.step() + pos_after, orn_after, _ = self.sim.get_pos_orn_vel() obs = self.get_obs() @@ -123,6 +126,12 @@ def step(self, action): if self.episode_steps == self.episode_steps_max: done = True + if self.stop_on_flip: + flipped = self.sim.check_collision() + if flipped: + done = True + reward -= 1000 + return obs, reward, done, dict(reward_run=reward_run, reward_ctrl=reward_ctrl, reward_stable=reward_stable) def render(self, mode="human"): diff --git a/stanford_quad/sim/simulator2.py b/stanford_quad/sim/simulator2.py index 9b4a7b76..30aa95a9 100644 --- a/stanford_quad/sim/simulator2.py +++ b/stanford_quad/sim/simulator2.py @@ -1,4 +1,5 @@ import os +import time import pybullet import pybullet_data @@ -60,6 +61,11 @@ def __init__( self.p.setAdditionalSearchPath(pybullet_data.getDataPath()) self.p.setGravity(0, 0, g) + if debug: + self.p.resetDebugVisualizerCamera( + cameraDistance=0.75, cameraYaw=0, cameraPitch=-45, cameraTargetPosition=[0, 0.0, 0] + ) + # self.p.loadURDF("plane.urdf") self.model = self.p.loadMJCF(xml_path)[1] # [0] is the floor @@ -69,21 +75,38 @@ def __init__( print(self.p.getJointInfo(self.model, i)) self.joint_indices = list(range(0, 24, 2)) - if start_standing: - self.reset() - self.step() - self.cam_proj = self.p.computeProjectionMatrixFOV( fov=90, aspect=self.img_size[0] / self.img_size[1], nearVal=0.001, farVal=10 ) + self.collision_floor = self.create_box((0, 0, 0.001), (0, 0, 0), (1, 1, 0.0005), visible=False) + self.p.createConstraint( + parentBodyUniqueId=self.collision_floor, + parentLinkIndex=-1, + childBodyUniqueId=-1, + childLinkIndex=-1, + jointType=self.p.JOINT_FIXED, + jointAxis=(1, 1, 1), + parentFramePosition=(0, 0, 0.0), + childFramePosition=(0, 0, 0.0005), + ) + + if start_standing: + self.reset() + linka = self.p.getLinkState(self.model, 0)[0] + print(linka) + for _ in range(10): + self.step() + + # time.sleep(1) + def step(self): self.p.stepSimulation() def reset(self, rest=True, random_rot=(0, 0, 0), random_pos=(0, 0, 0)): - height = 0.3 + height = 0.301 if rest: - height = 0.182 + height = 0.183 # self.p.resetBasePositionAndOrientation(self.model, [0, 0, height], self.p.getQuaternionFromEuler([0, 0, 0])) rand_pos = ( np.random.uniform(-random_pos[0], random_pos[0], 1)[0], @@ -158,16 +181,21 @@ def set(self, joint_angles): targetVelocity=0, ) - def create_box(self, pos, orn, size, color, random_color): + def create_box(self, pos, orn, size, color=(1, 0, 0), random_color=False, visible=True): # we need to round or small float errors will explode the simulation pos = np.around(pos, 4) size = np.around(size, 4) - orn = np.around(orn, 4) + orn = np.around(self.p.getQuaternionFromEuler(orn), 4) if random_color: color = random_bright_color(uint=False) - obj_visual = self.p.createVisualShape(shapeType=self.p.GEOM_BOX, rgbaColor=list(color) + [1], halfExtents=size) + obj_visual = -1 + if visible: + obj_visual = self.p.createVisualShape( + shapeType=self.p.GEOM_BOX, rgbaColor=list(color) + [1], halfExtents=size + ) + obj_collision = self.p.createCollisionShape(shapeType=self.p.GEOM_BOX, halfExtents=size) obj = self.p.createMultiBody( @@ -203,7 +231,7 @@ def add_stairs( steps = [] positions = [] - orientation = self.p.getQuaternionFromEuler([0, 0, 0]) + orientation = [0, 0, 0] size = (step_depth / 2, step_width / 2, step_height / 2) # create steps boxes @@ -276,6 +304,20 @@ def take_photo(self): output_img = pybulletimage2numpy(img, self.img_size[0], self.img_size[1]) return output_img + def check_collision(self): + contacts = self.p.getClosestPoints( + bodyA=self.model, bodyB=self.collision_floor, distance=0.1, linkIndexA=-1, linkIndexB=-1 + ) + # if len(contacts) > 0: + # contacts = contacts[0] + # self.p.removeAllUserDebugItems() + # self.p.addUserDebugLine(lineFromXYZ=contacts[5], lineToXYZ=contacts[6], lineColorRGB=(1, 0, 1), lineWidth=2) + # self.p.addUserDebugText(text=str(contacts[8]), textPosition=(0, 0, 0), textColorRGB=(1, 1, 0), textSize=5) + if len(contacts) > 0 and contacts[0][8] < 0.02: + return True + + return False + # depth = 0.2, height = 0.2 # pos 0.1, 0.1, size 0.1, 0.1, total height 0.2 From fe2499a9557d059dce92f37dde293503eb64c863 Mon Sep 17 00:00:00 2001 From: Florian Golemo Date: Wed, 23 Sep 2020 17:39:04 -0400 Subject: [PATCH 37/49] made the robot stuff optional --- README.md | 8 +++++++- scripts/robot.service => robot.service | 2 +- scripts/run_robot.py | 2 +- setup.py | 19 ++++++++----------- stanford_quad/pupper/HardwareConfig.py | 8 +++----- 5 files changed, 20 insertions(+), 19 deletions(-) rename scripts/robot.service => robot.service (72%) diff --git a/README.md b/README.md index 43e46279..c72907d8 100644 --- a/README.md +++ b/README.md @@ -12,7 +12,13 @@ We assume you got an environment where `pip` and `python` point to the Python 3 ```bash git clone https://github.com/fgolemo/StanfordQuadruped.git cd StanfordQuadruped -pip install -e . +pip install -e .[sim] +``` + +#### Robot installation + +```bash +sudo pip install -e .[robot] ``` ## Getting Started diff --git a/scripts/robot.service b/robot.service similarity index 72% rename from scripts/robot.service rename to robot.service index 2b18d5df..13b139d0 100644 --- a/scripts/robot.service +++ b/robot.service @@ -5,7 +5,7 @@ After=joystick.service [Service] ExecStartPre=-sudo pigpiod -ExecStart=/usr/bin/python3 /home/pi/StanfordQuadruped/run_robot.py +ExecStart=/usr/bin/python3 /home/pi/StanfordQuadruped/scripts/run_robot.py KillSignal=2 TimeoutStopSec=10 diff --git a/scripts/run_robot.py b/scripts/run_robot.py index b7f3fd2d..1a64b1a1 100644 --- a/scripts/run_robot.py +++ b/scripts/run_robot.py @@ -60,7 +60,7 @@ break # Read imu data. Orientation will be None if no data was available - quat_orientation = IMU.read_orientation() if USE_IMU else np.array([1, 0, 0, 0]) + quat_orientation = np.array([1, 0, 0, 0]) if not USE_IMU else imu.read_orientation() state.quat_orientation = quat_orientation # Step the controller forward by dt diff --git a/setup.py b/setup.py index 08084463..462081f8 100644 --- a/setup.py +++ b/setup.py @@ -3,15 +3,12 @@ setup( name="stanford_quad", version="1.0", - install_requires=[ - "tqdm", - "numpy", - "matplotlib", - "pybullet", - "gym", - "opencv-python", - "transforms3d", - "torchvision", - "UDPComms @ git+https://github.com/stanfordroboticsclub/UDPComms@master#egg=UDPComms", - ], + install_requires=["tqdm", "numpy", "gym"], + extras_require={ + "sim": ["matplotlib", "pybullet", "gym", "opencv-python", "torchvision"], + "robot": [ + "transforms3d", + "UDPComms @ git+https://github.com/stanfordroboticsclub/UDPComms@master#egg=UDPComms", + ], + }, ) diff --git a/stanford_quad/pupper/HardwareConfig.py b/stanford_quad/pupper/HardwareConfig.py index c09f39f7..3ac1094c 100644 --- a/stanford_quad/pupper/HardwareConfig.py +++ b/stanford_quad/pupper/HardwareConfig.py @@ -5,9 +5,7 @@ MICROS_PER_RAD = 11.333 * 180.0 / np.pi # Must be calibrated -NEUTRAL_ANGLE_DEGREES = np.array( - [[ -0, 7, 2, 3], [ 17, 57, 46, 52], [-39, -35, -33, -64]] -) +NEUTRAL_ANGLE_DEGREES = np.array([[-1.0, -4.0, -14.0, -10.0], [45.0, 47.0, 43.0, 40.0], [-41.0, -43.0, -28.0, -22.0]]) -PS4_COLOR = {"red": 0, "blue": 0, "green": 255} -PS4_DEACTIVATED_COLOR = {"red": 0, "blue": 0, "green": 50} \ No newline at end of file +PS4_COLOR = {"red": 0, "blue": 255, "green": 0} +PS4_DEACTIVATED_COLOR = {"red": 0, "blue": 50, "green": 0} From 6d19cf3e429817e0c71d250da13cc1e48b4dfa87 Mon Sep 17 00:00:00 2001 From: Florian Golemo Date: Wed, 23 Sep 2020 18:33:42 -0400 Subject: [PATCH 38/49] simple prototype for playing back the recording --- scripts/11-test-glen-playback.py | 68 ++++++++++++++++++++++++++++++++ stanford_quad/sim/simulator.py | 6 ++- stanford_quad/sim/simulator2.py | 36 ++++++++++------- 3 files changed, 94 insertions(+), 16 deletions(-) create mode 100644 scripts/11-test-glen-playback.py diff --git a/scripts/11-test-glen-playback.py b/scripts/11-test-glen-playback.py new file mode 100644 index 00000000..098f7100 --- /dev/null +++ b/scripts/11-test-glen-playback.py @@ -0,0 +1,68 @@ +import os +import time +import numpy as np +import h5py + +from stanford_quad.assets import ASSET_DIR +from stanford_quad.sim.HardwareInterface import HardwareInterface +from stanford_quad.sim.simulator import PySim +from stanford_quad.sim.simulator2 import PupperSim2 + +# sim = PySim(xml_path=os.path.join(ASSET_DIR, "pupper_pybullet_out.xml"), headless=False) +sim = PupperSim2(debug=True) +# base values from HW interface: kp=0.25, kv=0.5, max_torque=10 + +RECORDING_FPS = 60 # limited by camera +SIM_FPS = 240 # arbitrary but should be a multiple of the RECORDING_FPS + +TRICK = "walk-forward" +FRAME_START = 90 +FRAME_END = 400 + +# TRICK = "walk-backward" +# FRAME_START = 150 +# FRAME_END = 450 + +# WHEEEEEEEEE! + +# TRICK = "jump" +# FRAME_START = 120 +# FRAME_END = 250 + +# TRICK = "turn-right" +# FRAME_START = 110 +# FRAME_END = 570 + +substeps = int(round(SIM_FPS / RECORDING_FPS)) + +f = h5py.File(f"/Users/florian/dev/pyvicon/scripts/pupper-{TRICK}.hdf5", "r") + +vicon_positions = f["vicon_positions"] +vicon_rotations = f["vicon_rotations"] +joints = f["joints"] +feet = f["foot_positions"] + +# Sim seconds per sim step +sim_dt = 1.0 / SIM_FPS +last_control_update = 0 +start = time.time() + +saved_states = [] + +# move the robot down to the ground +sim.reset(rest=True) +for _ in range(10): + sim.step() + +for frame_idx in range(FRAME_START, FRAME_END): + + # pick the next joint recording from the HDF5 + joint_angles = np.reshape(joints[frame_idx], (3, 4)) + joint_angles_robot = HardwareInterface.parallel_to_serial_joint_angles(joint_angles) + + sim.action(joint_angles_robot.T.flatten()) + + for _ in range(substeps): + sim.step() + + time.sleep(0.05) diff --git a/stanford_quad/sim/simulator.py b/stanford_quad/sim/simulator.py index e9e053c1..b31bcfd5 100644 --- a/stanford_quad/sim/simulator.py +++ b/stanford_quad/sim/simulator.py @@ -3,14 +3,18 @@ class PySim: - def __init__(self, xml_path, headless=False, kp=0.25, kv=0.5, max_torque=10, g=-9.81): + def __init__(self, xml_path, freq=240, headless=False, kp=0.25, kv=0.5, max_torque=10, g=-9.81): # Set up PyBullet Simulator if not headless: pybullet.connect(pybullet.GUI) # or p.DIRECT for non-graphical version + pybullet.resetDebugVisualizerCamera( + cameraDistance=1, cameraYaw=45, cameraPitch=-45, cameraTargetPosition=[0, 0.0, 0] + ) else: pybullet.connect(pybullet.DIRECT) # or p.DIRECT for non-graphical version pybullet.setAdditionalSearchPath(pybullet_data.getDataPath()) # optionally pybullet.setGravity(0, 0, g) + pybullet.setTimeStep(1 / freq) self.model = pybullet.loadMJCF(xml_path) print("") print("Pupper body IDs:", self.model) diff --git a/stanford_quad/sim/simulator2.py b/stanford_quad/sim/simulator2.py index 30aa95a9..c8fb5ebe 100644 --- a/stanford_quad/sim/simulator2.py +++ b/stanford_quad/sim/simulator2.py @@ -34,6 +34,7 @@ def __init__( g=-9.81, start_standing=True, img_size=(84, 84), + enable_new_floor=False, ): """ @@ -63,7 +64,7 @@ def __init__( if debug: self.p.resetDebugVisualizerCamera( - cameraDistance=0.75, cameraYaw=0, cameraPitch=-45, cameraTargetPosition=[0, 0.0, 0] + cameraDistance=1.5, cameraYaw=180, cameraPitch=-45, cameraTargetPosition=[0, 0.0, 0] ) # self.p.loadURDF("plane.urdf") @@ -79,22 +80,22 @@ def __init__( fov=90, aspect=self.img_size[0] / self.img_size[1], nearVal=0.001, farVal=10 ) - self.collision_floor = self.create_box((0, 0, 0.001), (0, 0, 0), (1, 1, 0.0005), visible=False) - self.p.createConstraint( - parentBodyUniqueId=self.collision_floor, - parentLinkIndex=-1, - childBodyUniqueId=-1, - childLinkIndex=-1, - jointType=self.p.JOINT_FIXED, - jointAxis=(1, 1, 1), - parentFramePosition=(0, 0, 0.0), - childFramePosition=(0, 0, 0.0005), - ) + self.collision_floor = None + if enable_new_floor: + self.collision_floor = self.create_box((0, 0, 0.001), (0, 0, 0), (1, 1, 0.0005), visible=False) + self.p.createConstraint( + parentBodyUniqueId=self.collision_floor, + parentLinkIndex=-1, + childBodyUniqueId=-1, + childLinkIndex=-1, + jointType=self.p.JOINT_FIXED, + jointAxis=(1, 1, 1), + parentFramePosition=(0, 0, 0.0), + childFramePosition=(0, 0, 0.0005), + ) if start_standing: - self.reset() - linka = self.p.getLinkState(self.model, 0)[0] - print(linka) + self.reset(True) for _ in range(10): self.step() @@ -305,6 +306,11 @@ def take_photo(self): return output_img def check_collision(self): + if self.collision_floor is None: + raise Exception( + "You need to call the PupperSim2 class with the parameter enable_new_floor=True for floor collisions to work." + ) + contacts = self.p.getClosestPoints( bodyA=self.model, bodyB=self.collision_floor, distance=0.1, linkIndexA=-1, linkIndexB=-1 ) From d216f8ca2a3bde55405a8c1feda12a36e37f6461 Mon Sep 17 00:00:00 2001 From: Florian Golemo Date: Thu, 24 Sep 2020 21:33:22 -0400 Subject: [PATCH 39/49] added glen playback stuff --- scripts/11-test-glen-playback.py | 90 +++++++-- stanford_quad/assets/pupper-v1.urdf.xml | 239 ++++++++++++++++++++++++ stanford_quad/sim/simulator2.py | 51 ++++- stanford_quad/sim/utils.py | 28 ++- 4 files changed, 379 insertions(+), 29 deletions(-) create mode 100644 stanford_quad/assets/pupper-v1.urdf.xml diff --git a/scripts/11-test-glen-playback.py b/scripts/11-test-glen-playback.py index 098f7100..f0cfd0ac 100644 --- a/scripts/11-test-glen-playback.py +++ b/scripts/11-test-glen-playback.py @@ -1,16 +1,11 @@ -import os import time import numpy as np import h5py - -from stanford_quad.assets import ASSET_DIR +from scipy.spatial.transform import Rotation from stanford_quad.sim.HardwareInterface import HardwareInterface -from stanford_quad.sim.simulator import PySim -from stanford_quad.sim.simulator2 import PupperSim2 - -# sim = PySim(xml_path=os.path.join(ASSET_DIR, "pupper_pybullet_out.xml"), headless=False) -sim = PupperSim2(debug=True) -# base values from HW interface: kp=0.25, kv=0.5, max_torque=10 +from stanford_quad.sim.simulator2 import PupperSim2, REST_POS +import cv2 +from stanford_quad.sim.utils import segmap2color_fixed RECORDING_FPS = 60 # limited by camera SIM_FPS = 240 # arbitrary but should be a multiple of the RECORDING_FPS @@ -23,8 +18,6 @@ # FRAME_START = 150 # FRAME_END = 450 -# WHEEEEEEEEE! - # TRICK = "jump" # FRAME_START = 120 # FRAME_END = 250 @@ -42,27 +35,86 @@ joints = f["joints"] feet = f["foot_positions"] -# Sim seconds per sim step -sim_dt = 1.0 / SIM_FPS -last_control_update = 0 -start = time.time() +######## +# KINEMATIC SIM +######## -saved_states = [] + +sim = PupperSim2(debug=False, img_size=(256, 256), frequency=SIM_FPS) # move the robot down to the ground sim.reset(rest=True) for _ in range(10): sim.step() +# make the robot limp for demonstration +sim.make_kinematic() + +base_pos = vicon_positions[FRAME_START] +base_rot = vicon_rotations[FRAME_START] + for frame_idx in range(FRAME_START, FRAME_END): # pick the next joint recording from the HDF5 joint_angles = np.reshape(joints[frame_idx], (3, 4)) joint_angles_robot = HardwareInterface.parallel_to_serial_joint_angles(joint_angles) - sim.action(joint_angles_robot.T.flatten()) + sim.set(joint_angles_robot.T.flatten()) + + diff_pos = vicon_positions[frame_idx] - base_pos + diff_pos /= 500 # for some weird reason it's not /100 + z = diff_pos[2] + 0.21 # (compensating for the model) + x = diff_pos[1] + y = diff_pos[0] + + # fixed manual rotation for now + rot = Rotation.from_quat([0, 0, 0, 1]) + + # rot = vicon_rotations[frame_idx] + # # rot = Rotation.from_quat((rot[1], rot[2], rot[0], rot[3])) # ish + # rot = Rotation.from_quat((-rot[1], -rot[2], rot[0], rot[3])) # ish + # rot_before = np.copy(rot.as_euler("xyz", degrees=True)) + # + # rot_e = rot.as_euler("xyz", degrees=True) + # # if rot_e[0] > -160: + # # rot = rot.inv() + + sim.move_kinectic_body((x, y, z), rot.as_quat()) + + # Here we only do a single step because we _set_ the joint positions directly. + # In the real simulation, we need to step multiple times, corresponding to SIM_FPS/RECORDING_FPS + sim.step() + + img, segmap = sim.take_photo(with_segmap=True) + cv2.imshow("frame", img[:, :, ::-1]) # RGB to BGR + cv2.imshow("segmap", segmap2color_fixed(segmap)) + cv2.waitKey(1) + + +######## +# REAL SIM - to learn the imitation policy +######## + + +sim2 = PupperSim2(debug=False, img_size=(256, 256), frequency=SIM_FPS) +# note: technically there's no reason for sim1 to stay open and open a second sim here. This is just for show. + +sim2.reset(rest=True) +for _ in range(10): + sim2.step() + +for idx in range(FRAME_END - FRAME_START): + # start with the stable resting position and learn a policy that applies small values to this + joints = np.copy(sim2.get_rest_pos()) + + # joints = policy(last_observation) + joints + + sim2.action(joints) for _ in range(substeps): - sim.step() + sim2.step() - time.sleep(0.05) + img, segmap = sim2.take_photo(with_segmap=True) + cv2.imshow("frame", img[:, :, ::-1]) # RGB to BGR + cv2.imshow("segmap", segmap2color_fixed(segmap)) + cv2.waitKey(1) diff --git a/stanford_quad/assets/pupper-v1.urdf.xml b/stanford_quad/assets/pupper-v1.urdf.xml new file mode 100644 index 00000000..09de202a --- /dev/null +++ b/stanford_quad/assets/pupper-v1.urdf.xml @@ -0,0 +1,239 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/stanford_quad/sim/simulator2.py b/stanford_quad/sim/simulator2.py index c8fb5ebe..74b8d25f 100644 --- a/stanford_quad/sim/simulator2.py +++ b/stanford_quad/sim/simulator2.py @@ -8,7 +8,7 @@ from stanford_quad.assets import ASSET_DIR from stanford_quad.sim.HardwareInterface import HardwareInterface -from stanford_quad.sim.utils import random_bright_color, pybulletimage2numpy +from stanford_quad.sim.utils import random_bright_color, pybulletimage2numpy, pybulletsegmap2numpy FREQ_SIM = 240 @@ -35,6 +35,7 @@ def __init__( start_standing=True, img_size=(84, 84), enable_new_floor=False, + frequency=FREQ_SIM, ): """ @@ -58,7 +59,7 @@ def __init__( else: startup_flag = pybullet.DIRECT self.p = bc.BulletClient(connection_mode=startup_flag) - self.p.setTimeStep(1 / FREQ_SIM) + self.p.setTimeStep(1 / frequency) self.p.setAdditionalSearchPath(pybullet_data.getDataPath()) self.p.setGravity(0, 0, g) @@ -69,7 +70,8 @@ def __init__( # self.p.loadURDF("plane.urdf") - self.model = self.p.loadMJCF(xml_path)[1] # [0] is the floor + self.floor, self.model = self.p.loadMJCF(xml_path) + if debug: numjoints = self.p.getNumJoints(self.model) for i in range(numjoints): @@ -135,6 +137,32 @@ def reset(self, rest=True, random_rot=(0, 0, 0), random_pos=(0, 0, 0)): for _ in range(10): self.step() + def make_kinematic(self, color=(1, 0, 1, 1)): + sleepy_state = ( + self.p.ACTIVATION_STATE_SLEEP + + self.p.ACTIVATION_STATE_ENABLE_SLEEPING + + self.p.ACTIVATION_STATE_DISABLE_WAKEUP + ) + + self.p.changeDynamics(self.model, -1, linearDamping=0, angularDamping=0) + self.p.setCollisionFilterGroupMask(self.model, -1, collisionFilterGroup=0, collisionFilterMask=0) + + self.p.changeDynamics( + self.model, -1, activationState=sleepy_state, + ) + self.p.changeVisualShape(self.model, -1, rgbaColor=color) + + for j in range(24): # not 12 because there's some fixed joints in there + self.p.setCollisionFilterGroupMask(self.model, j, collisionFilterGroup=0, collisionFilterMask=0) + + self.p.changeDynamics( + self.model, j, activationState=sleepy_state, + ) + self.p.changeVisualShape(self.model, j, rgbaColor=color) + + def move_kinectic_body(self, pos, rot): + self.p.resetBasePositionAndOrientation(self.model, pos, rot) + @staticmethod def get_rest_pos(): return REST_POS.T.flatten() @@ -286,9 +314,9 @@ def add_stairs( return steps - def take_photo(self): + def take_photo(self, camera_offset=(0, -0.3, 0.3), with_segmap=False): pos, _, _ = self.get_pos_orn_vel() - cam_pos = pos + [0, -0.3, 0.3] + cam_pos = pos + camera_offset cam_view = self.p.computeViewMatrix( cameraEyePosition=cam_pos, cameraTargetPosition=pos, cameraUpVector=[0, 0, 1] ) @@ -297,13 +325,18 @@ def take_photo(self): self.img_size[1], cam_view, self.cam_proj, - renderer=self.p.ER_BULLET_HARDWARE_OPENGL, - flags=0 + renderer=pybullet.ER_BULLET_HARDWARE_OPENGL, + # flags=pybullet.ER_SEGMENTATION_MASK_OBJECT_AND_LINKINDEX # lightDirection=[-.5, -1, .5], lightDistance=1, # renderer=self.p0.ER_TINY_RENDERER ) - output_img = pybulletimage2numpy(img, self.img_size[0], self.img_size[1]) - return output_img + output_img = pybulletimage2numpy(img) + + if with_segmap: + output_segmap = pybulletsegmap2numpy(img) + return output_img, output_segmap + else: + return output_img def check_collision(self): if self.collision_floor is None: diff --git a/stanford_quad/sim/utils.py b/stanford_quad/sim/utils.py index 44bd8642..a1ec1d98 100644 --- a/stanford_quad/sim/utils.py +++ b/stanford_quad/sim/utils.py @@ -14,8 +14,34 @@ def random_bright_color(uint=False): return [x / 255 for x in (r, g, b)] -def pybulletimage2numpy(img, height, width): +def pybulletimage2numpy(img): + width, height = img[0:2] rgb = img[2] rgb = np.reshape(rgb, (height, width, 4)) rgb = rgb[:, :, :3] return rgb + + +def pybulletsegmap2numpy(img): + width, height = img[0:2] + segmap = img[4] + segmap = np.reshape(segmap, (height, width)) + segmap = segmap[:, :] + return segmap + + +def segmap2color(segmap): + output = np.zeros((segmap.shape[0], segmap.shape[1], 3), np.uint8) + + for inst in range(segmap.max() + 1): + output[segmap == inst, :] = np.random.uniform(200, 255, 3) + + return output + + +def segmap2color_fixed(segmap): + output = np.zeros((segmap.shape[0], segmap.shape[1], 3), np.uint8) + output[segmap == 0, :] = (255, 0, 0) + output[segmap == 1, :] = (0, 0, 255) + + return output From 010ee748a86579cd800549073c7a4f4e2551839a Mon Sep 17 00:00:00 2001 From: Florian Golemo Date: Fri, 25 Sep 2020 11:40:34 -0400 Subject: [PATCH 40/49] both simulations side by side --- scripts/12-synced-playback.py | 114 ++++++++++++++++++++++++++++++++ stanford_quad/sim/simulator2.py | 8 ++- 2 files changed, 120 insertions(+), 2 deletions(-) create mode 100644 scripts/12-synced-playback.py diff --git a/scripts/12-synced-playback.py b/scripts/12-synced-playback.py new file mode 100644 index 00000000..509b56d1 --- /dev/null +++ b/scripts/12-synced-playback.py @@ -0,0 +1,114 @@ +import time +import numpy as np +import h5py +from scipy.spatial.transform import Rotation +from stanford_quad.sim.HardwareInterface import HardwareInterface +from stanford_quad.sim.simulator2 import PupperSim2, REST_POS +import cv2 +from stanford_quad.sim.utils import segmap2color_fixed + +RECORDING_FPS = 60 # limited by camera +SIM_FPS = 240 # arbitrary but should be a multiple of the RECORDING_FPS + +TRICK = "walk-forward" +FRAME_START = 90 +FRAME_END = 400 + +RESOLUTION = 256 + +substeps = int(round(SIM_FPS / RECORDING_FPS)) + +f = h5py.File(f"/Users/florian/dev/pyvicon/scripts/pupper-{TRICK}.hdf5", "r") + +vicon_positions = f["vicon_positions"] +vicon_rotations = f["vicon_rotations"] +joints = f["joints"] +feet = f["foot_positions"] + +######## +# KINEMATIC SIM +######## + + +sim_ref = PupperSim2(debug=False, img_size=(RESOLUTION, RESOLUTION), frequency=SIM_FPS) +sim_ref.reset() +# make the robot limp for demonstration +sim_ref.make_kinematic() + +sim_learner = PupperSim2(debug=False, img_size=(RESOLUTION, RESOLUTION), frequency=SIM_FPS) +sim_learner.reset(rest=True) +sim_learner.change_color((0, 1, 1, 1)) +for _ in range(10): + sim_learner.step() + +base_pos = vicon_positions[FRAME_START] +base_rot = vicon_rotations[FRAME_START] + + +def get_recording_pose(frame_idx): + diff_pos = vicon_positions[frame_idx] - base_pos + diff_pos /= 500 # for some weird reason it's not /100 + z = diff_pos[2] + 0.21 # (compensating for the model) + x = diff_pos[1] + y = diff_pos[0] + + # fixed manual rotation for now + rot = Rotation.from_quat([0, 0, 0, 1]) + return (x, y, z), rot + + +def get_recording_joints(frame_idx): + joint_angles = np.reshape(joints[frame_idx], (3, 4)) + joint_angles_robot = HardwareInterface.parallel_to_serial_joint_angles(joint_angles) + + return joint_angles_robot.T.flatten() + + +def policy(_): + # make sure to initialize the policy with zeroed output + return np.array([0] * 12) + + +def merge_images(img_ref, img_learner, segmap_ref, segmap_learner): + # the "+2" is only there to create some space between the frames + img_merged = np.zeros((RESOLUTION * 2 + 2, RESOLUTION * 2 + 2, 3), np.uint8) + img_merged[:RESOLUTION, :RESOLUTION, :] = img_ref[:, :, ::-1] + img_merged[:RESOLUTION, RESOLUTION + 2 :, :] = img_learner[:, :, ::-1] + img_merged[RESOLUTION + 2 :, :RESOLUTION, :] = segmap2color_fixed(segmap_ref) + img_merged[RESOLUTION + 2 :, RESOLUTION + 2 :, :] = segmap2color_fixed(segmap_learner) + return img_merged + + +for frame_idx in range(FRAME_START, FRAME_END): + + # reference sim + + joints_reference = get_recording_joints(frame_idx) + sim_ref.set(joints_reference) + + pos, rot = get_recording_pose(frame_idx) + sim_ref.move_kinectic_body(pos, rot.as_quat()) + + sim_ref.step() + img_ref, segmap_ref = sim_ref.take_photo(with_segmap=True) + + # learner sim + + joints_learner_base = np.copy(sim_learner.get_rest_pos()) + + last_observation = None + joints_learner = policy(last_observation) + joints_learner_base + + sim_learner.action(joints_learner) + + for _ in range(substeps): + sim_learner.step() + + img_learner, segmap_learner = sim_learner.take_photo(with_segmap=True) + + # temporary, just for demonstration: + + img_merged = merge_images(img_ref, img_learner, segmap_ref, segmap_learner) + + cv2.imshow("Merged Frames", img_merged) + cv2.waitKey(1) diff --git a/stanford_quad/sim/simulator2.py b/stanford_quad/sim/simulator2.py index 74b8d25f..7e714ef1 100644 --- a/stanford_quad/sim/simulator2.py +++ b/stanford_quad/sim/simulator2.py @@ -150,14 +150,18 @@ def make_kinematic(self, color=(1, 0, 1, 1)): self.p.changeDynamics( self.model, -1, activationState=sleepy_state, ) - self.p.changeVisualShape(self.model, -1, rgbaColor=color) - for j in range(24): # not 12 because there's some fixed joints in there self.p.setCollisionFilterGroupMask(self.model, j, collisionFilterGroup=0, collisionFilterMask=0) self.p.changeDynamics( self.model, j, activationState=sleepy_state, ) + + self.change_color(color) + + def change_color(self, color=(1, 0, 1, 1)): + self.p.changeVisualShape(self.model, -1, rgbaColor=color) + for j in range(24): # not 12 because there's some fixed joints in there self.p.changeVisualShape(self.model, j, rgbaColor=color) def move_kinectic_body(self, pos, rot): From 44ff6ca8a3e06f5531fc1caf48f8c71f80366ca0 Mon Sep 17 00:00:00 2001 From: Florian Golemo Date: Tue, 29 Sep 2020 22:04:41 -0400 Subject: [PATCH 41/49] made imitation learning env into gym env --- scripts/12-synced-playback.py | 25 +-- stanford_quad/__init__.py | 18 ++ stanford_quad/envs/__init__.py | 3 +- stanford_quad/envs/imitation_env.py | 207 +++++++++++++++++++++ stanford_quad/envs/imitation_recordings.py | 1 + stanford_quad/envs/utils.py | 14 ++ stanford_quad/sim/simulator2.py | 6 +- 7 files changed, 251 insertions(+), 23 deletions(-) create mode 100644 stanford_quad/envs/imitation_env.py create mode 100644 stanford_quad/envs/imitation_recordings.py create mode 100644 stanford_quad/envs/utils.py diff --git a/scripts/12-synced-playback.py b/scripts/12-synced-playback.py index 509b56d1..530c2989 100644 --- a/scripts/12-synced-playback.py +++ b/scripts/12-synced-playback.py @@ -2,6 +2,8 @@ import numpy as np import h5py from scipy.spatial.transform import Rotation + +from stanford_quad.envs.imitation_env import get_recording_joints, get_recording_pose from stanford_quad.sim.HardwareInterface import HardwareInterface from stanford_quad.sim.simulator2 import PupperSim2, REST_POS import cv2 @@ -45,25 +47,6 @@ base_rot = vicon_rotations[FRAME_START] -def get_recording_pose(frame_idx): - diff_pos = vicon_positions[frame_idx] - base_pos - diff_pos /= 500 # for some weird reason it's not /100 - z = diff_pos[2] + 0.21 # (compensating for the model) - x = diff_pos[1] - y = diff_pos[0] - - # fixed manual rotation for now - rot = Rotation.from_quat([0, 0, 0, 1]) - return (x, y, z), rot - - -def get_recording_joints(frame_idx): - joint_angles = np.reshape(joints[frame_idx], (3, 4)) - joint_angles_robot = HardwareInterface.parallel_to_serial_joint_angles(joint_angles) - - return joint_angles_robot.T.flatten() - - def policy(_): # make sure to initialize the policy with zeroed output return np.array([0] * 12) @@ -83,10 +66,10 @@ def merge_images(img_ref, img_learner, segmap_ref, segmap_learner): # reference sim - joints_reference = get_recording_joints(frame_idx) + joints_reference = get_recording_joints(joints, frame_idx) sim_ref.set(joints_reference) - pos, rot = get_recording_pose(frame_idx) + pos, rot = get_recording_pose(vicon_positions, base_pos, frame_idx) sim_ref.move_kinectic_body(pos, rot.as_quat()) sim_ref.step() diff --git a/stanford_quad/__init__.py b/stanford_quad/__init__.py index 5e1b813a..5f11419a 100644 --- a/stanford_quad/__init__.py +++ b/stanford_quad/__init__.py @@ -1,8 +1,26 @@ from gym import register import numpy as np +from stanford_quad.envs.imitation_recordings import IMITATION_LIB + HEADLESSNESS = ["Headless", "Graphical"] + +def make_imitation_env(trick): + steps = IMITATION_LIB[trick]["end"] - IMITATION_LIB[trick]["start"] + register( + id=f"Pupper-Recording-{IMITATION_LIB[trick]['env_name']}-v0", + entry_point="stanford_quad.envs:ImitationEnv", + kwargs={ + # "debug": (False if headlessness == "Headless" else True), + "trick": "walk-forward", + }, + max_episode_steps=steps, + ) + + +make_imitation_env("walk-forward") + for headlessness in HEADLESSNESS: register( id=f"Pupper-Walk-Absolute-{headlessness}-v0", diff --git a/stanford_quad/envs/__init__.py b/stanford_quad/envs/__init__.py index cf7271d2..46c4f10b 100644 --- a/stanford_quad/envs/__init__.py +++ b/stanford_quad/envs/__init__.py @@ -1 +1,2 @@ -from stanford_quad.envs.walking_env import WalkingEnv \ No newline at end of file +from stanford_quad.envs.walking_env import WalkingEnv +from stanford_quad.envs.imitation_env import ImitationEnv diff --git a/stanford_quad/envs/imitation_env.py b/stanford_quad/envs/imitation_env.py new file mode 100644 index 00000000..b267a878 --- /dev/null +++ b/stanford_quad/envs/imitation_env.py @@ -0,0 +1,207 @@ +import gym +import h5py +import numpy as np +from scipy.spatial.transform import Rotation +import cv2 + +from stanford_quad.envs.utils import rendermode_from_string, RenderMode +from stanford_quad.sim.HardwareInterface import HardwareInterface +from stanford_quad.sim.simulator2 import PupperSim2, FREQ_SIM +from stanford_quad.envs.imitation_recordings import IMITATION_LIB + +CONTROL_FREQUENCY = 60 +RECORDINGS_PATH = "/Users/florian/dev/pyvicon/scripts/pupper-{}.hdf5" +RESOLUTION = 256 +SIM_AGENT_COLOR = (0, 1, 1, 1) +SIM_REF_COLOR = (1, 0, 1, 1) +JOINT_ERROR_SCALE = 5.0 # copied over from https://github.com/google-research/motion_imitation/blob/master/motion_imitation/envs/env_wrappers/imitation_task.py#L59 + + +def get_recording_joints(joints, frame_idx): + joint_angles = np.reshape(joints[frame_idx], (3, 4)) + joint_angles_robot = HardwareInterface.parallel_to_serial_joint_angles(joint_angles) + + return joint_angles_robot.T.flatten() + + +def get_recording_pose(vicon_positions, base_pos, frame_idx): + diff_pos = vicon_positions[frame_idx] - base_pos + diff_pos /= 500 # for some weird reason it's not /100 + z = diff_pos[2] + 0.21 # (compensating for the model) + x = diff_pos[1] + y = diff_pos[0] + + # fixed manual rotation for now + rot = Rotation.from_quat([0, 0, 0, 1]) + return (x, y, z), rot + + +def merge_images(img_ref, img_agent): + # the "+2" is only there to create some space between the frames + img_merged = np.zeros((RESOLUTION, RESOLUTION * 2 + 2, 3), np.uint8) + img_merged[:, :RESOLUTION, :] = img_ref[:, :, ::-1] + img_merged[:, RESOLUTION + 2 :, :] = img_agent[:, :, ::-1] + return img_merged + + +class ImitationEnv(gym.Env): + def __init__(self, trick, control_freq=CONTROL_FREQUENCY, action_scaling=0.5): + super().__init__() + + self.control_freq = control_freq + self.action_scaling = action_scaling + + f = h5py.File(RECORDINGS_PATH.format(trick), "r") + + self.vicon_positions = f["vicon_positions"] + self.vicon_rotations = f["vicon_rotations"] + + self.idx_start = IMITATION_LIB[trick]["start"] + self.idx_end = IMITATION_LIB[trick]["end"] + + self.base_pos = self.vicon_positions[self.idx_start] + self.base_rot = self.vicon_rotations[self.idx_end] + + self.joints = f["joints"] + self.feet = f["foot_positions"] + + # observation space: + # - 12 lef joints in the order + # - front right hip + # - front right upper leg + # - front right lower leg + # - front left hip/upper/lower leg + # - back right hip/upper/lower leg + # - back left hip/upper/lower leg + # - 3 body orientation in euler angles + # - 2 linear velocity (only along the plane, we don't care about z velocity + + self.observation_space = gym.spaces.Box(low=-1, high=1, shape=(12 + 3 + 2,), dtype=np.float32) + + # action = 12 joint angles in the same order as above (fr/fl/br/bl and each with hip/upper/lower) + self.action_space = gym.spaces.Box(low=-1, high=1, shape=(12,), dtype=np.float32) + + self.sim_agent = PupperSim2( + debug=False, + start_standing=False, + gain_pos=1 / 16, + gain_vel=1 / 8, + max_torque=1 / 2, + img_size=(RESOLUTION, RESOLUTION), + ) + self.sim_agent.change_color((SIM_AGENT_COLOR)) + self.dt = 1 / self.control_freq + self.sim_steps = int(round(FREQ_SIM / control_freq)) + + self.sim_ref = PupperSim2(debug=False, img_size=(RESOLUTION, RESOLUTION)) + self.sim_ref.reset() + # make the robot limp for demonstration + self.sim_ref.make_kinematic(SIM_REF_COLOR) + + self.episode_steps = 0 + self.frame_idx = self.idx_start + + def get_obs(self): + pos, orn, vel = self.sim_agent.get_pos_orn_vel() + + # to normalize to [-1,1] + joint_states = np.array(self.sim_agent.get_joint_states()) / np.pi + obs = list(joint_states) + list(orn) + list(vel)[:2] + return obs + + def reset(self): + self.frame_idx = self.idx_start + + # reset the learning agent + self.sim_agent.reset(rest=True) + + for _ in range(10): + self.sim_agent.step() + + return self.get_obs() + + def sanitize_actions(self, actions): + assert len(actions) == 12 + scaled = actions * np.pi * self.action_scaling # because 1/-1 corresponds to pi/-pi radians rotation + scaled += self.sim_agent.get_rest_pos() + # this enforces an action range of -1/1, except if it's relative action - then the action space is asymmetric + clipped = np.clip(scaled, -np.pi + 0.001, np.pi - 0.001) + return clipped + + def calc_imitation_error(self, joints_agent, joints_ref): + diff = np.array(joints_ref - joints_agent) + pose_err = diff.dot(diff) + pose_reward = np.exp(-JOINT_ERROR_SCALE * pose_err) + return pose_reward + + def step(self, action): + action_clean = self.sanitize_actions(action) + + ## reference sim + self.frame_idx += 1 # retrieving the next recording frame + + joints_reference = get_recording_joints(self.joints, self.frame_idx) + self.sim_ref.set(joints_reference) + + pos, rot = get_recording_pose(self.vicon_positions, self.base_pos, self.frame_idx) + self.sim_ref.move_kinectic_body(pos, rot.as_quat()) + + self.sim_ref.step() + + ## learner sim + self.sim_agent.action(action_clean) + + for _ in range(self.sim_steps): + self.sim_agent.step() + + joints_agent = self.sim_agent.get_joint_states() + + obs = self.get_obs() + reward = self.calc_imitation_error(joints_agent, joints_reference) + done = False + misc = {} + + if self.frame_idx == self.idx_end: + done = True + + return obs, reward, done, misc + + def _render_agent(self, with_segmap=False): + img, segmap = self.sim_agent.take_photo(with_segmap=with_segmap) + return img, segmap + + def _render_ref(self, with_segmap=False): + img, segmap = self.sim_ref.take_photo(with_segmap=with_segmap) + return img, segmap + + def render(self, mode="human", with_segmap=False): + mode_i = rendermode_from_string(mode) + + if mode_i is RenderMode.HUMAN: + img_agent, _ = self._render_agent() + img_ref, _ = self._render_ref() + cv2.imshow("Left: Ref, Right: Agent", merge_images(img_ref, img_agent)) + cv2.waitKey(1) + + elif mode_i is RenderMode.RGB_ARRAY: + img, segmap = self._render_agent(with_segmap) + + # TODO deal with segmap here + return img + elif mode_i is RenderMode.RGB_ARRAY_REF: + img, segmap = self._render_ref(with_segmap) + return img + + +if __name__ == "__main__": + + env = gym.make("Pupper-Recording-WalkForward-v0") + + for _ in range(3): + obs = env.reset() + print(obs) + while True: + obs, rew, done, misc = env.step(np.random.uniform(-0.1, 0.1, 12)) + env.render("human") + if done: + break diff --git a/stanford_quad/envs/imitation_recordings.py b/stanford_quad/envs/imitation_recordings.py new file mode 100644 index 00000000..fce76d02 --- /dev/null +++ b/stanford_quad/envs/imitation_recordings.py @@ -0,0 +1 @@ +IMITATION_LIB = {"walk-forward": {"start": 90, "end": 400, "env_name": "WalkForward"}} diff --git a/stanford_quad/envs/utils.py b/stanford_quad/envs/utils.py new file mode 100644 index 00000000..a03f4c3f --- /dev/null +++ b/stanford_quad/envs/utils.py @@ -0,0 +1,14 @@ +from enum import IntEnum + + +class RenderMode(IntEnum): + HUMAN = 0 + RGB_ARRAY = 1 + RGB_ARRAY_REF = 2 + + +def rendermode_from_string(mode): + assert mode in ["human", "rgb_array", "rgb_array_ref"] + return {"human": RenderMode.HUMAN, "rgb_array": RenderMode.RGB_ARRAY, "rgb_array_ref": RenderMode.RGB_ARRAY_REF}[ + mode + ] diff --git a/stanford_quad/sim/simulator2.py b/stanford_quad/sim/simulator2.py index 7e714ef1..e486c606 100644 --- a/stanford_quad/sim/simulator2.py +++ b/stanford_quad/sim/simulator2.py @@ -324,12 +324,16 @@ def take_photo(self, camera_offset=(0, -0.3, 0.3), with_segmap=False): cam_view = self.p.computeViewMatrix( cameraEyePosition=cam_pos, cameraTargetPosition=pos, cameraUpVector=[0, 0, 1] ) + flags = 0 + if not with_segmap: + flags |= pybullet.ER_NO_SEGMENTATION_MASK img = self.p.getCameraImage( self.img_size[0], self.img_size[1], cam_view, self.cam_proj, renderer=pybullet.ER_BULLET_HARDWARE_OPENGL, + flags=flags # flags=pybullet.ER_SEGMENTATION_MASK_OBJECT_AND_LINKINDEX # lightDirection=[-.5, -1, .5], lightDistance=1, # renderer=self.p0.ER_TINY_RENDERER @@ -340,7 +344,7 @@ def take_photo(self, camera_offset=(0, -0.3, 0.3), with_segmap=False): output_segmap = pybulletsegmap2numpy(img) return output_img, output_segmap else: - return output_img + return output_img, None def check_collision(self): if self.collision_floor is None: From 2503efe57cdc1f3dd7bb4ca9eb5e705ca84536a1 Mon Sep 17 00:00:00 2001 From: Florian Golemo Date: Tue, 29 Sep 2020 22:18:48 -0400 Subject: [PATCH 42/49] made 48x48 the new default and added better camera position --- stanford_quad/envs/imitation_env.py | 33 ++++++++++++++++++++--------- stanford_quad/sim/simulator2.py | 5 +++-- 2 files changed, 26 insertions(+), 12 deletions(-) diff --git a/stanford_quad/envs/imitation_env.py b/stanford_quad/envs/imitation_env.py index b267a878..497cdf0c 100644 --- a/stanford_quad/envs/imitation_env.py +++ b/stanford_quad/envs/imitation_env.py @@ -11,10 +11,13 @@ CONTROL_FREQUENCY = 60 RECORDINGS_PATH = "/Users/florian/dev/pyvicon/scripts/pupper-{}.hdf5" -RESOLUTION = 256 +RESOLUTION = 48 SIM_AGENT_COLOR = (0, 1, 1, 1) SIM_REF_COLOR = (1, 0, 1, 1) JOINT_ERROR_SCALE = 5.0 # copied over from https://github.com/google-research/motion_imitation/blob/master/motion_imitation/envs/env_wrappers/imitation_task.py#L59 +CAMERA_OFFSET = (-0.03, -0.275, -0.05) +LOOKAT_OFFSET = (-0.03, 0, -0.05) +MASKED = False # do you want to cut out the robot from the background def get_recording_joints(joints, frame_idx): @@ -101,7 +104,7 @@ def __init__(self, trick, control_freq=CONTROL_FREQUENCY, action_scaling=0.5): self.episode_steps = 0 self.frame_idx = self.idx_start - def get_obs(self): + def _get_obs(self): pos, orn, vel = self.sim_agent.get_pos_orn_vel() # to normalize to [-1,1] @@ -118,9 +121,9 @@ def reset(self): for _ in range(10): self.sim_agent.step() - return self.get_obs() + return self._get_obs() - def sanitize_actions(self, actions): + def _sanitize_actions(self, actions): assert len(actions) == 12 scaled = actions * np.pi * self.action_scaling # because 1/-1 corresponds to pi/-pi radians rotation scaled += self.sim_agent.get_rest_pos() @@ -128,14 +131,14 @@ def sanitize_actions(self, actions): clipped = np.clip(scaled, -np.pi + 0.001, np.pi - 0.001) return clipped - def calc_imitation_error(self, joints_agent, joints_ref): + def _calc_imitation_error(self, joints_agent, joints_ref): diff = np.array(joints_ref - joints_agent) pose_err = diff.dot(diff) pose_reward = np.exp(-JOINT_ERROR_SCALE * pose_err) return pose_reward def step(self, action): - action_clean = self.sanitize_actions(action) + action_clean = self._sanitize_actions(action) ## reference sim self.frame_idx += 1 # retrieving the next recording frame @@ -156,8 +159,8 @@ def step(self, action): joints_agent = self.sim_agent.get_joint_states() - obs = self.get_obs() - reward = self.calc_imitation_error(joints_agent, joints_reference) + obs = self._get_obs() + reward = self._calc_imitation_error(joints_agent, joints_reference) done = False misc = {} @@ -167,11 +170,15 @@ def step(self, action): return obs, reward, done, misc def _render_agent(self, with_segmap=False): - img, segmap = self.sim_agent.take_photo(with_segmap=with_segmap) + img, segmap = self.sim_agent.take_photo( + with_segmap=with_segmap, camera_offset=CAMERA_OFFSET, lookat_offset=LOOKAT_OFFSET + ) return img, segmap def _render_ref(self, with_segmap=False): - img, segmap = self.sim_ref.take_photo(with_segmap=with_segmap) + img, segmap = self.sim_ref.take_photo( + with_segmap=with_segmap, camera_offset=CAMERA_OFFSET, lookat_offset=LOOKAT_OFFSET + ) return img, segmap def render(self, mode="human", with_segmap=False): @@ -191,10 +198,15 @@ def render(self, mode="human", with_segmap=False): elif mode_i is RenderMode.RGB_ARRAY_REF: img, segmap = self._render_ref(with_segmap) return img + else: + raise NotImplementedError(f"I don't have a render function for mode {mode_i}.") if __name__ == "__main__": + # necessary for gym env to register (not here but when you copy this snippet over) + import stanford_quad + env = gym.make("Pupper-Recording-WalkForward-v0") for _ in range(3): @@ -202,6 +214,7 @@ def render(self, mode="human", with_segmap=False): print(obs) while True: obs, rew, done, misc = env.step(np.random.uniform(-0.1, 0.1, 12)) + print(rew, obs) env.render("human") if done: break diff --git a/stanford_quad/sim/simulator2.py b/stanford_quad/sim/simulator2.py index e486c606..1cfb2882 100644 --- a/stanford_quad/sim/simulator2.py +++ b/stanford_quad/sim/simulator2.py @@ -318,11 +318,12 @@ def add_stairs( return steps - def take_photo(self, camera_offset=(0, -0.3, 0.3), with_segmap=False): + def take_photo(self, camera_offset=(0, -0.3, 0.3), lookat_offset=(0, 0, 0), with_segmap=False): pos, _, _ = self.get_pos_orn_vel() cam_pos = pos + camera_offset + cam_lookat = pos + lookat_offset cam_view = self.p.computeViewMatrix( - cameraEyePosition=cam_pos, cameraTargetPosition=pos, cameraUpVector=[0, 0, 1] + cameraEyePosition=cam_pos, cameraTargetPosition=cam_lookat, cameraUpVector=[0, 0, 1] ) flags = 0 if not with_segmap: From 52cb8419d02b0463d4baed4ba10d79f5775ad468 Mon Sep 17 00:00:00 2001 From: Florian Golemo Date: Tue, 29 Sep 2020 22:27:08 -0400 Subject: [PATCH 43/49] added masking --- stanford_quad/envs/imitation_env.py | 39 ++++++++++++++++------------- stanford_quad/sim/utils.py | 2 +- 2 files changed, 22 insertions(+), 19 deletions(-) diff --git a/stanford_quad/envs/imitation_env.py b/stanford_quad/envs/imitation_env.py index 497cdf0c..e58a75b8 100644 --- a/stanford_quad/envs/imitation_env.py +++ b/stanford_quad/envs/imitation_env.py @@ -17,7 +17,7 @@ JOINT_ERROR_SCALE = 5.0 # copied over from https://github.com/google-research/motion_imitation/blob/master/motion_imitation/envs/env_wrappers/imitation_task.py#L59 CAMERA_OFFSET = (-0.03, -0.275, -0.05) LOOKAT_OFFSET = (-0.03, 0, -0.05) -MASKED = False # do you want to cut out the robot from the background +MASKED = True # do you want to cut out the robot from the background def get_recording_joints(joints, frame_idx): @@ -169,35 +169,38 @@ def step(self, action): return obs, reward, done, misc - def _render_agent(self, with_segmap=False): - img, segmap = self.sim_agent.take_photo( - with_segmap=with_segmap, camera_offset=CAMERA_OFFSET, lookat_offset=LOOKAT_OFFSET - ) - return img, segmap + def _render(self, target_sim): + with_segmap = False + if MASKED: + with_segmap = True - def _render_ref(self, with_segmap=False): - img, segmap = self.sim_ref.take_photo( + img, segmap = getattr(self, target_sim).take_photo( with_segmap=with_segmap, camera_offset=CAMERA_OFFSET, lookat_offset=LOOKAT_OFFSET ) - return img, segmap - def render(self, mode="human", with_segmap=False): + if MASKED: + img[segmap != 1] = 0 + return img + + def _render_agent(self): + return self._render("sim_agent") + + def _render_ref(self): + return self._render("sim_ref") + + def render(self, mode="human"): mode_i = rendermode_from_string(mode) if mode_i is RenderMode.HUMAN: - img_agent, _ = self._render_agent() - img_ref, _ = self._render_ref() + img_agent = self._render_agent() + img_ref = self._render_ref() cv2.imshow("Left: Ref, Right: Agent", merge_images(img_ref, img_agent)) cv2.waitKey(1) elif mode_i is RenderMode.RGB_ARRAY: - img, segmap = self._render_agent(with_segmap) - - # TODO deal with segmap here - return img + return self._render_agent() elif mode_i is RenderMode.RGB_ARRAY_REF: - img, segmap = self._render_ref(with_segmap) - return img + return self._render_ref() else: raise NotImplementedError(f"I don't have a render function for mode {mode_i}.") diff --git a/stanford_quad/sim/utils.py b/stanford_quad/sim/utils.py index a1ec1d98..56df3706 100644 --- a/stanford_quad/sim/utils.py +++ b/stanford_quad/sim/utils.py @@ -42,6 +42,6 @@ def segmap2color(segmap): def segmap2color_fixed(segmap): output = np.zeros((segmap.shape[0], segmap.shape[1], 3), np.uint8) output[segmap == 0, :] = (255, 0, 0) - output[segmap == 1, :] = (0, 0, 255) + output[segmap == 1, :] = (0, 255, 0) return output From 1148b0e3c8a12b63f03d6423b5540dc08d7f3b82 Mon Sep 17 00:00:00 2001 From: Florian Golemo Date: Tue, 6 Oct 2020 19:59:57 -0400 Subject: [PATCH 44/49] added incremental env --- scripts/13-run-walker-incremental-gym-env.py | 21 +++++++ stanford_quad/__init__.py | 65 +++++++++++--------- stanford_quad/envs/walking_env.py | 30 +++++++-- 3 files changed, 82 insertions(+), 34 deletions(-) create mode 100644 scripts/13-run-walker-incremental-gym-env.py diff --git a/scripts/13-run-walker-incremental-gym-env.py b/scripts/13-run-walker-incremental-gym-env.py new file mode 100644 index 00000000..2df71771 --- /dev/null +++ b/scripts/13-run-walker-incremental-gym-env.py @@ -0,0 +1,21 @@ +import time + +import gym +import stanford_quad # need this unused import to get our custom environments +import numpy as np + +# env = gym.make("Pupper-Walk-Relative-ScaledDown-RandomZRot-Graphical-v0") +env = gym.make("Pupper-Walk-Incremental-aScale_0.1-aSmooth_1-RandomZRot_1-Graphical-v0") + +for run in range(5): + env.reset() + time.sleep(2) + for step in range(121): + action = env.action_space.sample() * 0.99 + # action = np.array([0] * 12) + obs, rew, done, misc = env.step(action) + print( + f"action: {np.around(action,2)}, " f"obs: {np.around(obs,2)}, " f"rew: {np.around(rew,2)}, " f"done: {done}" + ) + + time.sleep(0.02) diff --git a/stanford_quad/__init__.py b/stanford_quad/__init__.py index 5f11419a..953891df 100644 --- a/stanford_quad/__init__.py +++ b/stanford_quad/__init__.py @@ -21,6 +21,43 @@ def make_imitation_env(trick): make_imitation_env("walk-forward") + +ACTION_TYPE = ["Relative", "Absolute", "Incremental"] +ACTION_SMOOTHING = [1, 2, 3, 4] +RANDOM_ROT = [0, 1, 10, 100] +ACTION_SCALING = [1.0, 2.0, 4.0] + list(np.arange(0.05, 0.5, 0.05)) + +for headlessness in HEADLESSNESS: + for action_type in ACTION_TYPE: + for action_smoothing in ACTION_SMOOTHING: + for action_scaling in ACTION_SCALING: + for random_rot in RANDOM_ROT: + name = ( + f"Pupper-Walk-{action_type}-" + f"aScale_{action_scaling:.2}-" + f"aSmooth_{action_smoothing}-" + f"RandomZRot_{random_rot}-{headlessness}-v0" + ) + print(name) + register( + id=name, + entry_point="stanford_quad.envs:WalkingEnv", + kwargs={ + "debug": (False if headlessness == "Headless" else True), + "steps": 120, + "relative_action": True if action_type == "Relative" else False, + "incremental_action": True if action_type == "Incremental" else False, + "action_scaling": action_scaling, + "action_smoothing": action_smoothing, + "random_rot": (0, 0, random_rot), + }, + max_episode_steps=120, + ) + + +###### LEGACY - WILL REMOVE SOON + + for headlessness in HEADLESSNESS: register( id=f"Pupper-Walk-Absolute-{headlessness}-v0", @@ -159,31 +196,3 @@ def make_imitation_env(trick): }, max_episode_steps=120, ) - -RELATIVE_ACTION = [True, False] -ACTION_SMOOTHING = [1, 2, 3, 4] -RANDOM_ROT = [0, 1, 10, 100] -ACTION_SCALING = [1.0] + list(np.arange(0.05, 0.5, 0.05)) - -for headlessness in HEADLESSNESS: - for relative_action in RELATIVE_ACTION: - for action_smoothing in ACTION_SMOOTHING: - for action_scaling in ACTION_SCALING: - for random_rot in RANDOM_ROT: - action = "Relative" if relative_action else "Absolute" - register( - id=f"Pupper-Walk-{action}-" - f"aScale_{action_scaling:.2}-" - f"aSmooth_{action_smoothing}-" - f"RandomZRot_{random_rot}-{headlessness}-v0", - entry_point="stanford_quad.envs:WalkingEnv", - kwargs={ - "debug": (False if headlessness == "Headless" else True), - "steps": 120, - "relative_action": relative_action, - "action_scaling": action_scaling, - "action_smoothing": action_smoothing, - "random_rot": (0, 0, random_rot), - }, - max_episode_steps=120, - ) diff --git a/stanford_quad/envs/walking_env.py b/stanford_quad/envs/walking_env.py index 0dbca969..9466e4ee 100644 --- a/stanford_quad/envs/walking_env.py +++ b/stanford_quad/envs/walking_env.py @@ -7,6 +7,7 @@ from stanford_quad.sim.simulator2 import PupperSim2, FREQ_SIM CONTROL_FREQUENCY = 60 # Hz, the simulation runs at 240Hz by default and doing a multiple of that is easier +MAX_ANGLE_PER_SEC = 90 class WalkingEnv(gym.Env): @@ -16,6 +17,7 @@ def __init__( steps=120, control_freq=CONTROL_FREQUENCY, relative_action=True, + incremental_action=False, action_scaling=1.0, action_smoothing=1, random_rot=(0, 0, 0), @@ -56,19 +58,29 @@ def __init__( self.episode_steps_max = steps self.control_freq = control_freq self.dt = 1 / self.control_freq + self.incremental_angle = np.deg2rad(MAX_ANGLE_PER_SEC) / self.control_freq self.sim_steps = int(round(FREQ_SIM / control_freq)) self.relative_action = relative_action + self.incremental_action = incremental_action self.action_scaling = action_scaling self.action_smoothing = deque(maxlen=action_smoothing) self.random_rot = random_rot self.stop_on_flip = stop_on_flip - + self.current_action = np.array([0] * 12) # new reward coefficients self.rcoeff_ctrl, self.rcoeff_run, self.rcoeff_stable = reward_coefficients def reset(self): self.episode_steps = 0 - self.sim.reset(rest=self.relative_action, random_rot=self.random_rot) # also stand up the robot + + # both when the action formulation is incremental and when it's relative, we need to start standing + self.sim.reset( + rest=self.relative_action or self.incremental_action, random_rot=self.random_rot + ) # also stand up the robot + + # this is used when self.incremental_action == True + self.current_action = self.sim.get_rest_pos() + return self.get_obs() def seed(self, seed=None): @@ -81,11 +93,17 @@ def close(self): def sanitize_actions(self, actions): assert len(actions) == 12 - scaled = actions * np.pi * self.action_scaling # because 1/-1 corresponds to pi/-pi radians rotation - if self.relative_action: - scaled += self.sim.get_rest_pos() - # this enforces an action range of -1/1, except if it's relative action - then the action space is asymmetric + + if not self.incremental_action: + scaled = actions * np.pi * self.action_scaling # because 1/-1 corresponds to pi/-pi radians rotation + if self.relative_action: + scaled += self.sim.get_rest_pos() + # this enforces an action range of -1/1, except if it's relative action - then the action space is asymmetric + else: + scaled = actions * self.incremental_angle + self.current_action + clipped = np.clip(scaled, -np.pi + 0.001, np.pi - 0.001) + self.current_action = np.copy(clipped) return clipped def get_obs(self): From 0cc2c882539622185b36c23aedbdf1901ec9e11b Mon Sep 17 00:00:00 2001 From: Florian Golemo Date: Wed, 7 Oct 2020 01:39:47 -0400 Subject: [PATCH 45/49] added policy --- scripts/14-test-gait-parameters.py | 49 ++++++++++++++++++++++++++++++ stanford_quad/common/Utilities.py | 26 ++++++++++++++++ stanford_quad/pupper/policy.py | 45 +++++++++++++++++++++++++++ 3 files changed, 120 insertions(+) create mode 100644 scripts/14-test-gait-parameters.py create mode 100644 stanford_quad/pupper/policy.py diff --git a/scripts/14-test-gait-parameters.py b/scripts/14-test-gait-parameters.py new file mode 100644 index 00000000..c02e5aa9 --- /dev/null +++ b/scripts/14-test-gait-parameters.py @@ -0,0 +1,49 @@ +import time + +from stanford_quad.common.Utilities import controller_to_sim +from stanford_quad.pupper.policy import HardPolicy +from stanford_quad.sim.simulator2 import PupperSim2 + + +FPS = 60 # fraction of 240 +substeps = int(round(240 / FPS)) + +sim = PupperSim2(debug=True, frequency=240) + + +def reset_sim(): + sim.reset(rest=True) + sim.change_color((0, 1, 1, 1)) + for _ in range(10): + sim.step() + + +reset_sim() + +debug_params = [] + +for param in ["velocity fwd", "velocity left"]: + debug_params.append(sim.p.addUserDebugParameter(param, -1, 1, 0)) +debug_params.append(sim.p.addUserDebugParameter("reset", 1, 0, 1)) + +policy = HardPolicy() +last_reset_val = -1 + +while True: + vel = [0, 0] + for param_idx, param in enumerate(debug_params): + val = sim.p.readUserDebugParameter(param) + if param_idx < 2: + vel[param_idx] = val + if param_idx == 2 and val != last_reset_val: + reset_sim() + last_reset_val = val + + action = controller_to_sim(policy.act(velocity_horizontal=vel)) + + sim.action(action) + + for _ in range(substeps): + sim.step() + + time.sleep(1 / FPS) diff --git a/stanford_quad/common/Utilities.py b/stanford_quad/common/Utilities.py index 4ca4ec6d..68d30419 100644 --- a/stanford_quad/common/Utilities.py +++ b/stanford_quad/common/Utilities.py @@ -8,3 +8,29 @@ def deadband(value, band_radius): def clipped_first_order_filter(input, target, max_rate, tau): rate = (target - input) / tau return np.clip(rate, -max_rate, max_rate) + + +def parallel_to_serial_joint_angles(joint_matrix): + """Convert from joint angles meant for the parallel linkage in + Pupper to the joint angles in the serial linkage approximation implemented in the simulation + + Parameters + ---------- + joint_matrix : Numpy array (3, 4) + Joint angles for parallel linkage + + Returns + ------- + Numpy array (3, 4) + Joint angles for equivalent serial linkage + """ + temp = joint_matrix + temp[2, :] -= joint_matrix[1, :] + return temp + + +def controller_to_sim(joints): + joint_angles = np.reshape(joints, (3, 4)) + joint_angles_robot = parallel_to_serial_joint_angles(joint_angles) + + return joint_angles_robot.T.flatten() diff --git a/stanford_quad/pupper/policy.py b/stanford_quad/pupper/policy.py new file mode 100644 index 00000000..a2fa130d --- /dev/null +++ b/stanford_quad/pupper/policy.py @@ -0,0 +1,45 @@ +import numpy as np + +from stanford_quad.common.Command import Command +from stanford_quad.common.Controller import Controller +from stanford_quad.common.State import State +from stanford_quad.pupper.Config import Configuration +from stanford_quad.pupper.Kinematics import four_legs_inverse_kinematics + + +class HardPolicy: + def __init__(self, fps=60) -> None: + super().__init__() + + self.fps = fps + + self.config = Configuration() + self.config.dt = 1 / fps + # config.z_clearance = 0.02 + self.controller = Controller(self.config, four_legs_inverse_kinematics) + self.state = State() + command = Command() + + # initializing the controller + command.activate_event = 1 + self.controller.run(self.state, command) + command.activate_event = 0 + command.trot_event = 1 + self.controller.run(self.state, command) + self.command = Command() # zero it out + + print("Summary of gait parameters:") + print("overlap time: ", self.config.overlap_time) + print("swing time: ", self.config.swing_time) + print("z clearance: ", self.config.z_clearance) + print("x shift: ", self.config.x_shift) + + def act(self, velocity_horizontal=(0, 0), yaw_rate=0): + self.command.horizontal_velocity = np.array(velocity_horizontal) + self.command.yaw_rate = yaw_rate + self.state.quat_orientation = np.array([1, 0, 0, 0]) + + # Step the controller forward by dt + self.controller.run(self.state, self.command) + + return self.state.joint_angles From 740e244afad78fba6ef0afb5f56dd1eae7f895f7 Mon Sep 17 00:00:00 2001 From: Florian Golemo Date: Wed, 7 Oct 2020 18:28:50 -0400 Subject: [PATCH 46/49] added tools for recording hard-coded gait --- scripts/14-test-gait-parameters.py | 24 +++++++++++++++++++++-- scripts/15-record-pupper-for-imitation.py | 19 ++++++++++++++++++ stanford_quad/__init__.py | 2 +- stanford_quad/envs/walking_env.py | 16 +++++++++------ stanford_quad/pupper/policy.py | 17 +++++++++++++--- 5 files changed, 66 insertions(+), 12 deletions(-) create mode 100644 scripts/15-record-pupper-for-imitation.py diff --git a/scripts/14-test-gait-parameters.py b/scripts/14-test-gait-parameters.py index c02e5aa9..792b2182 100644 --- a/scripts/14-test-gait-parameters.py +++ b/scripts/14-test-gait-parameters.py @@ -1,5 +1,6 @@ import time - +import numpy as np +import matplotlib.pyplot as plt from stanford_quad.common.Utilities import controller_to_sim from stanford_quad.pupper.policy import HardPolicy from stanford_quad.sim.simulator2 import PupperSim2 @@ -18,6 +19,16 @@ def reset_sim(): sim.step() +def plot_joints(joints): + joints = np.array(joints) + for i in range(12): + plt.plot(np.arange(len(joints)), joints[:, i], label=f"joint {i + 1}") + plt.legend() + plt.tight_layout() + plt.title("sim direct joints") + plt.show() + + reset_sim() debug_params = [] @@ -25,9 +36,13 @@ def reset_sim(): for param in ["velocity fwd", "velocity left"]: debug_params.append(sim.p.addUserDebugParameter(param, -1, 1, 0)) debug_params.append(sim.p.addUserDebugParameter("reset", 1, 0, 1)) +debug_params.append(sim.p.addUserDebugParameter("plot joints", 1, 0, 1)) policy = HardPolicy() last_reset_val = -1 +last_plot_val = -1 +joints = [] +counter = 0 while True: vel = [0, 0] @@ -38,9 +53,14 @@ def reset_sim(): if param_idx == 2 and val != last_reset_val: reset_sim() last_reset_val = val + if param_idx == 3 and val != last_plot_val: + if len(joints) > 0: + plot_joints(joints) + last_plot_val = val + joints.clear() action = controller_to_sim(policy.act(velocity_horizontal=vel)) - + joints.append(np.copy(action)) sim.action(action) for _ in range(substeps): diff --git a/scripts/15-record-pupper-for-imitation.py b/scripts/15-record-pupper-for-imitation.py new file mode 100644 index 00000000..35c272ee --- /dev/null +++ b/scripts/15-record-pupper-for-imitation.py @@ -0,0 +1,19 @@ +import time + +import gym +import stanford_quad +from stanford_quad.common.Utilities import controller_to_sim +from stanford_quad.pupper.policy import HardPolicy + +ROLLOUTS = 5 +env = gym.make("Pupper-Walk-Absolute-aScale_1.0-aSmooth_1-RandomZRot_1-Graphical-v0") + +for run in range(ROLLOUTS): + state = env.reset() + policy = HardPolicy() + while True: + action = controller_to_sim(policy.act(velocity_horizontal=(0.2, 0), normalized=True)) + next_state, rew, done, misc = env.step(action) + if done: + break + time.sleep(1 / 60) diff --git a/stanford_quad/__init__.py b/stanford_quad/__init__.py index 953891df..2cc8fdd8 100644 --- a/stanford_quad/__init__.py +++ b/stanford_quad/__init__.py @@ -38,7 +38,7 @@ def make_imitation_env(trick): f"aSmooth_{action_smoothing}-" f"RandomZRot_{random_rot}-{headlessness}-v0" ) - print(name) + # print(name) register( id=name, entry_point="stanford_quad.envs:WalkingEnv", diff --git a/stanford_quad/envs/walking_env.py b/stanford_quad/envs/walking_env.py index 9466e4ee..ff2ef013 100644 --- a/stanford_quad/envs/walking_env.py +++ b/stanford_quad/envs/walking_env.py @@ -3,7 +3,7 @@ import gym from gym import spaces import numpy as np - +import matplotlib.pyplot as plt from stanford_quad.sim.simulator2 import PupperSim2, FREQ_SIM CONTROL_FREQUENCY = 60 # Hz, the simulation runs at 240Hz by default and doing a multiple of that is easier @@ -53,7 +53,11 @@ def __init__( self.action_space = spaces.Box(low=-1, high=1, shape=(12,), dtype=np.float32) # turning off start_standing because the that's done in self.reset() - self.sim = PupperSim2(debug=debug, start_standing=False, gain_pos=1 / 16, gain_vel=1 / 8, max_torque=1 / 2) + kwargs = {} + # if relative_action: # if this is turned on, the robot is underpowered for the hardcoded gait + # kwargs = {"gain_pos": 1 / 16, "gain_vel": 1 / 8, "max_torque": 1 / 2} + + self.sim = PupperSim2(debug=debug, start_standing=False, **kwargs) self.episode_steps = 0 self.episode_steps_max = steps self.control_freq = control_freq @@ -67,6 +71,7 @@ def __init__( self.random_rot = random_rot self.stop_on_flip = stop_on_flip self.current_action = np.array([0] * 12) + # new reward coefficients self.rcoeff_ctrl, self.rcoeff_run, self.rcoeff_stable = reward_coefficients @@ -74,9 +79,9 @@ def reset(self): self.episode_steps = 0 # both when the action formulation is incremental and when it's relative, we need to start standing - self.sim.reset( - rest=self.relative_action or self.incremental_action, random_rot=self.random_rot - ) # also stand up the robot + self.sim.reset(rest=True) # also stand up the robot + # for _ in range(10): + # self.sim.step() # this is used when self.incremental_action == True self.current_action = self.sim.get_rest_pos() @@ -124,7 +129,6 @@ def step(self, action): self.action_smoothing.append(action_clean) self.sim.action(np.mean(self.action_smoothing, axis=0)) - # this steps the simulation forward for _ in range(self.sim_steps): self.sim.step() diff --git a/stanford_quad/pupper/policy.py b/stanford_quad/pupper/policy.py index a2fa130d..a8644bad 100644 --- a/stanford_quad/pupper/policy.py +++ b/stanford_quad/pupper/policy.py @@ -8,10 +8,11 @@ class HardPolicy: - def __init__(self, fps=60) -> None: + def __init__(self, fps=60, warmup=0) -> None: super().__init__() self.fps = fps + self.warmup = warmup self.config = Configuration() self.config.dt = 1 / fps @@ -33,13 +34,23 @@ def __init__(self, fps=60) -> None: print("swing time: ", self.config.swing_time) print("z clearance: ", self.config.z_clearance) print("x shift: ", self.config.x_shift) + self.step = 0 + + def act(self, velocity_horizontal=(0, 0), yaw_rate=0, normalized=False): + if self.step > self.warmup: + self.command.horizontal_velocity = np.array(velocity_horizontal) + else: + self.command.horizontal_velocity = np.array([0, 0]) - def act(self, velocity_horizontal=(0, 0), yaw_rate=0): - self.command.horizontal_velocity = np.array(velocity_horizontal) self.command.yaw_rate = yaw_rate self.state.quat_orientation = np.array([1, 0, 0, 0]) # Step the controller forward by dt self.controller.run(self.state, self.command) + if normalized: + self.state.joint_angles /= np.pi + + self.step += 1 + return self.state.joint_angles From 3cd466e95417966f6f1cccaf8bb67715379107e8 Mon Sep 17 00:00:00 2001 From: Florian Golemo Date: Wed, 7 Oct 2020 23:38:46 -0400 Subject: [PATCH 47/49] bugfix --- stanford_quad/__init__.py | 2 +- stanford_quad/envs/walking_env.py | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/stanford_quad/__init__.py b/stanford_quad/__init__.py index 2cc8fdd8..953891df 100644 --- a/stanford_quad/__init__.py +++ b/stanford_quad/__init__.py @@ -38,7 +38,7 @@ def make_imitation_env(trick): f"aSmooth_{action_smoothing}-" f"RandomZRot_{random_rot}-{headlessness}-v0" ) - # print(name) + print(name) register( id=name, entry_point="stanford_quad.envs:WalkingEnv", diff --git a/stanford_quad/envs/walking_env.py b/stanford_quad/envs/walking_env.py index ff2ef013..9c9c1085 100644 --- a/stanford_quad/envs/walking_env.py +++ b/stanford_quad/envs/walking_env.py @@ -160,5 +160,5 @@ def render(self, mode="human"): # todo: if the mode=="human" then this should open and display a # window a la "cv2.imshow('xxx',img), cv2.waitkey(10)" - img = self.sim.take_photo() + img, _ = self.sim.take_photo() return img From 96ceb4d7d0dc0ed5ee901323b1a1b7cf18cd5b7f Mon Sep 17 00:00:00 2001 From: Massimo Caccia Date: Thu, 15 Oct 2020 21:52:30 +0000 Subject: [PATCH 48/49] added support to change the episode length --- stanford_quad/__init__.py | 44 +++++++++++++++++++++------------------ 1 file changed, 24 insertions(+), 20 deletions(-) diff --git a/stanford_quad/__init__.py b/stanford_quad/__init__.py index 953891df..db8124dc 100644 --- a/stanford_quad/__init__.py +++ b/stanford_quad/__init__.py @@ -26,32 +26,36 @@ def make_imitation_env(trick): ACTION_SMOOTHING = [1, 2, 3, 4] RANDOM_ROT = [0, 1, 10, 100] ACTION_SCALING = [1.0, 2.0, 4.0] + list(np.arange(0.05, 0.5, 0.05)) +STEPS = [120, 240, 360] + for headlessness in HEADLESSNESS: for action_type in ACTION_TYPE: for action_smoothing in ACTION_SMOOTHING: for action_scaling in ACTION_SCALING: for random_rot in RANDOM_ROT: - name = ( - f"Pupper-Walk-{action_type}-" - f"aScale_{action_scaling:.2}-" - f"aSmooth_{action_smoothing}-" - f"RandomZRot_{random_rot}-{headlessness}-v0" - ) - print(name) - register( - id=name, - entry_point="stanford_quad.envs:WalkingEnv", - kwargs={ - "debug": (False if headlessness == "Headless" else True), - "steps": 120, - "relative_action": True if action_type == "Relative" else False, - "incremental_action": True if action_type == "Incremental" else False, - "action_scaling": action_scaling, - "action_smoothing": action_smoothing, - "random_rot": (0, 0, random_rot), - }, - max_episode_steps=120, + for steps in STEPS: + name = ( + f"Pupper-Walk-{action_type}-" + f"steps_{steps}-" + f"aScale_{action_scaling:.2}-" + f"aSmooth_{action_smoothing}-" + f"RandomZRot_{random_rot}-{headlessness}-v0" + ) + print(name) + register( + id=name, + entry_point="stanford_quad.envs:WalkingEnv", + kwargs={ + "debug": (False if headlessness == "Headless" else True), + "steps": steps, + "relative_action": True if action_type == "Relative" else False, + "incremental_action": True if action_type == "Incremental" else False, + "action_scaling": action_scaling, + "action_smoothing": action_smoothing, + "random_rot": (0, 0, random_rot), + }, + max_episode_steps=120, ) From bc0cc1f512f7cdfc3e8910799cd6a59fa68ced6b Mon Sep 17 00:00:00 2001 From: Massimo Caccia Date: Thu, 15 Oct 2020 22:56:42 +0000 Subject: [PATCH 49/49] bug in the new episode lenght --- stanford_quad/__init__.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/stanford_quad/__init__.py b/stanford_quad/__init__.py index db8124dc..c3cf7f9d 100644 --- a/stanford_quad/__init__.py +++ b/stanford_quad/__init__.py @@ -55,7 +55,7 @@ def make_imitation_env(trick): "action_smoothing": action_smoothing, "random_rot": (0, 0, random_rot), }, - max_episode_steps=120, + max_episode_steps=steps, )