From 5e4eecf2abbada3c91348738088891b8eaa35a1e Mon Sep 17 00:00:00 2001 From: paleziart <paleziart@laas.fr> Date: Tue, 17 Nov 2020 14:38:31 +0100 Subject: [PATCH] Clean, add comments, remove unused parts --- Controller.py | 149 ++------- MPC_Wrapper.py | 77 +---- Planner.py | 34 +- PyBulletSimulator.py | 57 +++- QP_WBC.py | 9 +- libexample_adder.so | Bin 115848 -> 116312 bytes solo12InvKin.py | 6 +- utils_mpc.py | 745 ++----------------------------------------- 8 files changed, 141 insertions(+), 936 deletions(-) diff --git a/Controller.py b/Controller.py index 06647184..27f156b9 100644 --- a/Controller.py +++ b/Controller.py @@ -4,17 +4,17 @@ import numpy as np import utils_mpc import time -# from TSID_Debug_controller_four_legs_fb_vel import controller from QP_WBC import controller -import processing as proc import MPC_Wrapper import pybullet as pyb from Planner import Planner import pinocchio as pin -from Planner import EulerToQuaternion class Result: + """Object to store the result of the control loop + It contains what is sent to the robot (gains, desired positions and velocities, + feedforward torques)""" def __init__(self): @@ -26,6 +26,7 @@ class Result: class dummyHardware: + """Fake hardware for initialisation purpose""" def __init__(self): @@ -37,6 +38,7 @@ class dummyHardware: class dummyDevice: + """Fake device for initialisation purpose""" def __init__(self): @@ -93,9 +95,8 @@ class Controller: self.enable_gepetto_viewer = False # Create Joystick, FootstepPlanner, Logger and Interface objects - self.joystick, self.fstep_planner, self.logger, self.interface, self.estimator = utils_mpc.init_objects( - dt_tsid, dt_mpc, N_SIMULATION, k_mpc, n_periods, T_gait, type_MPC, on_solo8, - predefined_vel) + self.joystick, self.logger, self.estimator = utils_mpc.init_objects( + dt_tsid, dt_mpc, N_SIMULATION, k_mpc, n_periods, T_gait, type_MPC, predefined_vel) # Enable/Disable hybrid control self.enable_hybrid_control = True @@ -113,33 +114,17 @@ class Controller: # Wrapper that makes the link with the solver that you want to use for the MPC # First argument to True to have PA's MPC, to False to have Thomas's MPC self.enable_multiprocessing = True - self.mpc_wrapper = MPC_Wrapper.MPC_Wrapper(type_MPC, dt_mpc, self.fstep_planner.n_steps, - k_mpc, self.fstep_planner.T_gait, self.q, self.enable_multiprocessing) - - ######################################################################## - # Gepetto viewer # - ######################################################################## + self.mpc_wrapper = MPC_Wrapper.MPC_Wrapper(type_MPC, dt_mpc, np.int(n_periods*T_gait/dt_mpc), + k_mpc, T_gait, self.q, self.enable_multiprocessing) # Initialisation of the Gepetto viewer self.solo = utils_mpc.init_viewer(self.enable_gepetto_viewer) - ######################################################################## - # PyBullet # - ######################################################################## - - # Initialisation of the PyBullet simulator - # self.pyb_sim = utils_mpc.pybullet_simulator(envID, use_flat_plane, enable_pyb_GUI, dt=dt_tsid) - - # Force monitor to display contact forces in PyBullet with red lines + # ForceMonitor to display contact forces in PyBullet with red lines # import ForceMonitor # myForceMonitor = ForceMonitor.ForceMonitor(pyb_sim.robotId, pyb_sim.planeId) - ######################################################################## - # Simulator # - ######################################################################## - # Define the default controller - # self.myController = controller(q_init, int(N_SIMULATION), dt_tsid, k_mpc, n_periods, T_gait, on_solo8) self.myController = controller(dt_tsid, int(N_SIMULATION)) self.envID = envID @@ -184,6 +169,11 @@ class Controller: self.compute(dDevice) def compute(self, device): + """Run one iteration of the main control loop + + Args: + device (object): Interface with the masterboard or the simulation + """ tic = time.time() @@ -191,7 +181,8 @@ class Controller: self.joystick.update_v_ref(self.k, self.velID) # Process state estimator - self.estimator.run_filter(self.k, self.planner.gait[0, 1:], device, self.planner.goals, self.planner.gait[0, 0]) + self.estimator.run_filter(self.k, self.planner.gait[0, 1:], + device, self.planner.goals, self.planner.gait[0, 0]) t_filter = time.time() self.t_list_filter[self.k] = t_filter - tic @@ -202,18 +193,18 @@ class Controller: oMb = pin.SE3(pin.Quaternion(self.q[3:7, 0:1]), self.q[0:3, 0:1]) self.v[0:3, 0:1] = oMb.rotation @ self.estimator.v_filt[0:3, 0:1] self.v[3:6, 0:1] = oMb.rotation @ self.estimator.v_filt[3:6, 0:1] - self.v[6:, 0] = self.estimator.v_filt[6:, 0] + self.v[6:, 0] = self.estimator.v_filt[6:, 0] # Update estimated position of the robot self.v_estim[0:3, 0:1] = oMb.rotation.transpose() @ self.joystick.v_ref[0:3, 0:1] self.v_estim[3:6, 0:1] = oMb.rotation.transpose() @ self.joystick.v_ref[3:6, 0:1] if not self.planner.is_static: self.q_estim[:, 0] = pin.integrate(self.solo.model, - self.q, self.v_estim * self.myController.dt) + self.q, self.v_estim * self.myController.dt) self.yaw_estim = (utils_mpc.quaternionToRPY(self.q_estim[3:7, 0]))[2, 0] else: self.planner.q_static[:, 0] = pin.integrate(self.solo.model, - self.planner.q_static, self.v_estim * self.myController.dt) + self.planner.q_static, self.v_estim * self.myController.dt) self.planner.RPY_static[:, 0:1] = utils_mpc.quaternionToRPY(self.planner.q_static[3:7, 0]) else: self.yaw_estim = 0.0 @@ -228,7 +219,7 @@ class Controller: pyb.resetDebugVisualizerCamera(cameraDistance=0.6, cameraYaw=45, cameraPitch=-39.9, cameraTargetPosition=[device.dummyHeight[0], device.dummyHeight[1], 0.0]) - #Â Update reference height + # Update reference height """if self.k < 1000: self.planner.h_ref += 0.00005""" @@ -258,7 +249,7 @@ class Controller: t_mpc = time.time() self.t_list_mpc[self.k] = t_mpc - t_planner - # Target state for the inverse kinematics + # Target state for the whole body control if not self.planner.is_static: self.x_f_mpc[0] = self.q_estim[0, 0] self.x_f_mpc[1] = self.q_estim[1, 0] @@ -338,99 +329,3 @@ class Controller: self.k += 1 return 0.0 - - #################### - # END OF MAIN LOOP # - #################### - - def launch_simu(self, device): - """# Default position after calibration - q_init = np.array([0.0, 0.8, -1.6, 0, 0.8, -1.6, 0, -0.8, 1.6, 0, -0.8, 1.6]) - - class dummyDevice: - - def __init__(self): - - pass - - dDevice = dummyDevice() - dDevice.q_mes = q_init - dDevice.v_mes = np.zeros(12) - dDevice.baseLinearAcceleration = np.zeros(3) - dDevice.baseAngularVelocity = np.zeros(3) - dDevice.baseOrientation = np.array([0.0, 0.0, 0.0, 1.0]) - tau = self.compute(dDevice)""" - - tic = time.time() - - for k in range(1, int(self.N_SIMULATION)): - - device.UpdateMeasurment() - - tau = self.compute(device) - - # device.SetDesiredJointTorque(tau) - device.SetKp(self.result.P) - device.SetKd(self.result.D) - device.SetQdes(self.result.q_des) - device.SetVdes(self.result.v_des) - # device.SetTauFF(self.result.tau_ff) - - device.SendCommand(WaitEndOfCycle=True) - - print("###") - print("TSID: ", self.myController.qtsid.ravel()) - print("TAU: ", tau.ravel()) - - if self.enable_pyb_GUI: - # Update the PyBullet camera on the robot position to do as if it was attached to the robot - pyb.resetDebugVisualizerCamera(cameraDistance=0.6, cameraYaw=45, cameraPitch=-39.9, - cameraTargetPosition=[self.estimator.q_filt[0, 0], - self.estimator.q_filt[1, 0], 0.0]) - - # Process PyBullet - # proc.process_pybullet(self.pyb_sim, self.k, self.envID, self.velID, tau) - - # Call logger object to log various parameters - # logger.call_log_functions(k, pyb_sim, joystick, fstep_planner, interface, mpc_wrapper, myController, - # False, pyb_sim.robotId, pyb_sim.planeId, solo) - # logger.log_state(k, pyb_sim, joystick, interface, mpc_wrapper, solo) - # logger.log_forces(k, interface, myController, pyb_sim.robotId, pyb_sim.planeId) - # logger.log_footsteps(k, interface, myController) - # logger.log_fstep_planner(k, fstep_planner) - # logger.log_tracking_foot(k, myController, solo) - - tac = time.time() - print("Average computation time of one iteration: ", - (tac-tic)/self.N_SIMULATION) - print("Computation duration: ", tac-tic) - print("Simulated duration: ", self.N_SIMULATION*self.dt_tsid) - print("Max loop time: ", np.max(self.t_list_loop[10:])) - - # Close the parallel process if it is running - if self.enable_multiprocessing: - print("Stopping parallel process") - self.mpc_wrapper.stop_parallel_loop() - - print("END") - - # Plot processing duration of each step of the control loop - """ - import matplotlib.pylab as plt - plt.figure() - plt.plot(t_list_filter[1:], '+', color="orange") - plt.plot(t_list_states[1:], 'r+') - plt.plot(t_list_fsteps[1:], 'g+') - plt.plot(t_list_mpc[1:], 'b+') - plt.plot(t_list_tsid[1:], '+', color="violet") - plt.plot(t_list_loop[1:], 'k+') - plt.title("Time for state update + footstep planner + MPC communication + Inv Dyn + PD+") - plt.show(block=True)""" - - # Disconnect the PyBullet server (also close the GUI) - pyb.disconnect() - - # Plot graphs of the state estimator - # estimator.plot_graphs() - - return self.logger diff --git a/MPC_Wrapper.py b/MPC_Wrapper.py index 41acab59..bf613767 100644 --- a/MPC_Wrapper.py +++ b/MPC_Wrapper.py @@ -8,11 +8,12 @@ from utils_mpc import quaternionToRPY class Dummy: + """Dummy class to store variables""" def __init__(self): - self.xref = None - self.fsteps = None + self.xref = None # Desired trajectory + self.fsteps = None # Desired location of footsteps pass @@ -27,6 +28,7 @@ class MPC_Wrapper: n_steps (int): Number of time steps in one gait cycle k_mpc (int): Number of inv dyn time step for one iteration of the MPC T_gait (float): Duration of one period of gait + q_init (array): the default position of the robot multiprocessing (bool): Enable/Disable running the MPC with another process """ @@ -44,7 +46,7 @@ class MPC_Wrapper: self.mpc_type = mpc_type self.multiprocessing = multiprocessing - if multiprocessing: + if multiprocessing: # Setup variables in the shared memory self.newData = Value('b', False) self.newResult = Value('b', False) self.dataIn = Array('d', [0.0] * (1 + (np.int(self.n_steps)+1) * 12 + 13*20)) @@ -59,6 +61,7 @@ class MPC_Wrapper: self.mpc = MPC_crocoddyl.MPC_crocoddyl( dt=dt, T_mpc=T_gait, mu=0.9, inner=False, linearModel=True, n_period=int((dt * n_steps)/T_gait)) + # Setup initial result for the first iteration of the main control loop x_init = np.zeros(12) x_init[0:3] = q_init[0:3, 0] x_init[3:6] = quaternionToRPY(q_init[3:7, 0]).ravel() @@ -73,9 +76,9 @@ class MPC_Wrapper: fstep_planner (object): FootstepPlanner object of the control loop """ - if self.multiprocessing: + if self.multiprocessing: # Run in parallel process self.run_MPC_asynchronous(k, fstep_planner) - else: + else: # Run in the same process than main loop self.run_MPC_synchronous(k, fstep_planner) return 0 @@ -94,7 +97,6 @@ class MPC_Wrapper: return self.last_available_result else: return self.last_available_result - # raise ValueError("Error: something went wrong with the MPC, result not available.") else: # Directly retrieve desired contact force of the synchronous MPC object return self.f_applied @@ -114,32 +116,15 @@ class MPC_Wrapper: # Run the MPC to get the reference forces and the next predicted state # Result is stored in mpc.f_applied, mpc.q_next, mpc.v_next - """print(dt, n_steps, k, T_gait) - print(np.round(interface.lC.ravel(), decimals=2)) - print(np.round(interface.abg.ravel(), decimals=2)) - print(np.round(interface.lV.ravel(), decimals=2)) - print(np.round(interface.lW.ravel(), decimals=2)) - print(interface.l_feet.ravel()) - print(joystick.v_ref.ravel()) - print(fstep_planner.fsteps)""" - if self.mpc_type: # OSQP MPC - # Replace NaN values by 0.0 + # Replace NaN values by 0.0 (shared memory cannot handle np.nan) fstep_planner.fsteps_mpc[np.isnan(fstep_planner.fsteps_mpc)] = 0.0 self.mpc.run(np.int(k), fstep_planner.xref.copy(), fstep_planner.fsteps_mpc.copy()) else: # Crocoddyl MPC self.mpc.solve(k, fstep_planner) - """tmp_lC = interface.lC.copy() - tmp_lC[2, 0] += dt * interface.lV[2, 0] - tmp_abg = interface.abg + dt * interface.lW - tmp_abg[2, 0] = 0.0 - tmp_lfeet = interface.l_feet - dt * interface.lV - tmp_xref = fstep_planner.xref.copy() - tmp_xref """ - # Output of the MPC self.f_applied = self.mpc.get_latest_result() @@ -157,18 +142,8 @@ class MPC_Wrapper: self.newData, self.newResult, self.dataIn, self.dataOut, self.running)) p.start() - # print("Setting Data") + # Stacking data to send them to the parallel process self.compress_dataIn(k, fstep_planner) - """print("Sending") - print(dt, n_steps, k, T_gait) - print(interface.lC.ravel()) - print(interface.abg.ravel()) - print(interface.lV.ravel()) - print(interface.lW.ravel()) - print(interface.l_feet.ravel()) - print(joystick.v_ref.ravel()) - print(fstep_planner.fsteps)""" - self.newData.value = True return 0 @@ -196,34 +171,11 @@ class MPC_Wrapper: # Retrieve data thanks to the decompression function and reshape it kf, xref_1dim, fsteps_1dim = self.decompress_dataIn(dataIn) - # print("Receiving") - """dt = dt[0] - nsteps = np.int(nsteps[0]) - k = k[0] - T_gait = T_gait[0] - lC = np.reshape(lC, (3, 1)) - abg = np.reshape(abg, (3, 1)) - lV = np.reshape(lV, (3, 1)) - lW = np.reshape(lW, (3, 1)) - l_feet = np.reshape(l_feet, (3, 4)) - xref = np.reshape(xref, (12, nsteps+1)) - x0 = np.reshape(x0, (12, 1)) - v_ref = np.reshape(v_ref, (6, 1)) - fsteps = np.reshape(fsteps, (20, 13))""" - + # Reshaping 1-dimensional data k = int(kf[0]) xref = np.reshape(xref_1dim, (12, self.n_steps+1)) fsteps = np.reshape(fsteps_1dim, (20, 13)) - """print(dt, nsteps, k, T_gait) - print(lC.ravel()) - print(abg.ravel()) - print(lV.ravel()) - print(lW.ravel()) - print(l_feet.ravel()) - print(v_ref.ravel()) - print(fsteps)""" - # Create the MPC object of the parallel process during the first iteration if k == 0: # loop_mpc = MPC.MPC(self.dt, self.n_steps, self.T_gait) @@ -242,8 +194,7 @@ class MPC_Wrapper: dummy_fstep_planner.fsteps = fsteps loop_mpc.solve(k, dummy_fstep_planner) - # Store the result (predicted trajectory + desired forces) in the shared memory - # print("X_F: ", loop_mpc.get_latest_result().tolist()) + # Store the result (predicted state + desired forces) in the shared memory self.dataOut[:] = loop_mpc.get_latest_result().tolist() # Set shared variable to true to signal that a new result is available @@ -260,8 +211,6 @@ class MPC_Wrapper: fstep_planner (object): FootstepPlanner object of the control loop """ - # print("Compressing dataIn") - # Replace NaN values by 0.0 to be stored in C-type arrays fstep_planner.fsteps[np.isnan(fstep_planner.fsteps)] = 0.0 @@ -279,8 +228,6 @@ class MPC_Wrapper: dataIn (Array): shared array that contains the data the asynchronous MPC will use as inputs """ - # print("Decompressing dataIn") - # Sizes of the different variables that are stored in the C-type array sizes = [0, 1, (np.int(self.n_steps)+1) * 12, 13*20] csizes = np.cumsum(sizes) diff --git a/Planner.py b/Planner.py index 1cd7c650..538bf077 100644 --- a/Planner.py +++ b/Planner.py @@ -765,20 +765,6 @@ class Planner: [left[0] * right[1] - left[1] * right[0]]]) -def EulerToQuaternion(roll_pitch_yaw): - roll, pitch, yaw = roll_pitch_yaw - sr = math.sin(roll/2.) - cr = math.cos(roll/2.) - sp = math.sin(pitch/2.) - cp = math.cos(pitch/2.) - sy = math.sin(yaw/2.) - cy = math.cos(yaw/2.) - qx = sr * cp * cy - cr * sp * sy - qy = cr * sp * cy + sr * cp * sy - qz = cr * cp * sy - sr * sp * cy - qw = cr * cp * cy + sr * sp * sy - return [qx, qy, qz, qw] - def test_planner(): @@ -885,7 +871,7 @@ def test_planner(): # Following the mpc reference trajectory perfectly q[0:3, 0] = planner.xref[0:3, 1].copy() # np.array(pin.integrate(model, q, b_v * dt)) - q[3:7, 0] = EulerToQuaternion(planner.xref[3:6, 1]) + q[3:7, 0] = utils_mpc.EulerToQuaternion(planner.xref[3:6, 1]) v[0:3, 0] = planner.xref[6:9, 1].copy() v[3:6, 0] = planner.xref[9:12, 1].copy() k += 1 @@ -1010,7 +996,7 @@ def test_planner_mpc(): # Run planner """if k == 100: - q[3:7, 0] = EulerToQuaternion([0.2, 0.0, 0.0])""" + q[3:7, 0] = utils_mpc.EulerToQuaternion([0.2, 0.0, 0.0])""" planner.run_planner(k, k_mpc, q[0:7, 0:1], v[0:6, 0:1], joystick.v_ref) # Logging output of foot trajectory generator @@ -1042,12 +1028,12 @@ def test_planner_mpc(): # Following the mpc reference trajectory perfectly """q[0:3, 0] = planner.xref[0:3, 1].copy() # np.array(pin.integrate(model, q, b_v * dt)) - q[3:7, 0] = EulerToQuaternion(planner.xref[3:6, 1]) + q[3:7, 0] = utils_mpc.EulerToQuaternion(planner.xref[3:6, 1]) v[0:3, 0] = planner.xref[6:9, 1].copy() v[3:6, 0] = planner.xref[9:12, 1].copy()""" q[0:3, 0] = x_f_mpc[0:3] - q[3:7, 0] = EulerToQuaternion(x_f_mpc[3:6]) + q[3:7, 0] = utils_mpc.EulerToQuaternion(x_f_mpc[3:6]) v[0:3, 0] = x_f_mpc[6:9] v[3:6, 0] = x_f_mpc[9:12] k += 1 @@ -1229,7 +1215,7 @@ def test_planner_mpc_tsid(): for i in range(planner.xref.shape[1]): planner.xref[0:3, i] = oMl.inverse() * planner.xref[0:3, i:(i+1)] - planner.xref[3:6, i] = pin.rpy.matrixToRpy(oMl.rotation.transpose() @ pin.Quaternion(np.array([EulerToQuaternion(planner.xref[3:6, i])]).T).toRotationMatrix()) + planner.xref[3:6, i] = pin.rpy.matrixToRpy(oMl.rotation.transpose() @ pin.Quaternion(np.array([utils_mpc.EulerToQuaternion(planner.xref[3:6, i])]).T).toRotationMatrix()) planner.xref[6:9, i:(i+1)] = oMl.rotation.transpose() @ planner.xref[6:9, i:(i+1)] planner.xref[9:12, i:(i+1)] = oMl.rotation.transpose() @ planner.xref[9:12, i:(i+1)] @@ -1252,7 +1238,7 @@ def test_planner_mpc_tsid(): x_f_mpc = mpc_wrapper.get_latest_result() """b_x_f_mpc = x_f_mpc.copy() b_x_f_mpc[0:3] = (oMl * np.array([x_f_mpc[0:3]]).transpose()).ravel() - b_x_f_mpc[3:6] = pin.rpy.matrixToRpy(oMl.rotation @ pin.Quaternion(np.array([EulerToQuaternion(x_f_mpc[3:6])]).T).toRotationMatrix()) + b_x_f_mpc[3:6] = pin.rpy.matrixToRpy(oMl.rotation @ pin.Quaternion(np.array([utils_mpc.EulerToQuaternion(x_f_mpc[3:6])]).T).toRotationMatrix()) b_x_f_mpc[6:9] = (oMl.rotation @ np.array([x_f_mpc[6:9]]).transpose()).ravel() b_x_f_mpc[9:12] = (oMl.rotation @ np.array([x_f_mpc[9:12]]).transpose()).ravel() for i in range(4): @@ -1281,7 +1267,7 @@ def test_planner_mpc_tsid(): plt.show(block=True)""" """q[0:3, 0] = x_f_mpc[0:3] - q[3:7, 0] = EulerToQuaternion(x_f_mpc[3:6]) + q[3:7, 0] = utils_mpc.EulerToQuaternion(x_f_mpc[3:6]) v[0:3, 0] = x_f_mpc[6:9] v[3:6, 0] = x_f_mpc[9:12]""" @@ -1368,11 +1354,11 @@ def test_planner_mpc_tsid(): # Following the mpc reference trajectory perfectly """q[0:3, 0] = planner.xref[0:3, 1].copy() # np.array(pin.integrate(model, q, b_v * dt)) - q[3:7, 0] = EulerToQuaternion(planner.xref[3:6, 1]) + q[3:7, 0] = utils_mpc.EulerToQuaternion(planner.xref[3:6, 1]) v[0:3, 0] = planner.xref[6:9, 1].copy() v[3:6, 0] = planner.xref[9:12, 1].copy()""" """q[0:3, 0] = x_f_mpc[0:3] - q[3:7, 0] = EulerToQuaternion(x_f_mpc[3:6]) + q[3:7, 0] = utils_mpc.EulerToQuaternion(x_f_mpc[3:6]) v[0:3, 0] = x_f_mpc[6:9] v[3:6, 0] = x_f_mpc[9:12]""" @@ -1401,7 +1387,7 @@ def test_planner_mpc_tsid(): # if k == 1000: # oMb = pin.SE3(pin.utils.rotate('z', 3.1415/2), np.array([0.0, 0.0, 0.0])) - # q[3:7, 0] = np.array([0, 0, 0.7009093, 0.7132504]) #pin.Quaternion(EulerToQuaternion(pin.rpy.matrixToRpy(oMb.rotation @ pin.Quaternion(q[3:7, 0:1]).toRotationMatrix()))) + # q[3:7, 0] = np.array([0, 0, 0.7009093, 0.7132504]) #pin.Quaternion(utils_mpc.EulerToQuaternion(pin.rpy.matrixToRpy(oMb.rotation @ pin.Quaternion(q[3:7, 0:1]).toRotationMatrix()))) while (time.time() - t_start) < 0.002: pass diff --git a/PyBulletSimulator.py b/PyBulletSimulator.py index e46b1767..74688139 100644 --- a/PyBulletSimulator.py +++ b/PyBulletSimulator.py @@ -1,8 +1,18 @@ +import numpy as np +import pybullet as pyb # Pybullet server +import pybullet_data +import time as time +import sys +import pinocchio as pin +from utils_mpc import quaternionToRPY + + class pybullet_simulator: """Wrapper for the PyBullet simulator to initialize the simulation, interact with it and use various utility functions Args: + q_init (array): the default position of the robot envID (int): identifier of the current environment to be able to handle different scenarios use_flat_plane (bool): to use either a flat ground or a rough ground enable_pyb_GUI (bool): to display PyBullet GUI or not @@ -462,6 +472,7 @@ class pybullet_simulator: class Hardware(): + """Dummy class that simulates the Hardware class used to communicate with the real masterboard""" def __init__(self): @@ -489,6 +500,9 @@ class Hardware(): class PyBulletSimulator(): + """Class that wraps a PyBullet simulation environment to seamlessly switch between the real robot or + simulation by having the same interface in both cases (calling the same functions/variables) + """ def __init__(self): @@ -516,6 +530,16 @@ class PyBulletSimulator(): self.tau_ff = np.zeros(12) def Init(self, calibrateEncoders=False, q_init=None, envID=0, use_flat_plane=True, enable_pyb_GUI=False, dt=0.002): + """Initialize the PyBullet simultor with a given environment and a given state of the robot + + Args: + calibrateEncoders (bool): dummy variable, not used for simulation but used for real robot + q_init (12 x 0 array): initial angular positions of the joints of the robot + envID (int): which environment should be loaded in the simulation + use_flat_plane (bool): to use either a flat ground or a rough ground + enable_pyb_GUI (bool): to display PyBullet GUI or not + dt (float): time step of the simulation + """ # Initialisation of the PyBullet simulator self.pyb_sim = pybullet_simulator(q_init, envID, use_flat_plane, enable_pyb_GUI, dt) @@ -526,6 +550,8 @@ class PyBulletSimulator(): return def UpdateMeasurment(self): + """Retrieve data about the robot from the simulation to mimic what the masterboard does + """ # Position and velocity of actuators jointStates = pyb.getJointStates(self.pyb_sim.robotId, self.revoluteJointIndices) # State of all joints @@ -567,23 +593,48 @@ class PyBulletSimulator(): return def SetDesiredJointTorque(self, torques): + """Set desired joint torques + Args: + torques (12 x 0): desired articular feedforward torques + """ # Save desired torques in a storage array self.tau_ff = torques.copy() return def SetDesiredJointPDgains(self, P, D): + """Set desired PD gains for articular low level control + + Args: + P (12 x 0 array): desired position gains + D (12 x 0 array): desired velocity gains + """ self.P = P self.D = D def SetDesiredJointPosition(self, q_des): + """Set desired joint positions + + Args: + q_des (12 x 0 array): desired articular positions + """ self.q_des = q_des def SetDesiredJointVelocity(self, v_des): + """Set desired joint velocities + + Args: + v_des (12 x 0 array): desired articular velocities + """ self.v_des = v_des def SendCommand(self, WaitEndOfCycle=True): + """Send control commands to the robot + + Args: + WaitEndOfCycle (bool): wait to have simulation time = real time + """ # Compute PD torques tau_pd = self.P * (self.q_des - self.q_mes) + self.D * (self.v_des - self.v_mes) @@ -591,12 +642,11 @@ class PyBulletSimulator(): # Save desired torques in a storage array self.jointTorques = tau_pd + self.tau_ff - # print("FF+PD: ", self.jointTorques.ravel()) - # Set control torque for all joints pyb.setJointMotorControlArray(self.pyb_sim.robotId, self.pyb_sim.revoluteJointIndices, controlMode=pyb.TORQUE_CONTROL, forces=self.jointTorques) + # Apply arbitrary external forces to the robot base in the simulation # self.pyb_sim.apply_external_force(self.cpt, 1000, 1000, np.array([0.0, +8.0, 0.0]), np.zeros((3,))) # self.pyb_sim.apply_external_force(self.cpt, 4250, 500, np.array([+5.0, 0.0, 0.0]), np.zeros((3,))) # self.pyb_sim.apply_external_force(self.cpt, 5250, 500, np.array([0.0, +5.0, 0.0]), np.zeros((3,))) @@ -615,6 +665,8 @@ class PyBulletSimulator(): return def Print(self): + """Print simulation parameters in the console""" + np.set_printoptions(precision=2) # print(chr(27) + "[2J") print("#######") @@ -627,6 +679,7 @@ class PyBulletSimulator(): sys.stdout.flush() def Stop(self): + """Stop the simulation environment""" # Disconnect the PyBullet server (also close the GUI) pyb.disconnect() diff --git a/QP_WBC.py b/QP_WBC.py index d6431fc8..4b114323 100644 --- a/QP_WBC.py +++ b/QP_WBC.py @@ -30,6 +30,7 @@ class controller(): # Logging self.k_log = 0 self.log_feet_pos = np.zeros((3, 4, N_SIMULATION)) + self.log_feet_err = np.zeros((3, 4, N_SIMULATION)) self.log_feet_vel = np.zeros((3, 4, N_SIMULATION)) self.log_feet_pos_target = np.zeros((3, 4, N_SIMULATION)) self.log_feet_vel_target = np.zeros((3, 4, N_SIMULATION)) @@ -74,8 +75,9 @@ class controller(): # Log position, velocity and acceleration references for the feet indexes = [10, 18, 26, 34] for i in range(4): - self.log_feet_pos[:, i, self.k_log] = self.invKin.robot.data.oMf[indexes[i]].translation - self.log_feet_vel[:, i, self.k_log] = pin.getFrameVelocity(self.invKin.robot.model, self.invKin.robot.data, + self.log_feet_pos[:, i, self.k_log] = self.invKin.rdata.oMf[indexes[i]].translation + self.log_feet_err[:, i, self.k_log] = self.invKin.pfeet_err[i] + self.log_feet_vel[:, i, self.k_log] = pin.getFrameVelocity(self.invKin.rmodel, self.invKin.rdata, indexes[i], pin.LOCAL_WORLD_ALIGNED).linear self.log_feet_pos_target[:, :, self.k_log] = planner.goals[:, :] # + np.array([[0.0, 0.0, q[2, 0] - planner.h_ref]]).T self.log_feet_vel_target[:, :, self.k_log] = planner.vgoals[:, :] @@ -163,9 +165,10 @@ class controller(): plt.subplot(3, 4, index12[i], sharex=ax0) plt.plot(t_range, self.log_feet_pos[i % 3, np.int(i/3), :], color='b', linewidth=3, marker='') + plt.plot(t_range, self.log_feet_err[i % 3, np.int(i/3), :], color='g', linewidth=3, marker='') plt.plot(t_range, self.log_feet_pos_target[i % 3, np.int(i/3), :], color='r', linewidth=3, marker='') plt.plot(t_range, self.log_contacts[np.int(i/3), :] * np.max(self.log_feet_pos[i % 3, np.int(i/3), :]), color='k', linewidth=3, marker='') - plt.legend([lgd_Y[i % 3] + " " + lgd_X[np.int(i/3)]+"", lgd_Y[i % 3] + " " + lgd_X[np.int(i/3)]+" Ref", "Contact state"]) + plt.legend([lgd_Y[i % 3] + " " + lgd_X[np.int(i/3)]+"", "error", lgd_Y[i % 3] + " " + lgd_X[np.int(i/3)]+" Ref", "Contact state"]) plt.suptitle("Reference positions of feet (world frame)") lgd_X = ["FL", "FR", "HL", "HR"] diff --git a/libexample_adder.so b/libexample_adder.so index 9ed140fc1a10e24c9bb2e73649c5cef8507c1b04..62a554a96cfb0b74bcbd36c63d0052d80711cbc7 100755 GIT binary patch literal 116312 zcmeFa3w%>W7C(N|hg3ik5wN;Gf_Al_KvF2Q3YyXeZY0G>K@lHmX$y2IZEaI1Dp+l+ z#2Bq_)@OaK;Ipf%%c8F3jS5=u!9!OnzHX>Wg%wd(`um=lxyd9=Dj@Rv{Xd`o)o|}Q z_sp3yXU?2CbMD;R8|=<;aRx)YB93_F0>yx9(*qn~6ZozFCM-W}N`}%yu_>o1r!v|^ z{YI2?sg;-0&x&GZRD?YSKXnwpuZ|kX@cMaH9|kHlMt;`I#Q~&pE$8uaE$8ua`q@SV zIP`N82bBbz>9?L2>vB#Jbo!ZS>2Q7NDWdD<Q+dJ2^B1B%{j8U}1m#H1gFQ@waFVDm zmR^>L2I*(f9M-me;6WWZe&Q6R*VdEzeg3zNZ#m!Hf5o$ZUQzVch-FNZb+~^eepFvi z{FWwPzVxpv)v;$hS-B`ly;C{sgtp`Al>t!S-L|6R<KuhWYdgbwnkDYG{GMtrHSW(t zQgT{OJ7z<VxU8H@CiJv4_qr?Frj(jCnd)+t+ALe`(ytfan&dt0*h>=5GA)fWD1F~P zqqboDS*HH$4YiY=Gnn#iNjY=Pi6ynSDM{BS-jz?XT!o*0TrDo#I2Yhoh+h$Y#rV-N zlb_hXf5E?V@T(BGYjCc_&x7Aw{A%!{<9hrS;CBOlwfNnLUju%0+{{mk7w6l=wSKxC z7mWhA7iTdflm`XwA#r{L=SRi$<Kp~;I6sN=Q{wt*oR{MFoPeLl`33y`j^E4py@KDX z_$|ZlU-&J@?=}41!0%1`R^Yb^zt#Ay!EYUY>+yRVzjyGXV*@`a@8aBw-zNMv<M#o6 zAL6$aKRUMalk%}Re~R-CaZRV4_<e!jSNMI6UjV;${Pg2HT<jLW_c-sx@4xu{fZsm+ z==c%8pV*b6{14|&aZOGGrlBO@cMN{V;@1nmlX~ZGoZ{*^$K7w_zMbX6{*?X07sr^7 z9qoDl_U!8m{<(C-(n*thRJ_=F;=tQJn||QI;w{Vk-}kv>>^aVw^d50Tr{3DjFsvlu zm~(p-xRyPgn|b|`ZRb3A?u>I1YfDnU7+^N^D|)h{se1DFzWX%Gg)84U=f;noGCj26 zm*s!*zMC;^?2j+MwI=7m{E7Fp4ZQBU4-?-0<indv{(H%b?{9eEo!71~U0c2OgO&F_ zcK5{E$tym*WqR+eJyt$G|ALp!`EcKx%Nw4~?S1(<561u8Q1j}7?a#!g<xE-DKli<1 zPw$-HoaDaarpxD!Jh#ucwmug;IQNzF@=iLiY08uLP3}2o+`n$EczoOCjl(wlXPn=# z`N^kCPs%&(iND<XXV0)d*&mF%<w?i3U$sjo_vl}jwe$1l2Wx))VdgD`xkJ-NFaP4# zi!c0T^B1T8)NsXo<C?kC_C3(&-pXsg9yg_P!QI7M?tkj6bDR5(?_79RNy4^krk-;3 zjdMKhnFH>6pmmA!(G%Zkd^5rR&duLFyzto9l4d-;>V?G@mYSBm`Ogn}Pn!1CDR<nx z;g`qX^}dk%NspCf7d-M&$wj*#$vMza<L%>}b<&^*?=z0yaNm7r^xBg-Ft67ZNAW9< zFMaHr@@IF>Pp@A3i@R6G>)JIN_V};7VDR8O`&$bdUS9p{IW+^k`(4V;`AzM^6!#te z3wEB>yzrg9%Rj&C`u@(Ib4DC^aH(PJrgz%k-`(e>Mb~Uk{rklCpO`)DPit0wd-YiR zhu_SYIJw8g!#)}|;{N)~H|{Uql5lqR!~gv9*~bl=h7Ne?;ujXK7+jLj{O`--KL6sW zrolUBo~BHzdiVP)AHF%TV}QBh`91}OttULUc<1~{@7=%Qmx}|J&tF$r`(;Di%{8C> znzHVjro|Z-$8UYV^&Z#PUtPZU)?=U9xwhH-X#GXcJ+S+o_j|1T@}e~#xcs+%bJ^&n z|9R<!9ybl&yX5-Twyo+VrE|_w$6mbora{mA^4RAYiyjzUe9w->6H=~8aNnVuceL}J zCn?JDQEp`PRTTW+<+ychbbQOG==jHN(ed}d>qq0?_k!s72S-H5m&TCOJ|#N+f)k^+ zcM@89Mwiwq%76=_^Vx2Xjvszrbo|JK==DD7ijIFhh8_luiO#<)M!og@qtkn#&uIN# z5rh7j7<#zL5}p4sG5Y1D3DN64Yjkuzd&fn`&rXkye=|nEl${@)zQPe5KNQM|W}i;z zIhx*Xg1woe*v}6!<T=nQI{!g2^xU2sz24<9#$9y``&kSjqqWNvLk|}p7oC1XjQ%pG zMW;X28XdpL6dk`E@nkeP2gT@@e+-X7AEV#b$7t_WG5Yu8k<t09&glKpX^T!jGlo1( zeWKHki!mOTK{?U%W6O$;9}+`9witSt6~oU=h+&^=W5{zR`Z3yg>A+ZtCVys1bo@;* z{M#wu1C#D@d=x{T`7!$Orx@eq+!*?|0UxbhKg7`U2Qlo#0Ljf=q*s*pV%Yh@812f4 z!KXuwu1{Z#d4I#P(djE=_!*}yI{nlbc6DwH`JZ9_q_<*wlq=&Kp_3(N(Y)MS>3EhS zP7wIFFmDc2`Y5(Pkp>mzMS&kah|^o1;|QJJ2fHQurjt1Rp9KAr>4N{u9AW3Tm3sI+ zs@EkJP5{~AVfFS?EExkCoGkDU59RdD5%n$x!DC9YV$0$5je`C;%)i9nChC1&;0Hqg zgs*svBXs^IfPIx?m8tg%LUCG$#qvO<pOPf<4P*y&oEFF1`_75HL5Uo#?7o=OCr8Nt z;9ya2g#7Jb$mD#DGq^?YIdd}SZx;Cnzra7h_(RVp^Lj54__xt~;?wpFM+_7A9MO-8 z=*M#fek0CA?`q-*-B(;G_%uiGIRU{N(VK*wz+Bm};&iV6wy`LPL)ZT?qFv3)7+U#- zi>rKP6nw-&8SaQ3UY&k9hjl&VnK^yOQjXW_os98I@|d6G_y_n&IUD^#_@*X~Ky~bh zzlh{KNm0jfIpH?hQGkDm-qOV3WB5rq5#xgTy;k(QP2jJG!U?ZN^l#62&ZoJF6Y6}1 zqaclo7BMdR3qIFna{5-$?=K2`HpVH*)3Kf-J{S1!;a3UY_zFjSh<4KP0~|DK?-CBX zgr1KT_FwxF#}DBrW%9{f5490`a3XFbIr9f_2D<&s%H{3VM4m2L@HsAz)7PHD>Gl3f z?9JtAdyEtQS<r96yd14vk4)nH^CR?m_W)s6*#j8|xLJ1mP4H<J`hi;5amJaPe{+N% zTg>F_r_@C7AA*LEJv2t>;j(PrE^{((7ph}NDnOFIqKU)$c&~(Dgm0rn299e)$2Xwi zti2KP{DY0_eoAA6JhiD@59>2|du@!HqFizsm$NBC&K2l?l7CqQ{yrz?(<1td{2CpF zX<Qz&FtmGx{cJd!<0Jj~myAyz#VqXh2F^wqAoSBF{2sy>cH9R8qxMGn=lcYGzR;)c zucn^C>0LrUy1kt?k?X%r)GOS9GP;M5^D$nZKECF`pVN4pD)gq?$qTRt!rLOouP2N1 z$?wbi>s)?P644OWk8g4Q8~91N>qL%k`Wr{Y3;G`gpBB;YeFeQq=zmGXcv;em^J#vJ z6YAsQ9A@VyDT^Zd@fx9jo6z$>!GFuSoKNF(9AOrC>!p<2JxOV{>y-S)_HkSftr7Bk zGMwX=2s^Y0K4%KQ(JcIiKCZW8ea-B-i4*GjAB}=!hqEH&KN<5i>3^%>Zxj40PvG<w z5%lN7kI_6{8!_I0V*2T)R7A+{P2%$83w;^||BnnpKTR9~wX<VA1_H_7_ymXV5cq@% zTpmk=JS(9eqL1{Sp9%lDB!d1m(O(s!zjQx8QuKSHkW=@cBOoxdx5v34`aHOKJjb{G z$nhHVMaNsh{%wK}n$M0)`f<Ir<_u)8&i^@K&&_Xhx<@fi=qT$${et*m02GA--NcT1 z*g4@_1-_@iSI6+TePLH5zv}}|c$w&cY3J~MPmb_oo6VfwBH{{t9^WYBuNCn_zNq&N zICkQ16Z2h`z)ukKxGh5eFA0BA`z$9MCg{J!z$88`B2LKQ%~tLb@o>vSobXyf{}Vcb z=vxIJv%n9V#Py?y`EItr_Z0C@M}+>zi1FAW<P_w}d1rI}rik(Tz8DvaBic0vadltP z!^51z&q96-3*e7aZaYCBL<LVl57dusq8~-KE0aM+?W%3!gz<v@>p>jvije1itY3(} z`DsoV5cGptyOO*3nSoF^(^~|e69;m9MMS^<-O9(^)QI+WLSW((8J|A|feGKz#09~$ z$d0FB&xCIh;|T7H9YevN@TM0zEX-56Ti8!VM7_!9ih70oV%RBLCy0I*<67qr6*K<% z5%t=IpKNR5_3D0dX%6SpBIZGu6FbHX=X_fJ&fzx%K2h|StBE6E#_Sj-{GRJE4(ooP zJ)84s{+#1=`cBkKdT18@M8_}B5O^`c-olG1KfzCu-)<7)H&x(=V?2_dcSY!JN>9!w z(!Z^RKWBbM=<OWACuuyVZxwQG6^ef2RL;L9g8v<V;{MGf<~7~F8DO7}LC(feFfbfC z{wZOH9ikum$MK49Kabbj@;ZmV?#0gw9K7D<h<d+)gCf0EEaP<P{G`n5&G9DD@A^D` z9~?f>D}UpJj|%#|g5D<Rj}!P$CUQM1Vt&-+zdup%5&a9ZXGe~hzidx%c&xx5E80~n z+Lb2oew;}jTN6j<e71=BIzOVlH!wTzr{oKLqB?eXV8F!3EacJcxtGA31Ri3uV~+5j zk#V@<cF&wsUgoay6jXZLZpB?vR^n0IGjLMej>)<1qT<TpnI%=8;>yXn*`?)W#ghxB zmlpGT(eJnmYYK=#L21dgAe=TaeR_F$m1ks8v8SM<)S6yZ;Vvw%F7p%@xu+LY6^|+^ zuJTlt&$rK&Xe;J>W|fzTB5Bsb^0K+bm5{*=F=rNg+@ARr#f}oY)j|M>0Y)i5yr7~a zv#PYDu-IKzQks)SB<`6tHSUVy%Bpe_&@<mX*V3ilh;mlWdcvsUl9|P274tLgHHF0$ zo|5u1R)21BRaL>v;<4$4H8oa2E1JxkVa@cElaOc;S}t1Rn3!%Sb|Z5OJe4Iijv{AC znbj`-vFH~-+3gcU6;p}H<*xaTyb*4@-8tQ2w_DRgI&hcFsVI%2h*9O!|59A&sY=Tz zgA5hrrSs>MS60j_DRh?<xxuoyvcOYb=@_2t%C?Uxt|>08_7vM))FG4e2-!tL(VIl1 z6Z0%?y*g_~VQE2CmAkOAc!qmkWkCh>?#N4XPs|(cwho_DFuNG$2FoieEDoa6<`$Gz z7rSSbm%{Q03kBeCPKPEArm2}h4F?TQH&bD7j!BnJU@f&;g0xk3YT|^jZqr+lHoUN) zv=p{iG2cC-x~z~oo+;WvZ56eQ<TMV~xVf%TZm#a4k|H~iq*;rKXB1SIdfY@r>MtoQ zDXzjj_i*&rsJZBx^2&6_+`N%)Dnm!+oRTtkK_v{dyY4(($qqrRG$t04sj$=z3Gu(; zcFlKBgfGbRR8|+lT^w=M9iD)ZN;?AmnM;;3?%>Dj+(VK)FT*`4FP)osr10ThGeh#4 zG|1f*MGn_oSkOrBSVCrR&8V7HPzhVF@KnNkmlnfqV(5$_FHu?!3k)JBO~~_PlIz4M zoKY@~ap9?dcb%D3Cp<l>C<@lf-24&inUa!86Ar$2^0M5A&_C&p66&22l%j&shUF1x zhihDEY3U(IHQYh;(S!-}UcWJSl3%i>hvp^bbsdu?lz?%>tm>NYEH9hso{V0UY=oQL zVb((ON7NFE6Cw?Icv^8y1zaR-XhvoE9DOEbhFerpi93Aa>dG*@ccdYb#-{|#dhq3G z=`s0-`Q9TmDtH(&ZStiNanbJ`ZEOY$GXbf=QG7y9c&KuuS|_;Xd90c4yilYk91;1f zLy*y)SKydycTUVi*j84Jz_P}g=604B&gPToe0!SR9@OX2tCEJn(W~tb>L?2{?xIo_ z<{i!E@QROOjaG}B)-hdI8Ar(GM-`P+Rg_mnTY+>x1QAfVCb0SN=vfn2MihaMkTR@R zn)LO!qf3Y}Iq#6hzk*IHoKtah2b^^T?4{dQ#A-uYniP9UlNFnw5Ug1(q5GHt^>u9t zR@C<3vZ2c)8#1D_G#172C6dHHR2b1vp4Dv)o8Y>e8M>7iRw)a7u=45)Cu{gxj;*=U zX<<i8AB#H_dfKOVX>*XrNMsU<C_Ul9YL(`EtV<(GV>KDOd=wdSxCaW&z&zpzRvD#; zU71l?+%^2Mrt9lhv0xRGQMi2s8C%(sS1fIvC0M+tV@+H-9}7w9v#^yf(-!n3FA*({ zi6bcXPb({+_%F0l*H@ff)X+u146H!02%zP?UTDso-!7KTawpR!l2qB@fdf}wmx@L) z%^*?@)`Q#&Wrn6BorF9{fv0fRZ`W(J6cu-sn5HbotFqWLtFnBafQn%#g71{Fd1N+| zimR&Uux<+v1@#^|#HIaV2kKQNGs_A*)s=jT7=LLnCl(e(BQ>Ve@uk1R`4<E@BWS$` z6Ok=JUj$@eeK)7L%u{8bYadyO)|S$0JZ1%HB9p-q3o`e^U4&!?C58aQ(H*EgM&tf( z)_sH&%WQ6DbwOp3yP)uzYOFob+{up8E_SS^p3-I(7Gf@(Q&2XOJp6=0VX2%)B{~lY z&@f!V^zzF8hY~7M_jYGjQS^&+T{Oc*Iw|N7;KHKYZww1MI<-XFX|N%3YVQ!%>%jzC zw6QW73nH?iyr5FZmX3(C3hDWG<slE>0!Bo)0OUD?jpf<S-)jVaOhu7)5UfSEgTq&C zbZaOgV{qWn%MmexqnNxrd@~7-ukaZz?GPT2Oya>(3~zGKvtdw@qoucKHW0)2MOx$k z%d#GdpFa59ZTFo_>&k<Do_0h>*U?TuAO1iKI<WA8Mp<qeKZlk`&!K#HbjN+r<1Hu< zA8$uhlfPr={eML4D5Eea`5$Zn;mcnseK9<kX~)8c9z4w`uf$SkCX&2ev-dIb#2F%Y zKR^AN>f*}zk*Ne4+%Za~#jL*Q;H!_#<Ttk?9E>6k-isXxk-1MjXw}DVd+CvoCKwiW zWi~la&sH2({~pRS!mgEv+tXp@4njfi;jA5`#~lApNMrBP4MDY7BezMgT|V6=#ttzJ z^Sf0UErAu3|LE?i5V^=B+^L7ZEcxRM?f1ykjkz6ecl{o5BA&>Fr;iWYn17c<;-OmD z%y(EOeYDm-N7m4ep43Ok6px<3N6uJ}qRdCwoR8|#;*YTGquhWaYUD>*_9JcYM_c?O zX8MQwOy|hj@8L^vgpBa;1vqk+^gCoYg60s4n}1KJA?*T=xzg63f2Bv+dQEHXh<(># zQH!)nPOt2;(}8vZ%q+Hso+=;ehKKG%qZNFZXjB_En-$KQ?Vf>m7rHEZ4s-kCAuRF_ zVV`7oEjxr7BUBLiAR^Q~;hRj-tf9@M(n}g)J1Bogpv+^BqwI@mf0mwi$aA_Cu@iP2 zcA?Ui*e>Rv2i(?(jUK}fb)&~{2aV8ZJ3N4=YQ;Vb0fpWV(O*mnZi<xN9ntSGzlxpT z#X3S?n@3?IR?7Mvyxu}@ppXLa4$7ezRrppX>qv}Z*Zi!?%7Xb9vsY6TyJNh4qU&;Z z)}%>U_}ArtwrR_;+fkKQJ)M$;G1YxYE3Ts##D-bVMQn>w_=DY8Ln-vSkll4D-yay} zA$2o5q;?<v6cpADd)KX2p=NaFfha>5=38kC?I_yDgO{ePX?PP1`@68)ucU0IqYxX< ztc7@s!R@ImDDhM|3TY#7A>N9?#yq@CMBA4p@oh^{UdkFVZ&rba{0`f$!CtwkF4Ggw zU5qFs{h@4yqf!tSFTaF5go}1@4Y$Ocv)n}mo`SAHO-O)fZ*E|-743E#Ijf+osI=Ij zdm}sXDVx`I=T_Qqwj;`2Tv<t}^-?ISXui9um?>mh6mJkU0Tq&|TczMJLf8gD`w>)& zZsgIn#pw<!>ZpiXpj$ttzd$m4Qt=E2+dp{_FXhqpJ+^JndNE#>tIUJt78N_#`+IQQ zT{d?{@py3K-TGA~4pniqq~Q-xGfMDkW+h&Z#5;bpxekMpUev^vC)zm}99R0TJa=#! zfkjTf6!S`umJp5z1O|PGfCt!Yn2LRTF(b+}YeAJe6k+J^;fam4zxB%DaJ+IjqU$S% z0v*2b61z!R2V(XW{z~7ZeQ@5}I+FJ2@)sZZdw|f{9HuU1PVt<=iuql9knT5!&n})n zue`FTilxjQ&N&DiqS|`51tM%c^tLKCaZ<E=$X=Ix4cnmZ<_1w(J`=v0c^I~(Eo8@1 zUDm^`3xNe*L3WpxOfRk}z|O~FcR>+e1%(W0FiqT<Q(jaJY$O5OM<3=9bS+t>V)jW^ zt80EPW06xl1ABSqc6G_a@xCVB<mB&J%|#n0cb)Zu{wZCzMe)`rYd5y@%FjW%R-wx_ zs;aOYK@J>rfrsAL!w5rt)J+yQy@oten2^}xJi$5=kLq3QUE)his!D=y?WWHq2q77N z*P2J#Be@kiz>Dl(uXA`=xyN0FSE@>8loS`)@n{YIlg-ba^t&5M8~#UB6qHmtT&xYE z&QZd$?RlB*uF44NawNK%MtNDmoZ_mAf<jF5T{Hpp;H5lBOv8xc;Ng|kW%fhcy)YtJ zSiBdBh@#5l<{N1Fl7%>D&`6$%2qc7JuQcWbaR{R6%@5FaHNRl1EW8`&Wp@lg$Ulec zM%n<6-a&JMFGt9;Du21HtI|SqbnuDzNbI@BYw~v2I9F(`4`?nFc5u;2<kNI;nqalE zefQiD*=U)Z7yf1d7m@lS%=~l(q+w$)|Ac_MXg<1@zjj_wUDLI;pz+M5H^1p6_byz! zZ?_&G;k}x!+@rN6y2w`eemutv^WxkTyL4I%22!V6>HTkaSvmW*0ym{FJ%w5nYnD6s zl~ypM$Yd)u{;dG^hH>O<)@|%@5Ftm5U@u0?eotH+wC~J{>Z)0o8w+P21rrxKw_5lI z8pdMu(kA?a(F_@Fa6=mJh{G-}qQHZxmxrX7d7?(7G?4T@$3_lX$LsIY(pM??YDQnv zAIaF$9`Z%5@WB!?{DU!%phopL{b=dr4_O}^DXmPzi~SYF9#1*m24dmTaLl3hQkJXi za;vI(x_*lpK*fCP@ZvK1pbPUBF7dGm-At?_7&?o;GK3F=h%s>_twVYtsp}dkroE(% zjJnJ&uS9a#!J-)&f{viUhXPZKO}5~m_qoE>E<xHZt^Py$|Bq-lVk<UZ{#O4Tj1T)G z<fE09?1s8%`rzj|`v{t#9c-~Smu6-}+_I;hjH+B+4N9&(b7J+J3YKG}Z(~rdk<ZP# z_CohZ(0hB)*s=E(^E??P<$TFDf|f4&`*D$YX|;=RvxYvigg3Qfc|<)}kM;<KV$-ha zv=}pQaP}NoT3$Z8x*{?xI&3MrKFB$|)^vI5a+q2<1mlTJMIN5uT~nGYFt)mLkrAp9 zYxr)zT>#xvh6EAzAr-lFBHrSr%xS^&lDSqZWl`C8me`hB`j!h1K)@KE>j`~>ffgW+ z?mwoW3v@W;!lg=sgjFTc1=DR_ymB7-MKC6Pa4FjzQC`q#hdFqjb_z>OMZ9(%TAGMA zA|p2~M*p_c;l2PG-lE^}80_$~_}z*i=PKBzt(ft0E7CjbcS!wz<>6ho4L+1zga7xW z4;t+e`ZhzjN{%Gcprqke5-k@WF2v!{cX`|V2%GA`PbG){y|3={a7a(~j@}bZu4R@A zmZp_I?$bW{Y;=^qBt+H4Fyuq(5cvgB7Hu8e2LOXF3L_KCT7CpP?-3H^NNeTy>_7TL zbn|-!iuKBN^occdPC-rR<Bs@H-z<7e>qd@TJl$484>yLeryoPB%7+dgY8jd~#5!`w z%u(qxtV8hWGtYb?<Sumh(2;Y9$~x4-N>hHPVm>egv4;ZU!)e2ZRLmbfl9P^1$M=|V zACLG7&pC&1BMGFh7F00`f(kj_T};ofv3j14FM48M6n&-uU)&&yum?4uR>o&%yCJSJ z-su>d?M@pyB6wvDU8W69=jf?ZK|Eq;npFms?5R_;#yZ^Ap~ID7v&!cb5349BEv^}s zQ(lNqdf<x}xT>luDXz?}sK9b)*knrJ<9e77hU;zE^y-q*qVtB8S9tI%E~_k`UXG%W z8Q<r{U%liX#|{2Va2)%at@6DDMyJ!p;cvV0>qJJ04@={a|78gL!@tR^f8m!(QMq_l zigVzl=vx2vQ0U9iM42FX0%RC|rV@t#|Gz&}1EguvabNaLbwx1)cAYgJU#9M%TnZc= z2K1s?+_wSlS5kscNFSqIEpYeTc^|qzQJE#+>XS?G1@(BPN-7^O?h(Ih_TLW^NK$SP zIM1NFU<e7y?E-%P#o73jbDZ*kD6jurX8k+k&Ek9cF7cgc9pCr>aaWY75%>y0umAl9 zoj#?%fzj*V?~cUhi@yh;<8^qJ_zt*^A0+tHM&K3keQW)D)>IolCC>i-F;%SpeUwQ2 zEFnMP7ZIU2Y9u`U?OOd<90RZa{SP9=pZW>b+bYq^cr6BA|2}vmAN}u3MdJ0pn-z)I z|6WlfUjMs0k$C;@<wWB3zgrWDZ<gfO|5gC$XqkjhqC(<WFX3O%kvMOa@GTO)O~Sh* ze20X8M8fZv@Tn5sB)+#!qR9BEG4P9G;G1ILlO(+OR6DEPEaA%~c~T|(gAzVN!e1ld zZ4&-?3Gb5dS4;R=5?=hN4tBRf!apm~*Gl+XCH!IuUnb$3CA|0(2JG(s3kI??%}p|X znM8lH#AoW55WS3Vk?0Rd^y?-3yAr-t!rvp|r(PK1FXP)Jdap#UN%$fO-yz}KB>a8} zUm)QX@plvqz&$D9lO#O;ghKF8W8nA4z*mUBZ$$iMKFu-kCW+6cV6B*YBs~3%Zv9A= z@S2Xq*&^Y^pV(k`GbFrl{S0rD@bq`T^}{9M8+0Vj`4WD%gr6nhKbP<o5?=i22X?nc z!W*P|n<V>`@wF2D0*U{A$v$QLB8h&NMBgak^}iWKw--zJo{~IEBz&R7r&+@9k?_kT zy!g`(>~4#MPmuVxN_hQmc~OC_65cKGZ<Fx<k?@*?pCREpB>X=lydv4*rxM;I;puNx z=tr`IU!fy$HcNP)gin?5(<Qt`!gose3<>|GgjXf}of6(9;l-c&Vt1!X`1d9Hd<p-B zgr6nh+a-LBgh#L!JQhj#`-52geMJd>m4sg`;kQWmCJFzGgkK`zYbE?L3BOdrE0X<7 zVk$`z{zi%3B;j9{@W~Q>orE__c=0En*xghKf4xL+k?_S5K10G^DdBAr{#6ODO8D0# zyi3B*k?{Ev{+|+lmV|#p!dFQ6UJ|}W!q1iPwGtkGIwp85lJI{CVqp&w9t(ruu~@?Q z31StcNy6`w@Jl58#}d9-!v7@Umr3|fBz%j6-znkOOZaCbe5-`l|K<$c-YVh$CDFG@ z_~#|OCgH!4@EsC<xrA3F|F8c|B)Xj>;op?#O%lGJgin_610=jz!hbE{QziWE65b-= zH%j;n34gkTw@LU%CA=!(Z<6pX3IDT%pDN+cl<@fyK1IUMlJM&#e1(KRTf)~!`2R`x zS_wZ-!Y`8Wze@N<34g7GUo7E!NRDZVguhFoZ<g>K5`LM4zeU2gNcc4pe!YZ$O2W5F z_>~fVtArmV;oBs9zJ%8#{5ul9L&AS3;T0*q{a(T+N%+4>c$0*GPr@fl_^lG&Ea6|0 z@Tn4hv4pos`27+-L&EQs@HPp5w}e+E{C5)GCE=Gz_<RZfw1l4};Y%cZg@m_D_!<en zP{P+r_{SvtA_-qF;Tt9Ve<l243IDBxZ<6p13BN?bS4;S23IA6Kzf8hAC47s7zfQuh zm+%uMe5-`NM8a>C@RKEcn}okq!fO&<q>9+x4hcU^qF*HPKQyF0622)0epw8>CgDGm z_#}(JGfMnrd}Gc)Miq%yB>D=8Pg4xMMZ&jA^lA+JA_-q5(Q6WZzJymLIc2;e;UAai z^JCy^B>V=6en|}cRtdjbqTes!S4;S0k(VQVekI|TNceFQKH0|g-vhWf32&D0@e)2& z!Y4?0i-b><@EH>R7zuBa@Km>cs1iO&N8;>~@W)E{sS^H237;?FjS_yAgnwJYS4j91 zBz%p8$DbSw9<>tw#2^+qObMSX;Tt9VNfLgsgg;rrH%a(YB>WNyf2xFUmhh)Z_+=8_ zEa6)u{Jj!>y@cnM!Ed%o_%kH>trGsv6248spC#cn2|q}}cS!ib5`MpgKS#nVSs}YU zSHdSr_#qPBB;kij_+$w`Ov0Nb{3;2bD&Z{>-Xh_x5<Wx1r%8C5gdZ;9RS7>r!n-7V zx`dx9;YUjNd<mZ+;b%$s^CWzQgg;-x*GTx$624Z#kCE_;Bz&EOZ<O#CNchDP{z3`g zB;jomeu;!nBqt}1W(l9ABXM3P;m1n&773p%;nz#}w<LV4gkLM+w@UaN3Ew8+$4huk z!mAR#L&7hS@cSkFMG{^S^DOz!2@*a@!f%uCCJCP_;gco&#S-2u;U`J>R0*Fa;Vlw= ziiFRQ@Rvz=n}nY#;Z+HLxrBE~_$ws5TK7$o>PwvSj9F0|T0C)`t!mxsq*Y31`dvVE z{`nsKYdqbCD}rZH$v|5tjz8Z@Fj-KbmBBX=OjBT>g~8VnOjBQ=nZcC=)07uzV(?!G zrl~H_$l&P&(-aq|W$-kDse1wy44y<VO=*FA246%lO=STWgU1rwlVBTz&m*`O!4?Lm z5!{<#GlK^cd>p|h2A@H2AA%JIpG+`KeSwYxK>WEc!6t&+7~GTK;|XqMa2&yX32tHV z&r1Q*R2XPx@E(Hu5!}S!T?EsV7-(ehPJ(Gk9;jvTc7kbY3{)_9Gr=?^2J#vFHo-I% z23!nYNia=;0ULvt6Z|KFEew8%V44a8W(Ge)Fin906N4Won5Mpf!r%u8rX_r!<5z0` zT?Cs6Ze#GR1k)rEXl3wC1k=<OXkqZR1fNN8GlMG$P9eC7!G9r`ro2ESgQpWrQ(d5z z!P5vno8SrtPa-&#;Cu#OL@-T(0T+YE5=>KHz{cS72tJ2k3xm@Lrl~GqX7FHwX^IP& z7<>l7G_?g32A@nYO=*FS|FQljn5L{i8-sfiOjA{$mBDcY(-akGVerpO0MpbIXlC#p zf@w+$G%<J=!88>G8X3HkV48vgwG7@)@F;>S7`&Nanu-GX41Sy7OoCkuUP&-bNdX&! zmlI4=QNY6Bmk6dQC}3vrGX&Gr6EHFOae`@T2`CJHfMA+Z0v*4w{wLT*a2tbfC77m) zKr4f9BABL#KnsJfC77m$Kr@3Y2__dGXkzeR2(}a4$l&P&k0ZF2!P5vP*B_{0@U>5v zl^KnI*^y`6ta^We_c9f!zJx!g0;zg)Qj)AKs(-vm^?s$UOGqJYtKJ@(5%R0PekrOq zUiGe1{pl0uE6TrU?5o~9)841RAw~6_pn9{D)+WR$st=5c)Zv`1Cs8{c1_8Hdx?<G~ z<LULRe$_wb&S&8>;XXAQKdNtx<0-)Y{x3aEr}Qe^)y{$@;a!ao9R#&cGJ-of!9}dN zVo<$_7ZUByXeDSL1Z{1GQhgE%-0`?sS*sYdPR6Ex8<qFQfoK435Ybt<3-C?4;j2li zy>PIx{$a?cZR91sdQ2~|L9ji8mw29T@DiRH?NLr`Au$>M7dU^<a4_EmQmRXoJU>*I zXP8#ZOMWLx)?w;^+`CbP<Q~uOD&Pjb?Jucy>kRGh(7%Cc)FlMo1eL-npwG83fTpPa z#1%NJnfq1mmmVk~@p0mfsp+_@I@@Lp)%AbXDw>r-Fv@$WoIm|0#%9m~lvh_AK!<mz zE3^w$!&-II0Z%d*dIiJY#4r}W+A$9BQL2Zjbz?f4a5aVG>5ay1MmKA7U=f;%Hmpq? z2s#6aQ>)<EOD2N$5cySs8K4mDgP|B-P3#Zi`WDYX)t5dUTp@KK%$%m&z^y-nHrPJg z3E+<AfeO+1_huN&6O&=Jz;B`wzQn<RjDr%-1VlG`(M@mS2!OzzN@bIO>g;U4m)D;) z8LCZxcb=l;EjK_;I|fSKHx|`*>R={EX-bmnccz%bMpG(?yt`HJl__Rz0?gCt`*RUd z`}*fTMyK>oAEncnVSt?8&$NH;Cll^Jm0{C2aV+k?i9*@~>}L9Pbkn;->&0#33&v>7 zy~Ni0skY`va6o++!B?gvtA6&6hrk`$Nl*~P(XL_V?+En~UHYzv>~+Ho)jd?-_@qu3 zHENEiB@rqh<4INPYRn4hJtrkKIJAuoe^V6FzU7LmvaVzn1@RrcQM-glX(W<wNH*iR z9lURR#H?7~QoT%q|L&u^{U65NAg+z$ykHQ-ZQ!_9h$+__Zu!QLoLV!#XJGZF_vOWW zV=hNM+C8`z7zZ;F`lGgbSA{nhia0f>2yt_l&_(-ay#Mpwq|gOj9^S*r))s9AYheHF z4?{F49CpAIp2M`R)~$r{O=#jv5J&a8lC;N|xYy%$L#O8$)z_obg)(F2Rx1iQ<xe#e zDLqQBq`$|i7~=w^b_IyEvrx5mBO}jANe=c)^)cuZ^A)SKzcJBbw0V%I2J)>UQQEmE z?VpoppzHjk(0H=8tO^0f({cYoNs0LujN9PYW99whlO$AQm-62I(8+fXnH87~`7d8$ z7VAG;*^*Z^E=z#AB?c<!S*X1*nbhS=`~^kTI=FB0nKK%f8N%r!;V$+2$0tkdyVSQV zE}S1~9E1*pu=TjX<UJ_@Cc9RB8G%dCzm1^3gnFxPU9wu&0u_(f0vQ;=Qu$5%zDeBg z2qcH!KOXn<Xp;8d5agl#mwME@<BGufKgjNm>bo&SALOa6*6Dk7p(ptS{}BB>I{nB0 zjo?2IMC+0RCx8#@|9KE<ohcB{VaCX}5IvK=^Z~Rx^G8n~OsAd`wUr=fXsPa_`m>X- z2<p$;f?yzMF*6#a@+INrZwi%10HNzIvb=i!m;lOoPJ|-%lWF)Yf%SVNeS7zZ)d%{2 z>GbOb{o-!u;r|`p|H6-*k5YN6-;FNat$hV0p>2It?^fmkLoIT8cXAI$_`uLGW%BWr z_}GI&|I9w%eBWGlW1OO$0b14fS`%Fl;Ma|G-IHI}()EG8jHZIF_weg{y8en^yXbm5 zzqZl!yZpKZA)B_6uHo{wqqWSEzQ;u)+PAzFq<R0Q5MA~Ds!fC5$@QmG$md<<@UGTI zQ4wFFMjhn8P8dzR)(FZg&|0VWYijKA--Dms`UNmo2-Ja&&Q36(Y74=`>1_j3Z7K-i z??{oqqH)@KNY?%p>e41sTS0s?&cXRN4-Np1^wc{SV~Tz?9$~;(K-3=$GS)9+<8sKR zzd}6kxhZ>%3lr0EZ5)u0VjM&fD*YzYWQS0cPgo$_p}9~C8u}8N_At0v(Z*RxwF{KN zHsd|(RKsq~2*EISYpB?Yb|j?8H}{}H4usB_3J7hyr$sfap*C$3H!M`g2511%`bi#= z-PkaRVw>OyAR20aLyNIK19u?H@uX(NnBa@Jl-RD*8o(1q_#Grc3Ds*?v`TOe^rj+S zRJ%i)L^YxMi%6U8`goZ_+C%hq>ihTW+B+AFj$@3NuArm=iO<vB2wf##an-6u;+)Fl z^Q?z#r-Ck0wg7dfZ^&|XYs_9ck$jt3FWZxe!`j`D=?)?2QUE0AV`vlEpXlEqKamWt z+9}SnLg32#h|ww3olL}==yrsNdUx7Dxm&9RL-Z#i>BMR(9HGN3Cg-Uqvs+^(FgfG3 zbC{Uf6yP?qes=ould@_@r!XsU8ot(!<rEfByl`(<w!4_#vsG&gD}@eo7*@mnwN3m+ zK8d#GJ9O4i)>*3vehM%t=3(#-83X)lu)ltRnB3Y&Lm6X&&_bws3yC2teKx5jiltNU zk-tVIvrq~2vJ7#PA0@R663jQmN*eHuna-G@!v->Wd585U`Fy9Y#XTlOwO7RH#4nlg zGuBr!dmWQWJink$^$i)rnC)N&u<2X0c}mDY{|=biz7+M4f!1Q!Dxv;A^~PWuX?*Y1 zA!B_jAKwFk(ObQd?nY^~ZV;^96{tvz?;q}tHok{JXpHY#VvM-)9<xG&TuTNz>d5Y7 zS{b4;!kiQg@ZDNFa73&U@TmauNllx+VLBWfY)Hc>C_~a?E9#+fPkA*M*CmiK(q{d< z#<L`~UJJH?|I*T#kNas<4eFi*Ztd+nSW2vp!plnfhdz3fW2co<6A-kVp+HLa7oz-A zRAI#U`JO70%jd@~-*8vg@_&ykZ;n}h%$F#y)rtZq=mPHsLg-J(-N@w~^Dxo7BI)0Z zMW6UQx-hbR$BW`Y{ZReU^)n`y>T7G~3JJ=0ajg2r^e6h}Ncz*G&<i`@u|XggDhl%t zuoEl#mW556MjHeg*xMBWGx0|}NPREL9~Y&3K}7igwVTSf?PBG>hpc+}jkp(C|0dj* z>tCvuZ{p>zk;?m{l)ogRe2HE@pO^PGhU(9aQoaQD<@yKd<;^Icby?P>4)1}iDa^5W z_o_F3vk2}3qr5M%^_7{OzA~(sq}*4HwZ-8Zfh5;%?ScR_(9l8|F~oV3v6A+drlcC{ zXJC~9&5pm5Sj<jEkV(|05H;Y*DH%kq8tdCwh1Xe#tJB-5X<Cr0i|D30z1OGAGS=@W zzt*rh*EcuG=`TugA&B*t!mD60X>xkMLeb96wD5NAF`5tn<)8w(zsGny1v40lMn+2U zCRU9q9zlSH7tir!5Rgn%Jt@`#K`JLOftxcWDaU)j>D`TMC9CrzwC#yI;QbIFsaRV% zGa*g&F}RtNlCRdSF{zoTx4JKaC|i4PzHTESX>hE<O<W3Uv+DDt)L=n6f~6L#N2oWh zCjC>`m339t)md(l=Rwh6TiYKBnV7Yu{dMhYQW#axl|9185;Buu;gEQnnRpwh5xfCk z@CLMh5@O$omM*=WdNCtVfLa>KUdUJ+-d{2GdVheutfy}AEtHL<K4lq@klB}bH!~xP zR`?a`RAc>gvJI@HeTk`1q0?6k9aw1o|DIEXjLGROB4e_mfYUeT42S{hREKXAQLhS7 zb7Lavd}IANjJg`e1hOBshd3Dvs&i5*$ee1N-hZStK|W*sX&}z^El6_2UuDYLx6a_f zx-5R8@A?e*g`AWcSc9?tEYMKOs=~>2SW3qBqw0lCsNQ!wTb;fl@Fi>G1l-OT6|=K^ zZbr#Y^fZhOH-wR~ySkAft>yIYfm`uevO2e@h5NNQ>Qo+vBQ=saIi<o_zYtP8U|&vV zUl);;+DKnXTEDM}8dvQjn7xtiA7Z@#<2r>KR~d|pI!iLHMkWy1B{y1A^?FokZeOX- zZ`PJjv)k)uz#d*tsRa*S>m#IHs+DCRRX@`(f!|=h)m*q6Dotynpy)lB=-Sm(-n%ta zdji!?Yo33w_RzScM3YcJ^}qG%wG@<Wf00Sw-Xhs6*=Cmahbeh%m8LJ!D5i%SNJzmy z=r`?e#2p=V3C)yz%~tmXH6?L`-^|u*Io|L1xW~U(4zcMWUi<f#AgWspH%E&&uE&7m zbNGB+Us%tz|3@t0n!r*l;qC>ESi+r$y0t_SpDp2hOa(ibJ+pj4;$LqI^Vh2H2Bf_Z zaA&T=BZ5*AlO~_{QI5yI?C}H)cgR#9WG8B$9p?%d&5zZWS@(gwv#}XgT(`fsr+=N6 zShv5|ykU5PU@BCU+R<@}=L}zVa@~G|r+3}{xa$7CY#UV5hvFQzUPoALQ>-6{!`jO` zS+MvuRo4DMu>E|Z`37S;%ptI4AJp4`wqdwyQ&5^ZAYYBoHmTmVsxLcfiJ>}6^?pv` z!ZRnP-3n6j#2MO&q&?qgOgXExb67t)Sr)H1vug-heF~&QB9H8I01Ps&v;7r_gnXIx z<MvJ3I;ng+>xms&9=a0x<G$>F+?UmTGu7!E;$>>QTJ~oMS839#hCn+s2bW#-!Y<%W zpd@6EjrA*ORQTqYIoWRQ44o{8EP8TED$RBo#`;@{j%Kma6gG{SJy5{sn7=SZ^7#wO z!<30(MB0Fo^a&}M^g@-wb7W+7en{iw6EsKn;O6Q?au^mq3!IX|L6hoprl{}&TwB!x zp{l9ebfGT{eedV(8-x9a`Q$zAei9vZv&kyN2i2Vl?T4yE=b*awEz<ZyK9mxZ>iLO1 z(SOw@75PooC*=c?oTO$TVxng_bt~~)itKtd+M(TndPBTe|55)q{WDC|L3=Tbr-p?h z=oK~d0ugUCbQ<eVMLJTg>tP_bgS0+NFkep&d$+cS83CW;jrFIHSNB2ltap&ChbVZ4 zV|vppoSQ{E{xj0T8tMrPy1`g)qcZ=(KMMUsX#_F3XyI|^c+Iem9Qb2mRJQ`GbAf;Y zn2)xb)OGe`6jQXzNf2N&w2Q@+MYD^mRPB6mW!9{?BEbg{2A-bf!H<)&$u3K7!xzT- z<4LT#F^}D1CZW)X+3-)<CSyIDnEm#o4umKjb*YBx%a~_?nYm2Mu!idFFs`s;%p0mN z2;N9;Ph)yl*FiBPE?uP3Mc^~|^hVSOdtEn<vi!I=jx~u?L>897#-r1Frm<lO-IfeZ z_m4<s8y1;mHG+QzV@7%eU}FG#956)*yn#x||M=`lbu9+Js}tgSrzBP17L?fJv-bwx zJEeEPDy<jm#x&k+h74%GvEcx?fJ6J6jVeOPB<<DzaFr$n-lGR>Pw$`}p->Vgz6<xr zY3|lsKx<dD;U0x6Q9FSA!LiIvR%t63<!)_0!RX&qtz2B0wPIXRUtWcC`^zC4hrdc( z3OS|tJlx-3|0z|!L;Hd;hu@zKgj7Cqd}M@;k5n-}zJpHj=)zcUXSNb`d~Bu~(2*<# zPEcVp!LeZ05}6nn3yDuOp!e3<dH=I%5t9vjiogbi*N(wJV+wwYF(FOB|JjqZ0#rac zxSUlKRh_Ud>aglTWUih(;uLy{#_Z}DYDwMd4B^0_zZ1B@=b6aN+t-TqF4<{Iq@A|E z0D6e)vzg$a{$39Ub+PIrC$%71n~r|(sGHN<P`yalmg;lCk@f$q4s=8DG$l|f*%z~; zvX4n;u&BV(urQXd#^`Eo|7Yjsz=a^za>>xTwVroKv#>qrXq`s<xb1!L2}<warL~z% z`@6N%VUVQ36LD^TmXA}cU(t>*`{DWVI4Ugi<NLr3*DOE2i(j++_^14u<;OSkYnC5h z%dc5}d^x{n`SBO{HOr4bPS+HP{0l+{=MVDJv|R#LFl7BrFqK1yM{1}2j(FtE?NQ?q zS)Pop@_1%yySA}{Mf<X|5<FLP`?wC`^Z3afBYsLp{M356kT+G1pZ>(-r+zfSh2kgT zUj4EhMe+DVo6W2Lk}7V$tMSbwX5iTEaT9L9Tdum1l$bu6WJj<Xd`wyhyjF%j2ss1s zyksEkl`qn;Ip9|eq6}>S*(pt7r}k8of79~|@ak-|kT;;^`zmAo565Da<<Dm;v3acO z#8j%&|C){FRR1fq?R<tY)o%J%8brhurZ+bJvn@V*s&UW+n{iM!Exqk#Z}u#o{anP_ z+4*~o<@OA3cB#*90a!yICZ`JH@pX&9g}|w}UM#L>;hN1HK6?!|8#L4cuX^j2;ba_C z*Mbva8#&l2z$Om139y-i9Rh6OAWhj+mI{HDNq}t}Gz*Xl;V$Wgh^Y`jn*ga0K$ifi z5Wsu^QXzm90;EC!YXwM!05%Gc3IS{qAQb}GEI=v*utk7W2w<xKsSv<60a77=9Rj36 z0C{hry&N>L&MR-ALbz)dAQb{=0k~Iv3Vm(C<7D)8M?Cf|H9{Fo-2gz;iW7lN9BdO{ zGY6>z-EHBZ0zL#%A(S-<kP1=t0C|1QFn82ffm5))4s4#pU6KpW;fRZZGeDaFO&oLy z(2TRw_sTMMdY*g}X!8m3{^&5i_$zTBPQX^+gn5uK#0;2PoCqXl02>8J#Q`=6kjepU z79bS@*djnG1h7?rR0v=jo$6md1~sx^3)8{rSi>1_vGf3H#n<s#%N8*z#{uK?zPukL zoZe@ZKDh6@m)Zl{@1T?M#e1nTb;ZtjEFF-?^1VW`(3H{ZBl5n`G{OGYTqc}+4eJ^7 ziV4ti+e1tq6W9_V$pyYi03oGWV5u5_76FnB0Br)KvH)EIq(T7m1xSSeRtS&^0jw1u z6$02OKq>^VNq|%cV6y<J5Wp4zQXzn?0;EC!+XP630CotF3ISA%!t^+35+D`AU9$kG z5I~CnsSrS$0I3i_mjI~{z<dExA%GPEq(T5|1xSSeHVTjm0c;W=6$02SKq>^VMSxTY zV5<PB5WqG8QXzmH0;EC!=@UB4060ip&bpa{W&u(m5L*ODg#g-c(%yO>X6S#d@i{V} zS6nzTlhOXp@vW+X@QpZe{9g(0YiRv~@UJC*$!>22#BRg1Oh9Q>oGKY}jnnsh2Agu~ zrqapRV8&^J|N1#(hZJuBmC6Zb(aE3i23!x#Ovd`#;4#$Y7&~-e{InWxIhB0Wimwy3 z+7HC|c@CHf{>h9V#WEN~HN<Ge&P08<SQvk-mp3DX@;$Et%x(DASU;Nh2gj!)bB*zq z_kp^|Kl)peK|4jSgRtPci1_&YR35_D(#hX%BNvwsObV1}U{>;)sL8CRop7?jnl5BD z^@ZH1>3LSuOQbMr@&~-8#l*+wXDaj7HS(JLa!oE#QxdO<bjNC1B-eC0tLYB8O{!i~ z9j|E#uZhZ|O-*!)XcOxswCRyeOnanUR?`JtYZ@Wf^eH4`Z90$Fw2aq8<xx{}l$t8o zt##T6Ueh9gtftkNse;<$ZF(4$2m8sR*K{Ya=%@9>$LFW=sHufc5pAkvx7KNIw^Ey4 zSqu<{L9G|_23s(dhSkgbcNI07{I{alc`>W=<*lsjvu(uKcP}wS)va`b|0c$=|88Wr z*J%@2_0N+oSVQS!8o`EgGr0<=pqcof7^c#{0*i)r5FekP%A+=oPX2yjX0n9cTBm*X z9!h#YrR4d2@8WV@w#fo>VlgUz+Q9N>r@l4UjL0tD(EcUzW7d|y^q-{o9`IfN3x~go zfN5KNa6JI}2O{9Bu~d@pe-Uy2rHK0{V&rQH)NJn>65c`Ws5{3{-IKD0Sc1@2OstA- z1c~+u)TwR3KOn}6ho&`cKMJ(3(N+Yp70`&bldzv?&r*TE(JkL=txQvEv~^U2@3j^p zdyQX{ezh0*HFc%-1ix;i>-+h2EnWL?-Tt69nb=;;Yixg0vlD0&;0M}B0<8l4mv%OR zX9(~SEt$X*I2iCy>yIIfL0}YMg8IYy#$Vo{`rT$)bW#2jYZq)%49^p(b?wLow^x5g zixO;f2(20L*pDp|qHS>ZCH7&aK-=<qsMrXI-FZn)-&v~f>Lfg`Pz~EWiL}nXR;~NR zNLx?lS#f2kF3d8%+An3%6wqH~TAPpz`^=Fxx>uJ#3cm3G^7<E`3%{~%);2RG(&l-j z5WG})J4=eL(^5B5cbtMvNl4*5%hye6!^fVc_K&e2^o)zp#UE~<9%oxcmJ=UjOe%5K zHlk>#u_9moE8nBa@`*?<NRKvYo9fA|w*JGbFbcd=k$S%piP$JxRW$?Esi%d+{#3Rx zm5k9tBaAWwVfi|iUkN74u#vcKbt<|;JB!sx)bzAN-eQb~EETNK3tji0(n3%5A2;5? zwuZ2V<vG}6ITu{6)VTT-6$s>m{E1B<R=vGb)OGbKTj9FsV7rD?Z+%KDc{e{l&oF+3 z2fK(S)~jCRoq=t`UE=^01!WtG83)~#(u%Y8#XD#(Qavo`YR0<tHKsqx1O=C@7KWlt zy!WJRr9$qvxss4A3hwZA`kzd(kq`8-J=spAJ^hqC_ovsW<nVSo@RUhq^7!I~)R4!2 zTn=snCfTk`Nu6OVU618y9L`7s)u&W|B^`8KBVE^uYibBpYaCRc;=&oPaA;;~Q>3Fo zpCVT*cM&ky;wfYNi64$9Ek4Ke#jOqXYC_i}!+!mm6v<Sc_%xNltt9jl6BV~Q_^tct z7C;5J(1CX`kb1;!5h^%0g?AH|o^_msI!bSsmQA{*tTWlN4IOlAr5QYV!WyP!0_uK- zawR#S@g!}<dfq!WsduPXzyWqcI>J*?3-ykQ-q}8m^$zP8G@?c5m5WDNY1T<wK}G$e z@}2_WdO;Z0VR(NAw`lE32eqLQ*VH#nIBU1O6}@BB@NPiIWQ1cNcm^1djhUdzH<Q7g zYD(5sj_XwYnwflJHfvW=N)jZ77bEJ7AVoc6gC04H+J#$YAu?U3O4k<s8l7lHaTNK* zPO7L+v2bu715pFnH@Xg2)ZPwA$aLuRrl5;UTL`Iu8&@o3<lDOHQyM|3T}6EckL99X zo{BE*S7C-=6z5ZIJE+5_hDKzca@@sUdm53f{KmDs&!@_L?mzBw63(AauTe3#yjx2U z#^LIs;8d7wP_dMEU{ymO$<j3?AQ+x2`D!o@HV7BJsj2IEb8ky&LvxufaGqh@%~a5Y z(pvdCgl=ePKDBlhHo?uH_K4Q9hx9o>`}2f(Z<Sih%I{diTRSVfwXHd<wF_~=GkHq5 z4nRfZ&GWmownlDkzTPUdmc611A;}UdbUbhEC@_xQS__D&wKkmf);3dXZ=}9KW2nUy z)Z!XGYPXe|DP+~#O<jyTyi-}h{j0h3*v}Ajvv8Qr*{qqb;Ut<lO!R(5mu9YqFu_i3 z)|-Q-Et9TW^lRSC*<c*InYAFMW;WuiH?xJB`2cka^_l;nlv*HE|36X|(V4lZ4QMRc zanPje#ZBJc77%Jlti7-E8(~e}I+iv0OFB__v0EF>OyKpDS`-XxwF9Hbg7}0Yr>HTN zGxKxAQ~s+gJP#j}j>lcT*V$A{JrEI^`S{EniV95Fra_apzD;A5)<YIDB0`{u_-yJo zH0E^He=%!9EOC{f;0k5o#J}kk7FSaHt7PC6dH}LSf3N3JLc^Yjw)%s11ei1ogb+6g zs=!>tq;zMNAbd7ZBrq;P%QtfC^y9?cshr-}Fb@d!0yPkURJx0a7yBr}f_zl)TQ1(| z{XFnJ77!$iO)#%-V+d+x;6u7Z6&vY{DzHq5tl~GPcW-;(K2e2Puc9GT#kHb}N}Sn# zDTnt*dQ4~C#~()A_zk7I!$LFa4uodD#CuE37!?SDeG1>Ru`k;em*rjU@Xs?DQ~Ra( zCM0`~#Xb&W{h4rvbw9;<E~xv-V5~>Rg^y2d_9`@ta{6nG^+S;4!m~OsXXhkwW|M*T z5(sI%kZpDrraB8NlKA-cVwV!;YU3bm#L-R*GV@{jrVUKSRN#&E?_*ts<*K?)@U{uw ze4_E3l-sb+(=WJ;y+Qq}<HrL?MBLz&*47OgiAB%j8umH8bFieSHhIhruiNJEma7i$ zJj^Zeuz~TWTyJ@Du6Ldp=hUpa|DpBO#~|LV`z8@kFXJtfAq}3#Tz?_f$%P4zt5_+u z>HCI#*%?riuLeR-?LjJow(iA+x^5+`47RXI^|nF+&kziA6RUmQc$JzJlHjsrhxZ2D zyBN}qPvzqs!*&sfg2UF>uo`)53|;D6eduEQo-Ri)$Ha07qex=p5Y#Yrzqo?+U4*W$ zA-;G+An*aRv21hJztP(YdM)4pMy!WKJ1fx69e9+(+Ib4Jq^@h>?W9l~Qv>Eg#22}~ znaR%ci&D%^AMF(Q4@x+E<FR+eoto<_ryXh(rLh7T#@mhHfQ6p%_G3t6{)GRadL`HU zo!$De9V;HZ0Zj;EtWxv>rBYbwqssgv8u-06>WVKDRR1Y!xx7wq2i_l9p~d4lhFXWQ znqa*7eqw^>#{FnMc$3<=C)+qUp>a=^@%UqMy<cDC@0V<S%Q0vj@+sh*>-`CV>W7MB zMIg>;Xm$7#YG*XgFqZYk^tA#^SDFEwn~Z-j!IX`#%rH*hs2Vh!AVcYjy~eK)VN|qy zXB>1<8vukAV>=v~Z_Rt%N$=3L{SWVvI5YPf>;C~koY+Hyh0yL6hri$XPVah1u<jy% zZxcitoUn)l%=r)|c$vYG`GN8Fo2Y~V+=;$7gxelT7YDk9S9ebnPc-Kd6VTxuvIOv< zc4q#MajO-zE<BNw>;RQ?<5x^)2`L6=yazthmyqI&$5tI@Jay{%*l}TOAU73ANA5+~ zGan~pKX2>yvkbFPxc%VG8CVY)4NL_O$HC56e{7;|J@a5ac>j&8#}l-kO~?;nxo*6D zJze+{et>qMs}axB+2Q>*7msOR8)QjjL8?C+L0t-r>n+)`Y`Wd-54W3Rj5j|<{KD*J zZ?<t7@0K2_cN^@+qz+nvK3n7PzJnh8h<0z994p%6tZzYUWI6i&l)c#QXVL8kfZ5ou zZSPp4ska%xDHTqGX6(1kn7Z0HV3o0Nt8v<T<Fu7zK-_rVnfE5`w!#=ghcOFMGuIpI z|4RaT_ftPHA^iQ$gIyT*X6aHUd_=aRX1)(45iMCMvmJxeusMP(PR-nI^s_c|GT32K zSF(6;Tez@WP6^<&;EHZZ5{XL&6WpM|29JTdP?wtd3zLf3V8TZW2M7wMVT*)6AS{q( zZDxU3E|MAQ7D(R<3A~IqijkMWJQVcP_aP)?{_7U_fS~=Yb$D0ilF^Zy&cqYzeYguN zH0S!p!y3y|nT-{JT`n2h6}WKF^Rg9R;`dd&W5wt3FsTXt-pNic?DJ=CPfYN-mZUwZ zac~@-SljlihCS%C>aQGdB504ppgA+&sa_Z835IOG49b~C0`O@B;yS$_VJC?%JCzLC zr~LKDPPMQ@j1)Ll%pbapEl8+ROPHK51BfE0Zjb2P(_uPJ?@BH&p0CFtuaN{PxwH_q zokYzw;6cr9N9MNb4FNZJk|fq|nIH$$#cbHpT(1@~KWz?V&|m}&ZMk9rL2T0ZbawlA zyPSosf>mHPx{&z~r*A?k8jFS+&~onzhc7D$7mh+x<_cr(3P+)uq%IEJv!5!Rkg75& z=tt#b;278hRwNMHV8<(3j<KNNk%+od_2rq-io(8uOTYq}M6X{=J_x=3t?~9U;tRst zi*Yg0pYS0Sbo%?Pp)>Wq%6k9f8I9=w<H>)=?tiCYrRe`v2G#JR!?4YP%qjXmOm?ON z)<o6{rr5w$@TPnkB}XWxQ4f+3@M|^<?H{RyG!K)g%L%H}3`{&swg`pE`{BL?Q!6=8 z7c42v3zky4g-@ss>;=Kb<rQBiz*nvfr8pz!RTcj62~t7~|A@S0X^NRVBxY8cP1Qkb z;G^&wYdiTz;T=Q#xi6F)<md`xzn_@bG^W0XbB5Ef-`H=zF?F4BzzXAuFfQgK=`6X) zWvUnMM0iNeSf4;6J?J4<!AGCxM5<{j`L>Y%6LYMS9N=bZlwoUBKgsFh7#-U%#_75^ zN=_Hg=xEOFo?n6kzVPbqX%dNs&Do#}`AdiFFHtL>vq2K(Fmt3i+ZE<9Gic7X85>R` zk9i}#aI6oa(AXwp6cD+g&`3AoJ^N5_C#Gjg<8iA@W9)RROd*I_<>&F3m_s&+SdT(N z7rka-k)ys)goovt6y()Ip%{eT@cCN(jX1A|Q`jR#dYGvlgVtaV$Ld^fKnn9PUmTe@ zPq#sOMq2+Y6Ss}c2ng?3q=(7eLLnRrtXQ1Kr)o#$riBZg21X3CGKGbBj06$hriE7s zk}gpoBSC<-iBGN|lLNe;LUEivxjGGq@7g4MXmS;%G8x;P5#H&hQb(q8>E3QkrBDkq zle1wa+QYBlpT+;cKX>DbGKu+bra~{;e_sOV-GMIF0<Y2~dyY7ih*&~^Z57{vjok0N zOsM|7r<pOQr$2Rt87A<xwkC`akLEIo_EFHX`~{Uk{^Cud@~**KnZ5;Z2dlITAPL<V z$<8~pM?j$c1OSsEw=Zlr+^fwb;r#R>LA?C61lkYB-*4-r^*61)_hLI=ckA!|5Ib!B zowaYgEe_8e!JXFMS-yGt0(>l7R^5R(kG<{ymXsq9v#<rUwu>6m&;m^v>$N0`5cu-Q zfr%C%A;gTU4MR)B`j7^wybgC_aHe`kuywdayD!Mohgak<MWoU?++wW11so4&9bWJB zevfgrQEhn3*pSQusnIF94K2BNM<FQ}bC1cB;q+dI(Ox*!>CMh}U{Ag3y$&1cXCr*7 zGUJTMAv=TGgR@PXRXW%G+S^#an%3IiCf5Cm<@uK5LFDg$oCT-CglEL^ocABvodGSf z^|^}1FlF9=1xRpxj$pkNl6mYDLy=6VZz|Ojk}EHnWK$s*_7=vJE7rRGI1=w**6k~d zw|s?AN%fE3$m_>c4OL<9Bi{3)2OQdWe`kG<?H?)@@yM4TCIS(4mJRDF6s8xZ19!8i zsg{^fzlYZI2HfCrp3qB<&xQroeY#@44`0xu$#~?63h19y=lP{r)FA9I*56O-`ON=R z_i~<(t~A!aMTsChF+GEFI9Q+U!w0ICQCa{8k~1nMj?Asb+cLqP{IAJre6ih`8So@) zuQyXX{jIU#Zm`fznZEo08+KqmNTPSSO|*hHDaP9$f&45CzZVxyI0nQkJX?TwOj))d zY)$9FpzXZKKjID2M6UN&YKD#0f)o8I2e=*(&(J5N!V?8gf}8>xw(Q7S2J=<+j5Q9< z@hfnU#~*_wADnkQmV7Yrbq?>_*b%XXmV6e+id}rkhga1a*!L#G=aI2U7?{Hn23YWQ zn=o)@ZmN8Z)_mv#w&rsf@Jb5Se0(-xYd%QPG64cn{IQ3NiFeVqIQ%Xw`4Gy~LViR| zp-^UfI2En<79d#=n*xiy?F&Xr6pp$UN*6dXw@R!QoD3;4shV5_Cx%wK)j*m%J^>qx zMY6!<Fnp}~C|}^jgHD7UCM0Lkn}L<I&7(2QE`Nr-umPKzfDQ>Ino{A!sV`YbYazSD zTbpj!;gzsUGRf5HV;z~;eU(C~t%h&8T_Ti^W|x}rw#Sf%AiGS3U4Bb;X(k`7nP1?x z3BPP?m;qMd_L=G+XBM>2RM_W%U&ubOVE6$SWS>)EpWj0L7?-fm@MxQISblq?eY$?b zK3xd7o4}Clvp?yY+b81YX$d}Io&lI=T+lq<(akfIk$_Zn-2Pc)Err{Ml8<m^ZmWD# z&POoYTw$#L8uB49V+O}<GmZt?OvI3B?lSsmWD2v=qi2~2mI)%tcy>bs<J`4iUN;2D zL+n~`X*UGOLhM?QPU3<HrY*7%j!bPYq^ZL~IAO~Irfl5DLYQO2?b_xr?9%PpLUx^M zY`Bo@dKXr=q4iCeeb?*u&E5fCho>-zq_J?p+6eJz=C`?+k&N|2VV${|YsjR(GuDrT ziPLm-D%o{}m;Ke5*<!ryeW)uJA%(Ez!A?p>IWaG27eC7k+DXHY(nxq_LXKPn5Z2CI zj42p295gdx3nWKX#@o-P1-idCOUq6a+uWSq1CAAKl=5Kn9#(irg>@i5y1NCTCd+py zP~3RrJJze2Tl9R#M~=)u_2$5bSnRTLVfxqv$=P^+og#+1UpuRNIuK_X>;DFFtpL)K ze@Mkj0r`)tANO<9cNVS(7VDAJz<Ma0DBd8KO_>Kakqc^(rQoy(|IkJ36Q5MzHN600 z2$baPc>%Z<V$KSf0zWdrZFsBuGAzN7u=mALK4PuIH<srkj?Y|c%w6j!yoT}-Pht%Y zDzKPGnG3bBEQ#b+3%64K!dcjdAT0HBGdEISi!P?;2)PY!#p>eq#@jlmoycq&Uks4D z(z_Twt8}U8;(mG;Z-9}>UF?**IF|%OjCOktWeY?XQ@V(C?`P=V77;JNvs3>fKZL~Z zI^>7e^WH_*B0toER2I5ctKJg$nJ))<ABbF)-e!tHlLCFn%%ODlm?1I~<M3T3GBGp3 zC`@@*bLA~&UB?nY#Fv2<wGh)XCX>LW)S}F_p6Q4xJg3q~2^%DiANSK@?2Z?ZN^yF> z#nh>(k_ItI1}|YgTpA=#Mre?Qu&9fTjb0=rx%@a>=o)0&`w}@p(%@!VCt!RGi#|S( z0ukc_@2VQ!&COhi@$t$J5p5TS!y6mk_Nk)nsewH(PDkda9v5pn1!Q4uSAYD4wf!Z` zv`7KLLF{#Aevcq*)YH_4ea40%U0X^)7~BCeo&!lHYH2bqE|TZ9@TWAiJA}Hzfys?7 zY!u9;N{J;st3-N<8h<@XV=zkmbuW*<oZfb*6AO5C&?@ATz}(^8Mw6Ua!i(UmmWJ|g z$6uJHx_MyZ%zO*+7kxsY?SE`~Lt^-85)av<RC0C{c;P<9U~C~D9)CG8v0N8Q>99vN zVH8Lr?OJeocN9n;?OHI3`BlSK5qIG+O>U+p;wv^gu~3zTT`VH&5_Xw#4OsPx$22rO zxr`09G(An&OO|$-a8Yq;;ZW|A;8Wqzn0p$R1cwzU#Uy|kC}><=XCG!<Qz${sjOzz( zT-%=%#`PfPG1(EZ;7OlrR__tU^%^e1j4Lu|a)sFy!s5uR<(ls83-J@{z?kuq(;J|C zW$1~H9zUf9pXf;O6MJ?e1yF~cucR;v-vXm>I6TDvhV0DCAJxPRqhK9I|4O2yl|<;F zPFNVlh#u~qh}qfo-Ec`DLyUZ!BUh711m{T{cqp|Qrb-c$kH=9bVVDdOBPR~iNGQY# ztr2oVvD8#DR*SJ=I2r3B9q_TsC``h^cj<o#e;?eX|L)`DyIZh6Hr8*z4O$I5ePSvM zD6n9s_Xp(q0-f-b>{1IH4>~6;voRe6hX0oXh?m*}H-F!yws~@G`BH6Hi`oKXyA~QN z7dl5OG)NQ*&NYE+X%Y!<V1iuw+s8r;YzHkhkn%=>*%-#5f-1dd@(!Dj#Cs<HkP5ye z3Wlmpr2tQ=cCGOiKZu}L_AphOE0y+$(t-2n2~T*TsdAw#snCUbp(UtEyT1wl+=bf? z@zIS}fuKa)3pmr>>H$!ab`6yeWe7Jv!tPOqa2@H8X9#-}QFw-M>7#_|zsqihmrk!6 zZ^k6^wf009p`IaJ09v}6NM(=+e3+;xLl~C-8&6fo&i_&J4|}31|Mx3>OG13(N-cDU zf8zrmwyOIj4&P0HBg8&-&pEW`q5jrh<QDl0?>Hx8loD*Fvo;3`5qYKYW{^7zEyntX zXhG1hFIFLZZ5%Uy*zOoM^RK<3nNL(}X>LuAc<ZUYFI<R!G<%}OR=+oqN)Y|i>bHJ2 z?mE17Q?9ofdsVJ7V=K``5Rtu09+uCfy+f=-72X8q--0pTlE!%Vf9MocQJ8QOOVBxJ z0itGZGuFRCIWHduAg#}_tmzuHsEDcWSOh&`Vj+{E$ORMbMn~qmh+gKScUbhYkMdvA zVunpHdh~K85~wVCIT;sDd{fC1Hp_&EFq9@@(F^wIP4p)`MSXz{A{5PJ(Cjk7pMcan zeg6eJ8|e|+ie2$_JK08)49qV}Ku#})@%#~c;7IH9oKXA%A9w<kH|Tvd;{!yE@3Bqg zDtjWf8C#z3Me?YYYQ_4zHy+5Y1@9GRdN?+EEIkjyMM4~ZAa<V9@N=vOVh-#Z$m&ot z_s;t#3s|rzQLWpFKxPvqhU&jV1y1kVY}$Yvcy`&#;UCc#9y#X~TD&E^=kPo5^|64_ zzlul=JBbttwZ2Znws0yuj@W3tou-)Xs4&L_7F;JNsH!e}Fv$cKT;3fI%rXHU4}l6# zrm<Mx3^rIokwj22$<22RfFPF(3N$U(-wRGLHWm+^!nUobw9f=n4DA=7ShYslbTt<5 zH6nSt2n~}qU4_>3*l;MurCK-@UjiwDQ)GF1Hij;Eh>ao2)w4md8i`hzYOHN-QH|e0 z#$SgeVK;+!CFNh`!Mo-`Y4AQusZ~rAly}GS9wQ<!8e$5+V$blYW}h7&Xo72c5BUIm z0R<c2AZd8Ujb(yW8Uoneg`vgLZulS(G8FWOIVc^B=YkZBXHrtH{#urM6FK1+xi{p5 z|BjZ?r^^t4;t7HAMFfO2ymJw0@+{l~5Afkl3T(JPS{6>u5>pl~gZhzHEW>a?Svc(Z z;aOtUU)9-lQ<;q(hG*dMFoyaY=x7Xe<Tk!axY&R0e$~6O>-c^gG&H_>{w-{L8;?gn zeTrPx$?BkwFu1qS*Q(k0Mq=Et;+r_@KHA^HM>zZkAIZT1ZZw^tZwMMpw@w-BH0+7C zBZ!Y|XXaOxZ}6NuKJKQE>^=I(#vT*|gvJ*)#TeP-e#OY<q|rtsa&VyHBRe(~l5pE- zWXGmJ7H%7j?AR1Y!)?<?_Rpb_jXfvQ$X>vlD%eCD*=js_Zb~rYF&1q|Qz;p2Y#0ec z2n>XkHex?$hOZ)M@5`{@W%gc_NOK3vz|rc(+n$R*7=cf>IGCwZF8LKuI5U5!?v;y= z<H5e4V2L=)ShUy<TW33dL?W)kc-uz_;K?o8+d<|H0D0?#6g5-xoJB@w(q6xxd=5|; z0<^Ks*iaIYlEav#r)J1DVCj7o^2#*V-98x?NX7k1<_fbFd)|184hD<Ksh(~r$OOZ( zJAyD-M7R05T;%884*Y;sTr~eM9BzT>D*<hb;vY;={loL5+(`dWN*+dkW)#~$+=*Z( zhJQ%b7TzbO{<UBhn)<mL3VV7)e!+}JF~4vkU4%V2l6L~){iAFIfg*8%*C7%bm?phg zSbmw1>rZK6NinY9F7rQaG<^*85%WKLe)KTUUpVl70iNkw_c;b_LH=SgZ8iOwoCG~S z!c!G_{-1$IM!m=C{(+!#&p=Kij;==F?X&3{orYaeG8hiA<ut3qnfX!WznrLmy9a0H z&pd-cj*)FSWr=t1&*UdCwVzB`1!?w=7}qDLh85uy<R9d5-Iap*2A09Vu*JAe01x)? zXd7`7Gd3UB4!ZNRK!?xR8MNbtjcZKSVq7nzaqYlbE@<Cj<J)sNv(;^sO-8txM6;Dz z_fw~_;e0}Q-*tF5I=qOz-f4G>c#A({zxf`rlos}k-9)4!s?`328)956z%H{~1j0R> zg(XPkT4{GoAtW46`(&Jj`-3$i4H9%3XJaH_{C49s$ac^b2#%dzO*oCU+-a=$oTA-! zx9}I_Dt3~CkpkW@S3!U8g}Dk^Wrkcu?=V+^rw!J9B0p)wzQri{-Jh%R5$m<I|IeBE z9rC-|v6Rz3gc!Pi2qn)Ef5Y%;Z{kmSTGnURbLXjnFX6M$KdJnAG|%EQRRKwx69PUO zmmmmc<JImNdeAb)kmdXB^w=16^KKxHmH<6jWGfAHg0Vgh`XX-)mmTpWkiR})yyMJH zT2p`PfJa6w@*PGe78x5oXVMdQ?}!xbxVuQH*!GB>6AiD)>W8r)C}LY1nATrLl9W9~ zd4?{64^MhCk4>9Kky@vHss7PO`|JtYFZa*#eo?34ZEWeM=O-;ZKimQTJcXG0Bon*_ zCOC*2o-jem*_}u0dPY`FmZ}yag)a3CnX2e1HJC&`otEms#hDxK_aGK$?MSCbU7UT= zC_MCPFp_OGY;i_^UxLkV3vdy(F8hM^g$Wa<H4<Vq3Nb}$IfFdCCFG&k(c%o-t?8jf z4F8+~|J+1o8ooZ0{WHri_dbKI&zOI<IIwOyDE|!i45u9Ko)PeLNic`I=jHOc?EO%J z*+SNU*bQGm-%josE2a~|oi8oUD8am)D9L*}4WETmAi<0Um7pL7T`1V1OeC1MlY0gQ z+%p1!F77$kfVcA5?tv}~s?=P=H>!^oRJ7v8f(qLSZy@*l3=+BrXM?7o4ZenfO};OX zMlNGH1|=Q*^DOjN_4Kul_Mh7Uh=kuv++f>Z_QH*@((Oo!v5OXF)8O|#V~nIAa(z<} z4@$f-yxHep%rgH468|28KMnpsk>JR-4Fn$84OZc)ux$_`m_HjSv1uXc5CpQc-FZSn z&ZdJT3TJbd%x1Sg)Y|!iO~6P_Fuc%Ja-ro?p&Y%?j_<+?Azhft3$fh_S_3a+tnVvI zutuLmstK=Z4?Ik;nHNh{ZNm-L8^@zj+Ecgjp7=lQeG7bCRn_mFBm<!>(-d0TLczgX z+ky}?c?a+_Ni%JyO~crP620ijWHM=nCYf<&k|z8>s)ZJ8fqYj$UTRRpA|OSPmsR6~ zM+N+fJOlxa!i82U)_W0oU333y@3m*nIdi5YX)OHi<+PJ^&N_Rqz0TTeuf6u;tb+|j zdv@WR=G=Y`NRxdhK{$IZLe@PO(x3C_Pajdb3@b@$ci_`skx6Op?-3HEn)@rFMDSvQ zDv&Jg_`7{8q2|2i^TKLXY$@}~xxepP66(3XFCi`QaRlYT+~19qist?TTQ7hg`^!CE zX7Cc+(Dp>`2YiTf<d_enco+X@rirn4KomhUN=$F!!F0*j@I0l&AHRY}VUyeRRN1|7 z5U`i+MhpVdQ)SdYqnk62)7xQ9rEhZ^X0z0N&^FCmtS35~(jSDg=YI-L4f6LrOx@>- zt;xbV+2=NHJ*%j3>vZnI!*Aj)x>3A37{GYuqER`8HuA-<;x(%WsAoR&vIWno-S4mD zv;Wk1>EoDDqOMKZUw)qeJr})C0Pq&}DD>@xnJEmAjd`T+G5MWao!<7G$MbVuya4TA z^NKFP!l>HOpXRm^6DAjZUUv1^yYM1;0GBP;h4(WGnAZaIyPD4z=xqn$?ztN9765O5 zCEix!RVeWG?B1J@-9i5IHD4Fu{y6!PGQ1BN<+|}I=Ihzlz?qvla}PCMy1VhxU9@Jb z<o5!-Xa@fN{#^BQ14Yku6|KMym73jsub8-e<b`MUzAIm}s>M)=>a)+w0t##ujoj&z zM_LOn0Xy=O)bB$~E3TP&@jIwT`J%}E)P>V-k2`UK-j4l5Rnzn?A#L~Y{gvx^)n(;) zBjvYv)d5{?1NO(seF5-WX3oN*&fA!=?c0a2>#l%n7wWkYgTKf2wi031xA&++DJyz~ zTXIC-EzPdOjiiEhd4Uflv4{ATQP<zW5*Ej#)c$0W+5>y(eKC6UD;9(P-urRYIi%VF zq6*PVzS+Vge<>|UdC^oz@&vz);b&%EOpYk+dA+<_(uOp{IBC4}IjwqlQKUc#QppWX z2rs5)%W=g+^%&BUT%|nmLQ>yLN}hj*JXh2_*7v~PLL!}2-?>;seM=UnX%=_EnoIGH z;KY$dv=cjjFTkpd6h4PlzPE{|{bru__C3BgMYJZ!Q(vbPS&inWMDg?NYf5O;I$m)r zp$+BY=ehHWo;w$fLvr;OGgpuGQTuov{TP*U#f1>s-rwL#$zS50K!JPjC)|*{-a`8D zJ$Wr{3zT&)%_RcLYxxzW^qqTgXV0%L#=P$mR2br#?^%2i3R9ce7hFQ8ax;5qGpYX> z3p2gd7^T}fr}pDs*yoC8Pf@+qTjq4Svw9Lqsk1sqlK$JC*C`QoR+*`2*$y-DmTDWf zuET_^QE2IZs$t7Fz3ZBJ)h{TN(#)$ys(+F4>^Wx3*x06OO#6O^o?xrHmpG#N6HG-c z#G8o}nS@@<D3ozSC=wJ+if*N^uil3lS!`)X@AFeMS7aV2I#<xYu_1~_gFeVh@%QQT ztH0dyn@!-FqWH)-MteRbpP%CJWJSSgT!={198w+=-+fIWR7*4P{Jjz|x$9&vHi^CK zk~{`x`k&W)fpNSfr#J(Xyv<1SwKt5eWY26Wn!*TgLYR2)t&h*d`n;j!`bdYjGnVj% zyx~}He<YEN#(KRQx}xDOZ#3!cjitQNo_KepC(@gWbQDwG_E0h!Hj=4Cw0GTUrx~ja zWW-fpIOXl_>+Y6$`a|8(4$%<l4E1%Vh_Xr$OB4&ki1tQPh9NpqI1{~~6p1J4w8dB# z!X2C~&1CRyh^D%{@lYbv6G?%+V$s{zV?=Q(1`?4@O5K^Ju%@rqyE?ek+nI><c!Ptf zu2^sJG?D1*73(4?qdSy}BvVErk_1y?c_ihf^1MAEJjwvlQ5wR?Tg~#+db2rwSCR56 zQr;!;M5H4chJd`OMCjZ|I2B6_dOuEb4M&pRRLmQS$GZnlLK!%~pa^wzh-6>8=#N26 z-O={QK!~Jl0FMU~;{2bFjXnO@*w`5lDoE$_+leRw1ow?te+v+>?U#QV8@uvp1?ilA zcRitC3IWf|zuB*jja`9(^-K7U5JCNW{bhAt0BHVg!x(_RIj$j{o3C5onbW;){Py9T zp3_CKb%cxlI377~IHt}<Hm7_(V|8CDGGIU@BZ0=I8pBxE+h>Fa27IMPV=TPhh{w94 z;X!|?-=CeosiHj=OQtI0Qcr4>`a`dL)yb|9D%6Ol5=KX)o79f72dj)&J5?@|vR!5s z0RAeC<~W*1AGMtcGpYIOh@?W%ZeK;xN-FD#nyMnvb&=lqV2ytu9EqpUkh9X5nQW@? zQ~Ju)QvU-TjnQ78pZ}ET6QCfwGSXT5!TEh9ia<TpK~u9a4tlCKIDd`gV#2wx7NGbq zTNCLVXSt2h5<fWf`ObvaB%0CeJD@i7*mUH0K1qMo_#SLR1?c)!`d6iND_L3=4s~}& z5=MN`=<MqaQ#Bf7g7J(cMx|1QN|h!MT-M#)jYldmN_`#5*cx<8>3uYkq{l5o=Bj>a zl*$5>o}ZS>_myPSJwO$$B?0}-x@DHp6!5>A%3BtVu30sHWo)i9Ch)`+f#{m%3L}bK zl#w4@K8EI>+gG)zeUZG4ct;@EPxU@71EHmsk&vcutzTa$`o_M9(G}~4skaC`lhwkX zHUEV4L&<mivhAOMWJ?3h)dtDdB2?2eK!0k?_K!^|33Vctw>cE(_fOQe6C2i2CfUCF z(^h{%qUmq0%qbTwqABLDBib<m7Ape8BIQXp3D<G?r@sV0_P>L{kqzj>F@6u8KQ=~D z{MrD$*p)O&5NjVr7s97JQivfyih@4$rLnPj*n6?@%VT4;NIwMF0yqqK3E&9eFyL;$ zy8uT4X>Ztmz~=!4yyg9XMS!&4S^~HLuojR4=?4KD0NVgt0poz(fExif0uBLQ2{;V6 z9dHNWPQVes-GHNjF98bp!fyhW0M2%U9$*RJ5MU$VFkl<t4!{Ax{eag1mSD_7^Hptt zj{*(>jslJX&cnib9AlJnz#@z;;($Sng|-9k2Yd!lU{<dP+duXL)&kaIzHI<-Bj7cF zBY^h;ip!85umtc;z&5~n7#$A-Rs-$^Y^BjMrUnN9y@1;QYXP?dwgK)0+z9v#;4t7m zz!AVgOtg&xE&vo)fF7V1uo18punVy5Kan3W4!9ez=*qFNh45N;19p)2dKKgiI0Sev zVC~hA16_X&&qewH*akRq-PqVofa3bGu@Qn_hdyEWGz7Q+(EAPO2jFhNZGc7Jgnj^u zTTxGdwSYy?tCHJLE}*y_^$R$BH_CyY3HZfV0(t={cD?vL^alHvyntT7qSxT>0+s*{ z0q%Gm`UXhHYz2htyfwl#P~<vp#^Hq&6LTT(*tRF`O(75Iil=CqXWq)0(>D}u6rVcw z^pndLew4CO{s#QKgODj9_@E`hbMUK1o1iMEgK%;D%7G&_r-RC%!*yP;QF3tj^%pGk zisLjNM4xymLLTfU6b0WU!6;fg0p|e^)sqL&-;LjF6Me$HgdgQ6(bGY=H}RVR9E(BX zX5hICfz$j_*<RoZfI9)_V!5Yit*20?rEs5=U#BISjkf%RYvcU-c?p*SP9U$D?@NGt z_ls6~Hvsph4Yvch*MZZrCVCXZe7_C%3~>8^Ge6%x;PwC~x0)g!<rT1TL{H-g&IXS7 z`xxC{;VIgb*NUfxtns5Lk|bZJdyTla#Ni&5Lt!h=z&%o5I!Lzff*;Zk!WBG04NB?5 zl}K9xd^sWNsQk`pp2EQNrQm|}<u2S0=D1H~J&F5q+$X)EgK#t_vCV`d+V29l9k_Z* zRPQO;mRIMQw>f{6$GfSZWtwLmimvw*uA075pCTE_fI`uaAm0^~Ps%6n%Os#`T<!+V z@{MC-*WtV%AJ3GbyNu`#fG*SsbeBzEj`Ie2?w?Nl%mCeMke76;;BPQEnY?wBx4~1A zw_=*d3oaFF4b#Ob$k%{;!{~G9^_hZ4kPmk^)3a>KN0xr|Bz2y`dNcqkCx!Gy=xg$+ zoLd~r*<dclk9<_lZOFF=`Swyd^e(-noV<o~LEwwZp}uT8`kEk>6Lu^o>v^btsqY#= zUsHv10RgQ;?fa)MlR7BtANNNOaQ{i%7wC&}<$oRby}17grr!$sjVAik7g8UW>wY=z z*B*d=3+}faAb$$?<2mk=u3m}z8*%?=;tvPu+;-r$0p}%z)VXFU4@&<l+@n6&oc<Z$ zZpe}Tb=(`ar7wgbyDdlhg}ArFmcAOeojKCC;NFNWeHU<#I;0PR{{r0GjeB#@b_&i! zM-RQfBCp;v@A7=V$9q{py=Tcbcb%tX^I>(K>P?5Q^o+RjH@c>Is)4KXEUEW+krsK- zsFstBCz+6+aRdAhZU3m8Zs4u~?kXzBZ7BydxE!>YbU7RI@^5!8hnkW&1HTc_d<h?j z{t3<tp1=k8xQuw;hPLP3Tmb$yxj*fx&1;<IS+ZQVUBzkBbXl((!A1xCpi_}w)oYuq zS86{u;NAf4ZJ~RawgxJBXDQQxMvaDHI+uNA3-awozT1(lU>$fu-c5PSVLejQJVnT} zbh_mIe57l|lBS>9=cjY<zTC6XmG=smhY5m7QOqx$PVMjvvUy(^8{5GAZORLPwe_+H zy8k@ruh@offfFCoLBGRO6hK?6gYasBdl&ZyaQ`W)59$pwvO~SI?5O<wJ5UQ223C^% zsa=eKhuQGgDsZmk*Cpjgb#o5!hkNhP^F5T4ep}Y#p>~Nj`G#)}vHX>tKaYr0-H^Z7 z4Zm;;&c|CflrN5aze2t{vh($s>Ji#PT?6V08cq7V9r@0{CZtlz7w{C-0-OO{7jUmY z7zH!&e868$x_4PV^m!ZU-ex!SdDCI}3#TaorW*=WKr8``ji5368)IXYI4|&lMn=yX zJ>H1yX~2bi=G%~V3DUkuX(>1(>WlkK=(_5kdd(dN3L!a?uRH=hIS=P#&p!tpI1}Yl zpCWMYSD^VQP78ho!<;GqOthLWK@Pxx11QZ3q$xrAj&Gu`11|-)B0YHEXNL0eGcTiO zUg_C*c>YfgpC)YtlsEn8q<->w&IhgS;OlMD59%~B&$EJ_r_mG4FNEfi-h&C47ytBy z$a@#^#giCI5YP83o=Nvh@@`S>3nh@fc^>Inw~vjT4I@<WeMLXZt}Qj$o87Mb7o6?Q z3gVe$xdSI1_b6YOWVI<TDD|DnYs9@S+<OKcK|ybh@-lX`(S!2l<T={Wba~zx@DG3O zT;5KU_a^S`q4LTs<vH2YCbHYR^Bv1urJrvI<z4xQ?DDAXoPvAT;NBNtN($bFbCIbp zseh=iybH|L1wW((`8tqq^rf+}Q>dPw%g)!}Y0LYZr|a{cc)e$!9`<G>5HM7kdS5;r zK7uKMe>&C08E{<h?Z!SB&=spZMfo07p0sX4jE%X}@A{9q=FLJ|S?IpR<vQKnp1;ZE z{)$Un<pK`*E<jc~kiO{r)9=m`oAcb?&J%a$;Wlv7+81ndiR&maU7g#v-zEOVS4H6k zueiiLF87lz@n?-Yf9-Gb#5eNXKh6`on8vZ6MDF$OUHRgxF83?>;y13YFBgbE=PR1W zRWBCe5|{gOx46UQ-ccZi@;<+>K)h0b+r$_6pZ_tOSG#X@xjyH<*p+{?%YC~`+-rRR zaOYWcq7W_aYh7YHb2GaX89(E`Hcwpcs{CP|_&#w&G>>!@F3c--RiS}gNElVlu>tqR zZgHM_Z-MJ6D*l~<Y2S5=Z@F<w5|#(?gLL1{7oF}0@?E>~YG7OFQGS;{?N9lpbYrge zIp~BM+<%-aemBSc{2cN293&f)rxzXLzVsMz-7&{~^BD1?W6r++7_n{c%>SG#uAl23 zo-4jHm+pRV?#w&piu>lee>zwEQsN(;>wavmcuHb^FVFGRR4>ynb=5!O63_BuAAKSU zTIs&WCDysGbBP}?`U_iJ?yns!cDmf}93`I1bMHJ#Y%g%%b(Hvhf%}@H#OrSNv$MqI zh3>~^iQg2ue>_Y4v(WwZS>oLz2(xpVd+RLmKc~6>UL^i9oiN{?;r?@xcyxyQks|T< zk%alG$Nj@1@iUKm?@aOiB6`>{*Ri#L9qV7r7f-p|59W(ETn|E)f8ffWcdX>}cP{A1 z{Vp-&f~EQ`vwO;EXlB>C+;^WKzJEND-FrNp{`PqHohOJFj(2Z8L2N#u5y?*=G)nSO z`WsyCpDq%AIST3TTSTW%EyC&V<>~8-+)pePV~gCkFBaPue_XOx_IdY{i^W&+koC2> z?pqg$H|9T%*80$*X*hp;(KOuLzsUVxi^V&O+_x+iH!W_E+2&Bdf-7dY_stO3&2T?7 zL;PaK$?`@)#raxOK7=1i;6n*~D1i?p@c)tocHE$zW{4)(aK!mqU1k0*oRfALGDy?e zd)+rB{qXcd3H*OA0o|Iuc9s%_z8<k%KV`dq(RQ7`)|&q)+qIXkX&H--dcHnhU5fAU zHJn6wv|gnkts&5{?P$f>e03>SRGlc#j^k^ZOQGXf1w<>~$525YnBI}cKmIiqqZ5p` z<N+^M9{B8;Jm7!IBZxUHIxv!v$2-g)jc4hgaUvZUb*iIQ@q;NZdC>eJ9kUe>Ois+@ z>uWAoCmO#*PNHC)itoocBc?;-q09T%nBxDEL4_aVYt6@gzV4QjcY;FX$mi8`ncRoq zLkWB+fhmx{$Z4wG+evL^`*k(Ln;G8C@Ii)8Gklrh8w?M-T2VZP;Ub2W43{xn%dnGS zKf}!ouV#2N!@C(i$na@~FEf0D;bC9n@)<5-Sjli1!?g@M8TK>W%<yW4H#5AO;e!mH zX81D0Hy9pv4VTYw5yMJ`%NVX@*vYV;;bw+cGrXDM-3%XO_%y?p8NR{ruxq(|hKm?h zGF--REyGTR{R}rVyqe+74DV+6Aj78_zRd6qhN^U|H`Y7rm%jf&f!v*bP}s@h<Acs$ z7Q-JRED|`$HtvJpBM-4`V(nx3(xs<)mz>p(-Rgbbs^W^`l2gn2<dyG>zUtzV@{<(S zQh1IFnwHj|BQ__=$L1UDUt00`Li?3ge1XvZrxouO+K;p14-?w|v*HgI+K;s23x)PK zt@tB^_Oq?{X(G=3kQEQ_m&fN;{0vd#h(9vzw_DSD#4!8wR{Tt{<M`~Bnva#zYrIbQ zSz`aGPWYqJ;{z-GqtoL8D}J_U<MDzOKSwzA@A={wAwHR{clqSq^EkjtXP%=S&lmH> zh~J5h9>rv+{4bmqh`-BsPBK`vfZ`GuRUM<`pvO-H^RO9F*UJXZ6b5vm+)*x9j|(o7 z_<5q1@m-w$M-uN5UZ%f<@h<`reLY_z*UEtVKQjG%v4q>DuALb;p>n;9*X4eU@wy#* zk)Mth;GLe=0G`Sny<Vl$e?yG-+UAXDPadVW&nIE2PV%GWk4t%Al?(W6JsDv-dY(#` z`>0Hxt#7&be^sV068jwV*6DfQLVCQ9m(?z2V4&&3DAevB%xC;|Tm4o@e6~LS2dCd* z)5Db#pRLbrz~lQTSw{l+6QPGA^CiP#4yV`(JniqaA3p>Bqo|i1x2ZdNkJC~NWS!Fg z7x0vR_-2)!_PEh;E|#Yyogb*{EeZ(Q4^8|Gv)&dno>nR;{m_jHF^}=Icgv~VVc>6s z-gepa_GP9M999H$-Xk#Xr}Qgq>1i8|PQyh?@O_yc?XKZOc|F88=VD?&KG*#Up`U97 z@I|P1dwtRNDoVfq7L~q=>0Al?QNY*ICPEzh6cBd<e<Eflo~c&l)-t{Z4U_OI7_a3+ z`>UnghE+m64^oZ^3a97V3_PU|vYd5$9|fN3MJ#YhLhHHQGcnOZ>1%(i5L+1kN5*gb zfkK?h__u&}D)$^PM)Hr_<o^@kWw~=zxwP+qj(-48<$CW>*R+R>j-SDR5}gtoox?F9 z<y7vx9QaD$iT?0*MVIzW(($hx=}(7foZ43t@I+@f8D1Q;7le*^SlK1~j(gQL?TMn} zdWl!(=D+s<PjYyK<p4F7#|ZFF&-FwO{A)~SnCX0+=^T%VIHEtw?GDu~kCTDF5qew1 zc1G*f)4&t|8;4aoG;?{hLI_U$TmU@PORKG3_5m;DaI4C%?a2U$5Z-&E!lSv#qZSDW zAAC|>(_S7r3Ni0S_@X=1HKWB=#_wi(<yE)EOc**!KRT=sn*L3U7dI<BH$PDW*MZWH zOji}9pYc)Po$CEL;BQ2Gj8~l~32C_*FwN9X_t@}%2A<?|iA_E$k&(*X|FGhR)ks{+ z_}U*Se4PT~9^jq$d7jf3eM=?$7^iQYuj<{){@Z1Y-^=)sdFpxBF#c0;afqL`8x=y! zd5G~P-&1&P$DU$*?Y9-ap6SfT1TfJl8CD1_e?RafpY1mJTmZb5Ig^m!ex@_T^snHX zujWX9GA5R(+#NQ3yPNSPwtnqgOmtJdY`4|RJiLJ5#7|8Q{Mo=e)k_q3S-&=Z-pN7d zxQ{4)s%`vi1D@J%Ew^i>bwb<;ynJ4+mrt;KKH_!ee>?D$e&i;VkoLaQQ2~Nv2S%4F z$}1FFT#rlYr$*R+JCE@{lz6@{fx?eEms<?HlYH8Mr{~(p{f_QmUd=&g&VN(<+xwkQ z0Pj>^K~5jPQ89^TB9EJ8`s{JgZNQTpHuC&V8>gp@h$Ocl*Q1tmE932c%dZ(fYO9x{ z(J-C(Yy_U##el7U{~hqMzJ?VeP#bx4Epn!_DF^;);7QKI$GT+xPcxlY89&N;^-0E` zvY4OOW>-fUzx&53;T@d5cZo_r%J!4?4AQZW@wF`fLWLH~PIBhIEeC!x@Wj8D{n!hc z&Jib5ea#j_Hhc0_;GOjCPT;+q*9;y6p5$CRtg!if^RSPra(5r2<Tj1*vw?T2M<1sj zWj^oc^nc5dKK~SFI&*<1eHh{ALU$~WGk_;PcRZ}FD;eJ-(|bgm>k-|YJT?RGB!~Ne zcjEt1rXT;F%CGJGtW%xSw*pW6?7vl|*Zuon7(aBI!h01Ex4_|dD)+@4_@mL#oYJoV zUbc&!iZJcTrsGA%*Zxpl->!i8R*6bK%6f=qC6C!Yg)jQHx<<2=M*?`Ka&HBm`imVl z`}{_Z^fjf5zV{|Y_d2G37vqP&r4ZWhtt(UX+idi=08h`m`=2U3?E$7^F)|X~Zr?5d z-iiNfB|dw8>6=WamiakSkr(gepmTbK;&aHx=gq)7mHSuViO(G`D#AL=tx#Z+=SCZy zYABve|6P@SFZ1&c#_#9)^{ZwnE~<7e_iEs&9qD-_-HvtvPj-HH!-<lz?ic(us$9FD z@D}izXJ$o$!%tK6TWb`Z6@2p?;GNQ62fVCDZZBR=zvy)5^daCW{V3Oq*3X{<Ka2C4 z!5?$bah>6uz7lxZFR;Bjj)|QGyc7RdbNV*6hiGo{*d_6^v2WQb&n@UsNdEI!KDC_Q z{~uhxH!6f~kJkh5RPG(X6P+O&{n}3{e47n_2k=zC`)&2x2?mJHZd-qGA@EY)xP56J zK2@jiZMJrLJMcx&+Y#1Vek}0=;E8@MuRnsUJU&_P{9K;~p7g)grvKLhPyB3TJ<)PL zVyQ}hjV=8a;Hlj0EC-l7c?<)upM_Bp{2F+oZy$HeZ*Wdu2E3FH+jBNQ;vV3s+=p%T zd#>M^&NqOk=N+)|U%E`u8D=_g8|2Xryc7Qk;7R`W`IavNFZmo+`43Y-%wJCQ;XllC zNer5aJX(R5a^9(~OBw%V;GN3-ZVvpbOeZ+32<W^X7zC2fJez)oftP-!&EI|vc%7G7 zk)SxB_>41sH{bj$<BM2NU>@c1O~$t!rJnZ`1;j^JvV0y^>9qgQ%=oyievewE_%CFA zhS`+Imw=aY{<XTM_k-wo1$Za^^BYzAAh#pkzg!5slO5a2>37_(=x$L!>;&G4{tG$q zvsNqqH`?0cw<O*p+E^bx&Gi2XJU!RYj}+pmJOu}ul>Uh0Se~4IJMg5>L7P6m2D}rW zhn=bDkM2?g9%VWwGd_N=LZG{pM+4(W?o`)5Vf>GQ_wu<J{0?~1t5F`m4Droq(3zhv z0Z;r7+xR~X0&(L1a*2nZ{B=e6ZPu$Ba-_d62mV>$NzTK=iq1^tGr7iDA1(%-(t}xf z<a7GBfOq2a*k)DlCAN0A5_qDs|29Qn4%hFWfS<)Q&0tK@!ML02{SLnQgBEA`{~UNH ze%{Q1FFlL-8CHa~z4{yDi}-nUdv9IqTy6q*r*i)X@btVTOh?oI$k_^SZ|{Eq-boJo zfhRq=*QO^mt%^<&%hSv9c?5VTe*TpMzw9&4>2Jt^|9K9)SlWDc%hDCaRTU+|_-s>i zs>+Zd*?hiIbLhZ8m;$(k5o*mq(7b3W83_9k>nH5@FD>;4SB2NCYA!R1qsc_5xV)xV zh7gP=V)5dNav#VpU;Ek8vfyBVLJ8XA=lN@TVjX?m5k$m7$|*?aE2of!(NMS1Bcr$p zV|nA5^>vMgff#;9z*rZFBXD1FI37oN&8fy}#5jym7J7b5tfR6}Jlg0p{0HXCSCK9+ zf*6J!NfAz@lBvGV&f>5@)Tqe1C_)}WZaqf0JJuUXBB)|V%vjeQYX^@Vh(4G!LVW`w z9HXFu6t}UevZmTOk<p2=j8GyG8Z;2&F)=7QDb%9T(bv;6h%BZn#9D;3%}EVo*_yi5 zegx!dKtM;sSl)D&;a|bX6%A{s$Yjju3iWn$M?}Nf#faEgj39jj14bON9Amu*6PX$` z`k^QdpJ}RF9axGSEvuJmf-L4Umo01dw-_yT^^JZM^Vya_w6=C>YinJ7!0;895vJKO zTA5w^B-mss)En0Ex2ohdVxpzPJY`kcBm+lHHZWU*&)=WLLnb(3wW|EYU`@O)*#&J3 zulEO+1x;b9g3J05lq=ZO>@&(r5-Qjj#lu8EIf{pgaGRlZ5uec!N`?F~U{p<NFdjkO zcE*U(Dg;#|gbGL3Pnz1a%A&)Q6i9}}gNamClZ>wG4W;@L5hW%a^U&v$VFZ`qL17if zAMwl&6C~rFrlRfL5r5EE3GoC6>!>}PsiHlSc3E3-raGKsMM|r8sDht0lsYI(X<4c( z5!+xy5{X#C2z4hSp^iZ#8A&;$%{&c97xYzV3!|e}u35XP!|y9ehsaDywXkRfS+<%a zqHRWu-e@;7wR~+Z!5vId8HUrXp%U#ll1PyP>#&@`RVtd@d#bn1M5j4RYZ^=*tW==! z+;YFaoI^31qbeenTDnvfQLP$LLn&fz(%<i|<ao1oTcn$jQ$Ro^z6iC^1K5JnvdBOj zaUCgC>7Z=H2sjI7*CAk@uY{u6DzvQg(rRhFRnM5!Ws=Ehu~n94a6%CW4<;fd8Fs6_ zOp1j=8T2q$rIuFr!qg)A>|jqU5l1v-BiaEsp*NBUp?6kMAFCn*kuU<0`hy2D_@$*X zba9p)&-7Rbo(Ws;E9IUcqyoR%Ib*dh)#i@e2dD~^gfvG67xh)7V!D@*<ptKPqG+L6 zx+HtsLlxT*58`a(b<9v5pw%~?(6cH+E5zj-19n{9L7JaTpk2paTWhbcA|1$8^{RfZ zGM_2ND{#%J@^~nk2n11~=}@m#>m!33Vu=oabB%Nx;rLqH$N}sX!X7)>D;)*a*-FXE zop9h{ySnLTpOEo*U&6tLP0n9)Be|E8>$SRV9b|B@h5V{OvbnFFnixFW@Ic6Dhx6Wx zAib$@m(7Qr3ODP0k)Yit%i%7XwOvLumSd@!p3s2mU}ZPeg7C0*xulzax%Bbsy1QeL zAI#{##R60#elpQ_bOwXgwwLilN-G^*?N|cNc7U30w#Q`3T$%~Ni~(2LSC{<+1*|s3 zVfOnep9-g+=>x{+?z0MF#D{U$d6C-M<&A;*rABFSX>kQP0L?PaH<~iRY8?(=xr|j9 z<VI4d7<#P`jVjA9^!0al%WUI!w`Fqeq2VHjEh|;=t<#Pd0(2`wcBuMxvr7BR5|QkY zysswHS*HEs2@E_;od`u?Z;4^p(p(NbX>2b+ms^o>-(*{%N|5$LYo`&>LEi1n#p0G{ zlq}s(I5_v?uRxoTn-a5+5o_9io<IoWQW?TnhA-A*pd6NGA|ch^9}C)pK0%H$xUof4 zB!8dX;&DZB%=;<vc>W#suFA>YP0|CMfNnats#beFDX(PmLz;#XRh?6ymIvQPYHT|8 z!C)#q$hIl|WT$hSJI5R*@jd6qgb^GxnlQtPZ$;qyHk0VE4z}K$I-)5VB~M<f$&;DL zC?wr^TfapC^PRE!e!ufz#MDdb?hdO1G<=%ys)BUDR%u@{GjuE8&=peCVs^P^%@#`% zhwifmz7l*~sRN%ZO2h_b^RUlDPSTuZ<bE(Su_O#)Nc!Y@3_kuLc&-sRs9J4y#)By< zP0x3koMbtFfiD>(FcYRGR<h<RauLiufkv~P84pa^CW{f#qIa6TtDtXt(5F{Q4AbOe zyXnbteA1`NQrQ7$+GNJz<h+;Rn^*pceO9HMhQ3xw9q1u--{vfpam{$-EN?=S1_x_l z{r&?^-b{#>Lp3}B&uZ2`ryc%aj-Z-THSM7etVdvkO;YC(XltucR$R^loOOMn1d_DJ z5-H2b#vfSjZwh|Ks9Uq94u6AzsaKzaF^5Wt<Pc3gK>}+4_#~F)874coGyxyjzDkqn zGjbRm*{NAtamM22HjoqI=zx|qQ<~FiPNuKI+Rg`aVRN!8y=K=Ax@@z(>EU|XL(ZNJ znXp5ZW5YyNOUl$qX@%pw7A+xXW}n8l0+HoT!IR^4CwMxvMI_W7?f3a;yGVB^nN%IS zT$i>rqKr--#J8~yzTcphBfUXGEw*;Y)?uMXF1cd=ip{oVRxvWJr!wNwW^^VZk@uX^ znW8V1DN{xJJ|?7glUhx%Ius_o%DHx#85Cr@V2954cJv9x!~Pm_zZ|?r>u@_m$+~Wr znN;)#*RGPSV=9(Jr$*PUb*Y`h2{}jy&j^-l@ZmE2C!>`$DUEGdG%4K^=?TXNGxOU% zI2Wc}98=VeEF+-FeFig^$2}pT9zw5^C$#h^+Hu#-R8CHgXLn9|jv&`;>3F_KS{{zY zF#%tOiOYWO&dlF6Z2{hSZ;-W7OmdDh>afbLX8ZAV+bH~C>q3pS%&dNu#|Bf>OHS6k zq1KVZr?C%C()()6=3(;AxY@DNi#IK6&0`N+-;6K)cF_(g18eO@7-y*nSr>~_{2nzM z%{KWh&FQX8+A2M#Ul!>N(Oxr};tx*Y#LoM&azVA+(M@Z%QbqMhPAwtUkmD~unynnY zbXPX+p@{Z^%Xk+=lE0$dQ<fgKL(R20%6L}NG^dNRd5O*o(UhfkLr>O&ShOJ1Z|5Ew zIjDkFm2}VPt3-EYU>UI&8*Y>FP&guIHcJfJOIOKTMc_$dJ7;rM?%A0M^%Yao!qW2( z&JQ*rj@}owb)3D*RBn1CTJeRxNMg`Fm1l0wHBEgzak<r_yeG8Yanpc#=1-|&rX;5g zq_iVN`hHgFW-^ufLKq#T_iE|gMZ8_0#7HYxwHiplq;(n_68H!`zBr6Nt_cgxzA|DL z+kVx4=rr2;d1Bci$|cq+UgUOUO&2(ciXZ<(!sI_rY}w+oQnsW+IFewWDVH5N(B2Pl zY2Nx_^M*|OD6E>It)|bk<<q~$=L-(5mM=y$L^@#y<lgSd?RDZYPI}*i+7CRwAx^0; zqq(LXhzFWu_eoXdFJ{vYK7R#txf}bu<;F*c4{BRyMoI!r<@81G(q3$N_xm#&FU=A> zbQ<9+$GQ%6jr>Jyx%DrzQb5)vhqCC3b=sg!-Hxq7bia5oj`6=^djNUarl*{u;TX@R zz@CNI8{w|?MrSD6opGHp1f=FL_2pJ|M3eDYl3z%$)SR}9zDmrtbkM68Da;VjZa{4M zwXF}q)PlF16Z#d|^MGl$*{bd1-i|)b_F9p1)lIcot!40t$feaA*bFG6+NP#=MNQ?v z(4UzY&bcRV9LxI?l6TI9?D6+uYIZ2+YPYpUwDx>JdsXu=%halD&h|w1UQK>af~AMY zJ7P4QnrZsHy^$7Fea32RxgX$RL{kl3M(gdPxo2Og(HMi_z@GhRc+ii@PCS#%5Nq>m zAHSw&Mko6KW>M-9tF;gKfa`*uE+xlcsn3tGJEWI+p=63IyzDfrZ6xCqTPIR|mDIs1 z_m@Xf*>71)N~q=$)FgK+9@ryH4?ZfpW3lypai`ITrI*Rbp!7h_Bzg&pH)(&@!Q>3J zps8e5YHdSeIWa{WbdA1V-8I-3Xx28Fmvl<8ypxQMdsWBGrP|S9_7<%6#fNbT-lDKn zG|k^xwq9VkL+VKHh)%5i+jj&_N@3oY0WL`_)Bdb7n?!#So!DNII=sM(Dk$~g73@%7 zHyR?Ti!`m#2<?oqzCIUSgDH+^bDe?za<FNx?<uk!a>U;wcOGPS3{zlh&1PZpQ<r#p zsyOPY4&D1z<Lu?q?&kZT&`upB8mD$WtrLG~bZ(FI-}2_jRQaS@8>dL~eZB*YH6y*& zuKFNMg}Dh#p#7Wn@%sfv4B?)*y@gJ0mcn5~oU7l=xf+eWMD1`K&mvORf_2W(+#&HG zVgGY95Q`YnUhTSY7*i5Gq26`$Cj6=}ERh2NxOddSPG<kD^c?Uq4ZWIf^BA<wAC&q{ zcBx7)m`%kC(8@TDUuh;kt7+~etzyGOkla9na4QiX^}$AOOiq5t0eeoRoX8YIRE}gP z<`pzh=kC1EJD02Cw7u3Zf`g5*-gO2Ad!Q3+9BjvSA<V8M<n)epgfJ<e&1}jJrZ=~} zbU{n9a^0^+{;fy-U=DLUo2GffOlHHI{D}U7clhuQnvC+0Om$#D%lj(Tq)c<FIvP`} zW#s`(d!f~4uhBW0fvO}t>IlV(2&Ga9#FYuFXguW5nHQ$ie3iA`+JZo+P$n5CdWt$U zQv4h~i-QXP`)6$|V$|wpZiCq926Nh@-s{dx^!nAfq{-o>1lg0UjwF-VXjflB(-Q{{ z3zK^_l3q)u{vQ^CrX8~f!KTq;j%B6s8#7aPk$I`Hf|~sSmydK0<haV~6y8J&`GY@_ z;fWF2esBmq`leOBO3cIrWyGJg(PT6obfTi4u52sgm8!c4poP=YV7fYbV<{tv2qV$X zXaoTWs%ROS#%KL&S}>rNy*b=R=a<<J-Seu~WYTl++&R$8_vFAhH%{v+r(DibHRTYS zYJ8rG^QMBS^em>TPm&`{-4XGe{CK(`6*^-Q@9i9LRtkDzUg9Kcq*e_w+l$Bha=U4V zpUod~sP1g<DPstA18`bqvxj+5&EUOV+A_Fd0X092288Z_nvj!!?YK2T8$6$FDHPja zCbkq>79e-VX$@4)*#=tZjWhj*I3lr8c)1qZt~8-OH$7F5J<~&NZK~YHvwAnsvf7$R zvag4x`<E`odn6QeFsF-aA9tl0{eaAAOk!MBgT-XEXU)H+$GUx~xRgRA)?ktr%af41 z?EI+$eAqaPxQW>3mP{EcJ{5Te(xUVGH{mbz;gz}r+CJwH2t=QJ#k9&gZbB(VPg9n? z35C(t_S#&^vx1H7aONCCBVfu5OTCtmfZFm;k<-Z{Lu3#{Sj4M6@W36`?J;ehj>|x{ z-!^rgGr*PeI44*4H6gcWs=5vH#%sAgkbcmthqQ&u)0!|Lwh!qz+E~}4A|obJ6vxu$ zHDqnDHSLMeizYoi@14z8(h-pp&@#A;&Z(k*O~IJ;&`HcTs-5bVCbx~^E2Qw?I?`<o z=7~C|99>gp;E~>rM<$M(KsDr<0{KpMaTgJLY@rt%ebPy^jzhdEqn+76M-Ee~ysq*2 zQPStm+Oc%-l9?)V=jeuI9?farrd|ZMJj8*sU|NRy%1RX>H=u2TWqXv>mn}s!A`buC zF^G-BDzqS?{YpZn$%WvubUe9!>OnEElRmF~W{9}9TW}cwil&T&C{7Ocq(be0sf2=E z`V7OvNHMlg6u0+9yE{(Bn!mj23MIQlF_=S61yc!iryntYqp@Dgg@Jo`RW?K!_$=O? z62)?_RxwVC*Try&JsbEd-&re8#AIO1;z$=qC+_M15q$;fn8#L~6G9x4>ne%i^-08Z zRW$TD(V@~oQgTY-ME+Qc3I>MaZx&;2Q6T<w4+Zq((AozD==&ar<Hupo)89$f-%DO- zqh4UU#%FrO8)IWJonL=XS;KQUP`QrJUTDi-jqB<7>HPY;%Nly;s|-{wg_hU(=P9(P z1ti)!f82`;92&lZc<1JWXqXRtUP0gk)oK3qcbqkx$AmTix*QD=mR<bIlwW`ES;Jv2 zjQA%Sntw)%4xG?EO;3LpTEqBkl~R|l^XupD<^1(3S^E3Y`a9Ai9N?Yu&&AK4e*id= ziH-xWzcZ~N<uM<`tNBRc!kk}!k6ObaTZSUetl<}J`P1L6zD_07{BpK5{~Ax<fiRb^ zzoV?-`GY#Ag1TIdz08(>8-MRwL;j3~PA=;zeSwp&a(-QZ`g_?L9y!gNS_rT8Qe1D# zufMCU;Y*q@=d+1Z++xeGzrU?v>yg$1wcIrJhqnCsJKY+duN99o*vo$acn^L$*$V!S z&Wb9k75XNN_0Z*O_&9FUw;pu<R?gqb`E@!?MPF<90&Y-AI=}v|Qyb@R(>Iuaou9t| zPr9#@>F<b-oTm7%W%=vp*5ztCUq)VY`RVVCe^TXt(^h{vzlQ(Yp1<})U~tr`{H^bi z|6L?Cm#@Dw-Bz#i2lazVqC$8XYLJIy#EVX*zq7r=ukuUcIx(QvbWW#-BN?SEvEg<8 zlWcgVnkGxvwnvmXM!9_Y?j{`z@T<g6%T3!qYM+{SoTiUA!>Xjm@LdS=q084e`nH8r Q{s(@dQWn`V*e=EY1^tW0?f?J) literal 115848 zcmeFa3tW`d_BZ~Ff>LTj9Zf8&so&H=k12zqkXj(1&*)&}rDL875Ku`Jf<dv&D4?9C zDe7d|?PPa5-8_{YtJ4Xum|2mX%IqR(muEtg^rV;>?{}@epJC51V`|p>{{El;=*;u1 zwJ&S!wbxpE?aT9UeWq)4CyS-CCO@6E3pESwm)<Q9sS>~8UxXE(R4rNSs-<dYX?;0w zw3!g*df#AC&b(@xjdKyU3%*UmM0(S(vl(w*TY50487GOWS*{a6E_Z<}cY!P?uc?#) zAM+X`KrISa`fd=#I$Z5CpLwOc^vV9pT|oCOXNrQM*R_(Kc{R&jf^x*?k$z%j#tD*M zB)QmRgUqXJ4!5l*>Y$DsGk&sG-MZqxjhklv`-*?A{m-ab{T}Kv`k<RgRO5R&zC`at ze4mQD?5TTK>!Z$jtZY$?eusA6ADVis)lRMNr2RFu;N;GoyDm;W$8lzCr(1JR)Vt}O z&OP6rk$q-YSJzHy8JE1(En#`L8`D#@;@CU1>MX4)E%k<~%(`1*oM)bJNz~GwmQzm9 zP8oYnRo)nz)@!4sYQi&?gxu7a47V-1sODBJ=BMa8bBUKL@HIbI%9~tVr{SBAZvnp3 z@ukm9e6Qj=O`C;l3BF|#F2|J`Iak7!^11-mh4@zCdjq~V;!AR%PmQ=}H_5AdSp?t~ ziMSotyX5_1d6g!j-3$0WiF;69|0b^w;ks1bKZ@()_&zD&Ww<_t?=$#5hwpNH|AFs| z_`Zbi3VdJ2cO|~B;!B@@;rlwi|Hii--&Odo!FMgb^jRk^+6G)V;`<i9n<VZXT;G%T z@5}3d<n<$5x5#_Ce1h+1_<oM>Hhj0^y8~bI^EGb1k$@l9W_))_c$d6>hii+x-z%?l z*@tf{z6bC<i0>hM+wkqvJ@@U&*(c6^;NeLR=JXu8Z+pq0)6;+Wvdh^gjBw}u^Qj@r zCQRzO_k|{J>GO@f&%X7GX+Pgz_|YrA?@xMu!Yl7qCUx!f?<HeA1E<{5%`&Jcs>^_G zdD$zU%t~3X?BhS(KVbTwqN|GHzdY4u=~?ht%hHNT-+S*iVjtLa@YT~j?<7whwg1I8 z*Ja$7JN~YZuDbHOrn9fT_JgR6pMG#-(SI*_{{2lSUsJJu)dx3E>%OJy>PP2a_`<8T zPiFPF>`(Wv?3MNIpeMJ_UmlZl`;C{)9XjBoU8yHsc>mlL7fkH)^LvvYyL-}!vq!&j zOX(vYUsgA0(`Tc7md%enS=?vhnU7v|i`_lwbpL~M{+xM#r<)&hetgKdbW+z|)oI&z zEWf|<&<`_i&d(Z{xZsbUw2pZ7%R?7mba3;RXC0{h%Y5s)xl{MuXI)%&&2@h*{OF#? z&l|A3=a{yI=M_bLeD##RSKct&-JEjjo%b~^b3N4it-3d>*xCy9XDZ@LJ6DC)Yf; z<f7u(m2dp>Kiwxx{kre%f8BKOk#{`LWqsOp^_&a;_F>W3-GA%T@BX{3V>aD=_c`76 zq?|pm+egmA6^}gi@XnH_x6e<ic<NwIx8#2rS8v*L>*W{rU-MAjkNxlH<;bgjaqXc$ zRi5f;&DOThU)nrK%ej5|!ngLmy5r6Ty<8{G9`f`3PgzF2_g3@!yH9#y(bZey|1tjk zM`sN>eckF^SB}d3VCVGlle%6!=)*xn?x{(6{hq>)qW_rwpyj=Rr@nCUa|<h{-al<s z|DvcJUp~IH|MnSYYE#SK`Tp_;Z}M+D)mHlKNqPB=e|Toe_W2Xuy=T+Gi~X0)Zz!w! z>Wf46hMh~7BwyTl%lnOYWq<SaWqWTq;qTkmFSk8ZGxnMLcE9z0*VWm+TXz0=#8aQW z_*~Z;8=JQ1mlV%FPak#h=IVZbKX_mN!n?LD8E3ybDu+z|u%FJ_3EI*-g0qzM(zKI< zQ4ICLICe@H{OS?m@ox<dkKcMhc>Md_!sGLk!{hr543E!>z~`Jv;qzblhw$y4fVQ3! zroA&#!q;<3YIyubN#XHhqr%gDIy*eRM+Cap3=3cXH4*3*qI1LbV^_#CT)$ruA^*V$ z{9Kw4zW#3z4~3&!?g~%$(zNjTZ;gQWN6?4;7lp6qnxWzGS!2WFtr7U20y&41+xZdn zVcdz~>%S&~JojXUuYX+x`&u8tUgq}=Pj{CyJpQ=|e4Y_O-zo=$ujiaW;qgV?!{e`s z36IZ%E!yx6{hSz~UlPv`Ur$nmet$edzZXU5-%BF2>xBsVJZyM)e##^8^T!BwcW(s$ zRvDrGrz6<o84=q1N`(G>AcB5A8G)ZQUBl~blqI|zPP2u_-xk4-L7l_u!#^YNb4ptH z`o~6SSC0ttKO6XP_Ff)A-#&?;4-i9G{+CD4=bQ-bg1LvS=j{k~UEC`?|HUVSm(O(( z{7g-RaXcx4UiFB;|3TLO?po>nXb3*vi;L#L;CqhNU0eQyKwy~W&)^J+rvM(G?ifeu z(};2NYz;)tAjxXl^Zcu6J<k>STSDsj6#Y*5t4<gBPnY>`fL#;a(!UGDWRa|0%k}rt zmL;Ff32`$2!u~S9oD`XSj?x7_wuh+TTA6=-PfdGR>!USgh<fTIzW+dxKjA5Xcvj+9 z!5^|5<iyOR8;kT)!o+XqXNvsw---$fCI5+?M0=m^BM{ND{u9x^RR7X{2t;q>qtCvJ zDSt1mE~LE+&XatGw0FO(r~XAz{(5oIToVP|T)F<>llX_Z{*$!azJi}iB>w3$BtMS} z1iFJi<7EHV%lsH_`11vRng0g_+*@3<k+PoBkb3?r@r@D>cgLScpa9e_Rq1ClZ1&5t zL{WdNl+VpF{}4DJ?w7{|!mK9=_DlHGhXmf7R}Y6=3Ev|5w90y#U@s4Ar)k-v1zmJE zf2t7=b3Jk*ZkPB9TnS$)>oH@hRurfHT57H%$^6w2EaB@z`ti)pq8?4^RTr86<{^^q zO9HV>;y;AqF<n{&z(+1$X*ZuQ@KrJ+K>j41D%!Ouq+KOhf}h+FeuhpEdQva#*Oapx z4di~w5c1Jw{V%|85I=RR1Oje>Kb_B#e1_QjDz3kmwk3q_No<d&X-h)*ynUqLM?1~J z^$wTyj{rz?>!tinJGvPDmidwPetB0>U^>_)e5fD$jP0VA))K-`9y*%(%NEj)iKhv9 zE(_uF1Lzg$Pkjh}JjNZWCt21{{(?TAI|M(r=LFm$?fu#R5%^F)nUXH>sb7iwR|#=w zJGp-NTj@Vddmk_5R^LZt1jwIx{X{*bA%5c>nLky^+4KV`XNvr>vL8)9aPD}~FH0re zS7rU5LV-!nr4I^(sn4Uw2z*s{!H-Ag?|p)h&&m{Z5I(8=t7*4Ge@Je*A@Y9)3PAO@ z^c3~j#YMXmhEMpWRic6qWIg475cs->1>y&ZA2dSXb0t5f{r&)csGdg2|G6@Mch>*Y zw7QV~?I-1LlX5;==3f~v>dBUJwn==(WLh&lO>4|FbBcuWG|^r?L=UIJkVy_PQa%Z? zo`<EqFPHXi_WO5Hf^KSv{3k%)NIy$M_&*4JVEqh{|3o-O%3m3hzc2g``2kyo;NSEE zTUkE6G%bYxeldcdrIH`h-+pTm_$Fz;aI^e*s=L51m;Uy4iT`4p;3qkRpHwM_P`|fY z`n}~L`R|qel`Z=V9P{Ui(Sok+Cjlo(LoI^;AbqHk{G&PiNklryp;Y#x84nzidRV_& z<m-H*xL$$=Qk+vChlb;WFoQpZ&`-j*NW9Fh-4MaAj!hN(G;R{*Pe6J44F99($I6g? ze6g>{-}0EqXO550N&aneoXr)<+C`&8{?ac5Vm-zu`V5BQvwb}!;52d3;$^?+A#(n! z^c$%meq%jc71#5SsNgIi4s8e8dkWe05`n)}*1y#z^4H0F0P?4q{cs<xE=2y>(!MrG zeq?s-bm><cL+W`+>iN<T{%_;?2>ShAQNwo0C)5gj_RxBsDiM;vO=vI2y;85>M))%m z+1Q^*J(uFtHo&nEJ~qTZR6-#MU-yV8|FNuRB)6+i2fxwjPcnZ<J*~3e6CM{8nEigj z0AWYDA?<xg`n}~+&rN-P1q?Hv5|3u`=O#&axuk2_b*a>c)R6igP80QLO`?3E6yJeA z3VedBN2;^71BSqKr5}Ks;?HH$za>b1x=8#N7Yg|=mE#w}4F0@^_EJ6dvi{d4p1O(f zOJ%?GmiTwO3VfZc-?aDtLH(4!X`9Gsju*o&5_s*WVEo640v{T$ZtX7Yv{l+^yrdfo z$4>rsN{HN^L`U%aNa_{D&Yw>+Mg0jo1-wyqz~B0ada6R|DMbUxUo8)@m+c&PA<juY zn=3N={Wb7I?QMKo)IYY9xZal}>8=oP4%$PXsWN_E8A5l4^cx9(7x_?}Kl4r&^?)h< z+%7KK1ljMJ?DrlLzk}nAURq@cpXY);@mVVK!)*D}OY+$w<7adSe~29AuM4rqC31Y6 z8Nz>0C>Z6>4biu!qXj-&;sNq!yiM{W{fw#4T29W4*(Gyw%H4To?wlMgr)W-*Tg#b_ zi<aY@l$BFZSXMZrsN7vxHYqE;xMWV@q`Yaxg(59{N=|-d9#xQ6TyzaGj-8t`LDrC7 zoL636Sgz$v9iKF<q@>(Ew4l(PS5)jsDlg5+FR7U0E-c8ImRDXlte~*mT~;zbbFPxN zbiR9L$sAcE(UD&=XKrB`_{st6GYZ`~?)jyK&Z1050s+VjFiiQud8I`u<;6w$g*kJI ziZc=^OU{hS%AC@|vhosQ+C4vKZbApTA>|yR>T$ygi)IwgDV?8^S(#s0>Mkmo!}PNX z%ggg-6pl*DudH;)yt2un8IBZp2{DNlq2;nA&hbf^RNc_5Ja<`9rL(|QG{=!Ce-g|a zpfWSZw-crklS;DZJ0}jw$;@<3OUTT0B(=*Rr)YL*aTq}iE17mxVZOUOF?kMnC@m?T zKf9!?bY@Y0PEkP)sw^zabC;Ak2WMrcXAUc@EX=QP7iMNthfJDC$PN+;-z3U9equt7 zNzRd+Pg;<ZUsgChXI@!eDdg^)n3ywu;@}*|;MsYz3Za6~#yR<g0d(TryyA+&oS7xX z&_=>S0Qk73K@vyO)RcgP0}5xVu2eYZgiFV9OC1S;yycnH#Bo90X0{@6aDHBKF?6qV ze$MoYIr-G_ENCaSRZ<x$@;I|c&&?i|Bg9=$RFFwo5*-DF)AK5d-8qzr#9x$OR9KF* zoWba?VRO+nC1pv@xf6%xP#OB9%r2UflUD`>JzRGlD`!W+RwA>-JmnW>f<ye*a<b>= zjE8@i=q{_shYLCGqB}MQLxpx6`ZJ3(W%QBT>fEE^d}4CWgo#N)#Y347_L|9x*CZp) zDJ^hj&xHmJ6^^A{?H$SGGxN%z>!t28c=X~zxJ{T&3V8{5U3kiZ0GeIyag$O}(S&hF zE~$xWIY%L@BxeyxstBd1U^o*w4(-SuU0hsz6kH8<QvPtv1bLEQ7{|y*IFj1O2=;)^ z3FC@TamWalJ>OL_XGYE>^kN5}e2i3x{}3weV|J)=4NfeqEQPy*4oxpBnQe}0q*ZWT zWk?Z&NXH6;dq+{%MB$z>0>Q5)CPl12$Pda`;@4V*2nnW6x-=w4`L*@(XcD9XN`u4L zXGU<?aJ*Xg+tixCJyB51@xgHx+^~Y8^3sy>aKYT+C5W*pdz>0U9w!+(9OO4mH#%Y5 zM0W}+d(oWfC9uFr6HNhxT1r?q+`(qs8<m)-xNXI@q&=A-a1jFX%s_;3*!qa^Vi8R# z^|cp<v!3Y4aRk|4N5wUxAV+Xu#sO3kMQIerB;>S9C39K_t^#!o#Z;ky<{xf^o+L*E znIWYS8b&T3hKCHHj_oEaIwC+aOp#1&dRbvd|LI6FgHaiMO79Td!-0w&9KXsq)m4N@ zJP84A@q9#uB-NlWmZb$bsqtQdbNmn*$P?$}(E!pOcAMd22QhSDFd5-wNq!#1>Sm$Y zvwyi*I!}bAjwi0tgMEY$UI#+MSTY#u0(3BuqN(3B%=R#;$#dt={AIe1go4739FrU2 zy2=XOGs{ZmNvIHtBI}(zXCA4|gu?QQ+1zcxV~N=#M;WId^GIJ_G-FPlyP`}usWF!Z zCb&X)foVq|pNQj~uB#F=Glx*{1{F~?!Hgo35v<KFoZ~LfoSQkc46QAu&^jW4L^&<t zS%O;ou|_c|0gl1IU~~tlM`+ytP1;ETHh-01S?6X{<dqfV<mF#of#3zro#ZU;pvPv1 zCeFyu$4D?cZ_W(z!Q=9!riwbs(0N$R2*Tw}D=GVbXm%8k8xP<S^(u^fG4~FqxR@IT z90FWec>Rr_LB9``P(2MaM4hJ}MZh1J4TrOpNtlt54owUQg>>n-IIDI!|EfiWW7mKo z;WYq@7J<f!rHfyy1iuZTP(27xQT5>1MH^ll3fQ4wZS}Y)!SA>daqMamu&>||F7YT< zJ12->DS|hN=(R$7IKav8CAV-o5W)BTZ{qc6{PdA8{v5uOX;yWli{r=Dx_<8!tYbH{ zfCCFQG+HJj`#HLmxC~lQ3-7p(*xmvR348lpCHX5%?|%u~VXQE~`ERTN!P8%5!D4V= zsSXn#S^%70Qih0phI8(buO}wU#lQJUS6394%@18lAmfg(jFuRYe8G{Ek6g(w?kygP zAdcLN9S@d;Pwlw!dej0eJ|5fz!orS~O`2$~Rvc6R9?d30N8-Wybc|~U?LqIc%pEc_ zJFGhgFIpYtO2)6{CbL5~1jOP9-Sgxv`@=4b{m#sXES>*f6{K8?JkBb1?9-CpPSJi1 zPlr*rW8KgGHSGL03iPWu5=+|0L5+T|xzF)cwBL{G<D`neAH&B_S${{KkFz@eu2YNO zLbHG81{_x<|DAb1-unJ~vwz%F|5*2Qj<5b6I~T`E36GtD<EKf#f`@SGaE!-xj$&?k z6z6-)y{@D%XC{w=;xC-6Y@a&^pFT)*v>$>}4*CY2{0R>59U;5$gO7F>ez21wwQ$?- zz|*`)Zjwu={Uok=1h{=F*D;Ni9w$Z$LozD|dIKqPAKt742Z`yd?`Ryd!fD^55q<DU z5ywz>-i++|X=P=3^DpK@z*?qrOy>CP%W~2tOi06Two}WVKZ(|FoaGZMrqN1H<oV#y z1n9qCgh7XY%q4}1WBL3@@UB}Vg=;^Uotb?p9Ur2zDfzQ<@@LM<nU2HiB#1D_zK6`4 zndc_0<UM3Q)LSvfTn(c#W-qp%6hEF*!(%<U5G1C|j>l};rF1wqK&wL`=cXgAFeR0B zIDSL|o>Ay%@2~KukmNZ>Qhz$|czhJ{`0Vv%W-8~PBQ8%KPJ*;Rd1MkiTrIRhdAM2v zYdA-5v%hnc6r`7~j(TafB;28@!!AXIEfDU&Q@iFL{umzR!^0{#^WLt&*>v7(a6&{? z&nd`r=XDH!+DV2xDTrfPbS`e_%)B`T#f47Oxn)v4bLMqC<CQp=&ranOmX*;Wd~sP} zUcvmF@<R4f?fxiuR51^051vps-N}amkKkbxI_btI+#DC<A(1jX0Z>#>=;Y^CFpMJ9 z_{H%@@sGj$$We~jArikAH)5|bxd@LWmEoZvJljI&(BP@)0VSLcqC<88Z*Lx8%LxqX z=#oj7Vw4Z$C4@5sF<ym5EXsq2Jn|ONk0d(s%5&PIBJ=qZJ{3wD60nW1kJ=2zqc%f2 zK58S;!Dke4@RB<av5<5t=84)P8%rHS>A<OY;72_F0-4QbacQ#)XXlsB@8HEv_cnM| z;rw|eWd-HDy6kk#Mi>{?un${+3>&c$o@vV|E}B+YnTL~hg*kZzc#a5^6Vbm&nO#y) z0c>anI=2(N-e!_=D8(`-I2_sYv$%?k!s!@K=5{pf!FbpQj{%7X1LoqG*rdaFv?Q}b z<s(CxayV4i-8+&nc^g)qUxK&|W}fG!hdrRCphs0C<j^y0LuEh6GqvL!L$NiS%@3ko zT2x*Xc;qW-E<uPg#e;ex#2zZT(uulAiA<V<=ajf}%JB?9(e$Fif=q1X;6EwO+zG$B zp>(`@NNHYCnKPT)AZZSh>XA7yC8wh>0v0e7T}`GkCvSFPd1+pLAqz8D5)cobA_2$L z-xS&pE~}W6d33wwLjr{z!}yFf4&au%bHss7@)M%wWJ;TnS0r695#wiYCI)br7tmRE zBy?22K&ui&H_(%kIJXP_XA9XV2d>dOAR0J|?nr1qNiI&0cNALt=o8q19f~u)c*Zg_ zdvvz4p#&X=z>aK;3*Eg%P2(I6KIbhIF^sjC?M%dZQ}O6&PQiTipm;PfucESJr2!q8 zOHT*VgODAJ_wda#M^ij7(6RO-XW0QiiS4l<k0)%eL*E2jmf2>+Z~S;9^{s=R5zLuW z!q4OiB?_{}_7+7N5srM0s7z1VpC{#~&_X@GIgbfDP9MSWoJnkV445Lc?AHWQ0X0r3 zttg*~aU_4%Z?4IKV@i$$@euDQbR?baJ`%~0(grF>;mQ6n7nc#!k<b<4TaF`q^hSnc z_BqZ*kan2QdC`;0q9@JOh~pWjWwyJV>|kSQSNtPUkAOtYnD+OQ$!`)%A1|ql$2e75 z=ysRjArp>@24kqqEav5n4oT$|)667RfYSMn!G&|^MF6a%+46y8Q%xL07@a1bM8QMk zzd;nQJm=DJJu9NVBn}NbCo3t#0)&%;7E<?#?qRfygD3YLiEzXiccA4(b7na6C%Q40 z!K1V}?lO$x<<9)fiFx?ROv%ZjC)(+;n+g254Kk+W<cLW_amfr+!P78|)nwz&fJL>h z2Eq6_`lsiRf+iADc!9Y{;t*b4!b9|U=!BjPp&<hAEyycBLO(-?!?N;9od^M?=?_(> zY=L<jKZPa8<dl>;`5|<Q=q8Mtlt4cY5yWy|A6M=iiRtr-$_ppY$t#<GaVc7bXJLnw zqty_6ejef~a6>D!2ncghCY9yQ;pYQsx+)qr9zlS!DDuk_4%=#qTmPSKdGRl`y!ijC zEua2NEua3svE|`3_?JxcNL4hVNB&L5rr*LRV|vH2e8iR<d5oL+TkuCKBs6A(EEpy7 z%RlgF7$#6TimNUzf$wVfQ-M$fLr#7PElyNA3zZkWkf&<bX}t1;SK4wS`D;95`pcfP zfZr|wXE`|MaBrCDpkiE%=Jex!X$bgV(DsmV<CjEn6v8+jiaLa5ku*NDxOr(+olZ;w zKD%Soqeki}<11#D@)jPgN6=QDm_VA`wWklEXO_cN$Iom}bSD>;h&8w&w2Wpx8yt#P zmM;+mRnj}8@RVw#u-#lZ3b&<9iz2_UjnN+e2c~#KVOX;&N<-)F$IL~?{g`8GO~)OX zW2@&Vyj<uO(6JHhxTP0ZObYa#^8OiGui)uxV8t-PtGzhWrQ;n59AW28E1K(YP_)gf z9{k7vy+(m^O$;9;)2lhu;)$rLyeMo9wBjDLCLi)@26NTrD9<M!>t<`PfPzmg{J+40 zy28wFv*NXP*%v_zG{+=3vHAZyZzLW!ng8G8KA^P6>HQ_aA~~Lw1~?7Y?Qnap!Au-m z{toY?IL@ki<WBe4U-5M~IUJQw`2CL795*Sehc9^KKC-vs1s=G^OdSI}R#SexZ#qt_ zL@<D(>PVH9U-QVoZz7vt%TT0OAA}!zQfB8>2HtqszCU|DZ{Q9rFBv#^V8Xz}^Bqa& z&nQSPbexaZjk)J*$SC~D;DJfADVJkl0wLwnB`^f>zNUOx+4-gO2PcV~Ny#EJcKY-G z^e4g%rQGzMk8;jIP`<$D6w)~ktlLe)3oUVoiC*l1choQ~b*mY<wLvpWW)}`B%_}av zrU)4aWt8OO%{6$j3+}LzS6G%_T8hYb&?MS7#Qh+-EGybNC}&zlQE|ZqgGx%>_!iD7 zE16b;vf$+cZA^N44g{f%aXCk&=Ohjs61a1;-zE-B66h&Yka@_!M28A$=~JepjdJEV z1`ZbQi<Pg{6##w-?!<q6Q{0P$D2W$PC;XL8Q7)Qu;+4q!cRS5rkxTr2Q@S_bIZdUg z9KoVIl{9IJYgdilcue`CWSyKv<`)z!+W-IWcu0UGOZA*PS^OPU8{q8o=6BQZS8>+@ zM;{A%Yp_gD1>Cc!2(Lu$qHU76yY9FfZzzt|K9q39X+?OGcW3PjrTnQfjq1C)^&WJ6 zjJ8YS-2LuEhev5YN%;NeXW>=GowS%sDL4IHUGZLM^F7%0^8M^a2;TfVzbzs7Dw*H> zy8vcAf9P%D`px%FhvKV71=BU*4I%hWvYw_8yk@?~S-vlts2yaA;wL@=-uycqlpn89 z=f7`DB~q3APZ2_X%)i$_`7gj1uhr*Iu99EHoA0j<&2RpFpHRH{caB2w^%3gd5&>`i zeUs37vX%U=N#5x)MZsq)_?Ze`z8arXOBH;)l7CSId}9Q>5dp8s_oWm6YW-D8e)$S; zroKeMU#;-7RKYJ+@XHl^xq@G*;LUfwQ}PA{pQGe&Qt&q`_*Mm9s^DXlc0HruTQ5AD zA$q^PijPzB*C_c*N4Doz@iry@4@&-c1;0VTCn)&a6nySQ?e(kpR3-mSN`76z7by5_ z1#kXs14^Ev;HN41a}~V&lM$RcQ^CVw20qIo;Irl5ks<w2^VdbdH%7phD)qk=psHzA z3cgjrFH-PdDEK-BFJFz%sY?|6-AewY3jUCSU#{S*6@0ydpRM3GDELnme4~Pwe=31f zw<!4iO8%vaeyaE;CI3Pte~gk}#T!cg?MnU@1^=^x*OY$ASMV_k{#ykftKk2s;Nukh z0R<ng;HwmTf`ZRg@W~4PLj|9z;Abd!UBN%E;HN0~j}-h&1@Bexr3$`H!B;Byw-tPq zg8xjxFH-P36#NnezfZw0Q}A~v_~i=z3I)GX!8a=SdIi5n!EaFTHz@cm3jT2gZ&Uo9 zh-pP)yn=sD$)BL$>lJ*mf?uxSQx*II1+Odk=?Xqu!C$W6rzrS;DEM3j|FVLgso+Z# ze5HbaLBUrk_>~HNk%E_hs)JMO6ukL2HYj0<f}f?-vsA&Kq~Mn+c&mb6uHbhm_>~I& zKMKBH!M7;*4GR7P1>dOPKT+^o6#NqkzDdEKtl$j=FaJ~sr?x2gWlH{51^=aj*A)M@ zLczx>_`u%+L3*5mH~)4T6|*V$UP?Xj3ck03Pf+mN6nwIRU!>qu75sVyuPb<)g3ng) z_bK=(3jRg~pR3@%SMW0xyj{VUD)?0jzEZ*eQNdR!_`M2#k%IrPg0EBX*C_ZU3jQYr zzf8g3s^FI^ctgRjRPeP5zFxu0sXnJ}Q1Jg&@;55@hZX!51)r?on-qMWf;SZWS_R*t z;NMa3niALf6?}|>FIMoe3jPrVAE)5oRPZ(h|DJ-6SMbj&_yh%ir-Dyb@Vga!s)BD; z@VbKcDfny!|FwdjqTpXt@G}+sqYA!M!DlM?N(Fztg0E8W4=DIW3Vx@8uT$_}DflG{ z-l^c1D)@N{ewl**tAbyy;9UxSrGmd!!PhJJ@d|!}g1<z;H!Ao^3Vw@%zf{3DDfqh- zyrJN)Q}8VceyW0xmw(UB0^D2$pBe!_B?5ktg5RptvoZocLH=DWqO0a#s^l+I>PgKw zn<2`t;v1Fx8<qS<1bn<wPlb|yk%FJE;Ef3Qr3(H*CBLS$OU1`2_;pHtJp#T`!GELV zU!ve&SMVzp{O1aOgMuHe;Nwz-Ji7wdS;5;Be3XKZSMbpaK0(2EQSiwMo@kh#R0SVn zB5~Cf{0Ry^TfyT`odrHq6#RDqtfu8E_*ex$Q^BuM@TCgAr-H9k@TV&HDg_^>;1?<Q zJ_^20!Jnq!mnitt75q{Ke};lzrr^(1@XHnaSqgrof)_n466+QG?MnU)3jQ1g->BgK zN5OAV@aHP{CI#Q5;0*<To`P>t@ck5gtAg*Z;I*`Nz5SDdk5TXg6nw0LKVQMeDfod3 z-lpIODfoB=|1Slfpx_e}e6oUfDEL$bpQzw<1;13mXDj$23Vw=$Z&2{L3O-4}&s6Y3 z6@00JAEw|d6?}?<uTt<!6#OCuKU~4rDflZD{1OE}LcuRp@FNxcG6jF3f?uxSFH-O; z6@03KuUGItD)<cwK25<lD)><fev5)nSMW^=ezk%(6#N?szD2=jDEL+dKSsf8a^0SM zs;=N;6#QcfK32hxRq$~New>20DfrC_K3>5WD)<BipQYfF75v2tK2^a_Q1H5fpQzxo z75rocKSja+S;6Nj_$dm0rh>mr!IvudzbJUUdS{I8jXvW!o2J*+yQ7UA7!CF6wJ~z= zXiFM}q_%T2@M}FQ6?X*Bq#FE9ZTOsf0l^l68yQX{xD&zk4EHCvGr`LlK8Ii$a{Wsg zK8;`+YW;N#pF%JVvHmKCPb8Ssz+cL6CxU56_2)AD<FkNiDD`JEyoX>KLj9=>e@k#T zf)g0tPH=aEZ47TExCg<p3~wg*B!V@DHxg_mxaDUc&RtC~4Y~d%hF>N4WP%$Reu3aq z2(D-N?*#vW;N=WILNE=%{-q4xM=(w4{dElANiYq?{wjuVA(*E2{!)f-B$$R|e=ft< z5KKd{Kbzq)f@ui$r!ssM!8G*x6BwRGa9@IL3{NGPhG2gz!xIRmq1Uf5JeFV@a{Vob zsQse|wh`RK@C5|ZVC8RQIFVo)TK)A5_a~T!RR3~@&mq`O@KT0PBbbI(e;vc85KKd- zzlz}#3H~F&r3`l>IG*5KhJSnpFb%2xY=-v`Ohc(ZmEms*rXkdy!0>j02M}yycq_r@ z6CBI%W`b#`^lJ=nBzO?PEkAMp6HG&(zlq^j38taX-^lO_1k;e`uV?u01P>;7Im3?- zOhcT1DZ}>>OhcHzj^R5ArlHGU#qccz(~#vaW%x#dlL^jc_!@#~=<;VXTt@H(1gA25 z6~Q!A`4bqPMlcOUejCG638o>)AItCrf@$dSYYdMin1&pG%R%mcf>Q}@V)z1rX(;hG zGMq>-4I%z|hWistLx+Dk!{-p3LGV(BPa`;!;5vp+A$T;wRScg<Fbxg<QieMbOhbY{ zm*F3u2J9p_o8dhKk0m&j;cp2h*Y8gd`Jb?9)9c#K?f(>Ab>B$O^YDFegGLqfUH6Vm zL4xk<wHoDgU(zh38q*;OcuDJ%KzT=2F5?UjiwvW<xMtBk(ZeY31tPB(d8?AOiascC zJ4mkAEJg_wO855KK;=E1P~n+KpiJ>d1^6T-cq?NZ^;H-3x87B+TN;evqRh_6%`&TH z#j?z6ln_#;t0)sk>@uAv1RZw@h<u9z3eD5Q&}`r)^x7cH(`bNJe1U@0il;>C9>G!b zGt&oJ&#HlZH4G4t*vOAzpt>)bE|c|st-9wcy}I?JxxGO9CaMv`%n4VtHBGmkm7!@@ ztf5h*y$Y1Sm&+&JDa!v$<yZaOS@*Q)tBi|u%X<C2pWSh&>}pwAcTt&OA+)}#k(Z$! zt>TY*^~koza5owCxx1q|+tJO&E=bDIq1IQdk4`{F%ifOsI35Di)fZ_M-TYS~r{Ej( zNgmV~KULY*cm<C)q)1gG&n24f({*o>3pCND#iUb^qyJw&wzW}<fwLf!@hOCfIzB*s zmt3zA`djEXbSa-oc%w52>50BVKo<(=&jLyo&?N#&6wo+8#(4+Y+L~`5I+G_thi6}> zX|K`{o$06tgSzfL<EKYaz0YM&&^_N2=-#Mv<B_a;GVIC7;<?<OVB867(Y-x}Qv<xc zdQxM(NlAPec@p%=c(0W*Bwa%_dA1oh3bj}xa@0^U&*#QZ`;iIt#nO*W_wkRLz->ky zWC8NV7QTK>sF6%`gk7&5WU1(?d&k7IWha2$LP;bG4I`Py>(!Mu&3(4+1;+*YV8Oq& z_6cf5^;-QeSFADnsaG16^^V*sIl78C@}57OYut*uZ+OI}Io{Mg-w^`?IJMVeqy}(t z0yiHO1aMIT_aI9rX}!qq9Z7r|#y+CZ>j3J7e10_3E(2_ALYjXx)X3P*;zLtCFs`n; zFB=Wptb2O5Hyi9+N22kD$+TU{rupMw`$2b)yzyER!cH5AuLI4X?v11F-C^`Xy>Czu zV|*eS^320v*2f+54XHt_UcDNf6pMCzK}nwM7-KoNYXQ<~+uU8ibX#@|$n^#}2RQ%S zxR`o}xK(@4aDsyIA5O}!#|1j8q6<38_Lnur$IL;PHU|11f^c(rq789@e6t|myrbQ9 zus@-+Zj_cA!|>iUYKBzJQ6Gdr2VF$my1SC$XFzVGa=8gmo*GC8uy0I^QlhRyc~2`u z^xRULW|oikbHAge)VMWuE2B_}Qh|>A9C9y=Bk6ggUqey78t$LG?DV>oWTr~~P#FBg zDajq`U)d?RJSg}dX69sjywM+rz$wgcvj1vyZyoaYLAqYu5T{qyL)v2u{~~B=Kpx)c z1K@a~?m4LYt`Fof3P_th+y3Ie_6NAgz=(kQ=0TMj;`}cHPve8<N8LLY4Ig<5xz&`P z-LV+$F6{5_@ybAOzW0fWDBU+Ij(VdCu%-_mc`q`$dxNpMhf%_t;9t2{;m6aehy&xf zXAji=Osd<{`bsp_;Q0u(cBR%pzC!p(hyI2PzRFmm7;LfVO?uvFkJ&zMKa}u|l{a+K zj55mUeQhb-PZ#%fbU#(xSJC}=abHUJqr`nK-47M_*>vAu+^5q0nc}{_2MqBPx`(Ep z_+KeW2X5-pCQW{|5m_hxn?g?AbI908RtOiEq<b1*3{KBlV+I5Q`7~0ieb++X)N!2+ z4Tkj>_%)a3n=8^T_owYaeVL9gf%%I>4FszBBve6!??5dsPZO#&ZUP<#t$TJGvp~)` zk9k{TJSTbl8du?8!QVv46n^3i&w~gohHLHtxIY)H;NDt8YbP*}*Gb;q=z(;pUK{%t z@FVR7gtwqJG-v}d_)yM)w#<yFx=!n#YQ3vLx9m3Vfh1hsb6Y^b(dP6-+112rkm!WR zf@dQ%hfV8<^E@F)N=q<$Qj5H2_`m@1RXY<dm>PXK)3(-3A=n$;gG3k-P4%IAyuE$| zb(Elh$}`CxW32w3(75ye57)J>xl{82s`6e+0R2@cSI5$Ux}UM*0U@0;G4`BARUr-p zigZu+813T~D%gO6kjIDMCzG;-@Z;g$K7T7GjqJv3WkNp*?a7QI7S00;%@67x$YGmt zg5<~4Copgl3QdHxH1}CxZR!2Y&OfL^&lc{RcK?TlBny5hMp?mGgCo=fLbOvkY2>wB zOJ`#Tt57-xYK@@gKnLc=q*aZubFaEA-x#Yzjs)b`cVEY5J|dEJM?IH9zd9{zp|^%d zB;=BeN48L-w?LSCL7rKs0Rkz1;FN8~aEL|mN8BG^>WtIDCu!?>xGzCjx}S!6x^Xk2 zAE0JbuZ=^;h;adeOh8rWmv`X2J^;gpMvQpRznZdoNB*7K;6X?DS>8~T%sAu0-IV2w zlLUc^hv1*K83xLso;y*<NA;|v0^VMCa0MtQ6)ca-Lct)Q9_{R)S4~YDL^;sbKchnF zzZ83XMYf9U@eI*gYt4(o9w&=d{!Et+_NWW~$R4k_H=I3o1;en%dah*TKahuv(rAIm z!&>4;)ED0KmvTl}Bk{aOX4VOKS#%Z^&NYg@W0_qg*tgbZNmKm?sMgk7YeouFUA=_F z9;}LUm{6~IA(HIPHIk{u1e@x2yMzEwMb*NeiSZ%&?J$+UN422ex|8FD+4@r<ehR2* z;0}zBVm<9M;vj^%J3`BAk;{K|Psj3?gqE)dB0T+(N#NhG$pU{c8NM9|sVB0W91lnC z0zIRJq=5zo^5;a#AN>`&GPHgFki`S?A^H*cdywc=h0@y%M0oxRDSvio{x`zp_eS4K zeJ93le-DVb-TEp1@J7!^I>#>}kKrdVQRq^?6F1)IRZ97{krrD1;gIrAndPfQ`4pwR zFHHG9A>~=$iGHdm{}1YW$$wUu@^>Iz<-eavUlZlOSlnK|N0{=fkgk^ZlUTX^&D{Pz zcT?Xc`_D#ob!n5+CZ&0Pm^_iA5HkpYmBj6_o*ZSzj|*erP+|d^b4hzl^8UA6*$8S3 zVv-EccYCa{$cx`7Ob|qbav^aHFDrr+a^GoJ`0w?zF^YH<@k;Y&fe__8R4PN19mpj^ zlnrQrQB75O))?JHYm9W(4eIZQ(H^C}y7zj_S}-uBG+?=V6R}B+&lmYIJ|MDXBR+p7 z36gSqGjT1A)l>GnPdBE5aBY3XNo4nq`oQ>rJdS;+sjY4~Lip;|?(SaIMs#&+w|O68 zF==v%rd5sTq`BYprpHycTHM{MTRT<!%bT7GsjZ-@c;sDEC&}A%??OzKlzBN#+z=me z-y|3-46u!&xw>~^jNUmtcHe4CMY`@;kNI@lW@Man7kKx4jea!dlcdBP(s-78#l_RG z?sCq*rQ%F5fSDMtOL)=TNhh~8zbO2n<CErhjbSV#OjAeLjafoq#ttY8+Y<uh)Hr>3 zbQz>o5vyaqq<d*HB<C9tWm_XK)J6=<@SLkHko#jOZj_)d)w(h?$T|9ZupY6$`f|5# zGhQNHrGD!MM0*{quTIZT)Qvx&8>hIu=UccNuM8F^!V0Ii0wUUG^bxYuF@$ksM=KR^ z)*9Ls(!H~7BHM0b&o?Y`njG6GU%c)qwkNw6V%DDJEw;zFd<Ax!8-e!@7v%2QP2E6Q zz43HK|L&j;JCQqOfjy3dLIl4<7p1j*0Ld6lXo?e~u`7jY%G9gZK;`<{-Tig1%dTVM zEPAX0GuE|Jgt0)PJIKX~oD~QeC)s10-)$ENArhKj3XD&V`sRNaGpNO$9nG-;Y8BC( zF;EeMXiI}}Fhst8PP>$R0tt98rX%_dI~PGv5cAkOY`9Ffxx90OMO`UGO`+R!Uk7A} z$|u?5T%H1ZytU?Tm<)P;#+_6}J_MFPxvSc9BV?FlPo~_uwMIv7WJ{o)p?p)?^JP=M zDU@%fwWf)Buy(V{dmTEb*q)6^BrXZG2o>w%X_4roZ1^NhV6c+J>F{Y3bfL4XoR#}% zfnBE_qu_;#XL!-Em~+T3{ap7hu*ZuGvBJ+~c)oUd_TyelYx@Xod%q4*QuR7a&NPcF z1>9I`>WDu=0Zeeagz!<hd#dhr+bhxGL)b*EwbxP38`hGfMZc$AnU*8$m0AQ1Af^I! zRlF3a3*DbuvAkU$zz~$O`ERCu%A(CT%5j&|bNz*glQ`~m)cZ?tZw!HqoBz-*zveh5 z*=(aWaeFGdh_dZmL=o`-Co&zj(_lOSTN3^yP3n`=b4aMv4LdhbV}spajeRAM;ME)L zg_=P>j2CyXDp_m(PP&7cjyF0UB8Fa|XIOpGz6`Hy^I3gHCf+WT&FLLRO7w^J-0jMi zYpv<Vxyzw!$hP0uDai7aIm2E`>Q?FUykuVr{;W0QkvR+MmbS0KVy%q>L|Re_EwR>2 zBM2+5rL@duD&c<JGXzcm<D%|)r>)WDEkHVJA{C)$*xGZGj^$E*p=WU}D2b>ioEE|Z zIXhnmJ^#Yx+2c(hCCqO%uKNlyLAS*4@?Od$d#SbNW0rSM49ZyX11g~c%c={|a~{O> z3rH+*RLwm^e{rvy9*1;wyzae~dne$ZthJ9)jW?{Njto*)_;>i9cW9h(dNax7qP6kf z1<7sx53u#Z`Uc)?>XrhpQJebh>2CK=V9kVB$P~dL@5;98H{sDMaJc@LP-mU){g=Ip z*ddhh9Q7W=8{_XrN}WR>REO(g3qpm>{b+`T1zEJN85<_5uqt|(^%?nGl`6FpS!%{u zuGDDPdolwXY5j7RWpuyWLdG|-zH|y#DAt#{h<jdN`f)q){2H$>eJAdDeQCS6=k=uz z#XYYtZ4~#szVvT#&+AJs&^?WqPko`pSLDlGzUi^%fQey72|AJ?`IHN-HTy_{wQbg# zD@Y@&yIRPf+T?oi0`jK2jWTW>jd<{!QRL>{ut~uu7!{z2=&T_%1{G)xsom)UlYRD9 zo2ECU#{xpV928RjBn0ZveG90c)8mXzsGsQk$g%-Zu?kI#w_~$vzr@H(VVdWPxR$nb zSW{-~N_25si*;3c3<X@5QoYH6)n}Kd5UW5hF<II!pvV&r6+H2lL-VuJA5zWh^oG%b z!-mmu#3=_yGQRP4M*I_t_~!*L;-4wHw>%c{Zk(~EsjV%*0ir$lgKNN#j{I0e@@6As z>h;YnC^7)+!2TR0vHt6x1<=!%Kc}3y^WV;fk&1?GYin$Nu5Gh_2(lWFqxR-#NVM4@ zd@|JQJrtr4bhj}EsYV$@ZX9B{?>5$<^GSHGvqDJW^$1$0r%>o5){!;M4S{%p^ummX zr-0p#@$guXJ?eNkv)~BhVU_+CPe=OK8yi0hM}J>>T9kXIh}^G5L@J{99>xQl+l|;P zV!Zw`;`PV#C4Wz;@%jTIUSF)l>qMvGWg0$(KD-gbDuvzTX`qBvoqT3GX%k&I`i&L4 zDxHBa7NVoteV2&8qo0D9WsrpcYa)g4=WRn>G$LGgqNe?u)`L-3TU`QKV{JXuz*=)H zQe3`V9{K(Z(in_k4%lBH!oJs1u`i(eR%p1qLWdI&<fNxk9*hKJcIgR(fmGrNi5TYO zbP9_yX_}Wlh3;&g^qJnw0R-oI(u=*B37&L}Rhh{sT#0L{?y0V##(Oh$+%6Kg*|_C6 z$D26?w@U;z7q?5r?M&P*6St+fT`q1baZ5wK?yaq&i>JC?KwPb-dV_$tW>0mafVgr` z^%emwrHiM!NkB}(Q*8){sd%be1jK|q)vW@mr;7*fi>WgqPc^wM@WO;V)v*F%LY`_d z%-1%FayF61ggn*p0%Ag*YVI#@EfexoCyO*D<f%>-5EJrL>jGjzp6YA?F(FU&6ag_I zPj#+<n2@J>rhu4`r@B-?OvqDRDIg|<t`ZOvLT?F(38BLT#Dvgi0%AhwHUTjq^qhd0 z5IRplObGoaASQ(V6A%+Z{|Sf*q5lNLgwTHiVnXOY0Wl%;pMaPU`cFVi2>mA@CWQVY zh4<DnA@rYsm=O9;KuiezCm<%|skRA-38DW4#Dvg)0%AhwKLOQs#<rFIIBYB-3M73i zT7Y<^PH00T?!m<px}aqOS}LF>0WA}dA)w^~qB>A+rGQ!mR4*Wn$e?8ciV+YKLdyii zgwQepF(I@}KuicN10>j99)tRPD@t);wh8O4ZRyS|Ctzy|P^*BF1*FjhDl4EE0qFvY z6;QT-;si8BKsEv83MgJcboLGum=IJ}KuicKD<CEWl@$;Zg31br2|;BA#Dt)-0%Af? zSphL2sH}j9kjuMbC10McCnOYDq!C#J`%dfghk&FkV34Upj|IfkYZ22_Zx9G(0IDn? zW&j;7AZ7rnEFfk8stm|lvxz!|;{*)rXJJjsdh?ywwbWOA)7hx|SbF{8gz+@EJWp#U z5oa&9a!rewGtX-+1X-V7ELdB?jaaoE<v*eksFoS@y%vk2=w@Q@l{jeUtEmrAt<^EW z3q@!YIqGoX90FU1vyUj3jf;ZKj%92tE=D}j@x4~}jL3)!*KNcKe4}om3hHnX_|^}Z zuf{J4|61HvoV*2)$x<v(#%7T#4uhS``)o3gdDT<s;;pseGS0VPHt|mZFi`O#!%VvP zqFzS>X=uc_NM`aXgi9X?xY2s^Sd#gwZ=#JsTcm)$VOzp>>T48QkMm7J&E6FWxQEOu zsmfK`qm5K>1XgswS+%>YH3?KI(09(1b=I4|0&1*p#4aLlG*bJChsC0L)U}A}^43xn zAXdfD3JTSAU(a=1=#vka2sM<6d_rEvBytfGc~%g4mh;atiR1=|Ea7TvSyrCc>I9K& zL8O)o%@ssQSWM(5mB?94q!p+@OS+gudIpFr6GW&Av}7qmE4VMrmYghzkocHLT1O(U zsYD*84kvMyQ$|+zm0WEtRRJQ)8Cp?F7n8^{|6y@00*;C7q(Q(GmuLz3=|D?Hm_)7& z5ZS=h)>0K9QqRzeD!Q0N#xRi;OMpZFQ(H~%Ky#wYf=IFn|3oM<;kO|JZj%^Y$b_4? z_={VJfOj#~395~BfeBOH(7ZajkO{y2J~xkA&dobRr6siCWT4PIp$%7<^lB(0%dmy3 ztfeYI$Y5y2GP?MB3T>DPB3MeNRgg0_;}-L=1gMGJ3r@Qt?Mh{T%Nu>dLL264n#G*j z^Ewpf^_wYvb+q{>;|y0|{s8z191K(8A41@<hl0}|3V}CZ3Z$0*G9*1EBs~U(ZajuA z(>?3_H=!ZMJrbam4&xRH)Dv)>1fC?IQ~=HMjp_34TH|tgcbPE(cSe>3=NRb(UPwPF z^fQEh2H^)pn{CFq1ls85box1!61?2YMt_pFm-WmzQ`}SE7^jGP(g352xUZx8AE`^s z`M<a?CH!`APtM=?5ckx5@4Sb+)qk>7oTz(g61<I0&tcj(l<0%89d$Hm9!Zm`L%J^~ zfi^mtPvCh+%4awWP~D7KG^R_)^c_zQ4f6<I%4Zc{(6r|-SEwhdrqlTb&mlfZM(e@V zJL7}a53p%rTths0dyTsmS|bjaO#x@}kQo-m#W^!$Vk2b>OzZh@8J{X6{`YZPLk^bF zgdQu+^6Vd-@L3y=?HI#D1Tiz_>G3(d^AYiU-5D%sNfk@+bfm5M>-H&G9j#At^UOu> zAF$#*1zu2TXN_G4f)=Tw&!0%MuxIQ|<XswS>~Tn-58cNr_sR0!<$KH?i+kNuBd)&a zy%R)s167zs$r+pXF=jO=VxywI=nW|1@;qbb2?;1|k=Y4Xk8)Hy4_3bDC#iOT%%Cs& zZxU=l2~>2S1T|6bVhJ{)4yP{@s)T}6pD%i&nIsA>lHhVqt+6)}8o5`B+(n#BoBPG@ zvNrs1jSaOtV6WnQP=*?L`?=HyXv`&)2j>oT-(6gf(fBr%#d;nUf{Mx`h%T?)uKOlo zZPeF8BSOBUlbGIal6ol|A$@euUG`LRil}W7U6EEP)0|k~ba@_=EZk*Bq{8{L<#h^Q zw^ETRSp>7@PJHO$>33+;W`NyN(ai~kjDZ>QkyXj2dJ>XVQAN1CFWE`9tYD@pxIAwA zOd|u;LIz1JC(=(kjU|N?IGH&}kr4I0@!X~e5-LCq5YbG?W=}RL%l9xVYEQk{9*C!o znhEjnya;I<WLl_rmQX(AUn;N5_{!pGltlvKxfOkO#NwfLs`7!JWf8a1NZz2Zm6*1f zRB#_}-a|UAl<upsCj&?Q*&_2N$UL+!ghhrLy9NYZV{mnfm1Hc_8}G9CdL>laK+}zt z%!brhRDrAk;bY)$*U&-pY)B&w#X`E_cq^>%p_Pj+CccvH!3B%)<j^XZ(gKhOY44ZF z6KE&RQ<*;68K>Oa%zHGUiJF2o^Gp@_s<;GjxL;)6BcCCg+#;{7xEh}`%RO#JJE*}4 z5gP2f1p0@Oq1Weu2H(YmjFB57wfS_><|oGo+I#~OqvhO?HZP_;zL)GYy$-ZJ*K8x& zG1I(9J1CRWH(ICmm6~|m*O_g_{SxyY`6>FNu1=L#9arOPX1mAjbE)05)e)|vF{d%x z{h`|?I~rDk%8kr7Bei=&7WGHc`?$Dp))js2VPZrjq}?kiYxNpkwAu53eG&8cfW1!g z%8m~BB?O~g%W<U--LF*c>y`VZoI~VUChv`X%x;f|Ds15Ga(lMfUY7^!#X_bC7TVkU zZ>7Cdp)q-bXfH`$alO#(y)IyUNgB1qvz6L=FB4k;Dnadq<K7}mpGYazn&qgO{5g$i zRH;NCkm%On+?yrZ2u43G(KMnemDETy4Z4D1kaXt}IU1AOQ5Wi7F@6Uk32QCc4fe05 zAfp-N@^)(m&|-hUpMfA#tk;VDf>-2zfw_NhcQDM)E-Lx`&fxO?b3)*Q2x>WqF<xcS zA5NUX>-e<H|24XR;=#|UE3mFVlvL0RiSQuKzu1gO2>+BZ&+}r-k9zDevkmtLiddCl zx8m*Q8!0oJv9-1wjGIE4f&1o-RH|z;PA05r#uG5o$60H~Dj6@t{V|UU=5XL|HDyGk zxK(U0Xw|2(RsT6+A~Lpo)NK2G&5xs2|6-b31WvPKf5_ag79q4}FE(6m*hzL46c3UE zLOke=KKE)HR7Mkrg7#&mc1pupYhQV6#YGw3%(yfh0<zY8ip;o!K|BuCW@lh5Zh%y4 z>z$r;)*7Q5JYGX4a={QcA%XM=2aIrhC<`Z9Gn1<ibjt9i+T64ChSd;kTlE1vjP{Z4 zX|&e-iH&8S?#+sIpR0Rj!PBMdRFUo}hka(!V{7B!+$Z7)*0naQ<m2px@Sln~tijW* zFb8U-Vh+0Zx_Fm2%LY;3o3_8zvx-FL%%2}akTd_}lvUQORr-?VDiF81@*OTDNl!;3 z4fed_GO#HdYdp2yY-<JrC=4@5p#u;J)|y?|)X1vcr#BGGaC@mS@)}E5_X$~;f7f;e zdoE8aR_oS7WbSbxt35lASNDxr$0ZS4siX%A(jDmj9c7$2%d6M!%kosjWO=TO#j{2b zpUX1~n;QYqrDNx_9EVu0wc#3{R{c|V_nB$cJEL*e&3g0ru0%Qd1_*p?e$S=4rLnDv z`ir{VtJ|zKwP=pBVGZ>eDS*rKISx=^3ntU?36$pE{Ri~?7MHgWxLG!rcOrH?cUf=y z3slnO9T%ss`nofo=W>XB!>rmj7ouec#`$`##X`ckc&9IFqs#K9)7O0?=?ivnIw2^F z(JgzhgOl2-r);Qb#)BD_EXx)>Wp~9J{?24gApQmd1JYUQ##c#bSd!6K>)y#WeTklb zivL+mzo|>pI3qgNf1a>I|57Uzl<g};`))(~gl5wN+j;|}4ZEi?haNQYUW;zd!jXfY ztu@KCzU)o6@%Ab0Xl2-K*4yZTUzew4yl=n?V&r0<eW<>wDJsjeKa(EB;sZNl+8n#+ z#1^_GgHHY!`u;6+o9aIYx?eZlx*MM6pk?nU>(mh*G(Fi`b2<8j@xD<Oq;)dac{tB2 z$TMO+7NJC@FUR?!&PJxrd#zLLHz2Lx)EH}xOC;{P*cbIjBt}um0hC&NYOJ-!E>ico zEKNv^M#&+R<~|jt%6{%5XlHR+7bZ!G3r>Z+J`#yvih?oiB;&2M{}5@rT$UE#2i&j{ z5~W?d;!_h`Dch_yr*T|&kj^ViarOJe<xBsG53;%XZFR0PIytccqgVgfX{@hrEy<G7 z60A4ffLjhpGca7k`ch#<?`K)wcYHG5*Y|UmWuwzKX|bkTHtuEpSp#{kvEjaNCu`3w zU_Q3{RrK4lzup<=v#dSev&OHnp1RuFJIZdIy1_a%%ARKJH?9dk=`GHbE%R3DUeF~< z**Ym6PTINi!2op!)V49p7u6}t*Y{+W%e{L>QD3-xsW>s!uyDA`LisjRI?XS#ER9%f zqntfCXV3Ku<Io`v<bmiLU6$1(`8yz^A?t}^EKVj_oR(EiOM^bV82VKcOHUitwk`aE zl69x&TbK3u?D(<1s1KcZux8bc5zbZ3SY$isvX0rNSGUEutfRMO)qaA<4564f8Fi~L z8DY?*@LkbKLgD-3PH(6uh38Y54X|IF*tsHB98j7S>r7dVvrA+aY{zfHlyTO;dfNg# znTK&Et9J9kkuJ|F*z;R#&p4#=w&t?DhXXNhE6>ZKvGruvdvt66PG~AD+p<SbSyk~h z^|;e=AS-2U#S8xPP-~EB4vRK9?T$OW0mBM$ieV535MZ0|FJ3sKlmph9*^~jc>GGz- z1F>x;SZ|{T`dl~=3QH6Q2;bNWOMRWR>tf%Ki^x*hj&)xeYDSN@8)veA57d?X67dfs zv7oE_N8N@7Xx5q+5O*=&H$mEG)CW{6=lS=ZG#os}&~~HDHO@D}K?b@96>wsP1`C}U zNbNa{ER<63rlJ`dEHqK3x-9#Vh=Xf^qH)&RZh=I&%0MaGO7y7aOnJ*%(-*uuJ)6kX zva|Yq>hvwJ{{%DBSM7$2ZD2FgeSKLF;w<S+H=?NS#bF_cK_}-9*Cj3OVqf1a?RK_j z`Y7w1?)@<<U`r#&e${mAoTyIt=|9~%Z4()q4L9qiTZ>oiwSK)}y0x_aJGL@F^=xT+ z%E7Xi$<ok?AP7ryrR;Fe)V+P}Larn5h{;y6H(2?JEY`oVSX=Q-oCTe}aD;BzN?9qL zY|Ul)2qT7?^SVBI=bl_0+uFu}sG{majg5{sT5BHNPsaA9Ft$|F*x+6pgN*Gh7~98s z^?@!hwvXA^J{HDy3ypg?V_W)0JfvxK{uiploHZ9=8cpG29h(vH>J3<A8bZ>Bq)UzQ zZ;;y4($E{1l~maB%4ZdFLPKhTyRcv&En-x0=4Abi0^9VGGFzTa_f*E{Z{RO0&n+w~ zFQU?=K*j2Bl+3Zsn^}}U6HuJ~hOMaFHmAf**=_n8Mf9fw@#iD}A%X%AM5c0m6js^2 z(YBeGX5xr&sg9pYh?CAs;Q>9JPN7?Hmkx#fAMk-Cew@Yjjf7oj#v`whL9X-D(Age> z>eYv=bntkl_2y5A^Xfy08^5Iuty&C&tF5)$xjnOD*GKiodDFEp<puUqSIRdybKOKW zdV76bXaiSCQ)l3UxxtUG6ZSf=-Bm;!6vyGtmA}P*J^E}V%wO|&MknyIto{R7zF!Fw z(fqsV4uh=b|BCKl6`KE(z}<8>h?N)#HUH&wN7mz?KzCf9PIq8i^Iu4JT;CA7<NEsJ zjyf0XRoBKiHXAoFkF<UTS&3-%Tb$s<28Z!9_V!4w(C&#b{!Zk@ID$gViwNpxJ>P+_ z1)UM=_mTpd4gFbSMPn(OE5F4*le1*T>-i~qLzErtK~h|etYZiJQ7J674wN8j$c7_{ zuOpWWTsS2Qtxj($L<%Y`dcMW~J+%(WqH4?_@>>bL6=-88_YpZ;gyq87##wKh@n5R2 zz#g0F*q4dtBPrg&a}aR1j}wpMd;{#JyTuviF`@1@)xRH|6Xa@N7OwUQh&!UIeS&?$ zd)At{G8abYf$VC@S>MFo)B@Gb3RKc_K(Md1z}KE@rdka4wMtny+rLT1bj!B^50YUq zo$WzujU5?u96=*ztHd=4hly)!)|+a%=WrIDx_*lAxMpkvkNYt~2^rZOna5531&>Ry z4SQT0S^pFn+a$Q*KQ6b&3QrmZW=yA>C|zkf#<Eou;5bt@TxU961URRX)8zoibh@1L zx<2E5QG=;E5#R(w7KPbYl--HZ$7xwl&q=1>5d&+@pgqtu_}uNpm7eAKkpmp~-1mZf zt{LEv&lLeqqwu-a@VUZXODWXBjwXhCGg8@%hvq0u85%K6K^#N8qAfx3$&X5W@_klH zQ^hO(n^2c<2VIFIyMsgIa-ck#e=ps!d-3Bg&HD0WZ4u2_SNl()2#)6sc<h<X1##zX zDX2_Z3z!wN1GbhC;jCq}X)UdRnS)f>FQKnIaj?_G0pXog^j*#{6Ndp0BhP>aYYm?A zp;otH0@ja=1wrTtj_`ZKRC<X-#IR9pDjdC1>ZIN<m3|`i6P-<kCJucm?egB}%FZI~ zOQ$d+Dk$b7y}{V0!isi@f;4duvytAIIJ`^-)EN#COzoqHI52f^_fBx8?6uaM!zQ-( zXiO~5dQ;6|OblVeHV$ff-qUgJFa&dl7Vsb2{Tll1dx4xgd~A(hZ#{L5wKvWEX!3w- z@a&;IreO;kj;RDiHNwI+!!%3_Gp7)8V$dL_5bGBX7hz3X&=g`l$#R64Y&0y4L)Y}7 z{tHYYM$i;uL<1glz-0OREX#jgDFf`*n)mscw|xu0k+v0>JbV;nTYC}DU{mX7nml~Y z@ysK_wkVzvN<A;2^0Vm<9j*EE>5fOw%jk|r&x`4fN6$>U<I!_C?u>t~z|RZ#37mYm zUcVQw-EgL?x8C*z`1G&E(``oSOPGCouhWbtaYM_558+B7K<}67x(>^Ao^2E}7?%>F zJ#cvPMUn3;zV0@@0V%n@iS6IL#?3Dv-G|wMr}JNww=qzBPur&Ac`Q6KsC%!B(Y+Vr zI|ow>MAAD+hiX4@pMmHF@ANUxZGd}y{~<kPjrDd~97Ck+vd20-pTT?Wa;Cg(t$B;E zn0(MeLX5EmY$0@_HKQ17?Mh0MgLkH5vlC-wj1v)4tfLLi3xr(WGZ$WFp4SESg@4w) zqirr<)LFW(`#O}yjCccr<I!<WUr)rAQ9ojev0ApbeH{f6FR!CCR5UxQS7Gs{!IkoM z#q-#O#zW(LoSdrUq?EUjT5(tN4n3tL)>?Zaf)tmxw|^F{#zA5pQv?4*3SCSI(8-l~ zJIqrnqM0|4^s&ITiS`|x9xTbAz5c!^)*c@6eznuH-`uS}ge`d;Vn-NAVjmp?vD1(U zhcXIImSlgfUX8IrLm!yLS^U6p2b_;=@Z;o9;~<o*SaiY;XUZmP&Dm4|snZm6Kh0fh z;|L>HD(O{27<AyJuRz3>8B62FK0ykqf+i0lK9a4s$3frywDQU4-)X#XR{v;0aM3?w z1ubx3LO4(OzIxpkbs-Wvabm5;0mue;)iLeq3z6PAC>?&ax0!BfMRHV7G9*D;V?<Zy z<Ss$UHf!xG?a4t&@p4AE6|zJYr{~kGe*ekxx$HkVSNXBvvdS{n*V9M(L{AAJFrX*c z`fa9F80$?>G5SYcPMAp+2{`c+MN5Ckjcw%3PRm9J{G*F~J#m6=5B3-rWB&gwrN--? zZ}t7yY@q-L)y9*g;omWH#QF?oj;n0|dIlzrry+XTNM1GuH#o}^JaHV`BqxreTC!3; zrX?EYmKd@$I#d4Ro`ILPuzWCKbosjD;g6oD?ny`gEY@&2IckH;r(=cYt%Vor7S2c+ zD1dQV-h>VXWnBnfNYX#+mJMhX3l!DRoF4tY-lAJRb`5uve%?tEf_3^~fg7+<<@8=3 z2Tw512Gw`2+K#oEZ?QJB74G$Y9dmfN*Y^>PSZiMu?v-3A^j7%GKLfxKq6|$FUUN)4 z43*XV!`fk}ist`gJB*&y{JjG(%v(M!!jIt9=_zAi(Jx`v<MMX(_XcgF-*V-=5~cx& zUyvNIE|~V(d0S!HU!i8rc=~x^)f-?W(4l(&dSq@l=urPD4S5b3vbE-W)NpwJ`2})x z^q-A{4fxL`&#C^C)-8U~e_pBj&&%Oh;==e(TNwYzy&n<}Zp1Pktyi%Vb*A_${vO7O z0#8o#cGHPQOD8&=oaoEc0xz8C_+N6OBapMB6YWh-l=Xx5cd$Zj`cHcFMR$1@2K=Wp z<z2E>#9Xxgg#8EMKk<g54*t{T#A)8!XCoW*kfx|MnDe+;^u}(T2C+Qymfqpkem(6* zuV;y^UDo)Xc57`mB{bj%n@E_(f*N)h;6&5eiS8mNYQrA*7&Q4L=|qP>ZT++z4*Bll zur*!Afc>pC8w7qIx&uoB2RrRelk1}Hci=ql6RC(-d!}-{ic}7H7Q6%3SuE?+Evu0j zMMVctJXHJ+O!OjIu}F+o>V<qxk@bqiE|e&%jkng|fG@Ku5@VEV6EK2{#C=E<RlbTP z5E=^H?<8lXU{08f3|XF^C_+ib0$di3Utj@l8$1Hs?rJQ+wb45FViF)tmE)~9J&Icw z?QjpM71%ZCi&lNrjwq)E17cshSnh7neG6X4Y0AD>W7)0m-$tbqXhk%RrjQHhp4=jh zYgh!wiL=0hxV@{jC;Vt^_YztiAEb94VYl`~M7x$E+EW@io?Wd*vs>rAPLV6SZaCVl z&XiBx`B>0E2hvLTkMN-<BTP-+i;k4R>4z>Xh-RgHL}4uD+ePU(jRHTr(V6lQ<s86a z?0^p!#!)>k3q0*cWM<*>&c=rn#=0yAT(ko2PJ;q3+=cy*cd|T&6IPssum=wIeRJ^} z;?Bb2w-bxsS?1jEUUIOT{nwIDtPAyruX4<KX~18;%8~2nb~qaH_YZA{If|tnBw>HA zlG^)EZHJ*nn!igsjIP)G`@n+8FZ{2Y9ISVkpWdcuJoR@@r1=RM*kJ!FLGD*aWc3L) z1b0y~8(%yMkWW}gYjU3TWQ6`&lnEEV2K(RR6TikirTX7vi(ik_{~q`FbvQ9kuJ;$? z*Hz2Hx!%6ydILM`9KV{*7Y|>E{q+s#si6IJk`eE(ue-#CE)Lya9~WCO%v%vx{WEsg z4<c*z&sZc~4NVf8>&b!<C%U@kKhQ^K11Txa{{m0@>T6M!HcL?6TM19L2#My_`p*`p zr;)eTN1;Bft<W}!dnERTai}JJ3e|%h^<25Nj%Pu!weIp@W0SVl8`6_GLqmG1yy|?# zmOHgb*>czEQH&cpK0%E*Jd=0bd1<lDvz}HKv+~ohy4Xg0?(3~t>-8o6g1~r&{I;z8 z_^kX&bMxJ0x6!Q0<-yb41E1tBfh1hsC_Bw3X!jjWejR2>Q>q5y4~-Wa?`hV>tKl)s z(?jkPGHVcUJ<)@_@c~C0oX6YPhjw47#yYF4H&-D8;+?m-D(w3wWGq6=3MMeF@rlXq zcH^-pm=l+`yWIu%8UtQz8P=CMwnYg%d5lWn9-W>p5PFtp4mRZ%#^Qyx5IpwYrzk?d z7R&3i<fi<rh(hPh`m@_N>;FLA>5Go)r)<{qxZSP?^n?Yg()GBJ3ZZ*Ggf{4&_b?Me zXVVfjMkBD}#&W;do}d>1cy6^<ksvXY<kD*dG9SaFJPKZo)`8P_8Gu)V+rsU*-wkhP z##_{%V&@&b>hDK2;FwA!w$G(MlzL0Y3znGtu3&!UX5=azJ&*SnV1}t<Khj#$N~!3G znL2bpa8HcWNk<HSxpY#aluyTU1L&OOH^lvD^1*ecoe(`bHO%t41vk!ywNOGVGvNIL z^hT7d6g-VP8{}$WY&zbU!17>O1*jDhRlK@`NfPl&<8mTJn+k#RRH8qKUM{+f>FuY! z6PvC4Vg@t=n?lq+BKTh>7`}ayVyTW(cFYjuP-)!rD2UQKpQqQ+VWT<?o+BPV#%&Kn z-e4E~yDoUsX^Pl%66X+&55YA}qo%0)P9ja&dRmGqb<bh8p2T6pqu+f3d*Tp}+<<y0 zi#DL1;fCm5oF^p0<~9^gx%lwbKnsGM%oz7sv<Gz>_Mq-R7wtWh+6(>q>V$xPRUbrb z1huf<{4m#Y5U%w`I8jVPc>n307;4lN*nc_=!RA_wm;YkAVhidDs?gi((s4Gp?WB)f zxL_S>9^@V9-wK38UEt32{0+2V;mj`;&Mg*x?H=kAj?>9*{!OufFdJunEb?PZzJgUH zRWlxagz7}wXp7Ky9ql5ef(%>;wUa`)T-?NANgf+XM&VN8i?rQ4ImSN%imULGm7j|O z;0fn(wh&Krw}j0oU-REZb`TiAT;9oWws>h!C$X94^p2wJ&U`%vh5h@OJ<LNfY>0MZ zpRGyO$(aK6UXHBP%Ak#?1GE^Sp@<Wd#hb?AKmNsnP&cfIQ_8YmRsxnNf~7M>TmyEZ z{8u3j(;2*N20r@?xbn~yxC8Vc*zGUC$GAMZ5R>{b2cu(9cw324KmwyRHvrb!FJNMF z6vZ$A=j`;1$AaCvbUy30GqA7a^i6I<i2XR2*RT{%n^lfCUGRoj%9uoZSy;@V$a?=) z938+}{I77Z3CD!6VuD)yXTrW^e^6NK!~r*2Reupvf(xuQHV~KSPK16M=mia!*&Kpe zBH>Fc!wf|kKEm@?Bo;KlE6@QAB<>pPb0tAh4@A+TxfiL$4Vc;dR}{rLl08V{BRo{n z-2k`qjz~jv{XNpU5J@VxpaJumWs;;Q$0v9MMNDhRN{FJ%vYlxC)tuE7H(*xd7sm=* z9>1&Kn=W4(4)0(fHc#%1^>wc$(Xs6LZBWRCO>!(GRkK9DAn~Qra;NqAH*v;=^gDUH zulu_?nDlk`Vp#?A5?UF;cNL%Dv6v@#E~8cWp4iT(akl*g4_1`qDts*FElxValZFMN z)pW7|olX=|X?8IjeA3M2J+!S2<Tqg@pc9sf9K5XV#YPtv&t2Ft$x2yAXL!CqzRgI- z3)E=lQtwRpfO7WaoIS+?{1D`!>7UDjBMwuCka&mSB}(0Shs$L#bjv%s<!#q+=nrC* zeH=b7#O$so;)C~`tG>YEkpChG6?2!joz;hE?n04?wf1!wE9NeAtkacpz&(v#?}5eV zH^Zp@TI=oq#O_j-=PRsu`cau1FNUEA$%AmE@Ie`}cel%B=WIkwiU~{)GJ(^;BAxT0 zMbOPyg>Ls3eCEeRBd{;(T?l8aZ_)=ilOFYMyS{hWKilI>sTb=dPRrJ;ly@s$^}q6i zxi2;uE^W2{8tg!4VbedG8`#0No%?@c+y0QUd3Gak`zZ_J=xz8OpmyO<Wfl+Nun`2> zY|&Ys>9JX!Z`h*8fg1Qd-R0~1Amt$I#_}iGb1a!HLJWHIlV=OrHB8-!nKvz0X4rAG zaUTMABq!*exBTD1aS4Bp4zGtbS+JuimVFVr%PlX$ccT5$jK^saAcIVs9<Zb$Sg}77 z$#nQ9!zWT<+y9ZNSkmZ=R66`aYn4<Mwr!@uCXh&nf6Ss-?0wd(*s@hA70=UHw$ihZ zA=pY|!da<}j3hP0O2wH)I)Y|>{#`Pl1Ts;mM8Hb@eEz48X{UVt=Q29~W5G{9tlr}M zkINn(Za3O#F5@az3NGl7B&;+AChMLqthAoUL&svtN?EWF9n3T;V5TFnLO|jTHq)T2 z3u!C*Lhb{$(|{PGq@k|IG6NZ^)3V8xg7co%nx1>vXbxkjT>^%>QyA)<FjW4_1^(;l z4oa!{E9ed*g65w^ckrs3KacKUftsI|dSOTY&oH`)Tn|CXMIDRjju$ArbVu6lzk%+! zj(K#)b<Czarj?I7gbe-<=wOJsKZ2*o@u>HGgp$h$VoYqh7Z_|p^O#t34bo}0g3{l% zs-<aJ@aD^riaF6Cuz>wIQP5g5y1mRI8o2`$$y#rY7iD%)nRZunl}XifMK$!^Z%Mfv z9?Ym*f}g)qHnTqL@bLEFI_qtta74gw!H&6cHRZrt!)OC=@_o1uirgN(hf|Hy`MS;6 z!MWEoH#@x-8kd3sO>4&EN*jvnktpn%_Xo$^4RnP4LHYhSmv0WggNo+-I8na=O$;;R z_m08KGdsBx`Lz7UutY?w)*9MDqKB4QE)D5%@@k{2aX(n%dE6KrLdXBo7%npc9Sz?Y zshG9)uWaY^4v3%VIf;G&*@>4l#L!u1dcwPz<UvoZcP9+iXkDIsOg_tDdeMJOv++wo zcL$azu)JWcp}D?zH>maIXNY%Suh&n*B|qv$jCpO_Y2AtDRX8J#hXnW;fv=#U+-Q1V zgq&KDH>Q^i?#LQmh~b!~I@cmjS7&g$>8O~PQ;~DVG!E|-H0L^oMyz*Sdx(#)_D}`3 z1z(i`zMh4ZFkfpSF1=wDP5E>WmdH0cv4=`0Na5-$<&>Bi081|WOcy37R3E8vF30Fb z;$kS`Y>vD$h|U;W8VC63HNO)^E%XUb16XSc00#Plb@^v(s#tGx0q;MN@&@8@vEnnD z6i_}+aREeWK2CuvrYj7y_87B~(VSnX@=t=;xt(@2SQkh3X&QteciaDI?_0p*s;d3Z zB$+m}WirsxmWMFKf<-aT<Q*QGw3#&1PTQEIC8F1p>12`&OfuulBu#jfXiK4#LIgx! z7vmMN$^|MS77=e+O66^ohph-k)RG8dxGI*blK*e*$C-1^oJo^3JpSLufpnc&XFt~2 zd+oi~T6^tvu=4rN#wI80ft!$!CS7*ivXQ+RbM`|wP<p)hB@{65j>WyGmR7{r@Xhq% zNl<Ok?;nx%Ze~0#+L!HyKLZz3-!@(^+YD+MuWHuj=zL?<_uPQ0-zEh{+83C{L3+X% zbMJ>!WpDsES4}W?<V?_L)Q2}-hjyKSKD-aF$o1ieQht~j^x=gy52ai&aa8=Flq;sx zhZ~(W52d^@8<8XBjoIj`c_`(L*|>x{qtT=fU;F6^>%&pfhcAFWylp-v69?Xx^C9P} zH?B|d)hp;BHlv_piAU1Us=SqV`EoX^jAB;VOOwXsD$QYALojA_I!B%$XQq^X{bd?b z@IcDj%ud7!{rWK);u-bpe}9!4`nb2wc7Y3vH=GLq{dxhqS*Op^=?$)9v(6=b7TR_X z6x5??f`cPoT6y4j`f(h-A?3de(8wQfvUP$ud`<}4Q>0Te9hNgm7~I6|X3$)<bRf!* zZsEw|s70jX_AIS1reu3*wjMbZEyCTsxLBLbrk6)XeoBpCSj^t>mk;G#eGUr6ff3of zo4*N;Ws@@nH!__Ix{uA3=R8WiHGCQ|GR@-G0ZS);Mq1c_#B7?fA1Kt@*7k$b`tV4z zAAEu3?WK~r!)YhlduC1WWZ6{0!4__x@W{X<;2ile-jt7jaxP`*{lSg7{^04z!&*e- z867zqGKsD~wDg9;Yl03qw5H1cCGi%`OTM$cSSW6T6a<S+-sZ(LX<$RqsbC$YdtIy6 z`~!G$0=ecL%zB*fhgUKVqk_t*pcSm3$CC&lO@$=qTNJSSvd8_{Ji}VBA3ftG50Zb9 z5VZMEkieKj(tI=@Q#+QTI5|1<y-&=r{{dafi_;s7%4=4<JvIgpM(o&e=hvF;E1{sk z#0ZNqxyJ6H1*QT<21x0od|-{N`NsjFd{8`kJa+rGJ~uJ~7N+w-n%?m+sR&kj$A2>2 zVV_R#fI^OgKYG1m9~why7C5x=QKR0mPp5Z4IyLGY`*eB-i~}jXV;|Q$eB}r7HlIwh z!PWyh>%hWvy@N!+@zoA|yn?G8&oH&)ZQpkPcBRI~^$z$ea{B<&JHk`YI|j)MmZ%VF z2aE#?lPw50z!ZhNd!G<$N1k4nzzH85#46u^Dbx;@5Nb!BunyFeKWj+3@%U94)Q%VE z)m`KQOWwD(pJQW}3<T&F_Wdq+lDrH9!9JaV0PPCzktc=s$dk-Ka722?s<SUeb@>=Z zOzj3o8|?~A<|exWo2FjjhZfh8N5EbROttwJ7-lpc*px7A+b)JITPglZ&otkvU-Cuc zQYX{LOUb;jz33&HaLB}f{|Cf;4?;G68Xhz_3rMzwr=hE#g9CwFc{cfB;M@@N!x&(G zj=0}5@)9(C<b3T<6l_>Ofd5Lqh3p&+8^CL?rU8rv?g1T{&}-R@V;aC)Q6|p7!XC&6 zu-P7%Bzquy`<XrPWwHlic+){g5*C>~ko;s*_7Q0h#Lhj&Z+YJ45FUfy2%kl!rAyfO zy<`u@Zv}q@li(a23t}e0W@a~N-b0MSpZ<B}_M$=>zpy<;m=9WH55_M=PC&7+36kB9 zY=TLaHMs{yLA$8aZ+i<5$tZXU%X!HjSg2m+IdQI!a*|b0RtmG=wfrH>g1@8swkr>k zNQyU!>?wm&l^ppm`_FjBzr7lELCkZhkzaH<bvhxjWl1e}#xrm>g<bF~K(j#fnqBZs zom~)40q^*>Cx3{c{{{?$GvvT0=Y<*4FxY{{bI!}J$)>ZoDZ`-tXrE>l93;OnMg%hp zzF7k&E*FjbgVYl+9>0l^k1*_WN?DI^gTpy{VCjVC*dsXVW}}2;7c8yWw43aLkZCDt z15Y|{4;%UCPzTi5cKdDnsQp<J7d=5Ee~EGA!~Y!}dNM2y<U@v$KWC3`>*LZim>T)y zmdi)}ePnTXe1t3x4>B78SsWh3SmqXo2f^6f;_x84np+&0DV<py9%QzJRg?qjg)*`X zci4@%?;jWz+tw;0t1#jzT>Z!ySiO9N`5iE18+b@2DUeC#$|O%xk{^>wg^P!-yYvu^ z9U-*Dw$j@{XlVtOgcf+ljr^V#dbx<h*9^9X8a&o)4QI<t1tJqX9!9Rmy*|^vyesDN zOn=AQARd*>^lwnh4o0J<Q$XJENmt^ZQhL1YV(0K`{33yK9}vTf@DH0D%77(zV>f&H z+u<FQTo@W&XIb@IL}y*W%eZd~!QT#FL}fkCvOe<K!Qm%yms0QOdl~RQrYsrk3-qOe zZ7Q~*X85;#47}jqhJn(SyYT}5w)1iiyul~SRDpD$q0+x~0RFNrOarsPxyu*QAxz)) zqQBPc{+%5ng&pT}rM~nMj{NP(eX;DtZs&__PI782|KH9(`PkXZ5pZ_rJumSuYKi$u zqoxK9u#6i2wwm0HO@17@I`9Vg6DKSXNDT|fz{Yd@*je7T!R6n2fRTauboW6<0Q~$# zc`w1+X%8%IkEci&^_35HzRE}RBf0+aXFKmB8W5(f3THl<Klb0&){~v~pLAl5f51U! zY{3pF^Q{QGT@YV|Zv``4{0O`t4Hvg!6u@v%L`s4*Tu=a{vTZR}B_Ow3bYe6xy}5y8 zOWk=`NNKxk%9rK(xM0YR<zu&p#BD4yFcdQ>jtmERv}x{Q$~L^S$T^`2g$`ejK4<y^ z$kjPcBrp)+IB_K?6<*j}Zsnxa=tz4KF96ayAErl;xi8LL1pyw6LW&CZ#|RB2B-cl0 zVE1D5`?pcwJdEiYi|CodWc^__{TE4Yr}Ot8$4<+O{;hjF11WwI{x*<F{tr_+z?*)Y zydMFB<oa#T`pSnp9~~*f@J^@iE>uZPclq(+F=$K}X~elQMk9`;j^=HqD53ssvvo8= z{yhj9U(NA=#?7Fc1e1Y{r!&j^<HSxwIey!IqM!2-$a@jy;zR!OJ)LkP+|6km>3n?T z225z_G_IC3l1-K#ACAT=zy{;cNbNYVvA}{pv?JqmO|Q1SiT1?ub%?kf0<}i#!z06( z$?2qME#I_1@MW4E7+;xAiaO;<(c0m~mm?8&>~YRBWud^CWo^5@febj~?A7CV+T=It z8LKynUHZ2_=|bD!%OK<{+NkZ%8;^<J&-(Dsd6%=eH`~vpjmqH-c*9lH`ZStcjE&(R z<PYZ61f#jc*^;B_6yn?d@}K*IgL#){(FmsF5FgFE=7+S@&<53uOnyx9FKnNA*L)R~ zV)@R49QhRXR9;-Uea>Dn|Da#Ul>nc0Iwnh;Jb#^e^4gxou`qJxeR!mi3K!>AU3pjB zjMC`bYBEF{$aH4)4#I3To>{Hs4g+UW=WRRgv`@G&7Zu-mCIHri>P^(cIpwe2Aeatg z_8n#|1XBkeW5c2b+uyfn_5*fY?6q6)vTOijkc`a1xFS1;6YY@Fr@<&Laq85GTDUWO z+NsmxUV0QkQaW{7fs#b~Be!h-nqUWScy|2LA4Isi1R*e3sr~uaJ*fR>=Uux7O~k%W zKG|ZDO{@!1#7-*W&#(=!c|OGs@(?OoMI1ui087tcO>pMO#YoMvXXjme2AXQ*9&TEw z0#7CIh9kGj1YnWt=$_3b6no<xESxk}*Fc|u31dIl;wiS(w|&mPFr{ei$>+a4xpLg{ zK|5Mg{zNB^*TLi4_AH{75TAU1#Elvtr`TRQDB1F4%Q`>9>-;sbBb}MRw2L}_&EESZ z#*HtY#dz_t&QW6>yGNdaaK-D;v%+F@pzil;+vGv0RgC=*e2H`8?Hkbs;J^6{{$==O zVgnqUdTn^#W!!#)FC(#_{hMBQli1<k)|zWrT9;sHC7a&Y;7<K7fPu0-NyqSfRD*c% zd7J-}M#47x8%r=1z!QpDkugbp0n$A}b#h_lK{$IUKLyhwCI0VrUZBu_V|^?#)~3B! zD-nEYAIV|2UrO8EEPUOo!;6UMZ6`rF$CM(zHa*u6DU`%$tfh0b4}&2@&|WvKqYxhW z`T^oT3*zV<XmN(_TJ;-28Y2^$C!-IfvGJIqZ{+i6<l)yr5v51LxsTu#Iy&3ca55BE zy5pf1HQb@JB$A<6g6^7=^lyi%AsW=yK$szyMLQD7cxNz)6Z;#&$u?Ik5D&D6P);IW zsS33OIwMIJ?8Y)tzM`Tm<W-fr&JNeA+GVbmc(mPB+mmdIcI3}e;+-8zYbdEk0?AM! zsm4PIl%OmRC0$gdt38m6hr5xE(h!C{s%N*xhxP0!Do_H=%}Szky%Gtp4|NA9K7a}o z-n1(kZf5y;WiDQsYe_5~Y7Pexm%x>b2QCQF%k{WEK~V{Up@b_Lbp>LvNY5Fd0@wOL zA{<21#KRq}XPu?4Qnj~rb#z7|EHpt^AcC6sMd1?m{d8>Xa}RMy_w?7ci^DS>7#q|7 z-L!vfEcd|J*b)Khp8j_Iio?kBV`KWinpe@e_^ZVSh6u{P!GrvM7x4PO8kj7a4uKa0 zq<j5uCln2Oc0b_rFc^r}NCP$s<*3-`AImG_1IyIu$koN`qtQgNB*r+UobN?|&pc&` zwg5UzjV0r1b0|W*=SB9~QZ>4sI!_d3`k7XNEWbIF41^<|;zSHR+1UXuP|?L9D$;PR zE)9iSLmjc6a&LDq6ibGq9cgLw8CDm2DSgQ*#=*X3f4IZr75}*94NzXMQb=5DzC?bH zn-{PYH2GH7s}m>>CE^nK%NZ4u&aLGytP8bFuwH-I?FEG%&zes3Nj*kLbI8Zu7%!RD zR)RiO{>q8H*rY0u{mc2Ml=DWSpfDJSL_%>j)}yv`b_A&#Rob<}JG#{p&I~0yjjy&k z5{clI+-iZRna^!1JyK)QNH`b{CFpevk-4;sO&WzhO3yB8KgPcvcZywo)X}mfrh&dy zR9<yBT(@%K%vN8iPU4M<ec`(LVl|9hlu^7IV^vAN7(ZpY@k8yY#+rS#UDU4=8o;tu zQlmhYZ|px$0p`}uklGfFU`97IXez6LK4bn#^*?XliMMUnBwDt>S6`-5+Zq~G_YT(Y zKPmcatGl#WaZ;pp)t6+XOOiOv^fiZ@CqZJdk4U6E8cW(v%szWBWV7=?;9z`gYzX%| zH;j!r5u{ML2<t6`w?07U(fGjBC1Yb11R)bq4Ag!=is-!)un}+&Fa|gTcqQN{U_YP& zL2ehI6L1jF1vm^?0jT6)4FaUSye2^UCQS^m2Cx^f39t{a8?Ya+4{#^o4!{Ax0l*=^ z{eVu$w1)s)fKEHg1zZBy3s?a-0N6-)NWtBJqkweY*7+5DcMY%~keqY-p+_|V_HG9K zfCJFA_X8@h@EroI09*)@YcF6K;7-6sz#+hHKo?9sHv!fH?gH!u+z;3fI0`rb=!DUH z2yh7*&&gN_=mKm4tN`o<Yy!LquosZR=k)^)0uBI<0uBP^V*j^~Y?6QjfNg*kSAlN8 zQNYLO_cpXQU@u@Uq_H7ve$)WEuSGgQ7dDd*0qz7`h~S-r*nV#Wto<6=8&J6s<p5Ry z4gvPVRh<GLjsji@IQT8l2RMX7p>5!g(E<DhbneD`6Tj?1xp2~{-G}FZ13yFm0S+R- z@*%*Ar%@ifk(@7~JU}<#4#3!-!5{E*=>v2D()YRPJ1+fz-Q@oQd21IzT=O_kY!}rj zwr;2G#5pr_`yfm$2L2@c4dbhzgWwIt;jDHnT#+|>LvF9~nG??bc;VtxDJ$i#!e0!$ zek>uxMffk^uN!z`WqDDVblEPd^|Kmh-n#vxF6Bg7FXf}UYmsjOV9t|h2wa5!Z~Qd^ z50=v|!tcc&rPtR(_}}2K26*ZUc@h3^_^SXOO{HCgr;inu0Z%L|FTzu3A~*0S6LPu3 zxz3Tx=s71t`Ua8STuub|B`C*CKYhc)Wl`^Kz%R7G-w(VKc(Af|5uHx~pKF2t1MoB_ znctV3YY+8+$Fx#-pU=ZwM(Ix@e2v4oDXS50%rB~k4k1(hyk}B)Kk!ul86qtKO5Y4T zy&v_fya;~@@YLSrglu*=8&C`J#|^+Y0e>ywS^ZgGkp!FrR27~N;`uGO&$$=9yVT*l zI;+yLa7%Wz!?h`=dzND%x@oB+w|e$++*h%CFJpru<RKp`_r=(1!TaZ2Z^&Os`Kui6 zj#&;D3ak{RD9V}0_Y>q>h`F5T%84Q$9&e#~H)U5jTwmlhRXTE);}OyMI?{I|J?*XJ z_zm^cP(6*v!E0DCJL?|pM<r6S{AYrp%di$4p!_G8>T_SfGoZfe*;!X;KUi+`5%NTk ze?Rh{Meq3rCaP3BWqeO+|9Lr>ldv|F;$A`Hwa#+ndS_R&E}-W{c&=bg$n>1{09@ld zPvUt6o_|V|k9NrQ>&m|Y&uI<H^!$E2ZyKlk=kUCDocw>o^S%tvi7)5Tnuh0di9T`B zd!GsX4&YscV|-aJ*^=?OUpzPGYX*MjIQce<=jMF30l#aUd_NJ-&H3o8>%chq$d*jc z&H3hF!g_3+d}oU1dG!9`B0iV(J&gODTQO6B&$eeRbu7G^#>JMLO2?8-_Rl&hvi!3g zOO~^Ng%lW`t7o(EPA3H`AX9vj%4F@@q_r#Y@f~<hvd3lgJT>M}QV49n%;Dr?00R-s zihD}77=IDuy9xR3#(mBwfJWX;S<4;ntoSUJ5K{v6>kUZff@Q9f(k(zb%tb!%Bn>5c zPH}!~@w^!KoW3@VKKA~|AH(ytG|q;R*y{b4J9=$d2hac*dZ3gyK;`TP6gdxB`XEEC zz<iN2!1G^A?RQP~Qip4M&QiyctL>Ez_m&xzj<QWNS2+f3*%#PmIm&=T+ae9p@&frJ zhcc<$2#UILGh`krcT0wHG1-Z7S2%jJvLClDx0>c8x~M&h&_piCU{?@=&(9ah2BG%& z1FGu7a|*|k^C@1h;0Le956c~~tiPL@qiQyrw{AfBwC6pU{w6+o3i);+-wvWHGoJ*& zG@MbE&Sv8_2Qr=;GG77Z^EsGgMD6$AD6bKC6*5}RwdiC#yN3E@JN3)e#MfKwXunM} zvM-&*Uq$PP6|;%i(bpP=cMYv0R9_Qh!YaDI7v)xK>&Qxns{@O|BVf;ctVyZ8??C## z_OY?6aZmH{=fRsk(IHe`gDCHL+~)*QUh3V~VAO5YuMPBGn~~o6b;wIt5^`1`J$Og( z8^%-`zpZfe&CGsvrX{~=d_i>l2IY2x&R1w0v>NEBcQj?aqS1i`lE&v8)L#bqlA_z> ztmWx9Wv#^cyn~NV3_w4g(cW{ce{Ae1OjtQS1HD$`V~u0TmUYmQ+{)S1o_|Am?jHzw zmCXsYl6~2_I}dG3&qH_*%duRARvk9+u2^@8-Uj4vx*zsd5=c{R3*Jv_TbdQJYqKqh z1$S~e;11jj{b+3Lg7N72b7p$}fc(w}$HwMh-J1wKuEWq%Gzaq6Po~~JImoa4bZqPi zEF?L1gQ!#+S@&meR@U2=O;pADb1%y4ecHM|iQkjrc`-(IPCP?>UTq#+Mf2b$>v^z- z`h+gxqjMktw?XG(dXI^Z&cyRCi04}=1Kv@{s7&_C`m&V$=pkRPu15ODP~OFaNR8pF z4ce;4`JoEwTrZD}QGENHzk|t8cG`No#<A0u^{k00mb3L{GxAr!PEUGG&H<iZ(1!Jz z<low?I!EK@98F6dZA%@o75KeIFA)1?Lu70GqI^y>8?}cYI_XU<V`IyRPggpe*(ae9 z*(ypeq$p!!Hf8MAMYaXUKmb{6UvE3x-kg28&3=_l`I-$VWV=+Pb2guikL0{!vv1E* zZpp$k<UOkHq)U{mC?S5#s_VowGb(;LSDy4Un{vI)zQ?9KCvnZ|zLll?+h*U9rTmbJ zK;5U=jz0}|W%kQ$w*RnSVawiOv*RS-E`9B+c*p6dC`z6EW}AW(jHX+Uw&gC)%D0tb z@}PwYG|Vf&qtDsDn+2*$?#WUH1)(RL3;c!lt8$1UxKux5Yx`HW@@NjQ$aP}b$FMBh z>^Iw$du{eF+m)-cT5qr`uh~UCr`b;M*&ohUTI>&H+xBNIg?yDg>$)6eJLRXAWfuxc z9*0J+vj2La^0WE&r{*iq&9@(zul#Pl{os7%jrsP!&R709-`=}GxqN~Bss+lm3+y*6 zP;Op8X>MO&|JDL!#{x=o_X0|D-vY|@BbM?f3-Wd^P@ZJz2NzJu&$IN;FXS&kFEMu! z?rZGOP(${w+pq=5AARZPS@wU<Rkmf@-=3@V=h(kJSNTT{VeYou`{yeEGsFJlW0luu z66Slk_Fcy+FXY;PaIEsuQG~gDmi_z3Do@O^f8|)^`PqcIagP1p$0&Q|*nfVE^61fo z+2XK2ag1`G!~QR)@+h$pXgQ%A@ch+}WGnaB?6*^M??W^FG@CzNcsgd8&)a`vQ!cUp z$fjIpL;w9skn1kNVse@NrWwlJbL|ICQ%2_5-<YTT;yC2|`+U0nExqy$r_Dl&=T3w8 zhuS=p=VJSPGn9k&Z(-~_dX)X{Q<Uwq?bpp#{x<t_it^$dy4`>B$B<;lDW|ebYntp| zpRJ78DE#3ycKbJGD_@z>3nKqG(|(srx%(*leRGsQ%tBpv9Zk18^KiTO6w34bDY*SL zyZ!4ag^F^gD-XFrhpPZ|e0_%fmk#B*nf7aE5h2Jwi*BEG;1+3eiZ77-@*(`N1wL$n z4_jcWEigc_WN`K0$YHPe&3`G%+y&awBvA%<xaWq%AO85T1wLRcAi4W4QYdiA-_MzT zkC=Y{!}NRpT4VmxOuq}oZ-~<DS}T4_n_F1?CKZaVe)8GG1(BXz^X7BPju*d&N*A%a z6UA?_?W5ovI=e>2bCTcbg2{tje}88zN;h;EhAs#c>~cXarVGLcyIjyg=z>(muDR<t zlzNifTOd`KT@{=j2tw?V`R9q>qBw>2e(37GibILtzk&ajbnXzFPB1;NOV;<!7^lBX zq#qN%B^{&UcTp$L_qO;g%N50a2tI6q4_jaYEiiNzAJ^ujFNpc+pnz`)IO95=a=w74 z3s@pxwSemcY!R?az%2saDBzs}J|N&e0bdaCpnz`)IOBRzzksI;SR!Dxfa?To5wJ_Z zEdt&s;GF_KAmBa$Ul8!1fNu#n;|5W`fTs&sB4D+E>jZ2OuuH%#0^TU#odP}};64Fg z5b&UYZwWZ#YodMuPZzL6z-j^43D_cFmw;OYyiveA1$;ojeFDB9;6VZ35^#o)Bj*cv zx_~7DRtvaJz!m|!1l%GZe+#S=ORf1&KA$MeGRd)6H`t|APfz(1rQ_X7XM48_o~Cj? z==4p~YkuI1S-x!9S*|5(*TY4*(^Z^bl<)pzNhkZ|+2|?BcNgV*3eMmUTm^1ViMzzj z+&IR2v1~}qk6CnZwvwgEnfm<MO12{9LnA&%k#eXJZ&#!|XT;A?q#S6(&s3y5X~gGh za;Fi0lqPQ*@w1cxv91~Mvz0#6JVnp5l{uOoZA^c(BIS1@-l4dJTyMnZDWeoG!gOWB z`D@oAEBrCaVz(9kSVigy`l7Oxxr)>ejQDxVA)z-I@yEfozDSQ^_u0yP#Y#TNhLrC* z*D5`vc%dig3(HoHx18s*q0J0=t;&&FPpTAp`yA!Xu@r{ikv?U^Zm{{iNRP@we~o_K zn1f0tyxU|4$rpIDeWVI_n~qMRgRXk~*(}=mBH*cfX?LNtbZx<(O-b*s&!9l7_xd(V z?@*c+@*1VyxRc>eP+VeNlX}mu8UA>sU#zEX_)S+9vfC7g(kseY!qEz`6VWN{LTv8` z&sMPXCn#=FKCd0yB?7<1RBv41<vQyU<x@VZ_xdJF?^IkSe!iFC)BBN%vnuBysz6B} zN6)Zw()sO0fqzW!n{2m#FuVnyL(#Q?ZwF2MIfvoX`TSJik0Fvw7x~;BYr@gbHsDW1 z`^Ub+AI=qN$oI@DeK!<fO5gWQp78G?{akE|5`O0nj-V|rx_W?Lgnl0o{Z9N%*ImF{ zmH#W?zX?8%nfmu5Fd$I*{kQS_QopYNp3>Kv(q9R@Rr!Bp>5o^2sur<=`gn25Y8WJ_ zeCPK$;tGMk40xwS`)?8HcizDhmWuRG0)H&ZiQUQ(ZwmaMfnTH?r<9fRdMgAz2Ezp5 z2gJN5?GGOXV-P(<;(et(<U-)B-s@qJzK>1@;=)gMEr4Nz${F|p|1JCFI|ARkgX2HR zfwCKTtMV7aKtt`^ZEEMsfv56a_wWM9SBS1PAehpZnbKoR%Ch_&8Swjnr}AUp;^mSr zB3;*DBC?|MN#L#c|7GB*9QW%yKlu*OwF8E)Q~9mo-@U*S-`;gRuMlj*uBU;ws&^;@ z{-2_pUQx~`L^&UafsV>o1YX*oN`d+&_-&^c?~)&W4?NL7DEL9zp+a~MD|)U1p4z|3 z)c$V+&)V}&PKX@um&33}_$I+WU{`jnLSwRepW?sChlZ}>P$}Veig`mcr*f0P_X)g< zrN;g~@=<!Xsr>H?Jcwo2wIY4>JV6gRRpXNHcmQ~-{v8JXn;1t@evs`J0gA>~lWBbY z1$b(oK2!UgH=ox#^j%I!B?n3;@K*KS0zCC&laQmfi}ats1V#A%6FB{K0{>;;sU7-7 zJIHqXrNEDx=92|@5lTPsCtg5^7pLqK_}J|nFNNn>5I87(Oz??pw-Vsxywgh;<r zlq1{!jtuF4FUvRaPZS1Ws&~|c|0o0<YUiD%cK!wMR`mRD2E6km>-Iktc&c}&sowj6 zw<`ZR;EA3J6FuIK@cwd%@wiAd(gnb?_WU+Sd`jT=18-G+08ajte&`!KA^C{Y^#<@X zu6wI^$u%6UG@L@^pxtibh^qxY!tmmU4(!f=e-(Hu{yg5r-)rC_oDjLL-2uE6{m%eT z^qbd(;SA}I!t1d17yJyiWS0v3vDj5G>mwoHsU2L)aD%If{R?jeQI1peqipA6Fga8C z{igOmA9ySJuLqvS`+n1SKl!7)9H*cY-NCMVfwwB>i46FcfM?_VBpb{BSy4{GV$sfm zf6f*71n@+^(=;D`>@<$AxSuB!%dql8f$uw-mrp)gbQPY?)AtJc<@&xIcq{t9lL7xU z@NC^Vk(YlNFJ7tr81>6>ip$h)zXslluMPoE@6~r3FCbf#Q?`VcKPu!shzIPd2HuL! zph({@==rfozvv8JzB0rSAx^IHKfqg+^K1tEtH2XKl!^C}`&V;5F6iIQ%dZmko(nv+ zPp#-jEEDWn2fS4~Yz5wmp4&wEZo#)wKKxyV^h+QZuyJ%JuTQSaKNk4f?{K_}1EuFo z>w15X0ss39_=TV3^}2t^3npJ>x_%(>-{rsW=0J((Ti1IR@HDUPGR>=RWk_F+0Z#8* z@eN+^Eu#GUfv0lXOy&HaNbmX=Pe{I)blu_>?Pi*PMuE5LmpLB7r`utU1)k_p#5#C1 zFJ9?j>BSEnxCeNm^ClCW#}`=F+XOt7KlEE(h@|c0LXPhha?Vy!#|cHe{3}i6e+PIf zr|-Xb!UH0GbFreh#JwJL15fE=-{V+1V?fu;5^Fk-2cG8Vm`VQp8t|-~-|_s+HyO9r zg0Ts2Uiaw>X7U|*4*u_Ffv54f%cKY0nIZijfM@S3#)V517Av<d|1RK<(N`$$AJ35f zwG8Q9XYqO~{>TepzSFop;cPxX^osck;tIRUfwy|!i-0HkcOK;Fm=85>ljrbu=r+x_ z1z0$!eY#EUGYUMFGbs2R%LKcsKW$y_`M^^-qo(p-1D^V~&(y#F^%<VN#+3dc;Hh3k zj63;`7gun+Q;Zi(v+NoX`2O$n-*kq9t}j%Q9({uHnBZrQRg?hmL}$}kix{dxJa`>= z8ecUg{x4d}>#Y#{AmxNRfT#5Rru3&S<K^dy_QbTnuCsxc?;=nPgfieS1D@I;Cgx!| zKWAg%Ao^V<`X2z^s{B6zPjvR0=-lY#<s1@pVp(L@J-}O)^HbodJ<WEZCxB=DCHQ29 zC?`}+<wJ=S`Uu#PU3UOa=|_beQXufp0B=?AUo+rKm-BMW_L=j6r}pVH@zuS+GdZw| z_j`?~_bl94)q4@}MCX8zH|!$)odQ4jZH|!Z>}vu)I?u))EapJz@bPl`cJuUd-T#Kb zyG{N3#TBC7Jv=>~d7*1B@K$sV0dF<`ye`Ty+m}AF(z={aXTZmSr}peO@msc^_iu&h z-_LR~l}3Rd5c2Ao0)Hj&#D|S0K70mvtM@txJhlIjXt(D@IkQ%Ay!(3`f#rr>iv@l_ zwCBSDe=G1VajyqI0-pGxSLg+O;-PP~H9Y~~iT)iX`cGJ6oxX$Nq1W8Z3w}lL!zIAe zdpU)?eX*!_Ypr!TcV@uv1D=f|!Jm1eoF;UH6+gs*w`%9>fv5i6VHz)w08ix)-o*>1 zvwn1)UuRu@H}Gt{3%&1No?Q7vy><Ja1-unKU&?^L3wWZZ!ZgpcHE?{bz{_#^3*cRX z20eHUc&mD6ujS>$Oy%Ds@aA!P-a6}c2m?=iGGOA9`+#Tdc_*hv(pGhzH9Z@EXYVW4 zyT#%qewHD9UZZt6p$zz|GT@b9Jef##wzT925u0qqvO3l8t8YMjGQ^V!wT2P%EUqTo z)nFvr5lSFMb5w1OMAru*YBS=3CDcG?w-Ss}R565#$}cT0FS1Ugwjl1A8i>aOJ!+^U z8ShbAC{mi*+}YmVgDkpVJVKg2>9YFs8kW`MmwAd6_59`Q&Mzpe?eS3<HFHceZ+UyP zxib<%cp{{nhIF1H3fC6K>$bBvSc<ybzh-HrUsVxOP4%g*p%{Xx<p*Oi)K{PMmm$7e zl(OKbF(gc3AQtv}RPXq7d5X3ALI?@hOif;0SGmfIFhy1972ZYie);OPs<%cYsHv)> zrcXrGwm?U7B&1ZGmycL>`KsF5-L1wDk}leTKy1k#wacxjRi9g3xyrW;IT}_ilZA_S zTT@+K?`=>UDwq1bsPg;<U$~-TSz}}6QlIL{FHCziB07-_bOdD}qEhx7!Jo8vJ85~| z;|Nq$9&c9~4XG$<Wt`XJJ>{{^L>qcKc%iqpx>gr22*HC8ov3zoy+<u{$9dEx3f+gu zSrobt5%2=7A&=S|NCvzta!+}(Cl&%Lw?wI=l^%~u2p)H<i@0F*N<&DuDK<!o#3KnA zRGtX8b_9~0@epq&8Qjg|Ve!(c@uC=U6A%65^>{>ty72l)$Xn|vLG#r1RMPNY!^6^n zt?G><B-I_(LG8>Vs-Q607LRUFL-BYtt_C9UP@uU-O@xx;cC`p<<|&rbn}~4dt6R6S z+3Rs@k@XU+lMH=CW4JtlU}qt<BOIwJU==N2m+3W*q^eY7XuMg1Q5A|OiJfFLzuJ{N z$kt(*%`_Qllxh8rsTos)&woLY*IOha!0CgzA;gqcD-SePhG2v3n9390E^mnlRB7%a z$<$VH%6RjIXvB;&G7Abr-7$odqX>sRY)ByvC5UbHb)mB;3?@gjt|%y@*;D0fK-%I! z6F`Hhvm}9&3?w%7KzKBp8u?{PB)pfg*fMo$L0JbTJ_P^kX^+NZZ3qJzZpMPx5sC*O z8t`CrrJ?Rn5b+Pawc|~{1qCeTY1*usT0aoe4>PZ)K+Mwt9&gf2nPBSzIr)(60#*T& z5a+O%hMwYNRL<F~K40BR3R0NHOIm<S;~Xes3(7!^o{5B@<dGUdzjZ9g3C)%oJ*j}3 zmW!HXCr_~!(2*}XUeSggU93mo>XSvWKsfHJMGI>oA4@L`^=yd7o4xhrOk#n|Wn|iM zCXfQ_2}DMNoXoT_sZsg9gnta`WSn|G2}@I34kD(Nr?#ho#0OuZzH>eCF66XecR*ba zk-P&zH<Q6OvqUxx(!~4Hf@aYp!+YqtmPIIK;&^#`pqsB;Z2oURj7@X9XrfFJ6J;tR zkto^^^V7RBlFJYemCCo2d1{SgD7C~FlvqlX(KuvE9}Pi>BCP+RL_vhVC{$6g-0xeu zOfASS$S0ksp`HcJ#e7JxOh$+1f>0@xlu$Am#atX9MXeC3i#HNs*(NU1vE)+jz>f?Q zLV*Y<E5!*!^yT8jd$nTe`N>-t52b5jp7PWZph<g^5N>rdF@-d4h(a{3FG45z*SoQh z6sLp|#;DW@tn(yms393K+03g3VKc=Z+GJ}XvQE4MO*4#n?Ud`rq~_cs52-4I=;=^~ z-k<5K9TPHRb}`sOJS?`yJl%+n5&@*AMQnICCYw?=*;o(m$;wre;7uz5%rF|J$evRb z)T`XQJ2R|ClM9=j(wrs{)3<=d^kwmU%S}A?!5~Ug9ZifsRg(eDcl<jEDX~A}ig{QY zjH1@|sH<VLMBsINpJ56M){)L_RtwRz=zd2Mhn<;Ejbezlx@aA$*#fl1+Zfm#tf|=o zz@Ql<`jt}hN+~Qw8`=WgI%95#G!r5jU(5!gDb4{YVvoc`CJACvq}2W<uKZ=v{qUN` z?no{Bg$0`FLvLwhMv&%k97YkYW2dXGhM6-}U}jqi8NO0t3m?$@gAK5#U<&|JXF(B* z^&dzOn~>c{?TEtY77ipP_&o&hP<cZ<(2<Bm@$Cls#zEn#K+IQPsEQ96l<2>apnWJo zSW|huYBc6!LC(AC8q~U#4Q~3!Lu!|?5hbTs*`10hSU!ELz^&@cX6tojWcUU~X)`{_ z5|8%q<{?455T9%DPVRdHMUx{|u0w_%)!uGGD!%T;jv)B|k<Nx*@3_{ANlBgWl_~+6 zrHR+XUvkd;U}`({$@2AqW(-cKqSWd_TWoAp3-f7vjw}hSoq;%#tdGW%1}((vTkc(5 z`#H6;uC5aQ*7~NOeU4-n=1in}gE*|v_!f-e9j0o8nS{J*-X};cRT(A^T0V?()I{dx zNl}zGfm?qu$Z9_!wM1ff;e)x+HC0JoFNUEHOr0PHa`AKuKN&Ws$K!xvO9K#XDW-(s ziP^x@B&lV54#Uoe$4z6uJFq_7<?)o_K7v)1na24(rD+hQc=~-^H)!P4Cq3n=%D4L> z(N=6VuuZ?(l|j?ocD~LyBdsia5@&NpOFR@htodb{KH<ZsDsp?66x&UM`FtWXOG<#Z zko>GCj?Cg?9SK7gBBW7KO_62X$4QyvytV6AvR%6A*djY}i6wo`mXg<`#FZl_1iK9Q zz7PJVDJ0FD3kMW3=eCF1gR!2JW!QtIUZ+A$6IUD5ps9V0&Abp!sZrlU8Bmylq&jQd z4}2HQdK2-T(5AUecE*W(7_TT8jlpzX2$NrzSX}g<*J}XY+H=Dw$cQy`vev<{#jY!x zq_KO_9fnkD+~P3SnYPLaNqw5utf>kcG&(X!7-m&L^Rv)T4^tP7^<s|P_GnnA*96j5 zN`p>$m`)6*&+ZNN+8V;9C29CB40Qy^>4)s#wOm=AmR@;Z%=>%^VDB=mmXHaVKA4H( zaE6cO2<>^Yu_6^bz6)4R`T+Y3EHhZ7EN&ClP^55ND7*m@Y|qu_Z!gredGxHD7gJ_F zwnk)H!mT%QDNDzO_Our<@Muba$SjIjFsgCpkgJWS1nZ`Xoxl#bp(bL1V2C+LxK(oU zDiJOd5HR8OS6`ahXftI=VCq9%GfP;%*rX_WUj~(>Q7hHCnu1#VrOr^i$84$7Pd4SN zJKJN-RidapaG~X<yWX(J^_WymR(^)$(ZPgJW9z0e6?g(rnlvXO>1D%gu{2^e1}o$G zRggX?y&;Z|CgTg8SZr5guh>&a<U;G>ZnGNN_&HCuGP50^Qn62MNt
LQUj`@+;e z=4o(|S&=@H<SgUS`R;k^Jf7N~Rm_(gpV7t=$y{cq=366_6K$)XJ9bV?H!1L>dRpg7 zCM@K7JxTV0$HTf-e36w*+umaK!EBhx$%D<}gRREh6}NA75q&YXpaY)7UT?~SPUn1) zi8p0iS~<7U%xG!@Idvb25czIwLX$*F!(7b%)1<lxI{=1U@Ip1%cA?sWFI}g^OsGr5 zfzw}aX>*wEd5p(2C9o4TlM{Iowhh|hfy1O}hXS(!Xq${Do+e@%8EnF?yb~NE#TmD$ z_!~<u!=g<xA&z=5xB1kU;-&A+boxekQzp$L*+d2pnuI_0HEeuo9lqGAZZj+r#nzPE z(*l(GSA7z5H+fxk`$D?UoYTA@zJAU=dOq$J7>e^0EZY!Hgw}Qh;yr7qBDd-(N?=DW z5QjTpBFQ$!*yoe6u~w*#_kH!W4K?xAWvGCrJ+;a3TE?y7i7zqSij;Xj*&qwb>GlJ< z=;_rlMP1RQ)``PZ%gE+RC#kgA?TC!4Q&m(Ai!u)RkYO}66>_IS6NPeZF)Ol~!E&m8 z3Hr8@s%zS?n}*%ziHsrogf?wWTkTY@t}jr1;nb*|)EK6vd_wx1T=b5BE#5=hm^fBN zBGxjG7dj0XJ9Wllnig&*3ruV=@|2L)%LQ+t!=)cQn9|&#H`7ebjccN6PYKqN3p-;L zdQXFI9D@$CoiQJc&JMXEn|E}Kdq4%)4@!g&w+-}u4aLaehGOL19*UaT%HvM71>$rB zDJjmi=*3gxNcCX7#|aAq3zBiw;B5jGkgWhF+2TE#<XR5bvMuj=%Vx3;O~$eEeX(6o z$EPMZW7khX770(zd#Dm8b-_sm9vpBEbVe}K!O4S;V1<L>5cxD2kL-o(AlrrOD^>hY z3(&iwRnhiHJM%R$3lJ%j;}Nuze%?J2n;CW71SJ|xZ+ag%%t{zSJ4zkOXk^vUnN_QI z<&?|xDOcQrGEH)V$3u&MGdzOevdE6Mr5ya&bgQ@5=nQ%Vso7mBr*x*9dskArbhqS* z90OMn=)fosP17)##2ldWBBuc`H3OQ3<;b9m>6$X*X<aOVT$7fHadYN1CVj6dqbB;E zC?lBfGmJk&GiVA@YcL2dY!7s_(%JWw6j*~??r;`~&a0bbvT2a_r>b~q8wu06piR7& zr*2UmNBDAcxobUK0zI@yl9Mu7^_V3pBNthCe`#w#`kG40&g7QuDq4N5-Q+Vhy``a8 zsqOJcJ6ctW$3Qn=to88Vg4r<6?3P9y>4?>wBUx@uXI4m*X2Nbc`*$h&XM%3yLS`{a z$~eNuLO&#u&DfI^uCCnLSf4BlNBK@=kq<o&wKRQy)N<UGCLp<oD1byDnT#XSO^^mJ zm)-T7g4_^m9Ji*(5L_)z$v@Myz>OorSg`QBZ;~@KqhvSiGBCeF8iVjXL=(32v*oG9 z*emoOiz6b;8*No6k$~^x(qeck!rdlagP+KXLr1D7=n|W0OK;+nnQnndoe3?bVL$HH zom?_3ci6e#rjgHNBY*H!4e9Q`(o=%@vX({3Sr<-(wa^g7UG&SO2$pc(@j=O<eNwG` zI-*H6fjA)HmT(AB2})^Cp7a?y2O^eN2wN5><Hd|gr|Hu~K-rj9bFFYRPY<0mvE|#^ z%RxFRO-~S#)DFjyOw=@|XtT4}fzfs^#u3uQjzxx$7NStSz&&1Tr?2R#5iWVaYERP~ zHh~LThZnO7AsYC&*aRNJ6h&NQ={qc(|Ey;^(^fCsVkWoMTj-;nv)bbYUQvAws~|_p zL*IzgMM2ma$hiu{X3%9V)`9m(lv&%cf%Y)#LW$0H+Dllr4986nX)N=WrCE5_2>pQQ z-K(*A$2{ge9!~+5Gi=R56AX8>`hsvs_XJ@RRFm;QIGOMTz4Zb7<1JTLsc`t901$QU zMt7$C0uLIa9Hv>Ef5Vi>S2d$tQ}F-6?xJaL<ZzpfY1<wdw;NgP3J=_y5!Vk5h)qo% zRf^Vsra*}^OTjO7;`HOV^RRV@2NK-Le5TDrmL56<Sa}N5J#+-x=)Zv-AzFnf^aG?V z%g_&q_XH;cWAr>&@wFHbv?d6{ndZNj5*&>d1FMB9ed?62Hz^rmy3A~PS9P{sp}lC@ zOPa#JO^NLHZmSFJthToENPqDpg<>?#z-cbYI?ovCy3^i%_-r0`b4Z2?Nge*-@w28u z!F%so%%lQJL3WySArJF!#pfR(*)?lMKTH+0YGzn7Q&PI-H%QYB35Q(Cn1=S9x-lk0 zdl{#INe$}vVI57`lzh$RY0n@;O-#VE_T4iSG^KfCx~99s?CDxLm`cUS@Di!kC>Ylo zZ8{qw=asZsB~_jk39yOKI#|L3#rk9^hV3CU+sPrNHuu0|ng{zs@LyJtPP4DA)&k0P z(dq~#j;&B;vkbL@c|~9X0NHC4B|p*Ao(!x9OvX8ElXp-BL;0;8o%!oK!;$7sLQrPE z+5(9-B_G5gCx^*6f6|4}x8Z1q;fIQ6I654l4B{>pNh<lw127-A`K?j>#7PwV%g*rS z$D=G%Wqznl1S@W9Mj`SSN{7{#FLnqzNHRJr46!s2^OTn%?=J`<BNav@pj<{SwJ8dT zCaHG*SjmTVPsxY>7{y!AN41{%{fWpr6MrJSxAwhT`Q2L?cUsnvBX0!6=T?-r#>S#D z|EP#_F5#IXAa}M%pKHpG&uu8P@h9`k@8?RWEaVxeUP>eL3$#)J9F?u*KLtN<$?xsX zMci%uCCJlI2-~mVgV`GW@_W1z%7P{RvK|Q$9$a}xmtTIjSHgZ#6VXp)Ncsg@X~vCw zH^Ry9`%1V&1S^;I%lz{FJ4F7alo?m=RYoY=k@8a>bN+7Ns7+?zkFNf&8X-QjX1It} z{guEEeSY~}VF?FK8Jr@sgd0uy<@bjrl<8!hl79L73R8ahT~`T{m&ueIn#<d6$}hhk zCgD-W?5wZ!sOv?3$q(|o#}YnmBG{$RjQd+n`Q`VKCEP0u7WqugseIRzUw%hf!iYm; z6u?A|@&i+T`MqTcyCma@{O0-}1)i#q$>evLhf4WKGq<<7{$C(3eY-&Bm)~z575UBS z&A(qlUaCpvm)}D^G{O9@nDWc-IVxqG{vlKQo8RXz$WLQO)-S&sJtRIHS|Rewc9ZnW za=v1!Uw&WObuO=ezo~wiU&2GC{MvV@D|r6y!{oOi8Kso;_loZ*_b%o6Yvlu^q07bo zP5m<y$%q!2On%pT(981=r;@Tem+3cshKf?UO?a7Ke&0hr=B4sHggXX*vTm7%;5`rV zl*h>o;-Tp$tJ~B>EM;yrPwD&!&v-IG8UAFu(_Bgy%@0=fFAVbhH#V|l+CS#{{~t`Z Bfw%ww diff --git a/solo12InvKin.py b/solo12InvKin.py index 89f6eeea..1cb2fcf7 100644 --- a/solo12InvKin.py +++ b/solo12InvKin.py @@ -99,7 +99,7 @@ class Solo12InvKin: # FEET Jfeet = [] afeet = [] - pfeet_err = [] + self.pfeet_err = [] vfeet_ref = [] pin.forwardKinematics(self.rmodel, self.rdata, q, dq, np.zeros(self.rmodel.nv)) pin.updateFramePlacements(self.rmodel, self.rdata) @@ -125,7 +125,7 @@ class Solo12InvKin: Jfeet.append(J1) afeet.append(acc1) - pfeet_err.append(e1) + self.pfeet_err.append(e1) vfeet_ref.append(vref) # BASE POSITION @@ -170,7 +170,7 @@ class Solo12InvKin: J = np.vstack([Jbasis, Jwbasis]+Jfeet) acc = np.concatenate([accbasis, accwbasis]+afeet) - x_err = np.concatenate([e_basispos, e_basisrot]+pfeet_err) + x_err = np.concatenate([e_basispos, e_basisrot]+self.pfeet_err) dx_ref = np.concatenate([self.base_linearvelocity_ref, self.base_angularvelocity_ref]+vfeet_ref) diff --git a/utils_mpc.py b/utils_mpc.py index 91d7aba1..b4bc00ed 100644 --- a/utils_mpc.py +++ b/utils_mpc.py @@ -1,66 +1,22 @@ import math import numpy as np -import robots_loader # Gepetto viewer +from example_robot_data import load import Joystick -import FootstepPlanner import Logger -import Interface import Estimator - -import pybullet as pyb # Pybullet server -import pybullet_data import pinocchio as pin -import time as time -import sys - -########################## -# ROTATION MATRIX TO RPY # -########################## - -# Taken from https://www.learnopencv.com/rotation-matrix-to-euler-angles/ - -# Checks if a matrix is a valid rotation matrix. - - -def isRotationMatrix(R): - Rt = np.transpose(R) - shouldBeIdentity = np.dot(Rt, R) - Id = np.identity(3, dtype=R.dtype) - n = np.linalg.norm(Id - shouldBeIdentity) - return n < 1e-6 - - -# Calculates rotation matrix to euler angles -# The result is the same as MATLAB except the order -# of the euler angles ( x and z are swapped ). -def rotationMatrixToEulerAngles(R): - - assert(isRotationMatrix(R)) - - sy = math.sqrt(R[0, 0] * R[0, 0] + R[1, 0] * R[1, 0]) - - singular = sy < 1e-6 - if not singular: - x = math.atan2(R[2, 1], R[2, 2]) - y = math.atan2(-R[2, 0], sy) - z = math.atan2(R[1, 0], R[0, 0]) - else: - x = math.atan2(-R[1, 2], R[1, 1]) - y = math.atan2(-R[2, 0], sy) - z = 0 - - return np.array([x, y, z]) - -########################################################### -# Roll Pitch Yaw (3 x 1) to Quaternion function (4 x 1) Â # -########################################################### +###################################### +# RPY / Quaternion / Rotation matrix # +###################################### def getQuaternion(rpy): + """Roll Pitch Yaw (3 x 1) to Quaternion (4 x 1)""" + c = np.cos(rpy*0.5) s = np.sin(rpy*0.5) cy = c[2, 0] @@ -77,12 +33,10 @@ def getQuaternion(rpy): return np.array([[x, y, z, w]]).transpose() -################################# -# Quarternion to Roll Pitch Yaw # -################################# - def quaternionToRPY(quat): + """Quaternion (4 x 0) to Roll Pitch Yaw (3 x 1)""" + qx = quat[0] qy = quat[1] qz = quat[2] @@ -113,6 +67,22 @@ def quaternionToRPY(quat): return np.array([[rotateX], [rotateY], [rotateZ]]) +def EulerToQuaternion(roll_pitch_yaw): + """Roll Pitch Yaw to Quaternion""" + + roll, pitch, yaw = roll_pitch_yaw + sr = math.sin(roll/2.) + cr = math.cos(roll/2.) + sp = math.sin(pitch/2.) + cp = math.cos(pitch/2.) + sy = math.sin(yaw/2.) + cy = math.cos(yaw/2.) + qx = sr * cp * cy - cr * sp * sy + qy = cr * sp * cy + sr * cp * sy + qz = cr * cp * sy - sr * sp * cy + qw = cr * cp * cy + sr * sp * sy + return [qx, qy, qz, qw] + ################## # Initialisation # ################## @@ -125,30 +95,26 @@ def init_viewer(enable_viewer): enable_viewer (bool): if the Gepetto viewer is enabled or not """ - # loadSolo(False) to load solo12 - # loadSolo(True) to load solo8 - solo = robots_loader.loadSolo(False) + # Load robot model and data + solo = load('solo12') + # Initialisation of the Gepetto viewer if enable_viewer: solo.initDisplay(loadModel=True) if ('viewer' in solo.viz.__dict__): solo.viewer.gui.addFloor('world/floor') solo.viewer.gui.setRefreshIsSynchronous(False) - """offset = np.zeros((19, 1)) - offset[5, 0] = 0.7071067811865475 - offset[6, 0] = 0.7071067811865475 - 1.0 - temp = solo.q0 + offset""" solo.display(solo.q0) - pin.centerOfMass(solo.model, solo.data, solo.q0, np.zeros((18, 1))) - pin.updateFramePlacements(solo.model, solo.data) - pin.crba(solo.model, solo.data, solo.q0) + # Initialisation of model quantities + pin.centerOfMass(solo.model, solo.data, solo.q0, np.zeros((18, 1))) + pin.updateFramePlacements(solo.model, solo.data) + pin.crba(solo.model, solo.data, solo.q0) return solo -def init_objects(dt_tsid, dt_mpc, k_max_loop, k_mpc, n_periods, T_gait, type_MPC, on_solo8, - predefined): +def init_objects(dt_tsid, dt_mpc, k_max_loop, k_mpc, n_periods, T_gait, type_MPC, predefined): """Create several objects that are used in the control loop Args: @@ -159,26 +125,19 @@ def init_objects(dt_tsid, dt_mpc, k_max_loop, k_mpc, n_periods, T_gait, type_MPC n_periods (int): number of gait periods in the prediction horizon T_gait (float): duration of one gait period type_MPC (bool): which MPC you want to use (PA's or Thomas') - on_solo8 (bool): whether we are working on solo8 or not predefined (bool): if we are using a predefined reference velocity (True) or a joystick (False) """ # Create Joystick object joystick = Joystick.Joystick(predefined) - # Create footstep planner object - fstep_planner = FootstepPlanner.FootstepPlanner(dt_mpc, n_periods, T_gait, on_solo8) - # Create logger object logger = Logger.Logger(k_max_loop, dt_tsid, dt_mpc, k_mpc, n_periods, T_gait, type_MPC) - # Create Interface object - interface = Interface.Interface() - # Create Estimator object estimator = Estimator.Estimator(dt_tsid, k_max_loop) - return joystick, fstep_planner, logger, interface, estimator + return joystick, logger, estimator def display_all(solo, k, sequencer, fstep_planner, ftraj_gen, mpc): @@ -217,641 +176,3 @@ def getSkew(a): a -- the column vector """ return np.array([[0, -a[2], a[1]], [a[2], 0, -a[0]], [-a[1], a[0], 0]], dtype=a.dtype) - -######################################################################## -# PyBullet # -######################################################################## - - -class pybullet_simulator: - """Wrapper for the PyBullet simulator to initialize the simulation, interact with it - and use various utility functions - - Args: - envID (int): identifier of the current environment to be able to handle different scenarios - use_flat_plane (bool): to use either a flat ground or a rough ground - enable_pyb_GUI (bool): to display PyBullet GUI or not - dt (float): time step of the inverse dynamics - """ - - def __init__(self, q_init, envID, use_flat_plane, enable_pyb_GUI, dt=0.001): - - self.applied_force = np.zeros(3) - - # Start the client for PyBullet - if enable_pyb_GUI: - pyb.connect(pyb.GUI) - else: - pyb.connect(pyb.DIRECT) - # p.GUI for graphical version - # p.DIRECT for non-graphical version - - # Load horizontal plane - pyb.setAdditionalSearchPath(pybullet_data.getDataPath()) - - # Either use a flat ground or a rough terrain - if use_flat_plane: - self.planeId = pyb.loadURDF("plane.urdf") # Flat plane - self.planeIdbis = pyb.loadURDF("plane.urdf") # Flat plane - pyb.resetBasePositionAndOrientation(self.planeIdbis, [20.0, 0, 0], [0, 0, 0, 1]) - else: - import random - random.seed(41) - # p.configureDebugVisualizer(p.COV_ENABLE_RENDERING,0) - heightPerturbationRange = 0.05 - - numHeightfieldRows = 256*2 - numHeightfieldColumns = 256*2 - heightfieldData = [0]*numHeightfieldRows*numHeightfieldColumns - height_prev = 0.0 - for j in range(int(numHeightfieldColumns/2)): - for i in range(int(numHeightfieldRows/2)): - # uniform distribution - height = random.uniform(0, heightPerturbationRange) - # height = 0.25*np.sin(2*np.pi*(i-128)/46) # sinus pattern - heightfieldData[2*i+2*j * numHeightfieldRows] = (height + height_prev) * 0.5 - heightfieldData[2*i+1+2*j*numHeightfieldRows] = height - heightfieldData[2*i+(2*j+1) * numHeightfieldRows] = (height + height_prev) * 0.5 - heightfieldData[2*i+1+(2*j+1)*numHeightfieldRows] = height - height_prev = height - - # Create the collision shape based on the height field - terrainShape = pyb.createCollisionShape(shapeType=pyb.GEOM_HEIGHTFIELD, meshScale=[.05, .05, 1], - heightfieldTextureScaling=(numHeightfieldRows-1)/2, - heightfieldData=heightfieldData, - numHeightfieldRows=numHeightfieldRows, - numHeightfieldColumns=numHeightfieldColumns) - self.planeId = pyb.createMultiBody(0, terrainShape) - pyb.resetBasePositionAndOrientation(self.planeId, [0, 0, 0], [0, 0, 0, 1]) - pyb.changeVisualShape(self.planeId, -1, rgbaColor=[1, 1, 1, 1]) - - if envID == 1: - - # Add stairs with platform and bridge - self.stairsId = pyb.loadURDF("../../../../../git/paleziart/solopython/mpctsid/bauzil_stairs.urdf") # , - """basePosition=[-1.25, 3.5, -0.1], - baseOrientation=pyb.getQuaternionFromEuler([0.0, 0.0, 3.1415]))""" - pyb.changeDynamics(self.stairsId, -1, lateralFriction=1.0) - - # Create the red steps to act as small perturbations - mesh_scale = [1.0, 0.1, 0.02] - visualShapeId = pyb.createVisualShape(shapeType=pyb.GEOM_MESH, - fileName="cube.obj", - halfExtents=[0.5, 0.5, 0.1], - rgbaColor=[1.0, 0.0, 0.0, 1.0], - specularColor=[0.4, .4, 0], - visualFramePosition=[0.0, 0.0, 0.0], - meshScale=mesh_scale) - - collisionShapeId = pyb.createCollisionShape(shapeType=pyb.GEOM_MESH, - fileName="cube.obj", - collisionFramePosition=[0.0, 0.0, 0.0], - meshScale=mesh_scale) - for i in range(4): - tmpId = pyb.createMultiBody(baseMass=0.0, - baseInertialFramePosition=[0, 0, 0], - baseCollisionShapeIndex=collisionShapeId, - baseVisualShapeIndex=visualShapeId, - basePosition=[0.0, 0.5+0.2*i, 0.01], - useMaximalCoordinates=True) - pyb.changeDynamics(tmpId, -1, lateralFriction=1.0) - - tmpId = pyb.createMultiBody(baseMass=0.0, - baseInertialFramePosition=[0, 0, 0], - baseCollisionShapeIndex=collisionShapeId, - baseVisualShapeIndex=visualShapeId, - basePosition=[0.5, 0.5+0.2*4, 0.01], - useMaximalCoordinates=True) - pyb.changeDynamics(tmpId, -1, lateralFriction=1.0) - - tmpId = pyb.createMultiBody(baseMass=0.0, - baseInertialFramePosition=[0, 0, 0], - baseCollisionShapeIndex=collisionShapeId, - baseVisualShapeIndex=visualShapeId, - basePosition=[0.5, 0.5+0.2*5, 0.01], - useMaximalCoordinates=True) - pyb.changeDynamics(tmpId, -1, lateralFriction=1.0) - - # Create the green steps to act as bigger perturbations - mesh_scale = [0.2, 0.1, 0.01] - visualShapeId = pyb.createVisualShape(shapeType=pyb.GEOM_MESH, - fileName="cube.obj", - halfExtents=[0.5, 0.5, 0.1], - rgbaColor=[0.0, 1.0, 0.0, 1.0], - specularColor=[0.4, .4, 0], - visualFramePosition=[0.0, 0.0, 0.0], - meshScale=mesh_scale) - - collisionShapeId = pyb.createCollisionShape(shapeType=pyb.GEOM_MESH, - fileName="cube.obj", - collisionFramePosition=[0.0, 0.0, 0.0], - meshScale=mesh_scale) - - for i in range(3): - tmpId = pyb.createMultiBody(baseMass=0.0, - baseInertialFramePosition=[0, 0, 0], - baseCollisionShapeIndex=collisionShapeId, - baseVisualShapeIndex=visualShapeId, - basePosition=[0.15 * (-1)**i, 0.9+0.2*i, 0.025], - useMaximalCoordinates=True) - pyb.changeDynamics(tmpId, -1, lateralFriction=1.0) - - # Create sphere obstacles that will be thrown toward the quadruped - mesh_scale = [0.1, 0.1, 0.1] - visualShapeId = pyb.createVisualShape(shapeType=pyb.GEOM_MESH, - fileName="sphere_smooth.obj", - halfExtents=[0.5, 0.5, 0.1], - rgbaColor=[1.0, 0.0, 0.0, 1.0], - specularColor=[0.4, .4, 0], - visualFramePosition=[0.0, 0.0, 0.0], - meshScale=mesh_scale) - - collisionShapeId = pyb.createCollisionShape(shapeType=pyb.GEOM_MESH, - fileName="sphere_smooth.obj", - collisionFramePosition=[0.0, 0.0, 0.0], - meshScale=mesh_scale) - - self.sphereId1 = pyb.createMultiBody(baseMass=0.4, - baseInertialFramePosition=[0, 0, 0], - baseCollisionShapeIndex=collisionShapeId, - baseVisualShapeIndex=visualShapeId, - basePosition=[-0.6, 0.9, 0.1], - useMaximalCoordinates=True) - - self.sphereId2 = pyb.createMultiBody(baseMass=0.4, - baseInertialFramePosition=[0, 0, 0], - baseCollisionShapeIndex=collisionShapeId, - baseVisualShapeIndex=visualShapeId, - basePosition=[0.6, 1.1, 0.1], - useMaximalCoordinates=True) - - # Flag to launch the two spheres in the environment toward the robot - self.flag_sphere1 = True - self.flag_sphere2 = True - - # Create blue spheres without collision box for debug purpose - mesh_scale = [0.015, 0.015, 0.015] - visualShapeId = pyb.createVisualShape(shapeType=pyb.GEOM_MESH, - fileName="sphere_smooth.obj", - halfExtents=[0.5, 0.5, 0.1], - rgbaColor=[0.0, 0.0, 1.0, 1.0], - specularColor=[0.4, .4, 0], - visualFramePosition=[0.0, 0.0, 0.0], - meshScale=mesh_scale) - - self.ftps_Ids = np.zeros((4, 5), dtype=np.int) - for i in range(4): - for j in range(5): - self.ftps_Ids[i, j] = pyb.createMultiBody(baseMass=0.0, - baseInertialFramePosition=[0, 0, 0], - baseVisualShapeIndex=visualShapeId, - basePosition=[0.0, 0.0, -0.1], - useMaximalCoordinates=True) - - # Create green spheres without collision box for debug purpose - visualShapeId = pyb.createVisualShape(shapeType=pyb.GEOM_MESH, - fileName="sphere_smooth.obj", - halfExtents=[0.5, 0.5, 0.1], - rgbaColor=[0.0, 1.0, 0.0, 1.0], - specularColor=[0.4, .4, 0], - visualFramePosition=[0.0, 0.0, 0.0], - meshScale=mesh_scale) - self.ftps_Ids_deb = [0] * 4 - for i in range(4): - self.ftps_Ids_deb[i] = pyb.createMultiBody(baseMass=0.0, - baseInertialFramePosition=[0, 0, 0], - baseVisualShapeIndex=visualShapeId, - basePosition=[0.0, 0.0, -0.1], - useMaximalCoordinates=True) - - """cubeStartPos = [0.0, 0.45, 0.0] - cubeStartOrientation = pyb.getQuaternionFromEuler([0, 0, 0]) - self.cubeId = pyb.loadURDF("cube_small.urdf", - cubeStartPos, cubeStartOrientation) - pyb.changeDynamics(self.cubeId, -1, mass=0.5) - print("Mass of cube:", pyb.getDynamicsInfo(self.cubeId, -1)[0])""" - - # Set the gravity - pyb.setGravity(0, 0, -9.81) - - # Load Quadruped robot - robotStartPos = [0, 0, 0.235+0.0045] # +0.2] - robotStartOrientation = pyb.getQuaternionFromEuler([0.0, 0.0, 0.0]) # -np.pi/2 - pyb.setAdditionalSearchPath("/opt/openrobots/share/example-robot-data/robots/solo_description/robots") - self.robotId = pyb.loadURDF("solo12.urdf", robotStartPos, robotStartOrientation) - - # Disable default motor control for revolute joints - self.revoluteJointIndices = [0, 1, 2, 4, 5, 6, 8, 9, 10, 12, 13, 14] - pyb.setJointMotorControlArray(self.robotId, jointIndices=self.revoluteJointIndices, - controlMode=pyb.VELOCITY_CONTROL, - targetVelocities=[0.0 for m in self.revoluteJointIndices], - forces=[0.0 for m in self.revoluteJointIndices]) - - # Initialize the robot in a specific configuration - self.q_init = np.array([q_init]).transpose() - pyb.resetJointStatesMultiDof(self.robotId, self.revoluteJointIndices, self.q_init) # q0[7:]) - - # Enable torque control for revolute joints - jointTorques = [0.0 for m in self.revoluteJointIndices] - pyb.setJointMotorControlArray(self.robotId, self.revoluteJointIndices, - controlMode=pyb.TORQUE_CONTROL, forces=jointTorques) - - # Fix the base in the world frame - # pyb.createConstraint(self.robotId, -1, -1, -1, pyb.JOINT_FIXED, [0, 0, 0], [0, 0, 0], [0, 0, robotStartPos[2]]) - - # Set time step for the simulation - pyb.setTimeStep(dt) - - # Change camera position - pyb.resetDebugVisualizerCamera(cameraDistance=0.6, cameraYaw=45, cameraPitch=-39.9, - cameraTargetPosition=[0.0, 0.0, robotStartPos[2]-0.2]) - - def check_pyb_env(self, k, envID, velID, qmes12): - """Check the state of the robot to trigger events and update camera - - Args: - k (int): Number of inv dynamics iterations since the start of the simulation - envID (int): Identifier of the current environment to be able to handle different scenarios - velID (int): Identifier of the current velocity profile to be able to handle different scenarios - qmes12 (19x1 array): the position/orientation of the trunk and angular position of actuators - - """ - - # If spheres are loaded - if envID == 1: - # Check if the robot is in front of the first sphere to trigger it - if self.flag_sphere1 and (qmes12[1, 0] >= 0.9): - pyb.resetBaseVelocity(self.sphereId1, linearVelocity=[2.5, 0.0, 2.0]) - self.flag_sphere1 = False - - # Check if the robot is in front of the second sphere to trigger it - if self.flag_sphere2 and (qmes12[1, 0] >= 1.1): - pyb.resetBaseVelocity(self.sphereId2, linearVelocity=[-2.5, 0.0, 2.0]) - self.flag_sphere2 = False - - # Create the red steps to act as small perturbations - """if k == 10: - pyb.setAdditionalSearchPath(pybullet_data.getDataPath()) - - mesh_scale = [2.0, 2.0, 0.3] - visualShapeId = pyb.createVisualShape(shapeType=pyb.GEOM_MESH, - fileName="cube.obj", - halfExtents=[0.5, 0.5, 0.1], - rgbaColor=[0.0, 0.0, 1.0, 1.0], - specularColor=[0.4, .4, 0], - visualFramePosition=[0.0, 0.0, 0.0], - meshScale=mesh_scale) - - collisionShapeId = pyb.createCollisionShape(shapeType=pyb.GEOM_MESH, - fileName="cube.obj", - collisionFramePosition=[0.0, 0.0, 0.0], - meshScale=mesh_scale) - - tmpId = pyb.createMultiBody(baseMass=0.0, - baseInertialFramePosition=[0, 0, 0], - baseCollisionShapeIndex=collisionShapeId, - baseVisualShapeIndex=visualShapeId, - basePosition=[0.0, 0.0, 0.15], - useMaximalCoordinates=True) - pyb.changeDynamics(tmpId, -1, lateralFriction=1.0) - - pyb.resetBasePositionAndOrientation(self.robotId, [0, 0, 0.5], [0, 0, 0, 1])""" - if k == 10: - pyb.setAdditionalSearchPath(pybullet_data.getDataPath()) - - mesh_scale = [0.1, 0.1, 0.04] - visualShapeId = pyb.createVisualShape(shapeType=pyb.GEOM_MESH, - fileName="cube.obj", - halfExtents=[0.5, 0.5, 0.1], - rgbaColor=[0.0, 0.0, 1.0, 1.0], - specularColor=[0.4, .4, 0], - visualFramePosition=[0.0, 0.0, 0.0], - meshScale=mesh_scale) - - collisionShapeId = pyb.createCollisionShape(shapeType=pyb.GEOM_MESH, - fileName="cube.obj", - collisionFramePosition=[0.0, 0.0, 0.0], - meshScale=mesh_scale) - - tmpId = pyb.createMultiBody(baseMass=0.0, - baseInertialFramePosition=[0, 0, 0], - baseCollisionShapeIndex=collisionShapeId, - baseVisualShapeIndex=visualShapeId, - basePosition=[0.19, 0.15005, 0.02], - useMaximalCoordinates=True) - pyb.changeDynamics(tmpId, -1, lateralFriction=1.0) - pyb.resetBasePositionAndOrientation(self.robotId, [0, 0, 0.25], [0, 0, 0, 1]) - - # Apply perturbations by directly applying external forces on the robot trunk - if velID == 4: - self.apply_external_force(k, 4250, 500, np.array([0.0, 0.0, -3.0]), np.zeros((3,))) - self.apply_external_force(k, 5250, 500, np.array([0.0, +3.0, 0.0]), np.zeros((3,))) - """if velID == 0: - self.apply_external_force(k, 1000, 1000, np.array([0.0, 0.0, -6.0]), np.zeros((3,))) - self.apply_external_force(k, 2000, 1000, np.array([0.0, +12.0, 0.0]), np.zeros((3,)))""" - - # Update the PyBullet camera on the robot position to do as if it was attached to the robot - """pyb.resetDebugVisualizerCamera(cameraDistance=0.75, cameraYaw=+50, cameraPitch=-35, - cameraTargetPosition=[qmes12[0, 0], qmes12[1, 0] + 0.0, 0.0])""" - - # Get the orientation of the robot to change the orientation of the camera with the rotation of the robot - oMb_tmp = pin.SE3(pin.Quaternion(qmes12[3:7]), np.array([0.0, 0.0, 0.0])) - RPY = pin.rpy.matrixToRpy(oMb_tmp.rotation) - - # Update the PyBullet camera on the robot position to do as if it was attached to the robot - pyb.resetDebugVisualizerCamera(cameraDistance=0.6, cameraYaw=(0.0*RPY[2]*(180/3.1415)+45), cameraPitch=-39.9, - cameraTargetPosition=[qmes12[0, 0], qmes12[1, 0] + 0.0, 0.0]) # qmes12[2, 0]-0.15]) - - return 0 - - def retrieve_pyb_data(self): - """Retrieve the position and orientation of the base in world frame as well as its linear and angular velocities - """ - - # Retrieve data from the simulation - self.jointStates = pyb.getJointStates(self.robotId, self.revoluteJointIndices) # State of all joints - self.baseState = pyb.getBasePositionAndOrientation(self.robotId) # Position and orientation of the trunk - self.baseVel = pyb.getBaseVelocity(self.robotId) # Velocity of the trunk - - # Joints configuration and velocity vector for free-flyer + 12 actuators - self.qmes12 = np.vstack((np.array([self.baseState[0]]).T, np.array([self.baseState[1]]).T, - np.array([[state[0] for state in self.jointStates]]).T)) - self.vmes12 = np.vstack((np.array([self.baseVel[0]]).T, np.array([self.baseVel[1]]).T, - np.array([[state[1] for state in self.jointStates]]).T)) - - """robotVirtualOrientation = pyb.getQuaternionFromEuler([0, 0, np.pi / 4]) - self.qmes12[3:7, 0] = robotVirtualOrientation""" - - # Add uncertainty to feedback from PyBullet to mimic imperfect measurements - """tmp = np.array([pyb.getQuaternionFromEuler(pin.rpy.matrixToRpy( - pin.Quaternion(self.qmes12[3:7, 0:1]).toRotationMatrix()) - + np.random.normal(0, 0.03, (3,)))]) - self.qmes12[3:7, 0] = tmp[0, :] - self.vmes12[0:6, 0] += np.random.normal(0, 0.01, (6,))""" - - return 0 - - def apply_external_force(self, k, start, duration, F, M): - """Apply an external force/momentum to the robot - 4-th order polynomial: zero force and force velocity at start and end - (bell-like force trajectory) - - Args: - k (int): numero of the current iteration of the simulation - start (int): numero of the iteration for which the force should start to be applied - duration (int): number of iterations the force should last - F (3x array): components of the force in PyBullet world frame - M (3x array): components of the force momentum in PyBullet world frame - """ - - if ((k < start) or (k > (start+duration))): - return 0.0 - """if k == start: - print("Applying [", F[0], ", ", F[1], ", ", F[2], "]")""" - - ev = k - start - t1 = duration - A4 = 16 / (t1**4) - A3 = - 2 * t1 * A4 - A2 = t1**2 * A4 - alpha = A2*ev**2 + A3*ev**3 + A4*ev**4 - - self.applied_force[:] = alpha * F - - pyb.applyExternalForce(self.robotId, -1, alpha * F, alpha*M, pyb.LINK_FRAME) - - return 0.0 - - def get_to_default_position(self, qtarget): - """Controler that tries to get the robot back to a default angular positions - of its 12 actuators using polynomials to generate trajectories and a PD controller - to make the actuators follow them - - Args: - qtarget (12x1 array): the target position for the 12 actuators - """ - - qmes = np.zeros((12, 1)) - vmes = np.zeros((12, 1)) - - # Retrieve angular position and velocity of actuators - jointStates = pyb.getJointStates(self.robotId, self.revoluteJointIndices) - qmes[:, 0] = [state[0] for state in jointStates] - vmes[:, 0] = [state[1] for state in jointStates] - - # Create trajectory - dt_traj = 0.0020 - t1 = 4.0 # seconds - cpt = 0 - - # PD settings - P = 1.0 * 3.0 - D = 0.05 * np.array([[1.0, 0.3, 0.3, 1.0, 0.3, 0.3, - 1.0, 0.3, 0.3, 1.0, 0.3, 0.3]]).transpose() - - while True or np.max(np.abs(qtarget - qmes)) > 0.1: - - time_loop = time.time() - - # Retrieve angular position and velocity of actuators - jointStates = pyb.getJointStates(self.robotId, self.revoluteJointIndices) - qmes[:, 0] = [state[0] for state in jointStates] - vmes[:, 0] = [state[1] for state in jointStates] - - # Torque PD controller - if (cpt * dt_traj < t1): - ev = dt_traj * cpt - A3 = 2 * (qmes - qtarget) / t1**3 - A2 = (-3/2) * t1 * A3 - qdes = qmes + A2*(ev**2) + A3*(ev**3) - vdes = 2*A2*ev + 3*A3*(ev**2) - jointTorques = P * (qdes - qmes) + D * (vdes - vmes) - - # Saturation to limit the maximal torque - t_max = 2.5 - jointTorques[jointTorques > t_max] = t_max - jointTorques[jointTorques < -t_max] = -t_max - - # Set control torque for all joints - pyb.setJointMotorControlArray(self.robotId, self.revoluteJointIndices, - controlMode=pyb.TORQUE_CONTROL, forces=jointTorques) - - # Compute one step of simulation - pyb.stepSimulation() - - # Increment loop counter - cpt += 1 - - while (time.time() - time_loop) < dt_traj: - pass - - -class Hardware(): - - def __init__(self): - - self.is_timeout = False - - self.roll = 0.0 - self.pitch = 0.0 - self.yaw = 0.0 - - def IsTimeout(self): - - return self.is_timeout - - def Stop(self): - - return 0 - - def imu_data_attitude(self, i): - if i == 0: - return self.roll - elif i == 1: - return self.pitch - elif i == 2: - return self.yaw - - -class PyBulletSimulator(): - - def __init__(self): - - self.cpt = 0 - self.nb_motors = 12 - self.jointTorques = np.zeros(self.nb_motors) - self.revoluteJointIndices = [0, 1, 2, 4, 5, 6, 8, 9, 10, 12, 13, 14] - self.hardware = Hardware() - - # Measured data - self.q_mes = np.zeros(12) - self.v_mes = np.zeros(12) - self.torquesFromCurrentMeasurment = np.zeros(12) - self.baseAngularVelocity = np.zeros(3) - self.baseOrientation = np.zeros(4) - self.baseLinearAcceleration = np.zeros(3) - self.baseAccelerometer = np.zeros(3) - self.prev_b_baseVel = np.zeros(3) - - # PD+ quantities - self.P = 0.0 - self.D = 0.0 - self.q_des = np.zeros(12) - self.v_des = np.zeros(12) - self.tau_ff = np.zeros(12) - - def Init(self, calibrateEncoders=False, q_init=None, envID=0, use_flat_plane=True, enable_pyb_GUI=False, dt=0.002): - - # Initialisation of the PyBullet simulator - self.pyb_sim = pybullet_simulator(q_init, envID, use_flat_plane, enable_pyb_GUI, dt) - self.q_init = q_init - self.dt = dt - self.time_loop = time.time() - - return - - def UpdateMeasurment(self): - - # Position and velocity of actuators - jointStates = pyb.getJointStates(self.pyb_sim.robotId, self.revoluteJointIndices) # State of all joints - self.q_mes[:] = np.array([state[0] for state in jointStates]) - self.v_mes[:] = np.array([state[1] for state in jointStates]) - - # Measured torques - self.torquesFromCurrentMeasurment[:] = self.jointTorques[:].ravel() - - # Position and orientation of the trunk (PyBullet world frame) - self.baseState = pyb.getBasePositionAndOrientation(self.pyb_sim.robotId) - self.dummyHeight = np.array(self.baseState[0]) - self.dummyHeight[2] = 0.20 - self.dummyPos = np.array(self.baseState[0]) - - # Linear and angular velocity of the trunk (PyBullet world frame) - self.baseVel = pyb.getBaseVelocity(self.pyb_sim.robotId) - # print("baseVel: ", np.array([self.baseVel[0]])) - - # Orientation of the base (quaternion) - self.baseOrientation[:] = np.array(self.baseState[1]) - RPY = quaternionToRPY(self.baseOrientation) - self.hardware.roll = RPY[0] - self.hardware.pitch = RPY[1] - self.hardware.yaw = RPY[2] - self.rot_oMb = pin.Quaternion(np.array([self.baseState[1]]).transpose()).toRotationMatrix() - self.oMb = pin.SE3(self.rot_oMb, np.array([self.dummyHeight]).transpose()) - - # Angular velocities of the base - self.baseAngularVelocity[:] = (self.oMb.rotation.transpose() @ np.array([self.baseVel[1]]).transpose()).ravel() - - # Linear Acceleration of the base - self.b_baseVel = (self.oMb.rotation.transpose() @ np.array([self.baseVel[0]]).transpose()).ravel() - self.baseLinearAcceleration[:] = (self.b_baseVel.ravel() - self.prev_b_baseVel) / self.dt - self.prev_b_baseVel[:] = self.b_baseVel.ravel() - self.baseAccelerometer[:] = self.baseLinearAcceleration[:] + \ - (self.oMb.rotation.transpose() @ np.array([[0.0], [0.0], [-9.81]])).ravel() - - return - - def SetDesiredJointTorque(self, torques): - - # Save desired torques in a storage array - self.tau_ff = torques.copy() - - return - - def SetDesiredJointPDgains(self, P, D): - self.P = P - self.D = D - - def SetDesiredJointPosition(self, q_des): - self.q_des = q_des - - def SetDesiredJointVelocity(self, v_des): - self.v_des = v_des - - def SendCommand(self, WaitEndOfCycle=True): - - # Compute PD torques - tau_pd = self.P * (self.q_des - self.q_mes) + self.D * (self.v_des - self.v_mes) - - # Save desired torques in a storage array - self.jointTorques = tau_pd + self.tau_ff - - # print("FF+PD: ", self.jointTorques.ravel()) - - # Set control torque for all joints - pyb.setJointMotorControlArray(self.pyb_sim.robotId, self.pyb_sim.revoluteJointIndices, - controlMode=pyb.TORQUE_CONTROL, forces=self.jointTorques) - - # self.pyb_sim.apply_external_force(self.cpt, 1000, 1000, np.array([0.0, +8.0, 0.0]), np.zeros((3,))) - # self.pyb_sim.apply_external_force(self.cpt, 4250, 500, np.array([+5.0, 0.0, 0.0]), np.zeros((3,))) - # self.pyb_sim.apply_external_force(self.cpt, 5250, 500, np.array([0.0, +5.0, 0.0]), np.zeros((3,))) - - # Compute one step of simulation - pyb.stepSimulation() - - # Wait to have simulation time = real time - if WaitEndOfCycle: - while (time.time() - self.time_loop) < self.dt: - pass - self.cpt += 1 - - self.time_loop = time.time() - - return - - def Print(self): - np.set_printoptions(precision=2) - # print(chr(27) + "[2J") - print("#######") - print("q_mes = ", self.q_mes) - print("v_mes = ", self.v_mes) - print("torques = ", self.torquesFromCurrentMeasurment) - print("orientation = ", self.baseOrientation) - print("lin acc = ", self.baseLinearAcceleration) - print("ang vel = ", self.baseAngularVelocity) - sys.stdout.flush() - - def Stop(self): - - # Disconnect the PyBullet server (also close the GUI) - pyb.disconnect() -- GitLab