From e1797f3d760b0efee28cf4fcf88201ebdd43187e Mon Sep 17 00:00:00 2001 From: URJala Date: Wed, 3 Jul 2024 11:03:34 +0000 Subject: [PATCH 01/11] Implement force mode arguments in urscript And in client library --- examples/force_mode_example.cpp | 28 +++- .../control/script_command_interface.h | 13 +- include/ur_client_library/ur/ur_driver.h | 111 ++++++++++++- resources/external_control.urscript | 60 +++---- src/control/script_command_interface.cpp | 11 +- src/ur/ur_driver.cpp | 150 ++++++++++++------ 6 files changed, 283 insertions(+), 90 deletions(-) diff --git a/examples/force_mode_example.cpp b/examples/force_mode_example.cpp index 4afe6fd14..409ff5903 100644 --- a/examples/force_mode_example.cpp +++ b/examples/force_mode_example.cpp @@ -130,7 +130,7 @@ int main(int argc, char* argv[]) std::unique_ptr tool_comm_setup; const bool HEADLESS = true; g_my_driver.reset(new UrDriver(robot_ip, SCRIPT_FILE, OUTPUT_RECIPE, INPUT_RECIPE, &handleRobotProgramState, HEADLESS, - std::move(tool_comm_setup), CALIBRATION_CHECKSUM)); + std::move(tool_comm_setup))); // Once RTDE communication is started, we have to make sure to read from the interface buffer, as // otherwise we will get pipeline overflows. Therefore, do this directly before starting your main @@ -141,15 +141,27 @@ int main(int argc, char* argv[]) std::chrono::duration timeout(second_to_run); auto stopwatch_last = std::chrono::steady_clock::now(); auto stopwatch_now = stopwatch_last; - g_my_driver->writeKeepalive(); + // Make sure that external control script is running + for (int i = 0; i < 100; i++) + { + g_my_driver->writeKeepalive(); + g_my_driver->getDataPackage(); + } // Task frame at the robot's base with limits being large enough to cover the whole workspace // Compliance in z axis and rotation around z axis - g_my_driver->startForceMode({ 0, 0, 0, 0, 0, 0 }, // Task frame at the robot's base - { 0, 0, 1, 0, 0, 1 }, // Compliance in z axis and rotation around z axis - { 0, 0, 0, 0, 0, 0 }, // do not apply any active wrench - 2, // do not transform the force frame at all - { 0.1, 0.1, 1.5, 3.14, 3.14, 0.5 }); // limits. See ScriptManual for - // details. + + bool success = g_my_driver->startForceMode({ 0, 0, 0, 0, 0, 0 }, // Task frame at the robot's base + { 0, 0, 1, 0, 0, 1 }, // Compliance in z axis and rotation around z axis + { 0, 0, 0, 0, 0, 0 }, // do not apply any active wrench + 2, // do not transform the force frame at all + { 0.1, 0.1, 1.5, 3.14, 3.14, 0.5 } // limits. See ScriptManual + , + 0.8, 0.8); // for details. + if (!success) + { + URCL_LOG_ERROR("Failed to start force mode."); + return 1; + } while (true) { diff --git a/include/ur_client_library/control/script_command_interface.h b/include/ur_client_library/control/script_command_interface.h index 2a5befde0..07c17255e 100644 --- a/include/ur_client_library/control/script_command_interface.h +++ b/include/ur_client_library/control/script_command_interface.h @@ -109,10 +109,19 @@ class ScriptCommandInterface : public ReverseInterface * axis. For non-compliant axes, these values are the maximum allowed deviation along/about an axis between the actual * tcp position and the one set by the program * + * \param damping_factor (Double) Sets the damping parameter in force mode. In range [0,1], default value is 0.025 + * A value of 1 is full damping, so the robot will decelerate quickly if no force is present. A value of 0 + * is no damping, here the robot will maintain the speed. + * + * \param gain_scaling_factor (Double) Scales the gain in force mode. scaling parameter is in range [0,2], default + * is 0.5. A value larger than 1 can make force mode unstable, e.g. in case of collisions or pushing against hard + * surfaces. + * * \returns True, if the write was performed successfully, false otherwise. */ bool startForceMode(const vector6d_t* task_frame, const vector6uint32_t* selection_vector, const vector6d_t* wrench, - const unsigned int type, const vector6d_t* limits); + const unsigned int type, const vector6d_t* limits, double damping_factor, + double gain_scaling_factor); /*! * \brief Stop force mode and put the robot into normal operation mode. @@ -178,7 +187,7 @@ class ScriptCommandInterface : public ReverseInterface }; bool client_connected_; - static const int MAX_MESSAGE_LENGTH = 26; + static const int MAX_MESSAGE_LENGTH = 28; std::function handle_tool_contact_result_; }; diff --git a/include/ur_client_library/ur/ur_driver.h b/include/ur_client_library/ur/ur_driver.h index c4970e3c7..e6cf099b5 100644 --- a/include/ur_client_library/ur/ur_driver.h +++ b/include/ur_client_library/ur/ur_driver.h @@ -92,16 +92,51 @@ class UrDriver * trajectory forwarding. * \param script_command_port Port used for forwarding script commands to the robot. The script commands will be * executed locally on the robot. - * \param force_mode_damping The damping parameter used when the robot is in force mode, range [0,1] - * \param force_mode_gain_scaling Scales the gain used when the robot is in force mode, range [0,2] (only e-series) */ UrDriver(const std::string& robot_ip, const std::string& script_file, const std::string& output_recipe_file, const std::string& input_recipe_file, std::function handle_program_state, bool headless_mode, std::unique_ptr tool_comm_setup, const uint32_t reverse_port = 50001, const uint32_t script_sender_port = 50002, int servoj_gain = 2000, double servoj_lookahead_time = 0.03, bool non_blocking_read = false, const std::string& reverse_ip = "", const uint32_t trajectory_port = 50003, - const uint32_t script_command_port = 50004, double force_mode_damping = 0.025, - double force_mode_gain_scaling = 0.5); + const uint32_t script_command_port = 50004); + + /*! + * \brief Constructs a new UrDriver object. + * \param robot_ip IP-address under which the robot is reachable. + * \param script_file URScript file that should be sent to the robot. + * \param output_recipe_file Filename where the output recipe is stored in. + * \param input_recipe_file Filename where the input recipe is stored in. + * \param handle_program_state Function handle to a callback on program state changes. For this to + * work, the URScript program will have to send keepalive signals to the \p reverse_port. I no + * keepalive signal can be read, program state will be false. + * \param headless_mode Parameter to control if the driver should be started in headless mode. + * \param tool_comm_setup Configuration for using the tool communication. + * calibration reported by the robot. + * \param reverse_port Port that will be opened by the driver to allow direct communication between the driver + * and the robot controller. + * \param script_sender_port The driver will offer an interface to receive the program's URScript on this port. If + * the robot cannot connect to this port, `External Control` will stop immediately. + * \param non_blocking_read Enable non-blocking mode for read (useful when used with combined_robot_hw) + * \param servoj_gain Proportional gain for arm joints following target position, range [100,2000] + * \param servoj_lookahead_time Time [S], range [0.03,0.2] smoothens the trajectory with this lookahead time + * \param reverse_ip IP address that the reverse_port will get bound to. If not specified, the IP + * address of the interface that is used for connecting to the robot's RTDE port will be used. + * \param trajectory_port Port used for sending trajectory points to the robot in case of + * trajectory forwarding. + * \param script_command_port Port used for forwarding script commands to the robot. The script commands will be + * executed locally on the robot. + * \param force_mode_damping The damping parameter used when the robot is in force mode, range [0,1] + * \param force_mode_gain_scaling Scales the gain used when the robot is in force mode, range [0,2] (only e-series) + */ + [[deprecated("Specifying the force mode damping factor and the force mode gain scaling factor at driver creation has " + "been deprecated. Force mode parameters should be specified with each activiation of force mode, and " + "can be set in the function call to start force mode.")]] + UrDriver(const std::string& robot_ip, const std::string& script_file, const std::string& output_recipe_file, + const std::string& input_recipe_file, std::function handle_program_state, bool headless_mode, + std::unique_ptr tool_comm_setup, const uint32_t reverse_port, + const uint32_t script_sender_port, int servoj_gain, double servoj_lookahead_time, bool non_blocking_read, + const std::string& reverse_ip, const uint32_t trajectory_port, const uint32_t script_command_port, + double force_mode_damping, double force_mode_gain_scaling = 0.5); /*! * \brief Constructs a new UrDriver object. @@ -134,7 +169,7 @@ class UrDriver */ UrDriver(const std::string& robot_ip, const std::string& script_file, const std::string& output_recipe_file, const std::string& input_recipe_file, std::function handle_program_state, bool headless_mode, - std::unique_ptr tool_comm_setup, const std::string& calibration_checksum = "", + std::unique_ptr tool_comm_setup, const std::string& calibration_checksum, const uint32_t reverse_port = 50001, const uint32_t script_sender_port = 50002, int servoj_gain = 2000, double servoj_lookahead_time = 0.03, bool non_blocking_read = false, const std::string& reverse_ip = "", const uint32_t trajectory_port = 50003, const uint32_t script_command_port = 50004, @@ -321,6 +356,67 @@ class UrDriver */ bool setToolVoltage(const ToolVoltage voltage); + /*! + * \brief Start the robot to be controlled in force mode. + * + * \param task_frame A pose vector that defines the force frame relative to the base frame + * \param selection_vector A 6d vector of 0s and 1s. 1 means that the robot will be compliant in the corresponding + * axis of the task frame + * \param wrench 6d vector of forces/torques [x,y,z,rotX,rotY,rotZ] that the robot will apply to its environment. The + * robot adjusts its position along/about compliant axis in order to achieve the specified force/torque. Values have + * no effect for non-compliant axes. + * \param type An integer [1;3] specifying how the robot interprets the force frame. + * 1: The force frame is transformed in a way such that its y-axis is aligned with a vector pointing from the robot + * tcp towards the origin of the force frame + * 2: The force frame is not transformed + * 3: The force frame is transformed in a way such that its x-axis is the projection of the robot tcp velocity vector + * onto the x-y plane of the force frame + * \param limits (double) 6d vector. For compliant axes, these values are the maximum allowed tcp speed + * along/about the axis. For non-compliant axes, these values are the maximum allowed deviation along/about an axis + * between the actual tcp position and the one set by the program + * + * \param damping_factor (double) Sets the damping parameter in force mode. In range [0,1], default value is 0.025 + * A value of 1 is full damping, so the robot will decelerate quickly if no force is present. A value of 0 + * is no damping, here the robot will maintain the speed. + * + * \returns True, if the write was performed successfully, false otherwise. + */ + bool startForceMode(const vector6d_t& task_frame, const vector6uint32_t& selection_vector, const vector6d_t& wrench, + const unsigned int type, const vector6d_t& limits, double damping_factor); + + /*! + * \brief Start the robot to be controlled in force mode. + * + * \param task_frame A pose vector that defines the force frame relative to the base frame + * \param selection_vector A 6d vector of 0s and 1s. 1 means that the robot will be compliant in the corresponding + * axis of the task frame + * \param wrench 6d vector of forces/torques [x,y,z,rotX,rotY,rotZ] that the robot will apply to its environment. The + * robot adjusts its position along/about compliant axis in order to achieve the specified force/torque. Values have + * no effect for non-compliant axes. + * \param type An integer [1;3] specifying how the robot interprets the force frame. + * 1: The force frame is transformed in a way such that its y-axis is aligned with a vector pointing from the robot + * tcp towards the origin of the force frame + * 2: The force frame is not transformed + * 3: The force frame is transformed in a way such that its x-axis is the projection of the robot tcp velocity vector + * onto the x-y plane of the force frame + * \param limits (double) 6d vector. For compliant axes, these values are the maximum allowed tcp speed + * along/about the axis. For non-compliant axes, these values are the maximum allowed deviation along/about an axis + * between the actual tcp position and the one set by the program + * + * \param damping_factor (double) Sets the damping parameter in force mode. In range [0,1], default value is 0.025 + * A value of 1 is full damping, so the robot will decelerate quickly if no force is present. A value of 0 + * is no damping, here the robot will maintain the speed. + * + * \param gain_scaling_factor (double) Scales the gain in force mode. scaling parameter in range [0,2], default is + * 0.5. A value larger than 1 can make force mode unstable, e.g. in case of collisions or pushing against hard + * surfaces. + * + * \returns True, if the write was performed successfully, false otherwise. + */ + bool startForceMode(const vector6d_t& task_frame, const vector6uint32_t& selection_vector, const vector6d_t& wrench, + const unsigned int type, const vector6d_t& limits, double damping_factor, + double gain_scaling_factor); + /*! * \brief Start the robot to be controlled in force mode. * @@ -342,6 +438,8 @@ class UrDriver * * \returns True, if the write was performed successfully, false otherwise. */ + [[deprecated("Starting force mode without specifying the force mode damping factor and gain scale factor has been " + "deprecated. These values should be given with each function call.")]] bool startForceMode(const vector6d_t& task_frame, const vector6uint32_t& selection_vector, const vector6d_t& wrench, const unsigned int type, const vector6d_t& limits); @@ -500,6 +598,9 @@ class UrDriver std::unique_ptr> primary_stream_; std::unique_ptr> secondary_stream_; + double force_mode_gain_scale_factor_ = 0.5; + double force_mode_damping_factor_ = 0.025; + uint32_t servoj_gain_; double servoj_lookahead_time_; std::chrono::milliseconds step_time_; diff --git a/resources/external_control.urscript b/resources/external_control.urscript index d132651ce..2cf2e6a8b 100644 --- a/resources/external_control.urscript +++ b/resources/external_control.urscript @@ -34,7 +34,7 @@ TRAJECTORY_MODE_CANCEL = -1 TRAJECTORY_POINT_JOINT = 0 TRAJECTORY_POINT_CARTESIAN = 1 TRAJECTORY_POINT_JOINT_SPLINE = 2 -TRAJECTORY_DATA_DIMENSION = 3*6 + 1 +TRAJECTORY_DATA_DIMENSION = 3 * 6 + 1 TRAJECTORY_RESULT_SUCCESS = 0 TRAJECTORY_RESULT_CANCELED = 1 @@ -47,7 +47,7 @@ START_FORCE_MODE = 3 END_FORCE_MODE = 4 START_TOOL_CONTACT = 5 END_TOOL_CONTACT = 6 -SCRIPT_COMMAND_DATA_DIMENSION = 26 +SCRIPT_COMMAND_DATA_DIMENSION = 28 FREEDRIVE_MODE_START = 1 FREEDRIVE_MODE_STOP = -1 @@ -113,11 +113,11 @@ thread servoThread(): end q = extrapolate() - servoj(q, t=steptime, {{SERVO_J_REPLACE}}) + servoj(q, t = steptime, {{SERVO_J_REPLACE}}) elif state == SERVO_RUNNING: extrapolate_count = 0 - servoj(q, t=steptime, {{SERVO_J_REPLACE}}) + servoj(q, t = steptime, {{SERVO_J_REPLACE}}) else: extrapolate_count = 0 sync() @@ -144,7 +144,7 @@ thread speedThread(): stopj(STOPJ_ACCELERATION) end -def cubicSplineRun(end_q, end_qd, time, is_last_point=False): +def cubicSplineRun(end_q, end_qd, time, is_last_point = False): local str = str_cat(end_q, str_cat(end_qd, time)) textmsg("Cubic spline arg: ", str) @@ -163,7 +163,7 @@ def cubicSplineRun(end_q, end_qd, time, is_last_point=False): end end -def quinticSplineRun(end_q, end_qd, end_qdd, time, is_last_point=False): +def quinticSplineRun(end_q, end_qd, end_qdd, time, is_last_point = False): local str = str_cat(end_q, str_cat(end_qd, str_cat(end_qdd, time))) textmsg("Quintic spline arg: ", str) @@ -244,7 +244,7 @@ def jointSplineRun(coefficients1, coefficients2, coefficients3, coefficients4, c scaled_step_time = get_steptime() * scaling_factor splineTimerTraveled = splineTimerTraveled + scaled_step_time - + jointSplineStep(coefficients1, coefficients2, coefficients3, coefficients4, coefficients5, splineTimerTraveled, get_steptime(), scaling_factor, is_slowing_down) end scaling_factor = 0.0 @@ -261,7 +261,7 @@ def jointSplineRun(coefficients1, coefficients2, coefficients3, coefficients4, c jointSplineStep(coefficients1, coefficients2, coefficients3, coefficients4, coefficients5, splineTotalTravelTime, timeLeftToTravel, scaling_factor, is_slowing_down) end -def jointSplineStep(coefficients1, coefficients2, coefficients3, coefficients4, coefficients5, splineTimerTraveled, timestep, scaling_factor, is_slowing_down=False): +def jointSplineStep(coefficients1, coefficients2, coefficients3, coefficients4, coefficients5, splineTimerTraveled, timestep, scaling_factor, is_slowing_down = False): local last_spline_qd = spline_qd spline_qd = coefficients1 + 2.0 * splineTimerTraveled * coefficients2 + 3.0 * pow(splineTimerTraveled, 2) * coefficients3 + 4.0 * pow(splineTimerTraveled, 3) * coefficients4 + 5.0 * pow(splineTimerTraveled, 4) * coefficients5 spline_qdd = 2.0 * coefficients2 + 6.0 * splineTimerTraveled * coefficients3 + 12.0 * pow(splineTimerTraveled, 2) * coefficients4 + 20.0 * pow(splineTimerTraveled, 3) * coefficients5 @@ -341,11 +341,11 @@ thread trajectoryThread(): enter_critical while trajectory_points_left > 0: #reading trajectory point + blend radius + type of point (cartesian/joint based) - local raw_point = socket_read_binary_integer(TRAJECTORY_DATA_DIMENSION+1+1, "trajectory_socket", get_steptime()) + local raw_point = socket_read_binary_integer(TRAJECTORY_DATA_DIMENSION + 1 + 1, "trajectory_socket", get_steptime()) trajectory_points_left = trajectory_points_left - 1 if raw_point[0] > 0: - local q = [ raw_point[1]/ MULT_jointstate, raw_point[2]/ MULT_jointstate, raw_point[3]/ MULT_jointstate, raw_point[4]/ MULT_jointstate, raw_point[5]/ MULT_jointstate, raw_point[6]/ MULT_jointstate] + local q = [raw_point[1] / MULT_jointstate, raw_point[2] / MULT_jointstate, raw_point[3] / MULT_jointstate, raw_point[4] / MULT_jointstate, raw_point[5] / MULT_jointstate, raw_point[6] / MULT_jointstate] local tmptime = raw_point[INDEX_TIME] / MULT_time local blend_radius = raw_point[INDEX_BLEND] / MULT_time local is_last_point = False @@ -355,34 +355,34 @@ thread trajectoryThread(): end # MoveJ point if raw_point[INDEX_POINT_TYPE] == TRAJECTORY_POINT_JOINT: - movej(q, t=tmptime, r=blend_radius) + movej(q, t = tmptime, r = blend_radius) # reset old acceleration spline_qdd = [0, 0, 0, 0, 0, 0] spline_qd = [0, 0, 0, 0, 0, 0] - # Movel point + # Movel point elif raw_point[INDEX_POINT_TYPE] == TRAJECTORY_POINT_CARTESIAN: - movel(p[q[0], q[1], q[2], q[3], q[4], q[5]], t=tmptime, r=blend_radius) + movel(p[q[0], q[1], q[2], q[3], q[4], q[5]], t = tmptime, r = blend_radius) # reset old acceleration spline_qdd = [0, 0, 0, 0, 0, 0] spline_qd = [0, 0, 0, 0, 0, 0] - # Joint spline point + # Joint spline point elif raw_point[INDEX_POINT_TYPE] == TRAJECTORY_POINT_JOINT_SPLINE: # Cubic spline if raw_point[INDEX_SPLINE_TYPE] == SPLINE_CUBIC: - qd = [ raw_point[7] / MULT_jointstate, raw_point[8] / MULT_jointstate, raw_point[9] / MULT_jointstate, raw_point[10] / MULT_jointstate, raw_point[11] / MULT_jointstate, raw_point[12] / MULT_jointstate] + qd = [raw_point[7] / MULT_jointstate, raw_point[8] / MULT_jointstate, raw_point[9] / MULT_jointstate, raw_point[10] / MULT_jointstate, raw_point[11] / MULT_jointstate, raw_point[12] / MULT_jointstate] cubicSplineRun(q, qd, tmptime, is_last_point) # reset old acceleration spline_qdd = [0, 0, 0, 0, 0, 0] - # Quintic spline + # Quintic spline elif raw_point[INDEX_SPLINE_TYPE] == SPLINE_QUINTIC: - qd = [ raw_point[7] / MULT_jointstate, raw_point[8] / MULT_jointstate, raw_point[9] / MULT_jointstate, raw_point[10] / MULT_jointstate, raw_point[11] / MULT_jointstate, raw_point[12] / MULT_jointstate] - qdd = [ raw_point[13]/ MULT_jointstate, raw_point[14]/ MULT_jointstate, raw_point[15]/ MULT_jointstate, raw_point[16]/ MULT_jointstate, raw_point[17]/ MULT_jointstate, raw_point[18]/ MULT_jointstate] + qd = [raw_point[7] / MULT_jointstate, raw_point[8] / MULT_jointstate, raw_point[9] / MULT_jointstate, raw_point[10] / MULT_jointstate, raw_point[11] / MULT_jointstate, raw_point[12] / MULT_jointstate] + qdd = [raw_point[13] / MULT_jointstate, raw_point[14] / MULT_jointstate, raw_point[15] / MULT_jointstate, raw_point[16] / MULT_jointstate, raw_point[17] / MULT_jointstate, raw_point[18] / MULT_jointstate] quinticSplineRun(q, qd, qdd, tmptime, is_last_point) else: textmsg("Unknown spline type given:", raw_point[INDEX_POINT_TYPE]) @@ -400,7 +400,7 @@ end def clear_remaining_trajectory_points(): while trajectory_points_left > 0: - raw_point = socket_read_binary_integer(TRAJECTORY_DATA_DIMENSION+2, "trajectory_socket") + raw_point = socket_read_binary_integer(TRAJECTORY_DATA_DIMENSION + 2, "trajectory_socket") trajectory_points_left = trajectory_points_left - 1 end end @@ -443,11 +443,11 @@ thread servoThreadP(): end q = extrapolate() - servoj(q, t=steptime, {{SERVO_J_REPLACE}}) + servoj(q, t = steptime, {{SERVO_J_REPLACE}}) elif state == SERVO_RUNNING: extrapolate_count = 0 - servoj(q, t=steptime, {{SERVO_J_REPLACE}}) + servoj(q, t = steptime, {{SERVO_J_REPLACE}}) else: extrapolate_count = 0 sync() @@ -513,6 +513,13 @@ thread script_commands(): wrench = [raw_command[14] / MULT_jointstate, raw_command[15] / MULT_jointstate, raw_command[16] / MULT_jointstate, raw_command[17] / MULT_jointstate, raw_command[18] / MULT_jointstate, raw_command[19] / MULT_jointstate] force_type = raw_command[20] / MULT_jointstate force_limits = [raw_command[21] / MULT_jointstate, raw_command[22] / MULT_jointstate, raw_command[23] / MULT_jointstate, raw_command[24] / MULT_jointstate, raw_command[25] / MULT_jointstate, raw_command[26] / MULT_jointstate] + force_mode_set_damping(raw_command[27] / MULT_jointstate) + # Check whether script is running on CB3 or e-series. Gain scaling can only be set on e-series robots. + # step time = 0.008: CB3 robot + # Step time = 0.002: e-series robot + if (get_steptime() < 0.008): + force_mode_set_gain_scaling(raw_command[28] / MULT_jointstate) + end force_mode(task_frame, selection_vector, wrench, force_type, force_limits) elif command == END_FORCE_MODE: end_force_mode() @@ -536,9 +543,6 @@ socket_open("{{SERVER_IP_REPLACE}}", {{SERVER_PORT_REPLACE}}, "reverse_socket") socket_open("{{SERVER_IP_REPLACE}}", {{TRAJECTORY_SERVER_PORT_REPLACE}}, "trajectory_socket") socket_open("{{SERVER_IP_REPLACE}}", {{SCRIPT_COMMAND_SERVER_PORT_REPLACE}}, "script_command_socket") -force_mode_set_damping({{FORCE_MODE_SET_DAMPING_REPLACE}}) -force_mode_set_gain_scaling({{FORCE_MODE_SET_GAIN_SCALING_REPLACE}}) - control_mode = MODE_UNINITIALIZED thread_move = 0 thread_trajectory = 0 @@ -551,7 +555,7 @@ while control_mode > MODE_STOPPED: params_mult = socket_read_binary_integer(REVERSE_INTERFACE_DATA_DIMENSION, "reverse_socket", read_timeout) if params_mult[0] > 0: # Convert to read timeout from milliseconds to seconds - read_timeout = params_mult[1] / 1000.0 + read_timeout = params_mult[1] / 1000.0 if control_mode != params_mult[REVERSE_INTERFACE_DATA_DIMENSION]: # Clear remaining trajectory points if control_mode == MODE_FORWARD: @@ -559,7 +563,7 @@ while control_mode > MODE_STOPPED: clear_remaining_trajectory_points() stopj(STOPJ_ACCELERATION) socket_send_int(TRAJECTORY_RESULT_CANCELED, "trajectory_socket") - # Stop freedrive + # Stop freedrive elif control_mode == MODE_FREEDRIVE: textmsg("Leaving freedrive mode") end_freedrive_mode() @@ -590,10 +594,10 @@ while control_mode > MODE_STOPPED: # Update the motion commands with new parameters if control_mode == MODE_SERVOJ: - q = [params_mult[2]/ MULT_jointstate, params_mult[3]/ MULT_jointstate, params_mult[4]/ MULT_jointstate, params_mult[5]/ MULT_jointstate, params_mult[6]/ MULT_jointstate, params_mult[7]/ MULT_jointstate] + q = [params_mult[2] / MULT_jointstate, params_mult[3] / MULT_jointstate, params_mult[4] / MULT_jointstate, params_mult[5] / MULT_jointstate, params_mult[6] / MULT_jointstate, params_mult[7] / MULT_jointstate] set_servo_setpoint(q) elif control_mode == MODE_SPEEDJ: - qd = [params_mult[2]/ MULT_jointstate, params_mult[3]/ MULT_jointstate, params_mult[4]/ MULT_jointstate, params_mult[5]/ MULT_jointstate, params_mult[6]/ MULT_jointstate, params_mult[7]/ MULT_jointstate] + qd = [params_mult[2] / MULT_jointstate, params_mult[3] / MULT_jointstate, params_mult[4] / MULT_jointstate, params_mult[5] / MULT_jointstate, params_mult[6] / MULT_jointstate, params_mult[7] / MULT_jointstate] set_speed(qd) elif control_mode == MODE_FORWARD: if params_mult[2] == TRAJECTORY_MODE_RECEIVE: diff --git a/src/control/script_command_interface.cpp b/src/control/script_command_interface.cpp index 771e1c7cc..63c48eabd 100644 --- a/src/control/script_command_interface.cpp +++ b/src/control/script_command_interface.cpp @@ -108,9 +108,10 @@ bool ScriptCommandInterface::setToolVoltage(const ToolVoltage voltage) } bool ScriptCommandInterface::startForceMode(const vector6d_t* task_frame, const vector6uint32_t* selection_vector, - const vector6d_t* wrench, const unsigned int type, const vector6d_t* limits) + const vector6d_t* wrench, const unsigned int type, const vector6d_t* limits, + double damping_factor, double gain_scaling_factor) { - const int message_length = 26; + const int message_length = 28; uint8_t buffer[sizeof(int32_t) * MAX_MESSAGE_LENGTH]; uint8_t* b_pos = buffer; @@ -144,6 +145,12 @@ bool ScriptCommandInterface::startForceMode(const vector6d_t* task_frame, const b_pos += append(b_pos, val); } + val = htobe32(static_cast(round(damping_factor * MULT_JOINTSTATE))); + b_pos += append(b_pos, val); + + val = htobe32(static_cast(round(gain_scaling_factor * MULT_JOINTSTATE))); + b_pos += append(b_pos, val); + // writing zeros to allow usage with other script commands for (size_t i = message_length; i < MAX_MESSAGE_LENGTH; i++) { diff --git a/src/ur/ur_driver.cpp b/src/ur/ur_driver.cpp index 9292681b5..ed67b4755 100644 --- a/src/ur/ur_driver.cpp +++ b/src/ur/ur_driver.cpp @@ -58,7 +58,7 @@ urcl::UrDriver::UrDriver(const std::string& robot_ip, const std::string& script_ std::unique_ptr tool_comm_setup, const uint32_t reverse_port, const uint32_t script_sender_port, int servoj_gain, double servoj_lookahead_time, bool non_blocking_read, const std::string& reverse_ip, const uint32_t trajectory_port, - const uint32_t script_command_port, double force_mode_damping, double force_mode_gain_scaling) + const uint32_t script_command_port) : servoj_gain_(servoj_gain) , servoj_lookahead_time_(servoj_lookahead_time) , step_time_(std::chrono::milliseconds(8)) @@ -129,45 +129,6 @@ urcl::UrDriver::UrDriver(const std::string& robot_ip, const std::string& script_ std::to_string(script_command_port)); } - while (prog.find(FORCE_MODE_SET_DAMPING_REPLACE) != std::string::npos) - { - if (force_mode_damping < 0 || force_mode_damping > 1) - { - std::stringstream ss; - ss << "Force mode damping, should be between 0 and 1, but it is " << force_mode_damping; - force_mode_damping = 0.025; - ss << " setting it to default " << force_mode_damping; - URCL_LOG_ERROR(ss.str().c_str()); - } - prog.replace(prog.find(FORCE_MODE_SET_DAMPING_REPLACE), FORCE_MODE_SET_DAMPING_REPLACE.length(), - std::to_string(force_mode_damping)); - } - - while (prog.find(FORCE_MODE_SET_GAIN_SCALING_REPLACE) != std::string::npos) - { - if (robot_version_.major < 5) - { - // force_mode_set_gain_scaling is only available for e-series and is therefore removed, if the robot is not - // e-series - std::stringstream ss; - ss << "force_mode_set_gain_scaling(" << FORCE_MODE_SET_GAIN_SCALING_REPLACE << ")"; - prog.replace(prog.find(ss.str()), ss.str().length(), ""); - } - else - { - if (force_mode_gain_scaling < 0 || force_mode_gain_scaling > 2) - { - std::stringstream ss; - ss << "Force mode gain scaling, should be between 0 and 2, but it is " << force_mode_gain_scaling; - force_mode_gain_scaling = 0.5; - ss << " setting it to default " << force_mode_gain_scaling; - URCL_LOG_ERROR(ss.str().c_str()); - } - prog.replace(prog.find(FORCE_MODE_SET_GAIN_SCALING_REPLACE), FORCE_MODE_SET_GAIN_SCALING_REPLACE.length(), - std::to_string(force_mode_gain_scaling)); - } - } - robot_version_ = rtde_client_->getVersion(); std::stringstream begin_replace; @@ -181,9 +142,7 @@ urcl::UrDriver::UrDriver(const std::string& robot_ip, const std::string& script_ } begin_replace << "set_tool_voltage(" << static_cast::type>(tool_comm_setup->getToolVoltage()) << ")\n"; - begin_replace << "set_tool_communication(" - << "True" - << ", " << tool_comm_setup->getBaudRate() << ", " + begin_replace << "set_tool_communication(" << "True" << ", " << tool_comm_setup->getBaudRate() << ", " << static_cast::type>(tool_comm_setup->getParity()) << ", " << tool_comm_setup->getStopBits() << ", " << tool_comm_setup->getRxIdleChars() << ", " << tool_comm_setup->getTxIdleChars() << ")"; @@ -217,6 +176,21 @@ urcl::UrDriver::UrDriver(const std::string& robot_ip, const std::string& script_ URCL_LOG_DEBUG("Initialization done"); } +urcl::UrDriver::UrDriver(const std::string& robot_ip, const std::string& script_file, + const std::string& output_recipe_file, const std::string& input_recipe_file, + std::function handle_program_state, bool headless_mode, + std::unique_ptr tool_comm_setup, const uint32_t reverse_port, + const uint32_t script_sender_port, int servoj_gain, double servoj_lookahead_time, + bool non_blocking_read, const std::string& reverse_ip, const uint32_t trajectory_port, + const uint32_t script_command_port, double force_mode_damping, double force_mode_gain_scaling) + : UrDriver(robot_ip, script_file, output_recipe_file, input_recipe_file, handle_program_state, headless_mode, + std::move(tool_comm_setup), reverse_port, script_sender_port, servoj_gain, servoj_lookahead_time, + non_blocking_read, reverse_ip, trajectory_port, script_command_port) +{ + force_mode_damping_factor_ = force_mode_damping; + force_mode_gain_scale_factor_ = force_mode_gain_scaling; +} + urcl::UrDriver::UrDriver(const std::string& robot_ip, const std::string& script_file, const std::string& output_recipe_file, const std::string& input_recipe_file, std::function handle_program_state, bool headless_mode, @@ -378,10 +352,75 @@ bool UrDriver::setToolVoltage(const ToolVoltage voltage) return sendScript(cmd.str()); } } +// Function for e-series robots (Needs both damping factor and gain scaling factor) +bool UrDriver::startForceMode(const vector6d_t& task_frame, const vector6uint32_t& selection_vector, + const vector6d_t& wrench, const unsigned int type, const vector6d_t& limits, + double damping_factor, double gain_scaling_factor) +{ + if (robot_version_.major < 5) + { + URCL_LOG_ERROR("Force mode gain scaling factor cannot be set on a CB3 robot."); + return false; + } + // Test that the type is either 1, 2 or 3. + switch (type) + { + case 1: + break; + case 2: + break; + case 3: + break; + default: + std::stringstream ss; + ss << "The type should be 1, 2 or 3. The type is " << type; + URCL_LOG_ERROR(ss.str().c_str()); + return false; + } + for (unsigned int i = 0; i < selection_vector.size(); ++i) + { + if (selection_vector[i] > 1) + { + URCL_LOG_ERROR("The selection vector should only consist of 0's and 1's"); + return false; + } + } + + if (damping_factor > 1 || damping_factor < 0) + { + URCL_LOG_ERROR("The force mode damping factor should be between 0 and 1, both inclusive."); + return false; + } + + if (gain_scaling_factor < 0 || gain_scaling_factor > 2) + { + URCL_LOG_ERROR("The force mode gain scaling factor should be between 0 and 2, both inclusive."); + return false; + } + + if (script_command_interface_->clientConnected()) + { + return script_command_interface_->startForceMode(&task_frame, &selection_vector, &wrench, type, &limits, + damping_factor, gain_scaling_factor); + } + else + { + URCL_LOG_ERROR("Script command interface is not running. Unable to start Force mode."); + return false; + } +} +// Function for CB3 robots (CB3 robots cannot use gain scaling) bool UrDriver::startForceMode(const vector6d_t& task_frame, const vector6uint32_t& selection_vector, - const vector6d_t& wrench, const unsigned int type, const vector6d_t& limits) + const vector6d_t& wrench, const unsigned int type, const vector6d_t& limits, + double damping_factor) { + if (robot_version_.major >= 5) + { + URCL_LOG_ERROR("You should also specify a force mode gain scaling factor to activate force mode on a e-series " + "robot."); + return false; + } // Test that the type is either 1, 2 or 3. switch (type) { @@ -406,9 +445,16 @@ bool UrDriver::startForceMode(const vector6d_t& task_frame, const vector6uint32_ } } + if (damping_factor > 1 || damping_factor < 0) + { + URCL_LOG_ERROR("The force mode damping factor should be between 0 and 1, both inclusive."); + return false; + } + if (script_command_interface_->clientConnected()) { - return script_command_interface_->startForceMode(&task_frame, &selection_vector, &wrench, type, &limits); + return script_command_interface_->startForceMode(&task_frame, &selection_vector, &wrench, type, &limits, + damping_factor, 0); } else { @@ -417,6 +463,20 @@ bool UrDriver::startForceMode(const vector6d_t& task_frame, const vector6uint32_ } } +bool UrDriver::startForceMode(const vector6d_t& task_frame, const vector6uint32_t& selection_vector, + const vector6d_t& wrench, const unsigned int type, const vector6d_t& limits) +{ + if (robot_version_.major < 5) + { + return startForceMode(task_frame, selection_vector, wrench, type, limits, force_mode_damping_factor_); + } + else + { + return startForceMode(task_frame, selection_vector, wrench, type, limits, force_mode_damping_factor_, + force_mode_gain_scale_factor_); + } +} + bool UrDriver::endForceMode() { if (script_command_interface_->clientConnected()) From 535b083aa25ac46ec50681b92807bee9b097902d Mon Sep 17 00:00:00 2001 From: URJala Date: Tue, 9 Jul 2024 06:29:58 +0000 Subject: [PATCH 02/11] Bug fixes and updates to tests --- examples/force_mode_example.cpp | 27 +++++++++++++------ include/ur_client_library/ur/ur_driver.h | 34 +++++++++++++++--------- src/ur/ur_driver.cpp | 4 ++- tests/test_script_command_interface.cpp | 21 +++++++++++---- 4 files changed, 60 insertions(+), 26 deletions(-) diff --git a/examples/force_mode_example.cpp b/examples/force_mode_example.cpp index 409ff5903..fa3713bc8 100644 --- a/examples/force_mode_example.cpp +++ b/examples/force_mode_example.cpp @@ -149,14 +149,25 @@ int main(int argc, char* argv[]) } // Task frame at the robot's base with limits being large enough to cover the whole workspace // Compliance in z axis and rotation around z axis - - bool success = g_my_driver->startForceMode({ 0, 0, 0, 0, 0, 0 }, // Task frame at the robot's base - { 0, 0, 1, 0, 0, 1 }, // Compliance in z axis and rotation around z axis - { 0, 0, 0, 0, 0, 0 }, // do not apply any active wrench - 2, // do not transform the force frame at all - { 0.1, 0.1, 1.5, 3.14, 3.14, 0.5 } // limits. See ScriptManual - , - 0.8, 0.8); // for details. + bool success; + if (g_my_driver->getVersion().major < 5) + success = g_my_driver->startForceMode({ 0, 0, 0, 0, 0, 0 }, // Task frame at the robot's base + { 0, 0, 1, 0, 0, 1 }, // Compliance in z axis and rotation around z axis + { 0, 0, 0, 0, 0, 0 }, // do not apply any active wrench + 2, // do not transform the force frame at all + { 0.1, 0.1, 1.5, 3.14, 3.14, 0.5 } // limits. See ScriptManual + , + 0.8); // for details. + else + { + success = g_my_driver->startForceMode({ 0, 0, 0, 0, 0, 0 }, // Task frame at the robot's base + { 0, 0, 1, 0, 0, 1 }, // Compliance in z axis and rotation around z axis + { 0, 0, 0, 0, 0, 0 }, // do not apply any active wrench + 2, // do not transform the force frame at all + { 0.1, 0.1, 1.5, 3.14, 3.14, 0.5 } // limits. See ScriptManual + , + 0.8, 0.8); // for details. + } if (!success) { URCL_LOG_ERROR("Failed to start force mode."); diff --git a/include/ur_client_library/ur/ur_driver.h b/include/ur_client_library/ur/ur_driver.h index e6cf099b5..02d4043af 100644 --- a/include/ur_client_library/ur/ur_driver.h +++ b/include/ur_client_library/ur/ur_driver.h @@ -128,15 +128,25 @@ class UrDriver * \param force_mode_damping The damping parameter used when the robot is in force mode, range [0,1] * \param force_mode_gain_scaling Scales the gain used when the robot is in force mode, range [0,2] (only e-series) */ - [[deprecated("Specifying the force mode damping factor and the force mode gain scaling factor at driver creation has " - "been deprecated. Force mode parameters should be specified with each activiation of force mode, and " - "can be set in the function call to start force mode.")]] - UrDriver(const std::string& robot_ip, const std::string& script_file, const std::string& output_recipe_file, - const std::string& input_recipe_file, std::function handle_program_state, bool headless_mode, - std::unique_ptr tool_comm_setup, const uint32_t reverse_port, - const uint32_t script_sender_port, int servoj_gain, double servoj_lookahead_time, bool non_blocking_read, - const std::string& reverse_ip, const uint32_t trajectory_port, const uint32_t script_command_port, - double force_mode_damping, double force_mode_gain_scaling = 0.5); + [[deprecated( + "Specifying the force mode damping factor and the force mode gain scaling factor at driver creation has " + "been deprecated. Force mode parameters should be specified with each activiation of force mode, and " + "can be set in the function call to start force mode.")]] UrDriver(const std::string& robot_ip, + const std::string& script_file, + const std::string& output_recipe_file, + const std::string& input_recipe_file, + std::function handle_program_state, + bool headless_mode, + std::unique_ptr tool_comm_setup, + const uint32_t reverse_port, + const uint32_t script_sender_port, + int servoj_gain, double servoj_lookahead_time, + bool non_blocking_read, + const std::string& reverse_ip, + const uint32_t trajectory_port, + const uint32_t script_command_port, + double force_mode_damping, + double force_mode_gain_scaling = 0.5); /*! * \brief Constructs a new UrDriver object. @@ -439,9 +449,9 @@ class UrDriver * \returns True, if the write was performed successfully, false otherwise. */ [[deprecated("Starting force mode without specifying the force mode damping factor and gain scale factor has been " - "deprecated. These values should be given with each function call.")]] - bool startForceMode(const vector6d_t& task_frame, const vector6uint32_t& selection_vector, const vector6d_t& wrench, - const unsigned int type, const vector6d_t& limits); + "deprecated. These values should be given with each function call.")]] bool + startForceMode(const vector6d_t& task_frame, const vector6uint32_t& selection_vector, const vector6d_t& wrench, + const unsigned int type, const vector6d_t& limits); /*! * \brief Stop force mode and put the robot into normal operation mode. diff --git a/src/ur/ur_driver.cpp b/src/ur/ur_driver.cpp index ed67b4755..2e2a5bfc7 100644 --- a/src/ur/ur_driver.cpp +++ b/src/ur/ur_driver.cpp @@ -142,7 +142,9 @@ urcl::UrDriver::UrDriver(const std::string& robot_ip, const std::string& script_ } begin_replace << "set_tool_voltage(" << static_cast::type>(tool_comm_setup->getToolVoltage()) << ")\n"; - begin_replace << "set_tool_communication(" << "True" << ", " << tool_comm_setup->getBaudRate() << ", " + begin_replace << "set_tool_communication(" + << "True" + << ", " << tool_comm_setup->getBaudRate() << ", " << static_cast::type>(tool_comm_setup->getParity()) << ", " << tool_comm_setup->getStopBits() << ", " << tool_comm_setup->getRxIdleChars() << ", " << tool_comm_setup->getTxIdleChars() << ")"; diff --git a/tests/test_script_command_interface.cpp b/tests/test_script_command_interface.cpp index 682adba6e..d834502a8 100644 --- a/tests/test_script_command_interface.cpp +++ b/tests/test_script_command_interface.cpp @@ -64,11 +64,11 @@ class ScriptCommandInterfaceTest : public ::testing::Test void readMessage(int32_t& command, std::vector& message) { - // Max message length is 26 - uint8_t buf[sizeof(int32_t) * 26]; + // Max message length is 28 + uint8_t buf[sizeof(int32_t) * 28]; uint8_t* b_pos = buf; size_t read = 0; - size_t remainder = sizeof(int32_t) * 26; + size_t remainder = sizeof(int32_t) * 28; while (remainder > 0) { if (!TCPSocket::read(b_pos, remainder, read)) @@ -252,7 +252,10 @@ TEST_F(ScriptCommandInterfaceTest, test_force_mode) urcl::vector6d_t wrench = { 20, 0, 40, 0, 0, 0 }; int32_t force_mode_type = 2; urcl::vector6d_t limits = { 0.1, 0.1, 0.1, 0.785, 0.785, 1.57 }; - script_command_interface_->startForceMode(&task_frame, &selection_vector, &wrench, force_mode_type, &limits); + double damping = 0.8; + double gain_scaling = 0.8; + script_command_interface_->startForceMode(&task_frame, &selection_vector, &wrench, force_mode_type, &limits, damping, + gain_scaling); int32_t command; std::vector message; @@ -298,8 +301,16 @@ TEST_F(ScriptCommandInterfaceTest, test_force_mode) EXPECT_EQ(received_limits[i], limits[i]); } + // Test damping return + double received_damping = (double)message[25] / script_command_interface_->MULT_JOINTSTATE; + EXPECT_EQ(received_damping, damping); + + // Test Gain scaling return + double received_gain = (double)message[26] / script_command_interface_->MULT_JOINTSTATE; + EXPECT_EQ(received_gain, gain_scaling); + // The rest of the message should be zero - int32_t message_sum = std::accumulate(std::begin(message) + 25, std::end(message), 0); + int32_t message_sum = std::accumulate(std::begin(message) + 27, std::end(message), 0); int32_t expected_message_sum = 0; EXPECT_EQ(message_sum, expected_message_sum); From 768be7a96d4c447c0b1b4be81253f7872c352bfd Mon Sep 17 00:00:00 2001 From: URJala <159417921+URJala@users.noreply.github.com> Date: Wed, 2 Oct 2024 09:54:48 +1000 Subject: [PATCH 03/11] Update examples/force_mode_example.cpp Formatting Co-authored-by: Felix Exner (fexner) --- examples/force_mode_example.cpp | 5 ++--- 1 file changed, 2 insertions(+), 3 deletions(-) diff --git a/examples/force_mode_example.cpp b/examples/force_mode_example.cpp index fa3713bc8..915d4ba02 100644 --- a/examples/force_mode_example.cpp +++ b/examples/force_mode_example.cpp @@ -155,9 +155,8 @@ int main(int argc, char* argv[]) { 0, 0, 1, 0, 0, 1 }, // Compliance in z axis and rotation around z axis { 0, 0, 0, 0, 0, 0 }, // do not apply any active wrench 2, // do not transform the force frame at all - { 0.1, 0.1, 1.5, 3.14, 3.14, 0.5 } // limits. See ScriptManual - , - 0.8); // for details. + { 0.1, 0.1, 1.5, 3.14, 3.14, 0.5 }, // limits + 0.8); // damping_factor. See ScriptManual for details. else { success = g_my_driver->startForceMode({ 0, 0, 0, 0, 0, 0 }, // Task frame at the robot's base From 683e5429dae2189649f866dca6f4e2ba8538a1a1 Mon Sep 17 00:00:00 2001 From: URJala <159417921+URJala@users.noreply.github.com> Date: Wed, 2 Oct 2024 09:56:06 +1000 Subject: [PATCH 04/11] Update examples/force_mode_example.cpp Formatting Co-authored-by: Felix Exner (fexner) --- examples/force_mode_example.cpp | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/examples/force_mode_example.cpp b/examples/force_mode_example.cpp index 915d4ba02..4d72a745f 100644 --- a/examples/force_mode_example.cpp +++ b/examples/force_mode_example.cpp @@ -163,9 +163,9 @@ int main(int argc, char* argv[]) { 0, 0, 1, 0, 0, 1 }, // Compliance in z axis and rotation around z axis { 0, 0, 0, 0, 0, 0 }, // do not apply any active wrench 2, // do not transform the force frame at all - { 0.1, 0.1, 1.5, 3.14, 3.14, 0.5 } // limits. See ScriptManual - , - 0.8, 0.8); // for details. + { 0.1, 0.1, 1.5, 3.14, 3.14, 0.5 }, // limits + 0.8, // damping_factor + 0.8); // gain_scaling. See ScriptManual for details. } if (!success) { From 83662d69da31cce941dd1cc4f992daa2b368d378 Mon Sep 17 00:00:00 2001 From: URJala Date: Wed, 2 Oct 2024 01:49:09 +0000 Subject: [PATCH 05/11] Helper function in example, exceptions in startForceMode --- examples/force_mode_example.cpp | 38 +++++++++++++++++-- .../control/script_command_interface.h | 6 +-- src/ur/ur_driver.cpp | 6 +-- 3 files changed, 40 insertions(+), 10 deletions(-) diff --git a/examples/force_mode_example.cpp b/examples/force_mode_example.cpp index 4d72a745f..29f354432 100644 --- a/examples/force_mode_example.cpp +++ b/examples/force_mode_example.cpp @@ -55,11 +55,21 @@ const std::string CALIBRATION_CHECKSUM = "calib_12788084448423163542"; std::unique_ptr g_my_driver; std::unique_ptr g_my_dashboard; +std::condition_variable g_program_running_cv_; +std::mutex g_program_running_mutex_; +bool g_program_running; + // We need a callback function to register. See UrDriver's parameters for details. void handleRobotProgramState(bool program_running) { // Print the text in green so we see it better std::cout << "\033[1;32mProgram running: " << std::boolalpha << program_running << "\033[0m\n" << std::endl; + if (program_running) + { + std::lock_guard lk(g_program_running_mutex_); + g_program_running = program_running; + g_program_running_cv_.notify_one(); + } } void sendFreedriveMessageOrDie(const control::FreedriveControlMessage freedrive_action) @@ -72,6 +82,17 @@ void sendFreedriveMessageOrDie(const control::FreedriveControlMessage freedrive_ } } +bool waitForProgramRunning(int milliseconds = 100) +{ + std::unique_lock lk(g_program_running_mutex_); + if (g_program_running_cv_.wait_for(lk, std::chrono::milliseconds(milliseconds)) == std::cv_status::no_timeout || + g_program_running == true) + { + return true; + } + return false; +} + int main(int argc, char* argv[]) { urcl::setLogLevel(urcl::LogLevel::INFO); @@ -132,6 +153,15 @@ int main(int argc, char* argv[]) g_my_driver.reset(new UrDriver(robot_ip, SCRIPT_FILE, OUTPUT_RECIPE, INPUT_RECIPE, &handleRobotProgramState, HEADLESS, std::move(tool_comm_setup))); + if (!g_my_driver->checkCalibration(CALIBRATION_CHECKSUM)) + { + URCL_LOG_ERROR("Calibration checksum does not match actual robot."); + URCL_LOG_ERROR("Use the ur_calibration tool to extract the correct calibration from the robot and pass that into " + "the description. See " + "[https://github.com/UniversalRobots/Universal_Robots_ROS_Driver#extract-calibration-information] " + "for details."); + } + // Once RTDE communication is started, we have to make sure to read from the interface buffer, as // otherwise we will get pipeline overflows. Therefore, do this directly before starting your main // loop. @@ -142,10 +172,10 @@ int main(int argc, char* argv[]) auto stopwatch_last = std::chrono::steady_clock::now(); auto stopwatch_now = stopwatch_last; // Make sure that external control script is running - for (int i = 0; i < 100; i++) + if (!waitForProgramRunning()) { - g_my_driver->writeKeepalive(); - g_my_driver->getDataPackage(); + URCL_LOG_ERROR("External Control script not running."); + return 1; } // Task frame at the robot's base with limits being large enough to cover the whole workspace // Compliance in z axis and rotation around z axis @@ -164,7 +194,7 @@ int main(int argc, char* argv[]) { 0, 0, 0, 0, 0, 0 }, // do not apply any active wrench 2, // do not transform the force frame at all { 0.1, 0.1, 1.5, 3.14, 3.14, 0.5 }, // limits - 0.8, // damping_factor + 0.8, // damping_factor 0.8); // gain_scaling. See ScriptManual for details. } if (!success) diff --git a/include/ur_client_library/control/script_command_interface.h b/include/ur_client_library/control/script_command_interface.h index 07c17255e..c6cb15f6a 100644 --- a/include/ur_client_library/control/script_command_interface.h +++ b/include/ur_client_library/control/script_command_interface.h @@ -105,15 +105,15 @@ class ScriptCommandInterface : public ReverseInterface * 2: The force frame is not transformed. * 3: The force frame is transformed in a way such that its x-axis is the projection of the robot tcp velocity vector * onto the x-y plane of the force frame - * \param limits (Float) 6d vector. For compliant axes, these values are the maximum allowed tcp speed along/about the + * \param limits 6d vector. For compliant axes, these values are the maximum allowed tcp speed along/about the * axis. For non-compliant axes, these values are the maximum allowed deviation along/about an axis between the actual * tcp position and the one set by the program * - * \param damping_factor (Double) Sets the damping parameter in force mode. In range [0,1], default value is 0.025 + * \param damping_factor Sets the damping parameter in force mode. In range [0,1], default value is 0.025 * A value of 1 is full damping, so the robot will decelerate quickly if no force is present. A value of 0 * is no damping, here the robot will maintain the speed. * - * \param gain_scaling_factor (Double) Scales the gain in force mode. scaling parameter is in range [0,2], default + * \param gain_scaling_factor Scales the gain in force mode. scaling parameter is in range [0,2], default * is 0.5. A value larger than 1 can make force mode unstable, e.g. in case of collisions or pushing against hard * surfaces. * diff --git a/src/ur/ur_driver.cpp b/src/ur/ur_driver.cpp index 2e2a5bfc7..779251e9c 100644 --- a/src/ur/ur_driver.cpp +++ b/src/ur/ur_driver.cpp @@ -377,7 +377,7 @@ bool UrDriver::startForceMode(const vector6d_t& task_frame, const vector6uint32_ std::stringstream ss; ss << "The type should be 1, 2 or 3. The type is " << type; URCL_LOG_ERROR(ss.str().c_str()); - return false; + throw std::invalid_argument(ss.str().c_str()); } for (unsigned int i = 0; i < selection_vector.size(); ++i) { @@ -394,7 +394,7 @@ bool UrDriver::startForceMode(const vector6d_t& task_frame, const vector6uint32_ return false; } - if (gain_scaling_factor < 0 || gain_scaling_factor > 2) + if (gain_scaling_factor > 2 || gain_scaling_factor < 0) { URCL_LOG_ERROR("The force mode gain scaling factor should be between 0 and 2, both inclusive."); return false; @@ -436,7 +436,7 @@ bool UrDriver::startForceMode(const vector6d_t& task_frame, const vector6uint32_ std::stringstream ss; ss << "The type should be 1, 2 or 3. The type is " << type; URCL_LOG_ERROR(ss.str().c_str()); - return false; + throw std::invalid_argument(ss.str().c_str()); } for (unsigned int i = 0; i < selection_vector.size(); ++i) { From 6a372083f6f90766440338e92356eddb35ca9b74 Mon Sep 17 00:00:00 2001 From: URJala <159417921+URJala@users.noreply.github.com> Date: Tue, 8 Oct 2024 11:06:32 +1100 Subject: [PATCH 06/11] Change damping factor values in example Co-authored-by: Felix Exner (fexner) --- examples/force_mode_example.cpp | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/examples/force_mode_example.cpp b/examples/force_mode_example.cpp index 29f354432..454ccc85e 100644 --- a/examples/force_mode_example.cpp +++ b/examples/force_mode_example.cpp @@ -186,7 +186,7 @@ int main(int argc, char* argv[]) { 0, 0, 0, 0, 0, 0 }, // do not apply any active wrench 2, // do not transform the force frame at all { 0.1, 0.1, 1.5, 3.14, 3.14, 0.5 }, // limits - 0.8); // damping_factor. See ScriptManual for details. + 0.025); // damping_factor. See ScriptManual for details. else { success = g_my_driver->startForceMode({ 0, 0, 0, 0, 0, 0 }, // Task frame at the robot's base @@ -194,7 +194,7 @@ int main(int argc, char* argv[]) { 0, 0, 0, 0, 0, 0 }, // do not apply any active wrench 2, // do not transform the force frame at all { 0.1, 0.1, 1.5, 3.14, 3.14, 0.5 }, // limits - 0.8, // damping_factor + 0.025, // damping_factor 0.8); // gain_scaling. See ScriptManual for details. } if (!success) From 972873213df82d7e8c3615141104b1935ef69d07 Mon Sep 17 00:00:00 2001 From: URJala Date: Tue, 8 Oct 2024 00:39:11 +0000 Subject: [PATCH 07/11] Invalid_argument exceptions for all input checks in startForceMode. --- examples/force_mode_example.cpp | 2 +- src/ur/ur_driver.cpp | 43 +++++++++++++++++++++------------ 2 files changed, 29 insertions(+), 16 deletions(-) diff --git a/examples/force_mode_example.cpp b/examples/force_mode_example.cpp index 454ccc85e..1b275c249 100644 --- a/examples/force_mode_example.cpp +++ b/examples/force_mode_example.cpp @@ -194,7 +194,7 @@ int main(int argc, char* argv[]) { 0, 0, 0, 0, 0, 0 }, // do not apply any active wrench 2, // do not transform the force frame at all { 0.1, 0.1, 1.5, 3.14, 3.14, 0.5 }, // limits - 0.025, // damping_factor + 0.025, // damping_factor 0.8); // gain_scaling. See ScriptManual for details. } if (!success) diff --git a/src/ur/ur_driver.cpp b/src/ur/ur_driver.cpp index 779251e9c..77496ba8c 100644 --- a/src/ur/ur_driver.cpp +++ b/src/ur/ur_driver.cpp @@ -361,8 +361,10 @@ bool UrDriver::startForceMode(const vector6d_t& task_frame, const vector6uint32_ { if (robot_version_.major < 5) { - URCL_LOG_ERROR("Force mode gain scaling factor cannot be set on a CB3 robot."); - return false; + std::stringstream ss; + ss << "Force mode gain scaling factor cannot be set on a CB3 robot."; + URCL_LOG_ERROR(ss.str().c_str()); + throw std::invalid_argument(ss.str().c_str()); } // Test that the type is either 1, 2 or 3. switch (type) @@ -383,21 +385,27 @@ bool UrDriver::startForceMode(const vector6d_t& task_frame, const vector6uint32_ { if (selection_vector[i] > 1) { - URCL_LOG_ERROR("The selection vector should only consist of 0's and 1's"); - return false; + std::stringstream ss; + ss << "The selection vector should only consist of 0's and 1's"; + URCL_LOG_ERROR(ss.str().c_str()); + throw std::invalid_argument(ss.str().c_str()); } } if (damping_factor > 1 || damping_factor < 0) { - URCL_LOG_ERROR("The force mode damping factor should be between 0 and 1, both inclusive."); - return false; + std::stringstream ss; + ss << "The force mode damping factor should be between 0 and 1, both inclusive."; + URCL_LOG_ERROR(ss.str().c_str()); + throw std::invalid_argument(ss.str().c_str()); } if (gain_scaling_factor > 2 || gain_scaling_factor < 0) { - URCL_LOG_ERROR("The force mode gain scaling factor should be between 0 and 2, both inclusive."); - return false; + std::stringstream ss; + ss << "The force mode gain scaling factor should be between 0 and 2, both inclusive."; + URCL_LOG_ERROR(ss.str().c_str()); + throw std::invalid_argument(ss.str().c_str()); } if (script_command_interface_->clientConnected()) @@ -419,9 +427,10 @@ bool UrDriver::startForceMode(const vector6d_t& task_frame, const vector6uint32_ { if (robot_version_.major >= 5) { - URCL_LOG_ERROR("You should also specify a force mode gain scaling factor to activate force mode on a e-series " - "robot."); - return false; + std::stringstream ss; + ss << "You should also specify a force mode gain scaling factor to activate force mode on an e-series robot."; + URCL_LOG_ERROR(ss.str().c_str()); + throw std::invalid_argument(ss.str().c_str()); } // Test that the type is either 1, 2 or 3. switch (type) @@ -442,15 +451,19 @@ bool UrDriver::startForceMode(const vector6d_t& task_frame, const vector6uint32_ { if (selection_vector[i] > 1) { - URCL_LOG_ERROR("The selection vector should only consist of 0's and 1's"); - return false; + std::stringstream ss; + ss << "The selection vector should only consist of 0's and 1's"; + URCL_LOG_ERROR(ss.str().c_str()); + throw std::invalid_argument(ss.str().c_str()); } } if (damping_factor > 1 || damping_factor < 0) { - URCL_LOG_ERROR("The force mode damping factor should be between 0 and 1, both inclusive."); - return false; + std::stringstream ss; + ss << "The force mode damping factor should be between 0 and 1, both inclusive."; + URCL_LOG_ERROR(ss.str().c_str()); + throw std::invalid_argument(ss.str().c_str()); } if (script_command_interface_->clientConnected()) From a7926d468c35c91881f15da1442fd986c27a4d18 Mon Sep 17 00:00:00 2001 From: URJala Date: Fri, 1 Nov 2024 01:46:28 +0000 Subject: [PATCH 08/11] Added UR exceptions InvalidRange and IncompatibleRobotVersion Added them to the various checks for starting force mode. I created IncompatibleRobotVersion instead of using VersionMismatch, as the VersionMismatch would not give enough information in my opinion. --- include/ur_client_library/exceptions.h | 39 ++++++++++++++++++++++++++ src/ur/ur_driver.cpp | 18 ++++++------ 2 files changed, 48 insertions(+), 9 deletions(-) diff --git a/include/ur_client_library/exceptions.h b/include/ur_client_library/exceptions.h index 49a4fde7b..9adbc04c0 100644 --- a/include/ur_client_library/exceptions.h +++ b/include/ur_client_library/exceptions.h @@ -124,5 +124,44 @@ class TimeoutException : public UrException private: std::string text_; }; + +class IncompatibleRobotVersion : public UrException +{ +public: + explicit IncompatibleRobotVersion() = delete; + explicit IncompatibleRobotVersion(std::string text, int required_robot_version, int actual_robot_version) + : std::runtime_error(text) + { + std::stringstream ss; + ss << text << "\n" + << "The requested feature is incompatible with the connected robot. Required Polyscope version: " + << required_robot_version << ", actual Polyscope version: " << actual_robot_version; + text_ = ss.str(); + } + virtual const char* what() const noexcept override + { + return text_.c_str(); + } + +private: + std::string text_; +}; + +class InvalidRange : public UrException +{ +private: + std::string text_; + +public: + explicit InvalidRange() = delete; + explicit InvalidRange(std::string text) : std::runtime_error(text) + { + text_ = text; + } + virtual const char* what() const noexcept override + { + return text_.c_str(); + } +}; } // namespace urcl #endif // ifndef UR_CLIENT_LIBRARY_EXCEPTIONS_H_INCLUDED diff --git a/src/ur/ur_driver.cpp b/src/ur/ur_driver.cpp index 77496ba8c..717bde4e4 100644 --- a/src/ur/ur_driver.cpp +++ b/src/ur/ur_driver.cpp @@ -364,7 +364,7 @@ bool UrDriver::startForceMode(const vector6d_t& task_frame, const vector6uint32_ std::stringstream ss; ss << "Force mode gain scaling factor cannot be set on a CB3 robot."; URCL_LOG_ERROR(ss.str().c_str()); - throw std::invalid_argument(ss.str().c_str()); + throw IncompatibleRobotVersion(ss.str(), 5, robot_version_.major); } // Test that the type is either 1, 2 or 3. switch (type) @@ -379,7 +379,7 @@ bool UrDriver::startForceMode(const vector6d_t& task_frame, const vector6uint32_ std::stringstream ss; ss << "The type should be 1, 2 or 3. The type is " << type; URCL_LOG_ERROR(ss.str().c_str()); - throw std::invalid_argument(ss.str().c_str()); + throw InvalidRange(ss.str().c_str()); } for (unsigned int i = 0; i < selection_vector.size(); ++i) { @@ -388,7 +388,7 @@ bool UrDriver::startForceMode(const vector6d_t& task_frame, const vector6uint32_ std::stringstream ss; ss << "The selection vector should only consist of 0's and 1's"; URCL_LOG_ERROR(ss.str().c_str()); - throw std::invalid_argument(ss.str().c_str()); + throw InvalidRange(ss.str().c_str()); } } @@ -397,7 +397,7 @@ bool UrDriver::startForceMode(const vector6d_t& task_frame, const vector6uint32_ std::stringstream ss; ss << "The force mode damping factor should be between 0 and 1, both inclusive."; URCL_LOG_ERROR(ss.str().c_str()); - throw std::invalid_argument(ss.str().c_str()); + throw InvalidRange(ss.str().c_str()); } if (gain_scaling_factor > 2 || gain_scaling_factor < 0) @@ -405,7 +405,7 @@ bool UrDriver::startForceMode(const vector6d_t& task_frame, const vector6uint32_ std::stringstream ss; ss << "The force mode gain scaling factor should be between 0 and 2, both inclusive."; URCL_LOG_ERROR(ss.str().c_str()); - throw std::invalid_argument(ss.str().c_str()); + throw InvalidRange(ss.str().c_str()); } if (script_command_interface_->clientConnected()) @@ -430,7 +430,7 @@ bool UrDriver::startForceMode(const vector6d_t& task_frame, const vector6uint32_ std::stringstream ss; ss << "You should also specify a force mode gain scaling factor to activate force mode on an e-series robot."; URCL_LOG_ERROR(ss.str().c_str()); - throw std::invalid_argument(ss.str().c_str()); + throw IncompatibleRobotVersion(ss.str(), 3, robot_version_.major); } // Test that the type is either 1, 2 or 3. switch (type) @@ -445,7 +445,7 @@ bool UrDriver::startForceMode(const vector6d_t& task_frame, const vector6uint32_ std::stringstream ss; ss << "The type should be 1, 2 or 3. The type is " << type; URCL_LOG_ERROR(ss.str().c_str()); - throw std::invalid_argument(ss.str().c_str()); + throw InvalidRange(ss.str().c_str()); } for (unsigned int i = 0; i < selection_vector.size(); ++i) { @@ -454,7 +454,7 @@ bool UrDriver::startForceMode(const vector6d_t& task_frame, const vector6uint32_ std::stringstream ss; ss << "The selection vector should only consist of 0's and 1's"; URCL_LOG_ERROR(ss.str().c_str()); - throw std::invalid_argument(ss.str().c_str()); + throw InvalidRange(ss.str().c_str()); } } @@ -463,7 +463,7 @@ bool UrDriver::startForceMode(const vector6d_t& task_frame, const vector6uint32_ std::stringstream ss; ss << "The force mode damping factor should be between 0 and 1, both inclusive."; URCL_LOG_ERROR(ss.str().c_str()); - throw std::invalid_argument(ss.str().c_str()); + throw InvalidRange(ss.str().c_str()); } if (script_command_interface_->clientConnected()) From 179dd0553477c4e40d81577d649e388fa80ef656 Mon Sep 17 00:00:00 2001 From: URJala Date: Fri, 1 Nov 2024 01:46:51 +0000 Subject: [PATCH 09/11] Merge branch 'master' into force_mode_arguments --- .github/workflows/ci.yml | 6 + README.md | 5 + doc/resources/family_photo.png | Bin 0 -> 199316 bytes src/rtde/data_package.cpp | 17 +- src/rtde/rtde_client.cpp | 2 +- tests/test_rtde_client.cpp | 407 +++++++++++++++++++++++++++++++++ 6 files changed, 433 insertions(+), 4 deletions(-) create mode 100644 doc/resources/family_photo.png diff --git a/.github/workflows/ci.yml b/.github/workflows/ci.yml index f679a5e3a..006f2cda7 100644 --- a/.github/workflows/ci.yml +++ b/.github/workflows/ci.yml @@ -21,6 +21,12 @@ jobs: ROBOT_MODEL: 'ur5e' URSIM_VERSION: '5.9.4' PROGRAM_FOLDER: 'tests/resources/dockerursim/programs/e-series' + - DOCKER_RUN_OPTS: --network ursim_net + BEFORE_INIT: 'apt-get update -qq && apt-get install -y iproute2 iputils-ping && ip addr && ping -c5 192.168.56.101' + CTEST_OUTPUT_ON_FAILURE: 1 + ROBOT_MODEL: 'ur20' + URSIM_VERSION: 'latest' + PROGRAM_FOLDER: 'tests/resources/dockerursim/programs/e-series' steps: - uses: actions/checkout@v1 diff --git a/README.md b/README.md index bc042cf09..1d7132014 100644 --- a/README.md +++ b/README.md @@ -4,6 +4,11 @@ A C++ library for accessing Universal Robots interfaces. With this library C++-b implemented in order to create external applications leveraging the versatility of Universal Robots robotic manipulators. + +
+ Universal Robot family +
+ ## Requirements * **Polyscope** (The software running on the robot controller) version **3.14.3** (for CB3-Series), diff --git a/doc/resources/family_photo.png b/doc/resources/family_photo.png new file mode 100644 index 0000000000000000000000000000000000000000..678d312d90de1a8891237bd3c3ff090d6833887c GIT binary patch literal 199316 zcmeFY^;eYL8#O+3h%`vUARs9rrP3uK3djIMheOv$r*uk)fP~WBIdqqj0@4jiigZZm zdw8D5&wAJT{sZ41-f>(m2JgA=bIx_HYwvyS6R!5`$!&ZZd%7{=;2$(6jVCgYvSGR{@B_A~$`d)rpPN4!E&1=jCwPvEa3=`l7TL{TG)T$^ zDhLFh%}Q2Q&C1LU0&)NFG0{y^bBZ!_q{YoMbBNEG%ClSpn|O;pM_ZlB9Gj{i(nTbAV8Jozm&bu=%j06)?|b=!iM3X{s-9v*w&zn}GqFU?x)Ii1aT zE!EzKu<%OW=cP|XXNtPFjN{e#A^1ZaqsA0h*Tf~R@(uI1 ze0eAui=hLx7uML;@}GBtT!FmcVaX3jh3`eOu8NW5uj2}IpTbFAti9+a$nGAz!^&>z z!GG_5)u=_fyesL0$5DNhm7*I2t~7ds;>?S0dA@~F9grb?h2OusyE?}_sZ5cFl)uuV zOYJo=NAqJ2-$f_nQtCEmW;>7#G>~s5htP2x+=~7afc0Sl{UBF={K4dYL%0%pBZEr1 zy}ivqh8Oac#zS;}B-6Wu&TrLQWm{I%PZwz*lzUfjfz{bDd3ls@T`fu&#mE0AOYM)# zk%RL5oV+LXaf1bM=^oLX(XZSowDu&j3G*{X)Hy!n5ekjz^&U~`Box9T?_$=JO@{*=6RarR=x^x$q}>iNTA zA<_6@(!=UIXWi+nQW)s5n3@?7O@Fp87`^T2(-5y^%z1wzTu3GpehE5vEan)5@tfa? z@vTod!NwxfIGobA3vi+`us%TOmj&w~_XBs9v8m9{I@psSBkkPox7VS#oiZ=O&^e^6 zV})Ph!lei-slO5alI~C=C&yux5mUr14MoWWtKn(lO~^!jsr$mQiSA566ZBKY?2F(r z*D-^FG3nD_m@)k{xq16=1uq?bc@WvkQ+J*ZIC}vDE04~p<_V4b%DZIu*{=xFWFazg zmSK-f-|!J@vp~WXNQot?NI0bWV;|*UZOM4P)%(OQ5ZEkh0&Y%^cvJPnBePSDTa(TD zZV@gl{85DUlambl%wDzXg6Eb3y3}@IC|R%UyQATobj}iu1PgxlvPLpQnfJbw^HUMr z&W^0?a5u@~`<&#G#5{=hlxtngocKX>a+hf(zK(1OhA?EH8^7Y$H2x3%9}j=1{=hut zi4J?w1z#3(92I4_e@8pSrt@RZLbvMb`hkYKT{FD|WTdyeQJrE%hS zA1ljRJ`!}$qsSQ9n;$MAB!`YWpZUsW7F`rg&=)9=Jt#F@rP z%}K#|2WGBmRrIXrb5U-Q1uTDp-Fo0_y>+hj#@Dnl#Mbb!rsuJHQlApQvHOpap z+UZkYCUD0;O;}F27btysX~|}pXzgk|(Oa zYJ+@P3uSG?DLuDR`|6(<;#FzchIxh`7wvrBNXSac|MB~M8)Le?pXqZ(zi~UUaE#3KjWHLNCH)SGq zLF7IE8UKjTp1_}p&h`L=Is)m1=Mml)r>gSkeRG9i%{Lu}nr1Wk%EP)@`w6>~(b?V< zhXqq{yKDrR#S6O!of!h?)bek*P?mak=2TJnc1ttxIlLdwrmsyMY|~AbUP{(#x^Y-o zU5_DgZsX+1mUe9lTvXK~LKCAN6+IT9-=SlCZ1t$}Bh3f4k0&4BeT;c1>BjH0(p1yX zjI4E9SoU1JjXZMZa@=uyk0f#`cYggXbLH*k=nwuKtM3iNN6mL;2c~Rdro!qXLz=l3{ObzI-N~ zl+m71lyR?Py<;cPOO_p42~~xb%Noc;%I<}31>APaTjJ2G#4b6R?`@7`NL*94pC~2!2eUwNtNqU>kpJMgCf!8T< zZ@}SGK$Vuc3w}XXdZ9#Snq#UXw-?+Mb~^WA|HHfDTMYYNw%Zx-qpz<+7z_ zr8|b@t-b>nmA8j!twm&L*F;<$#^&SetW2vn*0c3+^)ygdu{Mc%ahKLM-IHZv3C%+u zYja|CLK`aIj*gz7<{Zjr{AW8BM%$b|4@Z1V$DhWU!XLsPz?USij41O#{D%F~zSTtP zdU8ka4&!{(%+Q>8b02bKlyobumUYeR`V94cOy!oc(Qf2|TkT*~iMgano8uqL1|tuP zV6C2?5kv_}39_*Ju+oYCiO0oDbjFPJ9$&VMRicztO@=OI=Vjfj#ck$xoVWW4%?K?R zeKi;jmoA0Yc6zaULOMfYp140zh{0yuwW_hQwbiiav=2!Q9vbg6jb1qK-Ax^)TuYqQ z(zRJZI_kS$ZPg){2-Ek)M}6XuRo@@)?iJ0k+hOghU8bDQMCU}04i^k}ypYImZ2HkO z+bZ(w_b029ahS!+5%P4_4?~Ze9PM`-8jh$pEbg-yQtd_Ww!Y>+T-{B}Nc*kQ`o2v6 zwBEaNs^M&&B9tq?eAYnRB??)()_8JqDpA~uVl45s+^PHNz*s@O*=*vKZR5DLJd+wN z!aM(}$>kU7Y3L zXlpMd^6wR=LfATgFQ_T!Z~uEimQNHK<=-oIZT{aa{@+B&$^E~GV*dZzzL=HgaA{*i zzuBp8JO0_$Z0x!J?)A~u&c7cp1=TMR1>WrWPsabB1R>zO!^HJZ3bB+l`RBLTb2#DP z|5{2`?VVvT{gVs}~B31kVdG2STLeF?|rVAY?JC&t7LfJCqD%cC=Ad3FDDGsv6b za`#vAa?Wn?8k;Ac_3j7E_x0=j^y=)v)ws~7jqP0fh!oSmgH^xR^-I?k8u>Fvdi*QnsW6}{GuG&oNS*`!ZPo#XWRz76{pS<>cBqz6r|4+jDWPCzFGP-->DK2(4@8tfoVWXn5(qC)@ z4U&jRjzNPcOLGK+FGEnru}IVP;dT*stq||n?8qaunxZ^g2>Xz1o!mZRlTe+LowA*j zy*-!t)`bJ_3oo~e4`6csok@s$r;MEQV`UEgdPg*)KNnNT-&YCJ4W6lOXs~J6)i1MEUItccf{vO4p$LKkr;pXFw|5_n9x=yPiFdrveQXK$lT31 zlnH=f1~u$y8+u?Z*w>x6YUnh%+#-@Z#EsWj|DEq(_9%n1^*&R#W(6x2W{?NnqxLZe zlwH@6*m-M=d3Cr}aj-&mhyStMarEEXQxhtvda$tPL-hKn)WJlMh61LI_@0m_Ihjep zSJpYU8>mjM8YGveQCz>AcE*e8c(M)CZ*sjYgUg;3k84v@a4^>3$VivV!sYc7IXNQSzlH3-}|BG zlSY4pve-F`$}|bF5a#-@EtGWbt8WioVU}Bove&*Bc9aVW?mLq_WX3(nH?pCG(#lq4 zBE>Y@u10gk!D?-)H6)3$TY*ecErw6P@|;dm3U6#6_m`z>=IrcYELnB*|JBzlYD3>& z2=AlRB{_2WPgNx)tr~uuT={+m2|DXM+J02ph+L}(uo4M+cxU*Pn3&{W<-Wuts1>r` zHZVdlg+)YG8q4rLJJ;t*mPw#m0!p@hHn%IbFSp=2t$TMUbUuPPN81U#`!Yg)>af<@BsJ27%C37VLscV710E5l5>}ly zE^MD=i}o7x71VHNDSpkX%HD$Rjn^5p#2lms#eeV9=)7-XqQtS%$e_jGNshyC%|{uX z=65W{k|-zgmg>9I5cX_ZfDL~)b5c{p7!+o?kldsa_cW2wJRP5>)kWn+Msr@9UWB>* zeR{)}%5j({!^{j9`@E}fiM%muJ<0GOIS&s7M9E}KHo1^c~{`0fWc3nWf;4 zBM;hC71Q_gWJ)MyEJv_Do+287seikcW9j8}zLMM?>;E1jume(Ozrb0XpNGMO=q$Dt z(wuO9Y%J7W#eEAr!jV{gS)_g4V}2%y0f8JVEll`#CU>ZDNTK$gind#!7!Ieu)s|BD-%3h7{&xY(x2nvu}1DIE23@w+De##dD&f!L*o(feV-*w)7>9Gl9ajO@xo9Q zw3pPcGTC%V@Ct`Mzf6{L^_m!7(Ao*wa6V=bz6*4n>e(6Tqn!~J=3&Tf( ziHVD-ew1-l9#_`r`U}|Tv% zIY-;`&1}X6ZnCofBE2Ws!k0v7L}8$M`7vbW>fCmdC9o+bV;j8&9#9{Jx|*v<)~X_5T-!QfoB#8#9O5yMtgaeU?) zs>A10sXrCGE2^fvGC4~Vuc0_jZk6&(zi+ z4KF6nst2v1^TnlVigX$difp#&C4?l)IlJ z9_p_V+k~`4v|t7{P%%d^gMbdHcpQzfbT(=!_{F}CUql3FCecyf;xL+G8A~FXK|JE*#N~}b_CX2H zwP-)u&mNzF!s1)=R%7vL{#Z_rd-@tXmA`Ws{`swK@|cj}SNjv*(Ak*2zrv zDN;fMoD8bvO@XN*4#uLJYpF|DY=rcWf{dQ`e-vraS8}v6C62zLj_RZ;J`aSXXp9=ZzZPj|S;zyy+?tjCS0*g6lWE zqULS85&-bGX+eQ1Bv!)|fx!CstWUF%gk%BlZ()ujMsM9q-N&Pe6RkXRz3!zEJs$V0+@vp7V5E!jYd zxSF87NEM%`Dd%&UT-X1Aul)7?jtk|EEe zBoESX|New`IjXvR?eP0RUIb6Hnb`01HTNHteX$!4bK=2PN77|$6?eES%+QjDhqeDh zr~teR*z>w6pU*+MSm{sT0Um|$K_w<2|p`mozMpzcE5^1V%n>AIAh4z+k zyP&GcoUm>wrNrUenC0+$Y3)uU;-QjP*^-?`KG!>r26xi`Ty20!W1 zq8ho{9qR$p)Pe22o}BEqE)e26F7o9Ll1gK%KVRF+szYKtm%OAEJ>AcaZNQA};;*ic zz`s8bSC8BkNc*!`hy318LADOCG}toW$*LiKd;}|^gtkq%TNl?7bbZpLT7h;)f(c=+ zYj6Gk5uge>k^1h2>MMd&1Qm^q5$q9;7o$%O+Wwq6tX1|g1QMfL374Td-_ZMwOKS-! zj-@x1MaFo4yK7lDcfR-Mx^2zI=#nOyQ4*~WNrH(6Y3C84-kv+WhJb)B+mYdrD)ctj zNq8T)V&UU3X(kZkc7-|U=*Ge7DZ;xF`uY@SQ{o6NcA6QJZCHM1g^nejxFSbRly2Ff z?RT5wX{~l_g2~6$bfb%0qt0-$dw{bU&!Ma)ocle@tWr!ZEO4ZW+s}MZ6r`h=f3qUR zGgiJv=Pgn&T8V@3=gV%d&)ks9?PxEo5WPt|C=ve0-6<5L6d3u&WonX*@8rd#D438`v@ zG^T*d-6y8gHcf^MR2l10zGPTiRe2p)Qy2Y2@*I!5j4mLa@Q}MFp}6?GsqLEUYJYC2 z+fg)Vw?5V*L{w?NBR{S4PU}9FPGT^7#GoEAX3rPzsbIS~kWNJDQcyB|$Z0J_Imq9d zs|vQFG_kRn83rvat^37R{=vxa8Og5IRny$nA~kx?GP6W$+#2nZ7cRby#OTpx*)x`_ zcO(vOozEKi+}18PlrNr;Nkjk&-?~S!>+KN@NTYc*9(>VF$glriXOZ%ysUarZBkis> zz6W*ZZtFAt7b=QydvbE~oy@hyeQ}~%-P;1Q9kVtg(#J7(3q3U(QXLXf1iyhp~oXadF4Pv&bV#Yb8S)2@*j{GZuPTV3wK~@de!{+j;~x4zF%B$arh-U zwJSTHv1ce%Ea6sMFNG*a10(-a0Mvuy$80}) zoz7TP*3<-n$^#p#X_4W63R6txyq6%$3Aab5!;$yAT67Mk3Rs)>cgCQV83sWRIYCJ|Ppq*&{*U0O|AkCwrqx17VNy3q% z!IS(tyzTNG;ZEPS7(vy0Kc5pRI|$M^8cd1Z5l>YKJ8&YEkwOdWB;FYQ*maAy*^gGl zfm!8+B1dJ*Le~kc2ve|B8rMsB1O^V_vYYRQ+n22x5Hp3_q%ukA{)N4qTvg6OT8W4o zR5MQQ&)7~BVa@H+!bflq{XR%w;#B|J=UdK?ZV=h&a5P>;yhg0Xvmk95T!K(p{Z?;k z?K1t2-gUNBc46r#hNleYXx6nfDWz=d8|#%7d@)+ZSW_;Mb8kseX74BDh1i$6-rjw( z-$CR{-1aNA4LLF*%MlD>=SC$9?8vB3ulfiExH4I)XRg+0KNm>+>B#hpC&0VexHfh6 zE45RGUBS2R5Qk*`qQ1F(qca|u*OeU&&+`PMUt%EV`}@9z%rVpv%%bc#o7svgZJP*c zY+00$ZR+|2-p|KOu@g5uDh38Pa=+}Itu)>bZ6*_E`rk0E1ZfH;tfyyYq_u`4$1p0K z-D_)WgVTQ>=Zkus(xK|=-oDR_PCNT*E3AIY`uwL`Ti{w>O!mT0rZ!#u-Xr}%mvzU@ zFHkyhPfS2MqIcVmeCpFe1;a`D4!W-wZb2~#=|mwTNB_Xj(o*Tn>6-fHW&$WCkQvG4 zsR*#mg|&21M|QTh9@&C zUC`CZSAa;-0pcdizV4P4+);dF@YC4T!-|@qyH5z$=9Yfbx*L)-lS?N_rEN@4&$nOn zJ{tb`I24R|<=f|XxcwRT1~lF%tmqx;2N7>NKXU(bxfFA>F|sz_;H0xOD?``!DFMBI zSt(Qtkbt?lIi02H_Tkf0xt@f)_|8(jx-Yw~XzhczdJ?ZNVIu0Ptp^F3K-&!v8r9;+4XVj0>@6a6n<@={)SW_gXs8t+uO8&tG7R05+f)Cmc;u1G zPV{wkRdZuNoSO{(QFpITs=;P;rB2igO}~}#;dbo}atBDTD{l-}MkdfqDRhyCE^YgbmBuIrodg{MZ~0`}uk_K+tT3NED!1qB1%T8Kaiq zHp!|X^6m&}MKrx>Vwui3$`WN*B4HI+K63e{kmel-_lOf1#5n2an<4T{zHdFw(1-E(KY+1-i31NT$JgNGo-9n6!wA0`=Uo5MuzZD;VPz5v8kmuyB$@p$oncs7JZ z381Nd>l}je)(e_4gEo_phB;RfO%UT#$mMC_e>w}6g0uxw+XYj!xYlT5Q-N!gsmGZ8 zQQjJqE5t!FuL@+Vb93bt2Ri*RR4R7sT9Lg-I&NNGGY=1H$Y67!plYP?CtCw@sy@k{ z<+Eb#@)Vv(&%B8n#N&P5#VBm@woI1`otxgARdE$lDJ3aU)>v#!Wt(`L5SrN9>|5fI zsGT-buge_~0p0gB79(kC`l|}0F!w)%J%0Qc?BaTlBeqEqVaFevBv;EgOMRAt-G_(x zVk5yom#4?6^`zg`q6MWsdRHoOC7w0XRc`4lV)Efgum-*w`(lt3i2TI7bFk6<8X5>+ zC7AtcM{{0ZU-np>JEcnf|;?{}5=d~}2Z#D$ij zSGh*N5mzlsSE}x5L`!GO@u?J%%7rz!<#CuMqB2wpJ&7GG@+szQ^qQ+9k zN8SCP8Ij05Bv2rhUQa(z^>hvj(J~`x8Tj7_$M((+q8z+2qSrE}cGmh6iXG{2h(3yi z?@X0-9C>r|@JQq1^&$C0BtsQi2&EDzbhApvIQ1|Q)E^46E(#6Hp(9T0xnLO+-$$zY zOI~k1M_!%dedBzRJ=(rfHLj#hqcQ|tQ2Oo?q z|GARe6sr&#JErILXuX<80r3gN*2xd7X|A@8zZf-d9)m%2IjeZpC zkXU6i!N8$dDnLlQA<|=rKEurM{XCL-1{UAByVQW;eARvgRs9%A96rxt{K3bhJi>&#|LPQN}mvIR;xa|c9?U+%Wo#H?Mu~g!B^Pgl)K$Hr|!0zJ+>@O|(iN(DYq2Nt&P`Vf7#8g5G?P-(yBvP6JFG5eW?2I@oeUp7=`NvD`MI*d zU3r`Uo|w|{6P^eic))@{BrXaTa8_47O=893R*`vz1%Ee3-)DD|*clGX>S(s94Q;tt zJkS32Bn5lUe8fC2)Njy6-Q?u*rLVeb4rC5xGDGP-(sgwu7AG2F_nsDurwO;5jyBpX zbzm0Zj?nADmVqKhHSY8wsLT^6RC>+~>Tq9!mE{u=Ig6HXYbo6C4kuHC_yX8U6{Ya$ zD66yrB){r(AIgCN9O4jY5b^h;nt@oQ6#NqA?y7+byiWr>0am&}FsqqoNi2Asd>?Qt z*#fws5PrfE=Y2u(d4o{(M&%ORs>AS&Jg)NNUimo`JWBrf{{J!@_CVGCc5ykB;E5$F z#eL=1#^|mqa{mid6cwnD4N62Tixu^>XwM+mKtQP;9uK`OoQ?hMjkt8|DgF{30vX*vkgp$E}0SY|zx#_{+y%f6fYrpyS59cOOcY!9SKT@vz0yIuL zjQu(?Vn!{4MhgO6n+&i+erq;m36Yp@QFaKbzRg?vrF*dkkh8t)(y*f_=))Dfk4X(X zWz_o5_A&${mivbK@^LvysXNQv;h_~Z&c^z%Zw;1py3^CsehB!QT8=IChcaUHh=*#a zskAqp>niRpumRMIr%VziltD&tjravG+c8EUzPEK#A3rESfVKIzhqg4*6934DxF;I!bX*HO*R*l}k+9n*`2s zWlOVokor-%@tk_BP5_Ya%KpVU=EO3~03!oboVIZn*W0~S+m_LpUJ*KKD{Ks>M4?a_ z@tm^kbC?`b>Yo!>@Bnf}0?o7e>TqCsaj_R5aIk<#Q3RmTq7~fm;n6st9EmzE`{6~L zV)P+_j;vlh!N!^497Z8e0v1Feo1}_6)$-ogJ%cGB2h^GrK3Xm$_wZG{m%2Fk`Zz&p zI{C1*dRvZpaax;lVw*>UV?}nsY!n!5ob_4kDek^<&VMR{WB<{1EP+QrOG^uMp)p3B zOlE}3jG73ces`ZlgB~{U5P&)YdSkYBc9~0icl@8F-3>Q;qX2DO017M;<9)e)$Hgp7 zPQ3eeVgCMRc0S2hbSX4-^40aBo5zQMC?Q6VjEr=o+wlEE5OV6Y>S54cSRmrrI`$6_VjX!#eA(07H)~IDW z%47Sfb6X|)zkVu9qO=VY8!y_j9p-(XtC{p`N%vph-yeLtTntsnwwhf|8Olpek7vQN zU##~}zy4uyJ{sd2lz#Q?p8Ls!Hgb0sh6~+aA$m>Kb~VuU=GQMQ0PkGrKZtu#w*9$m zi@70p)0Jjm1$FfG=j-fjWpLfoLS38e%>6;D0vd!De9X;d5S81-GEkL|B7fva=Qee6 z!gMA$&`-?8ISVpt59mA}}tyc(Qgk>+*lpfdO=gh|xhy zF-n09U;sdL2a_Mj-_obH24%gGVf*9}Abvnv)h86z=IooF7fbWp=D4~j|AQ?7ihcI@ zmXxwd0An8#u=T(v3?7)Fg!G+bV`ELGN%aUgczQ6mY#BwvC?F1G^L1N_g4WCWqeRxB zLA7-o<kF^@brZ*>UZ z5$`M19l9GNMJ^BY7|_W9Z1C*Ts?7>erQRso`d8oaCnqN>T3e$_ckP0{8$0(QNA2q> z>g&UTgXINNZi^yp(iqSssR%}QT`B={9E!SaYipaevts&R1;T>Yy$u?l22MM;Ro_0f?&}>V{cnZ4%eRv z_sf=ZuXMVdtfnsd8jG|j4K#uo^zYYIqhz`JYA7f%X6Y5-S{hq(VPp@!h(|D!i4LVi z!LHpWCuRH>sw)TWzT-D=GGsq%ETV7)8WY-~-0`XDf8HkNJ2~-SU8PIS*A2s~>>OY1 zeC!5YhHlbDJ70GiIU-PGPH1MUIExK5o+g>x~Kv+q}PJ4FzJDp7Dv-g%2^NW!+;@`T}L` zaiq~}Ot|QRda8mnw;!tW@Ejq_+ zTNynr2AI;2rL!R|nK=}YNS=KV^#@=!S*u>RGz8RSb5n6#ipMgzz&!9QKadHR(p2jI7`tSlN8WpSgy0K{h?C(=`HTi>TQMtskc&Lyup+>uYv zf=3Ch^-1tg8z?_0@tM>wu?`bbUxDGZ-*8v?Jk~?$%W5{yroSSjXXI1ulc$R%xkgIXf3}tB}o4T9jmi9Lp z#%iRX?LlI+&9+`u&Opj$nNJ;GwR zN5H&>ECuaa<5>-|FBa@D5m$)l0g&< zFJqOZ1Jp$Tlj2zXh%5Rzxd&*7JlsA2FhW=b>@pc%Wq~FAuAOlIcS)YMYa(zh)6e2X zl>i8c7gstHQ-<_-^AdX8Yjpb;rEJrBRutuMS97*UoaEstkVQU3`1a4jCC7g4YU zO;IWWl3-|jKQ!nA)!|Q3RI=o{Xmp|TSY}*W6zpRHjK14YsQ9Dfq~qBEe?D%Bb8N0G zHx`!v!FP~bfNB|~u#E?h$10Ivxb`h)vbnfiN4*Nx|E|`M zQopc$lFbg3ETSJ$ud}>*{%yUTwpb@jE}+<+8T~XYKQm`snmcI@U)%v&YKtLn7Y8kf zv|LU8Sdg6vaAbo_g2YCiPUkK?F2k5Y_D^U&# z(kjjb@hSY6UJVW3Bk`^(*_%${u2EbiI#~{cF!^jE3`o7R_;!8%tlzs&rKFg&AI7;i zXF6&v3(}kJPH0))Z|OsITC*nlrfDbxXw4qMRx})DDg1A=)RZ^B(8JAt&b~B!$(+@6 zFUW6A6o`F5gdu}zT`bw9A;Pk#0y}OHZb@%dKeevsmnK+{PC`TpGcK1*;b*(xhhH^? zw2($__B`{|G%Avl{eEX~*+nR3=O`{bv63coQ}|y(K03F$VKp;XeBv;P*kcX5@WAeS z(9G;i}xiLJk#RZLDiwo#p; z(L=Fr164oI7|}*s|261_EymY9`jO<4%DUWqMvG%HRMhz1 zE}&Z1W3j(9=*C){czSkjK$&! z9ej3O{Bc`TE)!6bauury;3>@74as|k3*7A8-=3CaaoV`bQ#x)~a~mKiL!e`V2q8-G zFaO1wc*DZ}G5ntC#9m9X+NP`YSHqY!`=Xk>^13M(b2|#JdotN>hpl0Yc0t7ZKCeM( zY1@)w9}tiOE)N0{d6Gl1P)L8W4rwB6u&c^$uI3ItGz0Qr*agr(8~8DS1@U3dGB?Zk~Mq&4t&irj@O_;>59)QD;ZN zop1IRRTJgACrNpGZsmS9<(IQNzlIvqtsD@K(_3Goa7lMnwatW5hr+G7GjM~dUZuf6 z3n5AYP-+NMx9ENq_l*v6D&zC`LO24#C7WgenhS9`iv4QE1zG5Wk}uGVJ?k$SN`pgE z05#CVKXFRXpzPXSn-D&q%(kRBMk4V`vV{0Kxhi{iL#omD=UQOAI1v2)8rIz?j1}0*JE>NYSI03iXUVSlU05F$930t++=1~hU5CcaH?(mWHDN5-EhNuVZh8o z#8#Q5krrhK5O(IMt>(HxLV_lO3K(on#c8>ehT2RFs1XS;4HP1Z>qAhIHOJGZdM0Tb zJ^CeLvT20|6PaukoRVoJonU@ox69dNxS?wEWA!vZW(2NHbkX0m*=GX()zj!k14pbM z;z!%A2?}mSpqDSW>vApP)zZ{3yz5Ko<@4LTRY495iV679?5?nWUt!RTu^?%98Z?|t z4jIG}{r0;D(g0Uc1@r)NY6iWzo5nN>xEhc7&RCRUEvPliBA|PS0+^53MGHB)%riod zblBTm*oMjOqLye`FS_4~Wf=F6PL%wf)qjPT$F0e6-Cl3i{I>2C<5HoF&E(Wl#BQ*| zl*?)3;(~8f7~8{WAeMkei288D7%jSsim`+}&Ku?&I5s;B#i;y1bfI$h)pV1cOg?kB zhIxfo8M!86xoO5w2k&DLv0sucPyDMrCYA9g4;QjTC4RzWcsY#qgyUE`97QqvjU)T; zJJErDTJO8?-kK1O=?>*Grj&#foV(z_@+vDb71v3Lu%!hF6 zl7qG-ZmyyNkSFt6MlD*&!XCU;*Kco9^eG(hzI=0=c@tPNQM`mT}r`9{*)n#BRN_IvX z7k2|Hn`WBbMW&!x>FL0vu$BQ5yZH%9JDBd!DJe3 zGc+kc$Q}+FIB+~2&!XWPs_M_{{G3a!EA(mB>qTZj5rO+sZDGZscd_hZHFxM*MQQ9J z?cc;R&b5BRc7OSl7NdA6{iFq+K2oHdYpCY;wOHn)9>3ae z!?M0FQHypt@dZ;mpz!8#D&fEzvG`OUuqf$jne{XYQz%=(I!g*sG7yhMsM3unCaOfN z0IExMR^!Myz+) zp}g^0gFY^3qu+R7K*JA72f#2c+PSZvRJ14 zgAkW#WqJ4k?fPwC-oaL#u>}GO(>_LhnvL#t5lq9=EX%jJRgJGWMFmG|Vs30{pqc;~ zmthWL7!B=A>h4{FZE3?d~%W!((Yn#-U|93K*~}B@A9dk`Q(HI z3P3%Z3z>FYkBUxd<|Pb*1$_d}%=eroeU^sxDuee8d5@kg{2Xx-&${kL+0lu)6N57J zp4SNYM*(#NFkouu=I8>(=o49Rrh<<Is4(KvxOHT_25+?@dd9 z4LW)96EG@fRZIA|@fU!PcC*`$MC>fupWhe?@Od0EIFm2UB+74Bb z1G6g-jleDEwG{t5ZWLzu-e#(7h4=R=?|!xR>k!e1A-u7lCY$oX(zO?yD%Dx0&JiermEuN;=INiF9diNu=8J>J?6?Ft-Fmf{|MP8dkjL&gTcCX zw!1lXD_PLXPU^$NtSEi`!T@FGV}sBYiqVnhxBxLmJz?}A|LBTyhu46+i-qy=0zCl^ z1~97%s*diR5%(d&ChW7po}>J_EDAcTLKutmPZ-bW6lZ!sFCL(jsE|)b1Yj@U$KbwB zWWlqpO|i20kY)kSq_o0{8;Yd062Gt4m(-E!CSnyje^0v25eeN>C#QJO5a8EG{`Yw4 zXb`Y9uM8Od764`jYhCl>5NQb69JUJ+0P~3eIlQCnxy4n+o=qU&V-*k&p3Wy0Gf9d_k-$6;I-CecyMA{A{u>G(p#iunrt@x#=1mI8$y2Q?JA$B z(LbNKRu8rZFav>*0;!^GXK_ywKP&m)Z2$H~cE4I-{0#-VVJt#E(ztf9;L(xtNWiFn zVp%&W`>ZAb)UW?!&kb_3IX2+v;@_0Wg*Q`LLEdWIsd~a3T^2gt0EIJ z1zlX?v8{8vHv#gm*F0noXKy;aEA@7$ZyMj$Zc4TMu{}!=puo~MO43}t_b&nOrM}5Y z;l_pgAzf%dhympJ_%bXT*F?~st7O8)ksb$#e{oeMgNGob8e10YQ;Ka>2CE2^=$;dR zX3$LvJkh=FOAJyfu**W$tV@)Iij#_ZNttESw9U!1iYkHJKVg=+;h{K=)H7)@1eIm? zzw^hq5J%wuygFd~!*9RPDD)85UF$rDoE(zC^)jjC6HQ&k4||(J!aHg9J!BB5e^HUcEE67RHYbxeMGw&X4E? z^>{E_i3X}jFez>O{C6nr`o%}M5@GQ$eb2Q_!ZHvBAzda19@T(+RTh_i!91K^(9)p` z#R^J#bovZt21jAdrP!)}?UQLyl&#Y^I+wZp4?D}WE%j-)9#ZHxyh1RCB`*r-Tr&)w zO_cSQ08D4jQRRH#%L{sGm?O*pBQ&;r@A=eajcN~aPO;SPlk&Y31CdkVi)v> z=~Mq;2!R3vv~Fo)@_=^n#PTl&x;cK?naI-cwM4V)+7=5l3SNP42*hL=bWf(;#jTEF z8=o)hGW@3JJZhjkMzEm%=A(3wbUgDgITK_G^<|&VdHcSu^r(Q;v3*v2=ULkypPR#* zA0N6EHhMfy{q61<))-I9Oh(qVP<&5gVvc@^cratdIw4*IA2_>W&NSxh#<0xfxiago ziGfEK93`UKWaz=$j(mb#l}+y%TQO5Z1?wo`vJ#u4Tj|tD3V&=W_g?+Lk>$p_bcS5* z#sgh<{bqMOU+SAXpBA=zRk1I zJ)%M5^Mj`)%mm}91alw%4@>7APj&zPaWk^Bl8#lm?T`_&M}^EB9DB>&viB%5DkBmh zD#xDLn=+CWLRNP6-oNYg{XHJ{; zW&X6k(TknJWueLPm?%l}YoatSp26kA{X_2w$HD2{gZ0XJXKk-9BOcF|)^6ssfnRq_ zZ=%g|ig)~2eD`?Xo{J;ev!x$w=jMX+rh=S#CANEFb*@Q?2?JVY7&ndw<^zg9EGH?x zpUrZ=g8qJXmV}ESB2_(K8=W$yJG?KWtVjR{^?n@Bi9h_ zg7<0WN$|fXhVd15XJQOvKwV92#X6y;9>x4Of4Ufon22ZhaV-?X#JgY0%|@-wBo1Ht zj*tj4_Hw@#t#T0{MVfW5#&eB6iya5+Pj$%c8)<~lZ^|{#+6gT$Dt&#)O2eyXMn!~~1Jo!mg@26xlIAqL?Eb@E7!2tcn}>Hh z&gJgg5e>Ds;obA852&7ZekQ0w(TN#&0qh$ z&p?4vTMVsg4yB#h&z~2hD^{ldPTsIi7G=nL!uPw+snx^OVpp5!sawZ(l)Agxo@>pYyDLCVYeib0 z;M%u8u`H@HufvAJZAdCCAX19pmO7>W?l+rU;y#TfuHRD9c6hF(p^!9BWRnXYwqmdh z(a>XN=i*i2j~jM(1Y3KY?S8t|yt~&sS#y2k&z{I!^lvWiZWt9(!Xy{^5UBIbI6wPX zHa*5unUCLB64I`nl*#T7f)b8_z=OkdoEFh3B=^f#j8K_!P*MUx_VUAJ*PQs=&zDOe z9YcY)plhQ@JU~g2<;5=@HOb4@lNyt#RzbDGj28Q2h^c`g_zeSdFy}(Cw`ksfuj651r0jciGqXo`o#(B2o32l^^~XluBoNb0wae1jnW-hS z*Ow*2LWOu0$Ha6mZk91M24xto&bB?D6Z!FZYU87V;Nw@fFt*AH^hhzZPW+*^Sw5fZ z>f&)U9}4K(`jlk^%>O3gx~-4pVRs|wxo7h72^{dgzSm&{YgFyi0IwQVIjVJ3;hLjL zU*(M+_xi8Q`>{dpUqcq9v>eJ}@mr_*#^0ar>~ zN-Sxor^&tcxABxH)=vYOl)J=OgVFq)ad!J9#Uh?@#(orKQMOMjuBsAj4@cduSK#ly z^SDG|*V7Cit_TfUfeI?>OAJR&PJ_KJq94$dd_|$Lm zImd+L$32}3lIOIahUG*=KPFh5t`@fM4zbfeRe0U=O>vq4it}Rb>zHt(Rnc^g&l#%h zbDsX0p8!`!`~JRg7JEn+n_SY$-n^0NP>&MV-!UT*v_Az!uEHH%v4{s!N7qHX{)(&= zhUYppSKiV>xggh4wdVB;qlCK+XxY%FdgZiY2YlP>Yk3dNycBl7gNjK&hL8q}TaI$F z^U=1YS9;t#hO6KckmF#)yhpjOErZ`jKWA5M*hi<%!!nrpNk<}Pi zmlB7-l0Che6CyMiyuys!&{Un&g&xiUzIU> z6j(bugnmqrmZWdgi(+Zm>n&2#GQgz7`lK$zK^?$Yw|58C`urXZhNhvzD83?Nmq*lT zsNZ8<{J7@zU@DTmw|~RvL3bljU&)LfW#q!@;bBUv?uy|0LEO7_0T#Sd*V=@+(PuZ# zk`1JZ1XleFhRqw)PYthUY?|oABMZI`tO*U27FU-9i^Q4|kB2pBc5P1)?~5OO{_VfF zrM4(kMeMv=#oZYGnCU_&KVb%0BIBONT9nq8L(^A6SfaJnNAj8TciQ;G#XTYGs6-w4 z1Mq`DpdwCun-G*YZQgt{p3QFNZ|x>OB55MPv1dvRQV~gHyUG4hwJ1z^Vekox2aFif zx+tTKiXvy6!)|db7(- z`ainFM^-wtUfHtp{%NNR@G3x0c_MfRSw>R2RPb-6`DrNbj(m!&)Qind<0ChB-o_|3 zi9L4P3M|ek-<_1T(S_vi_p?y}Wp(j)F3crqWZzFNPjAmF!=Dw)`Sj4mt3k@U#h`lq zPcQpUb;v*r(L#?ANBD&64B`w+7KK|%9j($hikHmwp}M8dQDJncK6vVA=-QCqM!?0= zvLp<%c^BVMyA@w*pBkL4o%>NqqPg=~JJIEdP%S;0etRVk3){rszurElzv#TLVe(s* zAvvS;mQG{p_@k){K@hkinK}kCvz^1FC(Bsa78GSJ%-<2kbqDWIwD-x-lr_J~e{yrE zO2Te`xc+?Xug4k6*xF0MJrE{;p#U(QVtdQ~RaSWr3I$Ps1>KwvK^?4xxEW<$ zuFo^Hx@Y#K*5T%lP8A4i94#IALg)J|>(dhs?$%r|Mqr2>3e@3GI#k+RLdw%y4*Wr7 z9)Fg`@@*e_x*;zEFlciwMdsc;wLb_x&#n6C~Jug;n&v z=?kgT*St3k8^er`h90nlNvE}a)e_cN*3uHCnRywH)AEY_yex0`VndNI7>sx0o)lpA zP|cwZVP;oN>K!}$LmDF&K0ejZ<<|BaVeuoZ2un?mifx7{Xw~~mb;EPzyHzd=hudf8 zTZ8_$!h%*s7TOf6W_#&HBn_|Vp83_BSr`Np3Pg9^zDul^6fW2cH-L?5QeJr2G4ceJ z7&$zB|L@k`I8uC>IbX7oq_f0S-^}%Q;!(47T=5t(9O-A$F*$eKtM9ef!TCK+G*lbC z=XT~jVe{o=cO>w49@@8n%$F;DeB56m>qLey7#zd@WB^qH^i|#)gg-HDo*@BTB;Z<@ z$gzod=Xe!n$V77GzZ}X_RSsoLIE#1hYxlVU_2E)z06$#=V$%qLj`r4aL9oQmZS!DU z`UTnoG{s`>sf8W%jf#J~BgFgSEiIoVE`BX}sz38CBp;l4;8@vL$jTtNxC9&;?1!ZY zo5Ib+i#?$aZ*{iXt)-re_wm!maI$UJ(C4{|>3<*MPvlf$?k$^5)G)c@aYu)vsz!z- z%1pX#>3{&bJxgTg`fA-Zn^cz1_|D<@`hVKzhS>s@noDolHV}{R^pn0mIm`Zd@`zBw zz9kPVFp_^5dC-H#gQBau;uwg539%)i>3HR3?^zMqqLENb)YkzL(OgGz0mqNqU!sZ4 zMjDfsJGBimzvLfPrCHa8pqB$Z^S<0H^Dj9rQ>P>F(J3ege218=8TfiPa$BTynE;1UMr!yPvIhZ9X+)H4?0QY z&9H2WHBaKb`?%>g*yWsSqqmPkq2`-CMkSf@Ex`bn$`;%?&VqN=!r}Cip?H(jA~8;+ z5W#)*tJ`Ik4pW-#2}Il;F%?APR0f|P>6V3X=TQG^R#{+{UlAX=)cemnOI|0g^VM~F zBVhNjLBJW?p;W+JGPr+_&jPCb3-aChE(AQzxN(EFcpYV#RY6Y{mkdrH-MnIQgvupRFXw#JoBW^9JYt?d9%x8DUDOz5QEur!LzKi2O^WIpYAec`SHszC6{rBCQw3=?wqfeh$Jm_|6(;R4CjN9;7l5~ z4;4lN>c{2%cE`YYs^xCuk;>`uVgNQVG4aw~P43!dv%EWUMK{rYskt0kA`#|S8x4NN z#_(a@FT+GGA7WEI$6K02OCI2N&Hh&W+2`H2i?O$wqm2J8J**l{NV1w!?@9AkezrY4 zVGzvdJdA}lDrzm|zNILJ)Ck``8=9K$B6z*#Tgz3FYi;439u3c|skL?OlhBuQ*Yp>* zkJh`;oI8iP;|^RiG(j$J&Ae?`@G1)%f>)hRso644neQuJ;=t-lvRY5f`#m}&W8(Uo z)_H!L6=K;`?^Fp~5OWWtj<2M9FI)q|=9+hiXYCPE%s!PyWX+@g9=;Yy(X(~1`uz*! z=@n$ruO15>Lf<%fdqDvuob`$DJ!lNGA}!8*O~sQPPb~|hvte68Fw+c{mE=zChLBE*v6qru3o@9OmXz#RU8{g^!IrxW zzrU1Oq2#hg6@?Wl0`BjCMyI^eU16)N@qYs;@;Y|a&EAbuicYfftv2&GaQ;aXif$3V zyS=O~pj7OhsGV-P1op-?-R#mZV`T0lVht_-oO!NXCG2|FX`4d#pbFoPz8Cix1E0;F zO7z{a-xnzV5X0T~^49V?`WvFMnE8YB`OYrqfNu!n?COamG%SGJXhsjrkan0Rv4?6+ z>Sd|LCup|c!5tA=@f=z1n{UL`re@NtgAWKZ*rj#2SlY-DMI6l zQcN7d+>A5xjpui?l4k$BW@=F<{F6sm;*LKepE%S;FgLRg+4#TcB8X6 zmILAfB*8BAPNt`=(I`#c{_v|$AphB?!@Ix!sr+E`?TtSGO%y^FCVa&(m7!?o2dnRW zpwet$bdi5HV3TATT}>rja9MajO9Y1u{EPui#BAXZk=*&jFa;TRf_KQ9k^3&CABxe5dldb&SLk9QF-6Y_=S^d&ig{3y@|w{$0p`?Wz}Q6J6Qxq z)a@dH>)hvY#(}hzYk!G~+^I~--dM>pSf*tCCo!VL0YNDERbbX7w5>3+Q?GVVzpBB3 zOgp@fBxM!KymvMdlti)e-MU-J`cGeP=HfxD4b*&6no<=pTJD(mGQkGmiQ4mi0&^Rs4a zy_z2pnEmrCzxla!!@|`BMcLlcv}LcxAWk!^E4p1*TEW*Huf~wP>vFwGq|Mbp1Tx)T zT9KWr`z_qvVCBW-$g$zIK+>xGv(u2*6}-Exy)Z5k@Ru;6wco4P{it%)V(?V0*+S{K zRLK;&SMb}~*j$Df6c~oQa!TtyY4X_>VJBP>n#~e9M#0JTf_~cGO z|NOpE`;ni&-~&uLV1VGPQwSy*`qb=Fas!iu6uh8dQiE&tasO(~?KlR!pnvh9LW9QV zkI5OrH;%vrFTTvZU`*4PU@A^SZ%Gq@$au5zdeJO?`B2^!h7eG*xVV&j(p}#BZ(&7? zOKI2da^m7sU0D$!l^R#m;8{GeWXeiIJl#PCovb_PXN^R!a>q~UVUdTt$)))?a;ukw-Rkv73`lXEg8cNbADT?r?}r3I*J~1lJMiIT+lwU%_eA@?Bhno^&EriD~vuAwN@7XK;Aaq`@^bn@wR(6mS21^=T9W9() ztxMSd`b$Qyvu45vWQEjaOzvK+xxzaMJ9Hp>IgPfO{J1OdUswVRdti_==*ICuKHc(* z%b6HA2mi=2oI$Bdl=X%xMUNgg$-mD5NSzKAGbh`uYz(^DJt@)hS_0DkTF*XRfP?a7 zeIoZ0xlg$3|C*azH9@drmW}bbp%XMAI^B#(wiN?0Fd9s&%!Hept>kk6Z4n7Lh4{1X zogLJ!0nK>nOY}sTwsl{6`_az75ER77ChEMYGLCwzH)rDf@Cr&(rTd}>%gWuQAE)ge z<_^mvL-NM`#R~^0Yb)7e$8YwMYyo9<%BZ2EFyiN~lr|Y#* zSNh-nQ^aS#(64UKy9#UfYmYLKFy{!G4(;!g&4MGHsDHT}2q{Sn)$ zV3C559pWaJ9JjUoxd<<>K#Bqfa>rks&&4q=hqbk} z8_ziPp9Pt**QVbTyn8pYJ%<&q0SEyufNn?=-{VV-xg=aw*)gnhd>)>jZ_e1C9_LXb zW@ko}#IB~a#~U;M<7ip`wPw>5(K;{U^fLFxz|(T_rKB-v*w7OgBoLTDE``dtP!4aH z14jsxMcKkcFsGYC6Qw`Dnat&iopAkBym10wD_wfPu?-*^Ar+BqrK;BN^$WAJkkDv1+OMRHLV@1T0Fb^yQU_=UDlETg-}7j}wLHNTSRG3nKI^ zKh;(Dma3F!qrnoAUsMEO88D@l(63_uGZZs=z0<}e^7)-8C^x~=-2yiUCMAK%_ngTv zrLWFRH`8$Q7MYluV*b=YvPDy!zY2t4u!s--fWvQUM)yAsc5Kac!Wav{Q$iS6$)qE> zV(N?WcU{IfmPfYPg`01XzCvf2g*EhnHU^^FNQVN>4g6|K^(2Ds1>PVniuwOqKp}uM z$m&Q@_SA+sT+_fHx%iWDO67O16M#>Ul-%n)eM>Rwr_N-q&Lu^k>qrbhi6m=6tOCeM z#%IIE?SpDkF_?f-+eqU%DTJIZszr|mt`qDDb4rX>4cn&*ZF{qR(Bv%gOIPz#sbY+k z$~a9;u+<6AqEJ{Zc0i5RY>S<*^VWEsn)l8AnPUoie95+wwWPi}qUiMC;stTh*-+Z( z*-xi4T7W#n-cszDHZ`1oKc$nA0bUx5F`w6#qrb-@7LPt9hyD((VjHc_&?lMtYYxmm z@DV^n3KO{>c7)h67ua~xtHK>eWE!QUslyd~J?X%Q2QKY?c6sYU5K_YR)I%{m7WAjC zJUmp*D~?$64^U3sDW{LU|0%Ix=D6U~rx-TQ54&5AK6059I7!9-36sz!dw3!K>RJGyVzQJ7+E2{J0QizF=LTH=u_@9L8%MosL!dUXP!s z&?u8|@>I6qeFJ99ytKttGR=w8G4km)Lxleymp@9NPiz{Vt{I=<|131(UMT+~DtX)= zH#=sXAvAnh>=WSFdhh(1kN2I_(*=b%@lsNG)Jl|yaOiI*9aBCA$KGESB6hwktv9mH zR0xB8>SH6--pRro?unIo^*FGG<6SL6@*Rux!=z`vmeUBoEr3&Vt*J2iEmk*$l8#0A zKY#vvnq;1+ISMXWsHuOQihCIeeJy3qvE=;u5tpazN4A(rgCC-17X79#@g~vDHjNiE z&V&HQ5`q&j(O(#+(y}!V^=uB$_-sW7u7=HJwLqAp%mrMO^xq4^)Ke0hWVd@k>cqwh zi^rli@?8_E3)ttTrM9!pD9?o&ACFOqH43Genl z5ZUR`4meGK4x_852VWIIJS|(w@l^@sq{a`(P;^(qKFajxi?y(%1cmU#-(Dhf21300 z#5vRpuJY1Xrgx7eFc&O1OB#>SjZsr4^;4}ar#J)L;d%D|r8&yIb^JPx9`374U58f? z!tmAA;TS+mb8{jMoG723NW2`-(gz*48g%ks4uc_g7~(CxV_`tMm~y!|s>qTmQSEq@ zlS#)hCL=n`QgO5r(w$fEgaqjo&`Qi^21m=}n~QWhge(GDVIKfdCjD3!5o`ClJ|k-^*E`r7L%VHP4&OPF!^@R!{4{c ztv2Yd<7Dpy&n0_#{P9W*y$#&)(N}qAe^uC7g=Wm{^3mze+vgL4Qq6vw^E32!w6wB4 zy}g-6Ma?b-hXE!F|C?jO4x0ZsZL-BuyY0ZKNKDjPpDtbx>ODlGS2&{n}K%{YApAhw%AvSLM{P?48%pTVN z%WtV0EpGXx1rMiN!jYJd-jstIdZm>pm)~}|alz{X{sSdt^`R9N`d$Ek+VX8Y@P(K-uiUS#d8>Nt zGC8zg#~o~zsF}L-jk!OcAAfN_!g#czUbCqsnyQhZw3)myS<;yM^^z`3!z;HR8zPT% zk+S*U)Vc0Dgddl@Q3`g|^(&x-Iu!aj5TGzfo~h%XRhzTXyg1+xdFM);+;+9`P(j>p zg&I6nRXP$W-Mc4(a;Y()`L^#NIK{;lg7t%Iabn1}A|*6>s;4I}qsn8m;7y!IQQXTV z8CF1IjJ08KP;fLWC*MwC{^r6k8jFjz{~Vo7cyIik)o&zSgs!fxGd(c+7%V*1TN`|DUgF*^tD7; zK?AB{##v0n|Dq=8}~qOuP4#>|#sm{K4tI(}ggm+WFq$6Zfy*#glkwXy)cd z4Ckka|FNLt`Bog5>25qXrxJ`=mVP20-jznEjLr|^6yNmy%>6z;E&ypPZPl2FN};ne+S00WFg zNC4KvMvq8^HNl~^#Nmbgb#N%$QiQPxQu|H}MW^z=%+cz6$cy)yq)0GflSQ^u9F&S_ zIiXZv;l<9qfdtd0mOsf{SMgRF_jqY^$)!Xk?z7*OehP0Hez1%hQ z*Z6BfLor3XcgU?+(^Z)ti5K{Ir3NfY16h=;eat+>f!l0>A=wY&W;bVA|Gl?VEO?-` z2@4Bvs$DEgDSVuiNzHXeSU=T|D69)Pzsn~|;a|k3Nb5Ti-MEuvX=IrJ8hfT(Brsqw zg3t#WJ+j1u&965GSSI1Bk3EBG4W3eVIZyUo9kSXB%@Xwsixl7 zE+uXT3y#E_iXFi}^C5r4jwchOS74RinJ?9O&wtHP_3!$AgfU&^J%`fd0rM9KrUl`%x4wP|o zEgZ~?zWOjqFG3$)%nh&^4K%)Qgzg-z+|^ifweoAK5aS0X$L@73uZGC{GzMLNerOIb zB-X?8gGMJKjI<0kgJ33@aWa5Ky}P>`+@ooPr_1&K>_}IlsLBEw$va)PHe2H!k>Js2 zN=I#RMY3BzVpV*i+J$D_KHgd3CS+kHV-gL~zw4AL^I4JdD%;NdbN3|cToYTw3)36r zl(NX=tFcHie1&x8*!!EdduF*wU2M1CaKVu8W$rcAbdgvS)~2|?Q>xSEz!Tilxxmvn zm!;{U1_2r|C#-^y5&GkQb| zi90z1dWAc2I9R%Eh3mOxl|)4|?Bc)(jWThS)TY35`qq@66tC0ww?GShE6 z-Imn1e3ilY{+6`1{x%tdIMf&4%zJzZ|HYc#=l^(CQdeiMG$OLG8MfS_?ZGMj2?AS?mHu1i8*J+}y@ucd4EbwCE zf)+D5bc=1nWe3*l$=@<)N#F)qpxInjYJHxB>XywTNL;-3_s*C8neMhA*UVN*34(60 zsozEFf;pq(Wa{EPV^vgq`|C~MCU~76ExLd@X2xEJw5Oq#WhS`^(E(r_n!w9-9oWmi zCfZE+q*E;yrXb&yKVPpHGzO3+S+?#-4B2@MtqMWZ9WNkg z!p(G?jJwvJ<96uEG8UTN0yM?FPM`7Q!ry?8S0_3Pm?9BNPmkNPip+OYX6dhuPM`$z z#{bOkKuU;8akIQf_P5lmoNgdJYkZZZJNjzjD-mc`f%i({_0+IitF6ZB>j@-PDNL&~ zi$yxDt?XvN`wKnXNc554v99sEm#`HCf*UHMg`u|@^f*{O>o;|JF1^c7FSwnLd8Okv z0xwSH`Bj1LFtplUN_y53dcL6nu65D}P$Pq7?A7OWh*PdA8-s;w{U8)}mefooXhKeo zj_kpcic~5jDabBUXTP6ru>~G~1nx%Q3&HN_A1l&VJdXl`xcm4KFp(o;2?K)H9Sj*6 z67anRJRfX`I4r6s*;K7F8#c*Q%&!rHkh%9GO8;g zDN!B7E3FRen80=$bFI;?j;i@|>G>R8_I0QC^Qglnpyt5?2O8)Mfz&DXE0N}x*$<}0 zPQy23;QtIP7iWO&KnxBPH4N;n;j%zyGa+dF7!n1*af#9BFP?k!a8s1j54L|-y*hsH z-ssqG8CXr>EGU~~6|eb5nppbiK&X|Sge9j5nhCh*_S4orNM#5ODh3)VJ%`pG^8L*R z{^0as7=a--Kuj^$0Oqj(NNanA-AHj|WyJb-P_8b$e}qhN{8;BQcU*Xcg6|t6$>MaE z@*`;2ycH2QRbIQcW~TbpEj&-i+LJma_X??z=0t#}{ozIQ`(hG`6o`qkLhdEu72qD>I(iQ!ZOS~4^;)dE7TU3WTD zvOL6u+)AQ2x2bLP{1BZbqO{AT5egI;Dq89)I$JAO1>C)8I$h?+R2UC1S7*lgU|$8}wYf6p2BQmh``S-8P= zfrsQ5*ixr6B~TyjmBWQfy8xoK9~74 z=(iZeZGyPFft=U#V|!)d6Ca5S^djOHEyN!kJ$PB&F4*{Ro9+qqUn&-cftBFb-p zCG`0CQsLB>;Oiq!CT@1uVR)(p`){r!IaKVpF~Ihex1Cy~2DvJc9D|6?=H^fWjFH+R zg^^5(y~<7D;j2-tH%LbsSuB^d>Ek^+1ukW8XcIuynxo1%!~=`@K)J}6Qa4p4EYZn9 z9XaXBd`1j6C>io|a30+Jkao?&#+Nj|sPOX$TL8R%U~n6^D#{qy^{-3e!zrz; zkMXTW;PPbED{}mgYtPjgk%cVsaqlieDCV_(#PcrfK}a(MjaQP6yF^vCxU$zGFPC;i zvz2bS6p>W8d*w*|oT+U{v$@&%$3-5473lRGwNc_YUCub?XxMqT@dyr|!f5Dn0QJ73 zTPpt6%SEkE`tQNX*U}!6fR9hv{^y(d{t5D~1P71yR{ObURB)`qRB@c-W8?(t^Us!qv|F|n)n)a0pSt#q@2JOBM1LTugAQAX== zT7z-fUhH(ACzl_PF|v=C`YwQ%qtfNP1s?<6g?ko=-vP>2Yd_8tb2(<&L4?78jSo)1 zLgj1-Ql%^hrhS_6ow|_J<~0ZlVb|C0I$|rtRfb8(e zLaiaW-M)CP*`ic99zC>2(FQCh2V8@fgVBlb(c@b-Q4>AS6<^MamI}%xqe2vK^GvLrntOL9%BA#@D$skWzZw4L;!x{r z^jZ5W%6*%AdbIzh*L&Wd!jwBW$;4OdG^MSZwP6b0VDO%0)uWGOn5Dn|kH zy{SG<_u35*^-(p4qnvk{^@_D(O#<*`%1Ak=xid`^FDv83vYILeXS-pmGCYZ`x`G1J zGu*3k@TIGxP2Jq6qz-4uA*T)tAiAzmZkYa?po9L%p2LSA?cdnz%{W3AHAE#FpK}aw zhw6V9=TP;D8sku{?j>TkZsob1HTI;%#qgnMx|>-t+d~-f`C1cb&}9uf-spB^|0D9H z)T|}B9`~g$o1EswYsOQXo=G}N*vmmUvwt|G9pA3Mr3e&+c1;DCZ z<;EAxpECQ|g}pg);*oh*2JU>J&p<2)$bH;yPI+1rlS_X;MZNp<2+Jo}e(yv6@r1|b z)x_3Rv_8dD!3@onNr~=K%$~3(g7N6A79~|JF`A2r!F+p;7l1(|lTPS#7cDt$af!C& zJ`?J^Ms7A@s+F{uNFkM?tMt-xu4{|CTjeWKB0xpwDAl(A&cqbVt2QpqH!!*|Rp)!S z-T~XzTDi96;?g1eVwtoWf_Qv%%(3PI2I-xZPsuT-!fw-bvPjsY)eyW_p)caG%>s0; z$iUrB5w9hRSO%#Gm`Ljc?hDkN4rZ8$&;brn&TIBLo6AB;C+7C(>E(TcodeE~cd8#p z2L$M4=ZQ2Q%GV6DEAk_DU*>Y?0XcbL0j6egAow>-{F-CgJo{F)y&7;-y>YS`iq){# zOzw9WaO84S-*hlj+s>O>QJrX3oQG#X?2Kok7@kTh?p=;MMZ0jzNC$Qs0G|gcY`|o{ zymc9~I1MAuK*K6iHdZ$kXt66CU;3t>7BAR_=I@>l*t{Vv1qoA2-T4>P9MSKG1aJc- zMm_nBVPO!&Js~cRXE>kd*^O7IeQk(#7{F^OnJtQGCN?%#Aoj*zS7Ye$)5w@S1Pe1- zaR_gnan4fNg#P0Tw4`mP39u9jYBr|83#L=ta(xGPv3Il8)$NxV!=ww1&-ws-@#3rXWb(NyPSr`q!HU_N0V1% zMX`LTv`mp{PI5>|;i$RuqtqR(Xq5irL*kJdPLS+v)+|2xs#;jD@xz|>?Fagpj>1l1 zhM~VS&XdcluojFboIuBUq37D^o^c@Y)!S*ETt#)7*U0i84L3o_u~iZmh){gh1n$lX zEG6t%{la$#;_gp9;n2Kt|K;a4rS9NPmo#QoN(}diQ}s6_VZF?CJ(SIl400$a5_=6a zl`QUrer=OS21}L<@Wc)a?H%u9Kv@ca(8t7P8^^~z&snaB>)HKZwW1vz9Ij%kqlENM16WK^!uI;#M>Tcp4!X>BK@!m<($KQu z;I=kpRn$a8woo)|Bp+OFE`^{ucT?q>;m)4>=J|wM-wbS}NcC3z1!q6J;XOZP8D7CW z^w#At3TWc2xWSb%A1&BUOwuGWv2t(%efdgTG|oav0`8VaPRXJ-VVAiLW`|K^XT?)G z%wEQ&;E&4d$vR{$9)*PnpML=%mScog3W>z;@ zw1i*dGI!~G=i)%>rm7}@La9wfLLBZ;ud%a4-olB?~-RYiy2zE@it-4gw3Yt1Ubi0bpDP z33-diqc4;R@6(9wJnwP9m@C0U z9i8{^+U;zqrwmuYIM;qNF0CVxO9xZ!!Gfi-bcsG10FrKgQwu2lq=ZX>CnREdQfRJc z>#h)D$gRR&_AsHJ~Fd-VOzu4(~=3Ef<88o*pnLTmcg1 zo4ATqNv^WiU5CD7uVZV`v-*0RLf^{`zq^hM<;m#*yBwe0n*MFh%%$hy0JTPS4j=EL zHL`Wj41*Yg4x9vyR2jDYwDKr_SrlA(e$%*2P21b0Hm?gMg}Y0gVQJxMZQ#KMrh9vw ziH`-&;g^@@NS~+JsN@gZLVehQff@G+#Nh|oSdYYwiyv$se&TA|J^4^-%1f%mwy2O8Ad|ApDntjjCw_lq{UI-@PU4)K)Z807?&>GbgTPSIWy1m8Ixy&ADM#Z zMCLk~@fk$}=(K+{9T@rH-z_wLP^$qymlaTVg7AG_kGXMcvs>rvgFJs#)}ewXQLs2~ zfXvzffk@ztcow@nWy~gwLGdzRUjm58g+`6BTslQ8T<9W;d5dd&ZZm9pL}$z}7yy5Y zblR=MekkB)6)LG4Mj!@$8V91jGn6e5yRO?mMzJT(!K592U^EG{0jbr~-m6f*d~o>s z0^a>bvkeh4#CWi!;zN$8;;sY86T9a0ppV|EUWWyH^686Se_jq!;JnFrD_3unL8yh* zL!!2Bb^oW)^#k`e1NOq3aPg7DNPVQxxD&{h>5H&Up<_|amNCRMB#rQ`NW4-pZ%Hm;2(_Lgf!s31L4KPy%tWYV+Rh%D#a}Uvf4XfXiKPyf4k) z%I{qP*)C<4?xtt&`+?}&c{?Yt3d;op6RtIS^P}?v+}0RSZ!>`9Tc6|KNwS=QO6CbN zVB_n~L=PejP{Z5Xu47${GD@ge(@i)O!{Qgj+M@$558RSTYkN3raia-?Or^W=!o2Bo zbB0uy$rj~p`Uy_>3o7-c=OXQKdD7~=7>UPJL?SP(+GHxE#LaxNCij*LH z|89akIMkGV;yW4`Ne(vH+O4jFBEAElro?Kpni{z`#_NyxnE$hW2oEQe(z=x~m}LjB zNCd`qDWix78%7xC4AVI*?itKD7X)u+Nl63tc*zyE%Sq&jreNIe|DL6SpPuQk{RLO| z?bf_5^`{bCXz`MlnyJ0oSY59f!U0!+u>pgK7M~QZNAV~>w5aB-$sg63uKZOP#F4`b ze>e@N84Dhi+*{$ie%M@G-D29%=qb#bQ?opOT`J^tdTReb=f9=Aur2O9uxt#kTM|2` zzPL-R`n^L_fGL}CLDEitX4fq(9Z=0BP#pnSTEm;Ret>d;e~a+ z($xAy-5b%a>Bgxv4nH7;{YK$q76H__UeuboDrmu+r?`epjhD zwopfEnE;c>^|5JniFVBsCLg+Y*&kZ~4K2ft>{%)unuK(Q}JZQmlUoZw)yr6tPq{jO)x1hs)&e%e=5+tge$zaajFLXtZDj zVuo@zN+QpXq+M};Wkmt>I%y7Ap~cvFwQ&;ze}#k?dZaMZ*wI9Jki@1i@?GBc2d|nO z3Mv`|U}M0iS5QUm=l~kuA$ApY!vl6?ovYvBrfHh*94Vnj+ODpv`1M{ujp{iJg*1h| ztszn*-yg!D+la;+9h?i2I(I2Ss+zvnN8md!Sj}MN>EJ>oO1OT2!o|P`~Hn zg0wvGE<+?r_93C@HH*tESorK(T#a3E{6|hGf(;*G(jddPUw%IddMLj^=3^mCf%mo4 zofD5K5{0^EhTZ<3oG)ix-uFeWUzfRf!skb@AC(_kq9VW{GW1w2v;Rp?eqn{f^`g3M zqVwLyqr0#=gK8#m(Hrg};YMqW-Kvos3&SmcB8Y>9K{iCs+w+uB<0=d%rhm&Ze(@uC z7=xtL4a4jZ0YRb{7rLl#aakqqbk*?>?}Q8Ld{yy6Hgx_`CRadSkGGIc!>+{RuB2(O z{0HDj+~)4giPm9e?IIOo0S)7}v0i)lFcSKGX2qzAZq0`~#L8$=EUB$dMvL zxk6V&NXgd@EUX|bMR^%5Nk6>CJ^jXT&yO*XaY6v=DBN;Ylb;u8G6HwA5PvN7h*;$L zr<6H%Ji0k?BAdv6I9B|y7wk!Dfk7@p)D`x}tOi_Y3`lJIGsQ_Bv%?0FU`W3JOv$mz z`V!8)SXe>%!&WGIUsHe}=MC;WFo(LhwiT2!k>!owvV4li*IHomK3!{=MmJVDroJR{ z``6mfdwTskq@^&%gJTnl(3M1#!EjeDP}1A@A(HV5S@`Iyoz4PU_t-*B2R6~z?Z$iM zXjMlvoa%{2JK7)YbBW%p8(>oz1W^C8LP>Ie-(i^z7wW4Q9UHDW;^>lRzu*1i5koa= z$x4frX&gVuBGw};gRB%=ovW5yU#e_zq51jeZ2-0mX8)-5|oqAB`+yfh_QEVz~dW2Fvjkp;Zcqm{4nVq(_N#KLC8kX72EJ1fo)WSm$KGqWq4 zm6cVnx58!Av*d5p6B-=E`2BR)^pfhe)b{-DUi6DO5qPriqmlMDTmj2Ni8=~R zhxEpp7yh)}(RHU?ysv-NqXc%FgT&uN&N;%+Sh`VjJGFPAZ7QQ`C;7ZS4|Z~ae_0s4 zwA1xtZ#FFd&2yUM(7>HKkt+$gIhq+m$UxyNN?prbCC)y9KbG$kk$ELn5{1v3*L~|$ zE<|7@wtem|!cI6bAMU?37}G*m4RXJIQk}TU2T`BTv~r z0G?=YIic}w&XVWT_X#1ZHJB#>cJE=9EqyV9)v{prr)`J3ZvHNya@pIQ1>2nY-Vhe; zcD8Im3O*430pl4~LNSH4Xq1)m4paH83sRCXF!simmR&Ov<}NH{95T85jDLfGtXBz? zFhE&A){FPehzK)+s~^*bS6bdwH2a{aNtXTnQ)y9zm><0 z&jhR)xr`-va!b3rxN;YgTg7>0^FR1?YYOQ8DyJqA-Rj~FDy0Vk-l%PbIx&vDBaJ>$ zD_F?crB@9FY8Nsyiqd9a_e5CwJYEnY!u_C!kk>q#O^__LWhkifp^OskDuY2w({)Q96 zRz^MT3335BZ~23v)6&iff^H9#P+BI-oC4huUMnz_FPmxhA5Fa_9jnF)#*T>VLYl}{H(rqa?h*f!R|gR zWn1$cM|}JkYGb$t9Q;yl2BsNjeJKiE&&8xSLV}H$17hZB6S97bOxQW zw@;F$+6Md1B@p6!bft)g9;RX@oI`DGCtdt>bExok5pHabDBH1F1-W1mTm-T6tvG9` zf5M+UGLO!Jhq;IQ8d(3Pvk6iUAqxA)H-hD)UgzP9pvJQBJdgALYks)YDP`J_kx-OIgi6;^ z*7z=18YL`~6K^g0s(e&3!Lml|gUAT2rYw<-k>U`Iu_oa|G+htFAvW;&;GY4(c37%$ z6S^DadGA;d0$N^C5)(&b#3&%ti;OXvjg3zH5|s0=Sb6jjGHZ#ZU-wo=w!o)_S)Ty+ z9YzL!ROjPl^*I4t`hH)=dy9Xq`aTsX_t!@D=f^}ITl7|fYR3RRIvNL-BN42Df*?gp zKIf#xAo?mAS}@S{spyp=R=ED-q$mZ5xbw5OvlkeHxGX4XkkBjU)wJ+c#@AGRdk`Uj*#np z6Wzo0?&i_qo4$q`@{zdGzP(VU)9E=kc|(VWQcKN|3Hkno;b)*!?ysjC0cNoz8*3=t z*XpkeQ^Q8|i$@kTL`(Qf_fM@$HBc$nQm!RlIr6{QX!K%)N3Cz?S=O_vsenkSqt{Zo zQybmpM(jO2-GE?AU@ktQ+vB(ST-cPM$2B@zdvMii0<(kgKcxH;-ovM>qc zwT0ltF#jx$!Mn*;vQ94=oCvEkpklC?7QxqBt0cr77My)Jx^D2aNzK^rrBP8gEMnN% zF_WFLt$@`Z|3#U@7`qpI9j)-4!*CGD$`8;hLNRa*S^D@K`!}jua<~)WpU+h_w9j|z zNDm%PEJ}7y9o=hG%F*l~$1!*+O?NnuBq;n<&|SuYL)jET)vl2mo#?Fm=f4@B(BmgQW-TimvaVKV2e>3G&HCJ; zKDH9lWX(qhWe{eAByasLW#G=;z*f*&jx&g1UOgg3+g z{C&;jT*o(Vn(e~U5~A>yPpsrAPBfi|0n7=hrtGEWT9;)z^w@7}#sD)w^VZL=3VOcg zpDjZ5TSMZkIC_2=N3{JPQ{Np=_51!`kq|OVcJ?@Qa7Yo^dmZc8TaJv(Ldf3haE?vJ zp=0lvk&zu4$x3!sRz@Me+vodze7?UwdjC<6_k(j@_v^l{>v=uL5=xl-L$PETb+TT0x*x6>3>4|-f7$upJ-#dRSv#>{aPpE~D343|s$g=pLEopvr8 zf}$r4KtQ=S6>z}_NWYwqR6i5~niDUYSesfo!#qc&X$Ua-0lfoKQK}`7l9rQUt%7=) zyfI_6@UHy21}OLQt@)oDg>_kZ%8eFW6R-;u`RJsaN;23gTmAWt~ua>F_S)MV<4 zg9G+5mZ=jCA|U(7`}Y?`@1MCk_UWHaKvagNc{coNg|tqy^H7i zJ!yB*nMSWcRwHV)&(+0(mSECBM9(5_HdPO!Cn`>bN<3b2eBoL&z6gR38_P4+IEZOZ zM=^7|C*FW~1ug)_2Nf`NYcDU1Ppg2if~ij{Q%|03%Y30xncLlBw!YrnBCTPu3IGIfAgsCXMt{4Rp^*PTb~yKkn8bcJ6-dGxv=dTala6qB zKIx&uO)ciWrVX-qbZ%k_BaPOMWITMrTa(XrH zX^KKnXmc*Bl%jZ9U%+Y&6A_lQ5z4O_a3~o|F5Qz*n4%)75&yVKmn9#XSeo`Ay_UMX zynGGQc}Bim5a=`us>ilWAb4(9`SAcWzQPURaQ$%@LvJnuQfS!}s}KyX)QpXT;+w(*V2>p0U%yt78GBiVieyW33sQv;9w+=T9va48vm~~*)39LY?k?=-?|O1kV^BA)c~-e_-hgtKrT+Q$LNu z5fzhAk|aRu+#lep&??g(Cn;b!x%EjI4_i(5`wUz@8rc&4fW7VI2y?u-teFb4(>FgW)Wz z537ti?YKafxiJ@43E}G()3JEojwQFo@xEwOKS~GQeNfs2_I@Rv?kpAqBk-aJu&Q2( z1k^aI^0?Va@DoKK0ThY1uaJycW8<_kGMc%lQ%OLDP7yFw+0Cst2cP*{Aa~SQPz)S5 z^!c;smFbYC)CEjcb?|3%*p^S@FK+M2E#;*FPgf3aY($Axc2cy??Kk^V|0J<9)I@!U zdu2@qVPs+D)+#p!6L`JUi%VDN4P1ovOp&NMcrjuWE^d{#%3InZ|KE3<>K&49QYADk z4cQ5`fWDk0WsT=l9t+T`Y%=neU7LptjqHE3el96gtzb*V4}oambiXYuaK%}x4N`i` zjvcdAds06LwdbDD3k&^_Q;XNFtj5rT!$RR@VI*Y{&79leY#5oxO2a7nI7gm0pjCB! znsT(f^-bTI=Y#p8n1)I^_?(4b+aZA>{;dc|^@k5b*6~k2C22nG+0ZEhASPADKMzv? zt7M0U-YlNnbRzn$Jli;b!8Pw9aemHnL>VKx&iGr*bPA`-3z|yHG)_xeY`os}-8@o0 z7Q!BmxO@+BWb{-cCFPiVv=~`9X{akhzv`QJ7Z1;xdoT5Gi3pLIzjBNA1)Virh-dpR<04Z6)}dW?lBnSi2L}$^AXanFd1fZ6e4^5iX;VMwI%iC zKK3>JoZDJ|eQ`A9QpJr?;Q-KT6@*VO=&UWrtYXsPe4yf-7#uR>mk>f5=Fud~$F|zr zWCQ}`>)*$GXyqxiGxttY+6MYHpQ>jP9`I%$vB~hTLd*M4FavFHj3dj1=5Z$H_n)K9 zS=yGdVQtZeE!Ga+cfT^Sa#gym{O7Kg)#9c`q~<)g^C9jU9rvozt!7c=Xx6pX1;5MP zd)}vu<3Kd1!;Ajaza@||2)?N=8yNaw8atkn?9 zAb0gw2lesSXFCnvfb?n`hGBJ=TRt2Z;O((;{bolmFXyU;HCg<

sYra=}pNLpnmU z@<(nGJ=E+re;u@3>+@ns`-a(uOTq!`kE*i9Ud{xgL zDIYsyAsqc^lNz~c5wNGRtqF6x!S|mwd!><7_v~Bexx}EVDtNtw#l;7=w;_k_?tmFo z>Eno|>YXw)H-C;qCR$a!9^rSZcdDtZ1gj@l#&9lHi$EzU!eN^`Dk48MgngW)KzS15 z$TWmV?PO8v!iCxjjXSz&h0|b~-@mj`FK(I;6nEs0(P^=Iqbj`gjgOhg zPby**)vjh(`Q=Tiv7Vu!YQjL;b-90L8q}+O`&D7ARU}cUtNfA3*Ss#T#)p0?S&lFJx%`6o#(mVwIr17W9 zKysEE1>vEOR!SDJd{xyScbjX;9o|~6M2(97Umv6xQk?kkZnSQRUSZ*;nz}lecyPLM zzBAzz4(I;wK&M+%lRRka_39*InQ&0(=3`sBw+f~DDw8V)hud*5Y}+(?VXd z%B{@;4eqLdM6Q^ zuLcH6CJ-A=R=xcw{M@&?18-l-5#ijdLdr&!&G?|!7N*jzHQ{P*U&bq%c&`sdG|3Ap_%h9q9}ix8%h8y@@=$pfpcl~$S} zO-TC9o&O1*yEkA~u+aq}>QhTU0xwc6wLVV@->G!Rw1N35;BJ9F6$0LlTVfC@?iVzA z>;+D<$U-9w$z!kux~jo7?lnJWptscPXr9C+Q5rbRChcigC@hfv@uaQ7_GKECecIkG zB`h+KdsvXvEEY%9wdk6>|F3^pi3jhuM|D0^2D|GFHJw5t%SUQ3>#*7Ac$pW8nv*q9 zX~0usf!79wwIQpj;q82GI*xvDsqa?>u~w;#tL=nzF_g08f1U(drTYgC?(RuIu$!$> zy8rNk z7i~mpI#sF8Mrv>`cZUvxqf#I$%uPmgo%6kY9ptC=A?HD~=k35yxH)Op+?S58B14(W zQbPZ|w_ZO3#$SN1-R;`xpPwj7o!;!ogTEBRPb4J0GhHa79#e}_%a$V#>kQ*QtO%oW zp;6#h@Lk4qs$j3y1yFSXv*vCvnWY;OOR?H0m*n$iPZT#=60%lnamSdbU@3KUbf~ke zR1h@8p|Ic`XZp*ygBi|M`1~(dX3;d1o;4aPLZGgSCK|xq>s=Bf#!^zIJ}iEcoM^Am^CxZ^m(s`%)C6kPb1SpE3=!>2BGdquA`F2n}LrNFfHjIMtB>|ZMB zQT~G(vH^j?M7G{9x!WO8-EiyB?W*$6hEcI&u-M@;b+gxt@=vmk`%aq6w;%!n)s2m* zOc~APHOw!|UKZ;}{B3GiuhQ*Iwm~O8 zKtp6j1@Y=1O#Vze)Pqc}TKTfw|An+~q1&~$mirnJt98!-!Z-4>2<%Vj&qPdQI88v6(NR#~#(F z75vn6N^rtK zr$aB0Y*HNY0Lh4L?GamAf+M5Y=`=$y#3o596C~P{h6cq@_F6!M z*Aj>!mRxF)kXrD=GM#uN`ZQA2-Yg8PWz5{VPwLNnXGfFyk%E=FkK~cb=HWY|f$r{c zRpAb@Gv9f2>mR4qaVnVAosh?F3}ou#?{#^TRcxgxbK_jori+jpf8?e-!LmwF+Z&6d z16F5XhO|2{H5m78Ro zW>hRHklkrcJ8)syNiNLNVp>0)Pamhd=a+NUDE%2&orAy5VHN)Z0AsF;(sJgI7Hu=e zFmY|$c_-+(n6zi|Nhy*pZW$^rt_r#(rv^9TWR!FwNJGq(z`*tLF*ELyRovM+Pes#| z%p$i~&urn*sXk7dr$hCMOcP>{{~6LENs=loDHG8g-6-}4Bwfj)Zl(rCiOzM8+HyuZ z6!#k$9y77qrz

Sb2HfovnsPR}O6J++8|cf4G;=d=cT?Ab#HVjC>8e+(5=O;2J{c z%}hc7NG;$we2k@k1eQgB8uZkK)f+32YxFEB*@AM@u{tit*9!d!`O z@}h<6j2OG1jUM}y6)XIqCp6XGi0Pb~DH={5)Te+;?H|tk5#bmASZ*(AQ=5ia0wK`2 zV`(jpd`$nL?JB9PA%;AP*N1dW*(yC2`yy>SmBbZGZ7THhY1%s!Wrg6OPuiTCm~yPh zza}N3MuZVvZ(pfc()Ge@gF&NMj$ABV_l*Tj2^ z_HICXktGQJXupOotZHoR0}B^9Q43bxv{titD2Yzpng#U7r{N61O95a5%AwSCQqLhH zF3RhC4z*-)3{BKZAmP91Kq*nH$uo!|J{Lf%0Lg7s4=cb^*3DmEe+9L0av~LPp!WaK znC0Yvx^OY^ggMjbo{CZ4c}4X-d;Z?7`RC_ey{;gOHQz+w&dDroB1bxLcy2cp%}r}B z^_vvr%mZ#=mddilsdO)RGk^c%d~U;7+NXk&n~Cai=QAFOs1pQzpD|Zj$EbfXQchd0 zVu}q6n&U%6+W9b|^B3g2TbESLkI#e(y%KmqN zemsWhbZ$^>n5AOJfL0HO)vC|rXfPu7?CKcx>>jg5X=Ddmh82nls-9V)SQAFtXAiH`5$jR=#G^M*d#MOD8^x`THVM zg5F06ccUoz7N56}pB+`iKLS7ujV??t+AFr%8 zo;G`?XkG_gh2PU?OxPPiB|GQIe=#*0;#q0sSKZDhW&hu@n21M?>BM3=t{opA3u9yw zU&#yA5`A*b3~MN?mysnQ7cmWa{9Y{+c8`zA2?8(4d&^QyZYUMztfZPNJO+QgdSGkj zy$WO~bRhGjiFMg;>D}ETcTyusrDv#$ zT~A$`wop!}Z}}ld^4M<+CCbj1sYTccgewDMs)45#=3gV}^Y?`eD5GT+sJsmyrHbL( zAQqOPZvmgoWf^*L)#C}?unT`FJ&zSRP~lIQ0g~(KiO%_xmXm8D;C{HK9>fBO!-sur z@s$9jYSLW-K7K13MLEEM4qh?|{8QIY|2_c=42HPny|2bDV00(Ck^3wb#1plTeE-gb zL1HnTV)yS_ko51mj+ti4jvYoqN+Xw3R~57KbRkhJp5q-tA+cII#1LHd*jR@b`c_Vz z9E!LK7Ba?bhlt62PFOl2^IjFDMzx~%acIQ$RnUJ|0&WGPo>|k=hQ*V_;OT}~zO|iZ zb?+r7E)m0A-v#r8m=*)UhiD8emn9M|uKkq&`~0AGl$J4MbLKs^QoqZU!4jZ8-UPqi zE^qa^t1g~(SlWyg#N;c7d~Ix1n?Layac!CXKC&gX?Z=={Y3tISRC&^MP|3NIqa3fd zW2_R(A@nmjnZ*-F*aN3tJiBg5t+K@R`J3%;3VNmlqnnCEtGPl4m0vrRckyVemSd7Y zD+WQkfJb9UKML)&vlqs%gz#B6QBaLSNxXOJro?=YApj0eR>4LFB)MXL?36G3Isq-0 z*b~ry0^S~pro=uz0BWwll8ULcw6sO=80-LpaJC-29Yez-I%T>xU$Z`gw*fb~`Qhkm zMy-)LGT`p|&4m-BC_Nw743P_S136uK7?xv#c;)z`xZM9;F3!?exTU3KpvKh=(^Jj= zc#rDq16!ULt4a9#Sao}>uKAR*QbYl;_mdOFq!y6%S4_bB-rrDq^xLD-s3a28$wDZv zy11(9t-7cfB3^Z$>Gx@i_vbrXehkMZ;S}oAfL3FEE72?|;$2t0G30JqP7Z)JYc2U( zXUrJ5P}IkY)N0e2O|GoSZ@OaaQOU)s?{k;%9Q_zhzXu9ZzHpN?(+4r4UDe@>5zdIA7Cc} zwk$V5VTpw|#W)#)OYW)(YSLAh66u5%EbM-9tbdt#W6}Ywn(}ZQ*`U~W1SLVfdP41( z0q`bCbIb?$ZKQ0cgP4F|ah`BKv#=@@~Z-24&Fj!QAP6DxM)k332K=FECXo4#S~X%XX#liPO11=S{Pv1itVf3m~9E;*JVQ3}acg&}GxR;O>zvS+*aUvR)$)qt#hA_6f z3;WT19__-uS||z8`8C-4LC&%Lb!Ak@dcXmdXt{aO?8Y8Y zTv*PE_Qo@h#9v+&O5nuk<@M_R@3U*jA7>L2)Nwlal;y6?Nzj!3!nHRzo-mO;!caYgO^Mdz(A$G^pgGGmnueHjIA^(t8QsfBoF(B zL8El~fQzRUhw>A02K3&Yj9bh06Y%#C+2y3~uBy4n)Nl3bO(uDmD(W^sSppv;j(LPX z^i@>;`y$Rn0mV8ZrqyHL$UBF1u_dj}Mce5GKjG5|&@m%!T82bKEr)1{()=BWOQ|~E z9EN;m9rs2r=+gn-4seo=SubH|mS`Z95Dp;ZV zUHtxeN6|l0mm`-+Kq!q&$G23fnYIBOvtC#DtR)!De(^7ffptt0px*%HfD7sxIGEFE z_d!L$*i!WX0n?acJ-%yQYuB$|0%x&)pdzLh3O{`+pZ}#`YHL34&CZdJn0z=K=MkOd ztz=J%H>ViEFRRF9IqD=BaIQ@pCyOHF%LRSthZ4bAmVEZFdme0&yh6DY6-QAQB-c`Xs5UYO*9i5Hyz`cHVxt zH^1xusI{E%7$`=-IRwVgVj7Y>Ly5~wK$mib{`u~#=@$qqhwRxCw5#DHS zWjZ@M1M0wOWE}C zj(-U4fZq>nE~g@S5~AICKEsoE7|Gc+S7$6#LH((p5ABH+)HNrv{i+p-HM(_cn32GD zDlIG9%E#vk*WB)n|L=HHI?mc5T`5@VsObs=bE7BKCNX!P8x!9zPo)cs6Sx)sZl03& zY3;LEql9Oxd+b(F`=62c~Q(aLWe zLGGjN4CnLah!qdYf>=6EE|N<%P_J!J$aGF1yGZ9e^2xHQ63bhI13mBgN9ObEfcC|l z_P)HLLRdsZo;C~&d|z3(wZnG(2l1Dp;Z z+9hbMN6=wy)x`+x{aAnN+a%$*9&4P>0Ib_-!*}q*h%q4qtH?!uAaJhO&Y1JqPtNmkkM@uTjv~s zk+Gzwlpd2NC+~mz3JbljQJZGZQ|lP*hJ$dn#mQQ?12ue`Qv1Rc;yNoZw`F=<)v+Tp zG`Y(qI;KttlNxZJCwkyfH2n6~{5tm^<6BRscD6A|Ztt8^u8T(QiI+BM;i>>nV7xy= zKrdm8mRq<)_nGfAT6}ht)@MGJCIP`ln z(v@^?@(HcNgZ@;Zp<0MqSBEPDFM7b<_}#g|l&AmS@tlL_0msj~T{E-q5r^Km@*u9? z(Y>I-zYe_97f!~Zr+0$zhv|vkSHx)BcHMzm2iSVbwD8ACjl%%03CI&_i7tXhh`1ii`haw=7k-cd7lC5W^nPL#!uee^N0EN+6X2)9`r3(d_h&9`dC%lR(BRkYU$`f)bp~e}TsXt% zU%(nod1#l}If;e&gI!6KS^HLo1mDLQo8~Z7mMigLi{U%rL6wvaAo>kR-lsej1%f}a za8yc+u#t38us#u&=1&>CWpoMb;4Zf=|F(lQ*rbOWG4$!v;e&&NR6p$x&QqQn9#5`` z#ks3;pDP|s_a`nV#jq;_?QjX0Z=EYtYrfdHyoztV zcnaopWZeu<5Gf}sZiwn_y@%TyVfrU@vw)nas-{M^U5Zv)zsEIZ_iUnQ^ILsZ|397k znNg*zjN$JEBP(w!)Ham=_(Or7=I|K&yy8w)Q>IY${ezk{Uea z3jCpNV{y8!Hjq%@KH3Fqa{EL4u=Si$ugNWAHu4u!!)=y;_SwHsvxV@ZQ)T=K?TP2F z#@fW%=3Q;|QS1#i){$MRs$9r-i3tT!IHj5ENkf9RG4H8K1aa2(75z+II9sT!&7ZdL zbs{$h7NU~<==DFRZ7CR0o0Fs`h0#5fSh(wwxsJ$NaBL%av2O7T~vF$CXsm zWb@gqVG1kt)0&PmROSI!9^h`h1^z<3F4b6U~HvfQW!T z5jcUDd1d%lL~k{BZZhmW{n9yl80Z>z=gvufs5}U&fBqad>9GCl7v-sBy=~Es zRAeo6;q}i|j(hzR$|Y}Ki3n=$s7NbOhsstzLm|SP3(jQcIh7z)aARKd`>A3vjYPZr z{;PYmVrtNs_)dpqPKmNgZkJnn+(FA35%a{Bc+?U^RROovFi1#0!a~ngh5sji0wHf% zp~__=+Y((#z{$3B~puAmO`2(qD0qw72p(j;B~wBcx}pa z-%qOU4(|c)SsI)-8n>|l>w7w@U4f(nh|lF}z#ntqcC{7}RcuyKQ(cY9Hdj!FSYkm} z&#nQmSdAh!{t?ka zE1I<&-Cb7ob)%MNbJ&7-+s=yKY-vm7`FZm98{xqEx9x)5%^@sZ#9F|(gybt*4>l2UQX(4WKU;|4Zb!1CL5l2db7Z#kx;BF zD7il`IsaACcdFv$1qe?4_qhb-Viq=Q00NzzQWvX%rs9PGcf=>F3<6Dc6$C}0v=rCZ46aJKElSjXMgk{x%`8Q z2qqE9Ln0dlRnlWK?9s#Q(T!Xe;*Sn8eFrboD$y5IPvSEuzw$59DFd`Ra7*8Ft1LfHOoIdk*m$wr=~Mjv~fK7N;D)#&3(1~ylmAKtDj=&&ocrJU4XA# z*Ro#l--!vO`LbuUhA9U-(kph9D? z>Xrt_C7Vqgxit-Kj2GebOFo=@_r;aXB&(FL5Wb8e!&+_JUE0J9zGma&9aLc>lkhpq z*f#S{DT{Wg_S|<8ec0ABeB0&aa_iLehnI1mVxwQr6NF(b?m1=#u^eOu1us(rykvO- zrvr+8#brni;R>|{7!#T70f{94-j6UMY3jqxjNQGzsv|m6Pnpb2E$n>AX6xln^A(%h+c8r|{QYgSL6syMi1ATa83L12E?X^o7?FFw^XAK)#ZRN&Xz{3}*{a=-nl zws4?KTC70rUtsleI4Tor)c+CY!5bHgTnj#AU?x@T`T;zG?266S0f`iJav!S&S3*4A zZJlOwaej7#zZiV`we~)LJ|TtY%mdIYVSwim7O?s@q6*=r1*Eod_H5PIGJqQG1IXs^ zto`!Lq}3<10#GM)c_)2a2Y=n3L*_4t8A>uCBsV0(ZRO^F)z9862q52e&wNcE(3X$j zx}$?rpZVUn>2&_8!M9v_7FZ1c>YX5Hj=%`ltB~6PIJ@;u<6A^W!Ry{3+H&nuEHSLE zYCU=?u0hMx@FO%b9W=aagWP%r#PS-H@!Ve(=;XSf4BEP24fHt5Di;;SmdD)(|*SxV9CGZwe|~fyTL>zf`R!ukWjyX^L}0 z#xJfeC~zZsXH=riV=zV{p!Ibvm)}tBb11J|4s?3>s#OzGm-So2cj!oWeCEyE~^>S^}(;^$s zp*e%~w`IIJMx?+x@X@0|U%{P9y(^joBKC7s4b)0q0wr`R2))Xp$$$Sf*9@cW?a*?;*+DTeF7VrY$E(R|gcf zHozIM^@RgtcM$0l7f%MZvsaGAKfrl&+}-{`O-yYYvDq=|Y8uZ?Lik2X?>VAA6iI8} z%t^!#0>}JvxJg`Z;pIVDNy3Ut!TtlVR#8pHtg4QkX~wDXmK?C1052Q{-iChV zrn5gD0SZ4LL$yz}Y*_~eM-&9p9g+DA%}btGPVIV$ziJuY_IYk`E>D2Ol$M>nxP*<~cHFg?Rd1eW3j5M^=+_DDK9tCfQKMY4w{IQ)eWTFX z!q7@4jh)DnmLlvrFf&PSvlsa7XF0EP-+&uyo7q-ho2YxUvsdu>=S)in2VOlZvRvzQ zx{B6gI;qo-ci;!SQLLjDc6NZ6BSWqD-bM8&JsJy|&b0r)=DcmYMz$SJt6|J|{`uw9Z}zI4eXutQu_Zu!A4cnujCk~ni2CYO*!iHHjEV&LMaoEX_W z5N|&e2QALOzZI88+-)MJsF?@A8m6?Y%=X}+yyUy;yPBP1A4SJz98wYb^^Dq-h|mY# z*v}&1kxHEJbpeFj_u~1v+=Kt{Z1y`q2zV!Lx%036TLGsfhHh-buPS zDndG2Jv#U#PRGK_%T7tG-;Ofj!6acuPt%lnFJM}6Q=)-Bvs>jcmPu(qQT_Z63;SEa zfT+fL8QPu+hO7cJ6)p;Aa`$}k9}msix);vI@{^-OeOqVUC7yAkRj!ouAbmR#?5Zu& zIW>S$%rgSKDVqBRfqlJ^OSH4~m1lyJI*THHz* z+N@Qj=yQKD|sBa2OkDV6&?} zWg#r{t$O&${F2>mqw?hG#)YQOkmdEg@TVi}TXt25mBnyPVG+Ic*2DEC?_~mjL!}l< zYl?ZR}7drg($#cGTc+}H$iT!~JD+(V;6D3F@ zTt}{;-3KJ8V8AD5Pr=~oQ&RLxdUF14dY2sd8LvBrTROL5voPuWvR$_RgtQh zc8z@$f|2YjCthIKdM%YuAsR(pz(&rMK}R5EUm_kzBrKo_-bwX@FL#fD0C)QlUC;-I zhK&m=#vuw%CSm*Ebr+W1PMA`^JuqukfOcO04! z*P{s(PHr)^?P8sRT^Xomi7>VU%2jcN(;LM0EXL7)FR}@>(e=43gn)?*xLPn zd=OVI%%@qNZ_bJ#>To2Z0t;Q(l|u!9o1=AfOxiq%TC_SG>Oim`YYi_+gzdavX7_#Z za!fs5A-g`xBHZ%HbS>nzEHAgNe5=DfodF&iV01~;W0lp*93WB0vDr+Po{oq*IV^MW zi+=R|wKaQ@#yAW}{&i@SQ0zeIv(*fm?kfv1i4jQZ5$*PMJYPCtoM?cHG_B(dMR3P5HXK zXmyRvsmyT60i~j5BDW%~&kyuHmA7wZ$^^PKbw*P4f}+w}eeifQJW!(hX|G>2G-}%6 z&g&hAV0U_T(R3#MM}_yEJ$l4%l3flT&55nuwP5Rcch#Dx?%Hz9CEDSqNc5dFp$Se+{-RV5F?D zIq1hbA18WNrJr!Ry*UR4Qot;d4jdw|(kKMyj1-Ur2s^cA>^uqZQd%$kz+4P0Z7l-= za_V)>Zu&o?CT&llp|I)ypej#5Bh;kNfxP5LN8vWXou-XTR&)%BOM37*7UD__wz$`oICzxF}W-_QuPYfpl>L&ZK9V& z!Jv3~v2e*%SQ?RYvGhCyCA$_#sEWr{0!=D@wJi4O(9hCoK&_yMgEdB`ljXP}T4~?d#Usep)HVGiFo~Z_b6bW#jtV8FY^-+?0tGm!1-Vj4QcUEXg5!tsn0Vui0|*S*qAP;9O74j0hW} zERcC8qTZXp4zsyYLBWne61T`;;kia-R&<=e=yw&HVwPtjAT`P#8g6)N@+cp1yLVr^ zp4>lGJ-EU5{FXFAZDw6jyLJATizO{V9ax`D8|scfPe+u}-dCUORup<^7}Fj`j4w>p z>{vk6w`~j8^P`pr1!S+AN;Bfa6K8&I(1V}X1RRevzFZ8_efR>IJrBI~d#nUGDvZkX zi{~1fn);VIWgMm{*y|;Qn$%ShK`c&cLzMaeHSn(hYb5I*f7Qw|t#-z9ieNQL$@ciJ zGRf@SLf2UoOsWI!s>dJ7LJSo&tX3N@f&V4oJs^=XI9;IC0%rRwv95&!g<7Dy}aY=2wKm(d_yYup|6#QQ$$STnu7{PzKrWP&=-w+mf? zFgsVuzt<5jAc{Pa@LyZ>F8$!i-}~Tnqv;j$*WAi0{|f`cAd8iHSJ@wZ#IBV2ZQCSW z&+sT9Pchg;J!B+$PO=a=w&S(o+0v~nVdAGTAC*>loOn<0F=NSA?}R?XlGy#4r(_LW zZF3?^+!g`tuPR>o#xc-_eeAlEQ)pIkrHwHeNy5lX!+%C$I-$fmd^%4o(7~!Sd*wJx zCtzRm>dAkFr#kUa%elnFg_Un0?J%~08YN#m$?MX7NY;LNt9_*Ig~6XqgLZ|wzdz8- zF%2`ZmlAQaBI~gWE-2KNvk~DgX95_5#JS}zyeeGB>f@_5$!6LcUa&|wF2wIHD+ly~ zBnB$YH|e16f`FB8^-k%9$`!L+M<&yE?~XH*;Cnm9h=$%T=4ae>CZ}NQl6e0*}5L$aROX8WsCc4LDST%U_Ses^@ms|WgJGi2(M@eCW z4+K@&oBR0;X1@`<*-r$cgqPb~(Oy?X&WBUt_Vd*dz^w(p{!&EPD3mlf zXc?eAt!6IC-KgAJWfYXQ5&6TmVHUfv8(%9tf7hBngvF6Ow&R@@BE&W39tjcTXh6O^ zg57sHByfFU%QS~gF{&237yAf^)C(={aX-FEBK!PZH1wxZeOBa}5XD}3(7d{=EMLTK z__ITzE+7jUe~T1(P}YZ$nMFBSD$6i%yosPZV$g1mZ{cd`~kkp6n3hLoXMV%2`7Ku4&Smb_1z<#5Xl^B-QJTR_9+WtQI3Cyv1+$(|P=0{2 zMxc^EjCo}B#ebV?RPbGY(&(hZnS7fQgM8OZ(b}e3GmiZd4=u!`itp1(`MY%NHwp0x z-}ye^9XGqY8S4~P|FMY4FIB_ky~>k=N})iOz5OMGu7d$DxZj%rTIZjNWb>GpRDR*?ZhVxek-6is(#LrxBi#yWRitZ40uzSzO2l8^CNTlA1EM8kEh|M z-~Sxu@mE?zD_7($l6eSzOy&=DMOpMz4J~~c4=gQzVc(`f8$pD86cy2_gzyc1`~I#r zFB){NBs@F!az86S`6GZ)$@?U3&G%-v_2je&WHG&2-t`Y2@jtG~`KA_~UtB`g>_lnl z&LuZ#S+S+zBCfK$2u7N$IWKZD-|zdg&J7i0z88w5pL2d^s(6B6;$)-OAiN{YGCeg+ zIsnSD=hs9otmJM1N2ANFH`fsV(AjoYX=y|d!f1H@7bW4MbGQ3agxo0u03zG3_&3>Z z<>C?#U{(!L5q?V_AG$7p{-glxf*k*wS0EtCTorDphzLjAd<;tVsX48}(wUKD(Ym+L z$v|()dNd0O(HrI#-E|%Fe{`xv%xn=9(eJqjw-Gi5tU@i6wG$NN97H}4LIKlp_AD$# z(kRihsayxfEOG$Vb%pGnfxM0+@WYzmz*Ng*3Onua1=&C(TgAO~>-xNNyj_WW$#lW^ z2K492{YJd~3%ckzl`;1yQLFZG(%cX5oi|YcwF^8r*{rX1)k-utcvJBCae6t{+L4yG zB2Oub*(MX10|>QW%(f3-o&#Rc?-hhOw;&Y=w^C^}D>4yaru^z`M@JdDs@?h>jswM+ z75I}E>X)qc{#K09TvLMd_EIX}u*@V^5Y)~b-6nf|lJ#o3^?*#ru4872;jq_^J4J=I zP#VR8C*hlFq}1-6#rLqizh}zqM|X|Xpymrf^M4br5=}lXvtCakRNzZ2_Yb2O&u3Vq zACb_tebygjQ+nt8qI3k!11#|{FH*zohX-6Qm&PWy-fSj@gERBf&e7As!zVg?Pahn` zEpM=S`5y+&lByq+HcWGHI6}`{6Tu^KXXI!s(Dm*ul>TNIEL4;tcu$733rg5YD5bUe zuyRT@$DN9CfCAFk9PPeo9wRS=` zKSkg6tw5Hlx$9YRBD(rYG$Bv^k@&f-ei%rh(|+d7RK5ikLc#tyQs-S#D*&dXCce4f zO4BQ+4YphP2*^_Z?kt!znoR7hm+6W$rG~b*847K+U&`^wRw38}Ve})1ZzM)~Jm)EH zsJ<^RfD01}W(sMZpHCV3{1oiuexQ7kcD{*b$CM|=os0^R+VS4wQ;sNT)f$&;%KIz% z>ot)14Lvu1{ObWq4zU3^G?B|<{QMhUEigLu=GO8domc>sdbP;ba8MgwnB98?Wg*04 zMc*&^%w~Pu;`k-l)(|(QLZQfptwP;cEBhH!_v0l-^*?0^2+!SnO} z7gnjzwMG|~YUPe2w$E*T+4tHmr>KJo?o?D%H&&|P*wfiYVfXt|3b-Jqk5bK3pF3M# zC*@8(b8Pd)Ncrv3Tv1dgmW{}Iw;$jP@@4gYo#;Z@X?uPO25fpC=el8VlyebS_%GOLWmt>D@}1zf8W zK`wM*Dxb7t3VTAvzQTYaGi^OF|(&t3;pMn&6S-mBc(F#Z-d83)6=lSb;~+HIOe zwN zDpmKHX|Yg;6w@z8%3g0pDHHtQlyl&{xJR`5TpYpStQaf)d1f>_K}cT$FHpu_v4`!6 z@JDZDDO_L+%R44x8nM#}el>zU?#tHR;$U^4u`azg- zTDP*}F)0+JaA4bv?JtM;+t5;z+CF$PH&C$G46fu>x&}1SlB&PIqr+UxjBF^JLZxhYk^d|aUo-K)m2}m!N%8 z7#(VAj$R^rsM&+wXj)lq6M405+ZogNc7WKN{@@p`hdu6Eu)mMnr)2bd+Ej2)T0cYI z6W-zLzI2^wdO$ZOO8P?D{W3<68fPXFeft_tL~jTV!?@3d*f-BV4Hw15m%_XB@y$Jz zzqC!x{`idto98F}otx|iEgv@<>Xt_tX`sux@4rT7z$Dabs}jNm9s=bCj2k^`8fK#~ zXG#`oWE+-oi-;sBeUIyvXJaos_e_u6_2goS;v-jmhm`|y#oK}S!%8AZ6ol(OZ(tPi)ome5Y9rpuzQCwhxsK3`; zHmKS2%3ury%^F2e-~?J?dp-D-<87?*@(ursoQR6<7+a> zw^zY4(A{T#P??TDD=QZLU1Hd5pV>2AF*+b=o%Cvc;oK9popG*>X%3IE#KF_izBr;* z)IZR2WUS&DC70JE!+vJyqk)XJ5Y!oG0S!J3(SWuY@%87hvorb{2 z@1QPZfA8=T-#-hdDu@e}RD7bsK8#B4?fN1%g;AP`i}9-A?ld_mB%lCc!c&65Ct4Aj zYt5Oy%WYL7#q}Jk1GiX`4)0Eht<7S}kQHA@OaR!Dr}v!}W9V9B5Vxjjf7jM(ZjTpt zC>MT>r_J3~?s#l-_#wdATxfsY&gccLs zIim~Ic6V|)r}*{RaMvc)XV!5zJ?Py!lveAz^z3bdOx97xHX1g1W4BAx=ee7Cn#e! zfk*?yka$62QW8KG0WIQ=)zNm0Dyzb@->W#LEk5(|Q!Q?&*OyO$1d#`Y8K-pkr{2Pq z%3LM>4N^rdBZsOZHv4Ol)KPICG@0UZc<*FdJ*UnHTsc8@YI%Bkf}6@@hOb619BhBC zja$3Bh;`?co64~6&K%nT=IXj@Zs6pxq>LwHH;YRf%S^d-h}LsSVWO~3EI;!|{n!m# zeHY$pEWN~4D_4q-=rs)Aot*Ew$FXxnQp@6}do9ZP9BTWG%a3$nCmY-*Xvjsl5@@o(`>!8Y}Gay6Y9s7GS2G_ z>Cq-Z_u{imljzf0`c@qtF_iC!e_?-YoJddGF&JsXGCe=P2q8T?{h7=uJAAY&o$-bs zq}!AT@L|ZpqS)deu#1FvS^pO6&f(^J$G91b<(tXTI^k333>P$;N-|~Z4N|E!-{^Z7 z_mV%9`?wiW&I34%~cpHhXk^UOZOLS>FCB5|DI zJ0l6nV-1W8wPRuxgoW(9`?I}(jaYL+g72F?a+ zS;0z`wXPqNrgXE0_JzEX3Rm0>rQBEYdhsL;163smgP>q#J@)ipLaSJo{-aRSEOPY? z7Fj)OIqy7MYhYy}sUyfSdkg1(H^t)TjolnXiVosiSGQV^9Pt zfxHUx80?7A57|0cu4eQBrM7QNyTZ4hrF&kCHqSRd`Qd2dPSMBn*PH)x4lF82Koi`q zfzTKU_Z+A*{|O|ELl5kkT1juW;?BeHP2@rv(x*Vg1q#3M<%tul3!yg}-lx%^VlflN zr%FVgoY1kvX=;XlzSBh*xKytbWQ@yXyNE*hn^CFUF6``rYv%k_Re5#4bLPRqmD}~h zh4cC2ldkI%N^X9Bw=!gs2OsDCLk(Tb#|91G8+V(7VHcYAUL)ua;Fa#sL{Ad1RA{lH zj|w(`e?d*R&^Capx*oBPdmF_E=wB#s`l!`Qd?Tjbu_+g-$Qxo;VM++h`+MPjwZ40) z-m>S``fW|*`c#>a$xG$kd0Id)rSoOS_siHW7s9aLs>fq#tM-Z>1F~!ZQ|A#P0~}a@ zqQ@}1``N>*OgWh@&dh``*5C@L8OYAp_k_J>lV(QO^>5aor!$-Oy-b%S^B{A?qbU;N zXj-u(@MJ0qU#=@3oGe9x8AYnHT4R3fx$bR)`-8`O&v1;UiEcR&<){h&wC_#| zkkkR-vcUvcKBN#lpal$DRl;u3m!l0w4E_tTKD=HHzU+VJ&zioyqxvUnVmv`0u3?PO z4(+#_*GzWNEO)|Gl6#5WF(XfidGx{MZ)OwASUPscWJCvmA;-l?*h*Bc=`s3$4nQM{ zPt5hY?^y;K%HtF<&CJW*UO5}mFJnc>kH4m-26^OuXRyqTTQY^c;_2_ZkN5g~H>(Km z5|?Pbp?xohh-EeC;J}XMWezpb$8X@`@nrmjN2=2xtN|6_FwjKTixaT=Cv`i7lUY{-!hq&<~}&w}YrO0@N#e`kU% zYj^>0S*B648_uS;|C7&@V&an4hVvo&lVPhgiInwMPh2!O5P0sQDq4_B<*)_H#pUT? zF1W8f^tr|f$omULIMZDNYHxKqew|$YAQD1f;qV@Ds@pxJ(i}~Tevht;(Y5RQ^n6X! z_k7D#5n*O;ueiL>O)i}mzwbS~e_wL{YnUl=%A4735+@0;YG9nhOVU}CSDxSnFKF9? zS4~W{;xzO<&$CosLXWV)gfx9&19fSJpi8pRNuW`#T48S1mYCCuMf7ANqM zDYV^L%#Ns7=-%(W6e(#C{k-ynE-oCYM6hAtzRyMaDvR z%2U{mKQ8uo96b14==T3WYQ?0@r2lB2!M4);3aORZN2ql)|vkV{K=LLwonN6-g zha^~MZ_{znX{`t1;@L+Y1o=6TBor_vh$dyeU1odU zpUWF4bpe%>5{BQFe~b+uP=0s%ZYg{~n(lq1>vOS0nPZwe_-1>WSNOPoP_;x0e2r`H z!NKBFm}BWn$2l@HtN`5!7n?CMR0`tRd$^-TXB_hQy zs3Z{83OU1nD?~|tpHZtuXVP(crc6w|J-`ml!^crn#6v^z{U`1FefMf-cTr%V`RWZA zjTylpaoS|ZG&?;Dn(e(Hhaqm~SwAQ&Kv5+pcwu9%jr9>5@u|o#jS4pmE4`BNwlNvA zL5UV)Z@ien1VW!8??X}pIpOpQ7s7MXqbu2H2xP(L;q5e8q7qe1K-+y%O(*h-#>T$G2mEM2Nx|*e zPy7CT2-{hF?Z*#AL!VP3>p@DNGQD`@RXb43SVI#fHcS%vQN#8j+&UR_K%v2yUX}zu z4Sgn--yh5&TPjZaGz#m@Yho>B&SvM2v`Ry4&kPhs%y!~R{qr{eBukOdk=#yfNaw>X zlG{vEf$sHIC9*=P+#GyrXY&6w&A*nN@XuZ`QE zV}mn)lsQ9i;ft5ebiV22BtjEbowiHM?F#6Q=TRHePp+gJXJSG%ggXI-Y2121*sPxd1g`*Ycf#}QoG!NyTxVe%LIKmbHC z*pRltd~2>}-2TQS0ir(^i)hAwtYH?NI-21=y&$*PiESTpsqO}zg58V~IzsomlNd=z zTc64BH?F`H$Tb`smieZor5S+1s_**H_tMB~+t#R0_RBd5&U=HujEqEKLg%0@Gfq5!CJb|%&Ng&cj z709rv*APbNVA`gNl<8q!vu9ji+!yAHZ|@k*2!6Jzv>oUs?$EsOqYdYE$}akDL7?Ns zSz1$F&L_>7JH317@qOl^CWQ**yh$HTF4_vlY@m8Igl4aq@rRR|aojtLZ#(nskDE?t zE`45o&o8zngX9<73Kj(@TF@0u&8|o7g-n7V7VReIb-D)_s0Ny`9bCF zC-V&L955OH#Wu=90R?oHpBDaebI+#J?x9ZPOgtD`KLQ`szjFh9w|Bes9j1cBJjGP; z|1>&Nu`RS~MGmXV=bx-g8fb67U+=7~pmmS4KN%-Uud56#-t(;z-9{%4w@P}Gc%dAR z_SEM>09mwwRPq|A<@6w6lix;U_o3Y=v(x6nM1(-{yXcossTXzkf!Z2wg3H+9Lb920Wixo23e^D2s6HgS1lJRom z1*0|+fd_hu7G3@4c+P9lJp(Exp}rT1X4ZZ2qEXVuYsknhz$985c2_l$6;B|P=5=Wf^RfYX3ievIkO{WsmXLB@_}qfGf5 zE`}m*5%3OBF9%cy>Y&SB$M2W3p{A@;4!PEPXJz?4KxqS0H9-)yALXy}7Ob~rzXUp8 z=wZf4U^P7~pps<`gT!u)9$tL=!ZoTj(?!ksfSSPiQ|l3lUmRRZ9BRu-DJYTq9=k{0 zO6{uM#U0%_9kouAm-M>m49)ZYqYmi0IFa}l!b}SrN;1-c>+9A^Y3`0h2?!k^PBTyeD64Jvt&G8`zlW>E7rQO1_J&bPZz z-Q8lZ>lUQQmeNh#ohamko71-cNyMc~^k9+E7H2BGki{=Z!s4!~0w)^Zt9i4;XB-~U zjV_uB!qU;CPF9cHaNA#X#P08)84TLV^!_9Yqi%o3>-tLn8zSsEfXA+4m*UF%>gP{IdUP&UEsulGyUxq^H>!>%mm(2XeD#2Bud!h>7?vBgac=OS z6?W{U_}q&gG|0a$o+SC6*!}J0y%oKOJoeRb+=t?>3#YU+?-}4W6#@w|pxQxm@?U#oXl`37)f-zwX0oZ{b>!6~G+w zF(SQ`+Yvp$SY`{oGK+&==?jm>^pFeBj2NP3RP9d#yD{N!bRQe>qA@XJrfN24MM~8O zk{}zVFD5eb#<0rYcANhlEOLQ2!N+$}vT(sh;qfO6HU?@6f(s8NKFyc9{QWGKc`oT5 z=e-^Ln-SaJt!f+RsmK=9>y7f%Dp|P(|M{wXYbbi`o@EieS12_|E6bsPIyZ*#?}lPg zW;6+;nBcv^1umq|Ka6;#QqodPot&(f>o*VoL&AV>m@0HBYeOzttMut7SJA=-%$qlT z^<9VxME^4T%RLJ;CSugGS*Iyf(^}uRM3A%)BZd$apJ!#GapgxgH)aH**!*n*o|GOa zFBiqqRLTS(DW#2~gcvhBKrw)*K74he4j9AaYTaBX=jI9!+aufc|IWN;kp#BjwIfNX z)LlH__h%JpXy0fse)-2^nnuSlHMSg9{eltx=2L{2u0>aBy)5Q*_`em&~n4wyjcmYV{Mo1LSTumNG74 zeD{@i4#T?lUgj)MTG4Lp@{bI;h};=TrTjKIlNjHx@`-`DV&neM?%{{UMDRftkI`VE zGP#e{Lt!Ntk%gT1%^DgCDyw4)UQ7g|%ruljbg?u{R8BwH-1w5`M*1#}(c2@5 z@69=_wv7eNr?-jE`PmPS`b5lZJyQ?`N-OCb=V)S*cxokDfeq}QFUSdkhPxArqS?Z_ zLPg=|{<;IbRWQtwC=o~jl--PNWm?EP868kRN(uWu%GRHj%w+vu=MN-*+BDk&+! z8`FuV1x{)O^cF?w*>{?P0H$lG`)vqYNO}1X3+f6kQ7%O@zO^ZGm!pNOfGDP6$h0rV z7IaUOZbOIHE;u;-lxyrPRzoLbqGa=>)uIP$mrH(Dp8_jqr*=S0sV!~K&_?1;hQd(< zJ)NPhOTtM4k9_e7J4@!}H?d^qlav zQi4N)cjD$Of z8QfhDX|!Lid|gv1b}}Zxm(Qls)Q`IJB2%N|PjZlh&bkhD6hpmMu_R#3ot&bIwaadH z)MB~d^C@ya6Sa&}pSq4PyVv8V_2tnU9>Ib2dybc;rvBiqsjRD$CX|Gy2dFSevLb80 zdZ7m7;@*~~1PR4_x;M!Z$IOj@0;^#AnMcd9iR8g123mcqHid&LC1u(rAI%km$;g~Y zh8G(B>aIQuMc^lu#U*156I9&l7&^U3X!#z}DY)&5KEtk3qA9zWnAb@MP=2lAz15Ug z``fR4Q{Zp6AO6bAA9QKY%QX)wNB-P4jVa@8-*m+KQy>X`0YkoJh`#TuJSxn0+HBnoB< znSe@Rs7~ndV&}=dbgKSCb?Gy3k*TP1Y%gK zUihW=%5ds-Rd2D=*w|a0b6SuHVqzMp%0^v-;zf<5ZU)eBS80I#HzY4F&nxQ4^y7aH zKdMlZY#EJA&-AXtaBQGJLfbbXi`R#^Bgj&2&9cG>2uM^lXL9^DoSW19uee0`m0|n0 zKzV1Rw|7#K)-Ufijrf2KkD1JaM^*R+Uw*AO1ldQh$Cw9`HVxUeljPH>FPYoPDAsai4@%0YbgLEGQUaN%b zN(+YtPrm*B-1N%~qwJmIS0lUCj9LW_r`g)!A)i#L*(?eGIA0`iD_Cbb!=#WTB`H1Y zbC2Rt{{xNt(_-etY50sHbosVVu z6LeUQ6cAK*Zk}CI+<$CnwshvA6`#OFEHAz<7k}_Uc09}rxL|&;;+b*wgcN{}oT0meZ>}+i(xNk`k=J#|t!ulEOf@2w5gXcxUM3ai z&_{mTq5Wio4T4|H9r4}cGz}Hob1&MA$2BEz@0_>pdZLL^-T%V6aY)t`@z4~$*?#1Y zyrVx2X1W19D%ST&ZBrW>8dCTW{f_aD%+}3@^axk_d6ADMs){mV zg*sGLho{4RBD5$-*J9Ypiuu)v@>KxxcpEG8iPI}_Epxj>MV8C#%=?h(w15vYwQ5@w0sqLqTwGqeAbsp}2`0BIroumf{2EA{k%&j^)Yik%g8}^+MC++p^@? z=p)HNOfNVsS?(Rm;mzPn=%>=+cF~lN521v;&TF5ZCd)Gk(X06Zcfy|Qqt?q8K09kZ z@kVEPMsjo;fc!24{jng!C%LeYY2N+VfQP47Qu+&H0b3x24=z4K_MTQ@#VFMbhlYF> zpT=8f3E2-|=wsy1)Gt+W#3TvAu;ECjB~iNspd2u!Ue_zYl-z!LaB%>`xGr$QRTziX zok1GB(kH0Q_i~fcn!Za^R~s`%LlE6u-+O4=_t-QgbDF{JKzJt~T1qLn z*RNtI08k;w%Ib4r=`zQo2(8+{<%9aPaBZV!eNg!$-f}*-TiLqM#`Uv5mj~WGj{D29 z(CmxgL6(O=k=26-6K~hj-2MthGKP|T%|>I0paI{DuC5{RUGe?IkJ%hQ8yn2qQ&gu5 zFjfZ)w14Q3) zHwELZji<(CW`4ab&ZMar$vk@RZ%{7%emZWWmm|oWX~X-YlsQ(4Le9yZ_-`0@TM8Sg zBQUr_S)vg4vytH7^78UF*g?$KUSc3q!e1W`{l7P;-s=<}2{eqn3bG1H$;g0rV5r(~ z6xSQb*n`BHmSE_f)OvPgw1*6WP1Qe9$`A}3U*`}Ji7efeP))UnyAy_vC0j0VJTHFba|EU>p z=nE-yK%)$7i{Jp%u;rEO1YHrDcY6Ty1tajq#o#r$$i;BvS6BOY#>s^8CNx6a+~TRU z;9)J%D$rrZA<~@U>gT-Mo}1r4Ozw_1TUx_6fVfHI!;ljd!so!Zqe8L6pc+?w} zc`7=XcPsOTGAAbX^o^OwSAR0$_kBvzxt&i}L#P%$mZ0m_vbN+-p{_34fSF!P_=8h5 zI`>H^FcJ-JHz&wRf}#w0XbAX1t*0U)F)gi=BS3ExB!P<=NC3SC?AFz=$XPICc718j zS>;v813wFP2f03dzsmU2TiU%}mEzck;thlSdr;;Wk246feHt$XWFPXcpPd|-84YgR z`J*@2`H$*!nnWQAl&hS){lSn6PfVT~Cjyg%`{@g$s~PI4;9_936YDvWC z*i}e(7k@dEi_&GzZPsB{P0eiRm8v5*Bh~os%#+_D$oTo0dOH*i#3-!nQJS%66>3hd13Jc@nac>=zS z)!OIh7YMj7(!#DRONV*yM?JrQ@0CzQEJ80{l2DT8fg+NTy*PpoBJcW}dp%#aS{K*0 zl*!0s$&JSoV7}n48H}O6&0|89BQ3mhL>F&aaMF4`am`!BjVz6TbAnOu9weuhK%iiP zuX0mUYF&%B1o%emcJ07RC0&R3Epl<1!Oi`wBgb+8R~io)vpRfJ_GWzqXn7GQH@|2l zr6(CXxWkJWkU6(OnQCz?d;^$Q@Z(-5$<<4g=t0B_*dcK1ig(qjG&OP`P=d{MAu6zO zDA-W?X0Kgxpv5(Qy|6Hrb|7lWC#bi<@mYdvaR{4skRpOsv=1vahKJjd@z>A@MoDjN z$db;z=w=>u090np%G`Y}p;=mVYl1hb%v_ha(T-y-tm*r{&H)vX~C=j`c2 zGi>r}gClOo#;%7FiFEs(EAZX$0#iMmEItIh0G^Gg)_L*thj?Yb1q{oBUaM8)Piy61 z7zGSaXXmW}p(7IHR%&hG>0n&3_J{UQZ8*6P8NvSoEGeZ5nb#kFGM*d$!*VkJoPoX9 z+sYIRA#4H#aniuuyNUeg=e>xZ~etMjCpP8<7`PhNS;(k9xpEUJU zjD($Z6r|>;G-XgHYk$Ho8Gf${T@~QA`7dih4jj67Yw4a5^;5dHORW-6Ml^5q@o+-9 zgcnXb?gY_Ko?3&KE-rzPy@Z_6v*FO+gtGV*+nW>oiD@a&Zo_16DIfIcQuDY%u4(lZgj4x6|X(yB8nLsN(bM_!m*<2 znTJ067s@b4e4#WNOyLkVqm^w376=;wyx(iQ{n`@)6>PS4-&$QgI}C;uQ6rRwPE zt?qSEtPOKVR<`)00{sW}i4gVi@DBAbm=tN8QxbICmESB1DsS|;oM`#6CVWnse%@c@ z_4^=W&9dc05)4=fp|d}az+oK(otG;W+>x(WhouD${yYNvZwFdKN6ohPMjXECFZhfC z^(0D7Jbj)+?$GU3#^vR0*o?Y@t!DLh+P1C!+XL3e*UO$41tO<)UmGV*x8RiKGN8xu zhShY?W<%13Bj<05QY}j{2RyAJs053(VVa#;3A}Gai}k)KkE5&WX79Y2E-`3>R%EX; z?K72Nkut_ay0FK=FVn^`-%u?qZYcpIDqmAr?Y?SI6vE;T1Pwb%N3&IQS$k@)y)h_ z(akzMkhZ5LXBhi|F|f4@$Jj~x{gyUl2Z^^$=xO~EIBJ|yX$q8{eTRe1x@e3{9ia}J z9l)W6+uw)sB9D@R4jhqwXy*hRTxfS)Xy7z(G(fXaC4A^8^f}(z`#TwL6N&Y>GWnUt z>O`V}AyIC0>5|TwN?;yS-^=J|wI#ALC!!iF`dE>IyJ8!&9JBeQ)`<;L%~Y|5&}E7z zJF^8py!5!<}Gp&rhT^&=cEOk&dw4Rn2GpWVx zIS}H!zjeGP1YCcpq6D8k#0TMKB45(`L|FH~Zwuju8848HztsXobK)T`nxBT>WON(X zh(5k*7{#J{OXAnvZM-f{mg3^Aovm{BH!(?5qzZ_37s;P?&4zHqXbM|O^(NoRmg{MY zK{Ltae{rd#RWV&vOrk|?;4+x*7|dY!L`MOim2EjJ!{b9se&I6rm(?Aaq-B2T>vtF5c!Q7Q@wr;t%fCU%J#H<_bi*vr{!4(ln#!szb#mL z*n|p1)HhUs(jX_&`u;~8s*3?-{%Af+rBD)A#cjIwzibkO3D%B zZm2LhrKej!85C3~P2IDB3b+PiT!s)<{E+42HWUdhvKwi*Qc>mjXB0la2yXjTU)dy~ z2xZgg^F0fZqDNi8`75NIe%B83R?2#z_0|5&!YYUm6{)NYqnqk*cKoMZLBTPXh{zxi z9?^wKL_)FI=Fm?iezml16Y2#|5$u|!)T#SF%-`TrjDc5@@OAy*n~hN>p+P{lM#2AJ zow0DW2+GSdhp%0}HNIq)m8vZtq@+3nZ@C`3);nE#OskZzLv)>17SzT^WtvR%E>m}u zpIaE;xbg0Wtc0irEB&bWh@9DP44S?n{6(~QC10{W{JXhwfqApO)^8j8o8Q}Y?J~OO z5ng6?v#8k`pEW=`q3Yd2qJI~Oy`1mi9=g((0JIQG_$}#ae!j}#Xn*tU$Q<=IwyYs< zG8<$+{eAAc4H2+4sLBvZW)D60VIWm=F;C1Vyp>p|cPmUXlzBmJ`c_yc&5Bx*Tun4{ zdF8TZEvvjXvsp-NQ*>x?$NOmp^Ih{SR{!jtr!qY(NK#)08j?Ts^XJ}>IF78Xj|1sN zF0!v~_RZ(=R4PtE{4ZwHA6T;rX~4OGQc=sv!Qy%o(!9FQdZ`(Rx$Egr&j{~ zj`Ub!NC~P?!{Ts~^GRZiyJmOHCP@|%LpO)vhnPfKzizi-Orou6RtyYdLT;|EsO#jQ zAp4C!wEb~x@yxgNqH{;yU0TY#7Z0z zo@chwtW-CH%x9W=SR_wPJ!!er_C>ZI6lxT==V#s?z+(7}G%Olj_4)SnZg9dm2T4|) z+VHFgnSPW3sRAuZHG0iU6FTg~I>{*(PR8jbg%UYaxv&b~KKiSlz=0JMV|(fWfWfz? zc?m$+2<()+D!$%u)73TT;i_E-bJY@rdT@uS0grja9{uDiR|TAZom8aUGTS;R4tGDR-(%P zfIj)Dy7x*6SMPVGyo*nGVZG!HEI_xc=Ok%G_auMy9r<+9Up6E)s=ZE;kkW+dP_s}YSB)4gzLIEqebz3~Juh>#YpJN1 z)z4+7iDmDeSw$2saX=;Bq|4kW7fBEv0F#*#bPWtvPWG07n{?s%hadteqAF8sH3u%o z(8@BPMx~;)ISyqeUTWN0YJiW4>}QZbNFJ8243JHPdBcs9c~Y=bO`>XQTHpw z8{Xf;-~30=OJnA5;DAq!NZY`ip4ITZp!b&b*hTlldr7gCEz88Ctw3ZGI}X z+*btH5-TG6KOzuhjPvFk4leFK9b`eri+@N~)3(VwiC0Gfo0#e2Gy0AG&u|Q1D+TrILsX z812=_dd{N=Z1V>2mu?uxu*S)QO8Z+t^2qg#Jc#o50YhPI4E+Jn*b>vrXw4Ms?z(>C z0q<8WpEn~~Tn2Kiivq-`Hp*YnJkyn_YPUZKKlf49|5bPTXVZtV&y6$slw9oxGHzb zPJEL)u2WrTU1Ja9Q%q65^@E@+1V*oF~QacC^T^2nwy)W)`%9WC>lx&By{+`T*k{=q!w%i=;8lvL?u=d z4zi#5POB5-XKhtzpmIk<%JY`=k?2`fBcik@%L%bLsB9~z#r_K$M@Y?5a|KWPCR z!o(yP1ht9*`4rAH^VE9**0Gg!ja{qb#801kwsTD)qpl?XJm03vQ_WPy*irk@+Ey|9 z_EoBDzoRLvRP^tq`6EE{rCFazy-y5b7NVp5XBWtx0J!XJ&~aq&1?TP|hwE9m7rX6X&wFjM z&3hjk{8vq|ZSqI3mTfv$f5IG=BvLscYv+ZOdK1`4^+bu>$kNy+9darWltyc#Ju$FP z;NXAy=rQ;M6u9}hJD?M@ikll8h#b$j6~D2+Ou8*u@Vs6l8}6Y_3UX2(4T@e8g~r~! zt@)zk4*DO%;Q1^1xw!{_4AB|3GO?#6j1#A&Y0*F3^Wnih?WAD~JQRdX80~+=Xh@^= z?T_Fi5C{P4{RSxJ-ZcPL-#d%qPUId)s~B!PaOR_M{WR-%-YX#Mh>psms9f9@ z=P`(Lle};Pv*Qy8v^35K-p_fS#KG4GfCE7>MnO+*tQq>IfexIF0+N=mAJQyJi;U;T zD+ct+QQszo7*v30axqa?d%EZkdS078+*WmzT3E9edZfwKgo49xe}e^Hd~9>UP&aU| z^4$t9K)`AU`SJ{U*eBJ(^X`t7*a)cmZ<)!M6dDxU)jH9%&!M9xTxCW+b?kJDPW6HZ z)l@&JrF?zkXC<)MF)i0w~M_#Ve>@T)a8XqQDEOgy9l?f=45TUhPW6Vg94J|>(*kzEp zEVm~gJ$u{e?M0I0%OUBoAjjxKw7C~3}wI9bq>m&v{Ggl?TES-Ew63Kt( zs4#6jZEUoA1=#+opWrdrc6~7M@Rz4Btb;@gRqzJ03O4YKrcdSbMmWBBdl{>-D@EYz zydTB%VB_gCb~u!BFP&0=>uEiaGc*>F8^c_NTt(FCLC)o@nSCb{5^C_Y3~*O|*W}Cewz^Ml zf4`r(d?e_b2?#*~(VltTEHx#vy4oQh4MNoSndu_}zfwJs03+D!fF35%-ikYg;SY9_ zp!Pg*G!eo0dNXq6xoM6bMG^MM9^Rq$ccW7KBMnM=i){OI_>h41xTYtF)^X(GK7;ohH|NT`5h z)EeO~lHnEQR77pmS=~<=xlMU%V#7OKr0VRoC$&y~^ z`UTdJ`}i2@2YsYXjVi))Aj21_bpf94Wd68y5P57t&?9maGeyI@Xka7sFE^!#Pbyry zAkqLv5HOp;tj&}l&&tNO)Ibq#;opYiNS-q2yYpsr^U%4IdM4VbF$}7Q1{Iu;Do$-J zee#0YrgSk7HXVlNn`PZR{e4VR#;@21MXpUf=GYfb;Mv>nDKPt5ONI7cMQ2b=xq)oH zo0Yv{k%2X^mUb(@0BR!(K&DyCfSI$hr6poX0Q`~1A@3+pU`{{<&VIi6Ygo9#s;bq( z!N;(4!-Fua)A?n3(3N~m=lHk<+1n(UxU>@!B7eg<4jmEKEz}ynjfMd*ZODg((K>yH zj|4btg8qJe|N607PiL;5fcT6hBx0XJde4qab1^8Qbe;A&i6mO6S$Mm1duC;g#v=eP zq}VwJ)bJC>x2uJC7*rGPZ0{o5SALyRY;JDCHd|b(wA$mELoo(&^jl(nP)0x%6)z_G zJj}12`~yQzH!GhkL&e4`DoiP_1^8A})z|c#9;^Y5izHt*`V)SqzbNIqSKga1QlFhC ztGG$w9RM75FU$zuFcL?yGF8LKvP1pm*GYHpKgJj2PCeZ(bGj&ejF(K;P^$c`woscz z0shhK8?_~BXhvBZ6dqhPObA!{-kC=6(;=hCRFzq$uEuxeEBEZ<`j_ZTMfYstQ=J$5 z9Wq9R5-;63NF3qa1=$Vg^XTB{*XUGrB#%a$^^=E}yKn0^c+J2&2krIA*vK=}H))w9uop9XW=}e9FWYE}yT+-wV8PLuuF;ED;b; zgll2i<9OlB|1>AG^tHV%-+hL+rSkANt|S-{Gvf|Ixd*HZyZ3uB5$XuwRL(i)Nkw^%q3eZAd*o{a zNWgSeEYtvVfITkn^%^Z+j^+7?bJXWz#iURDQOwoNRW>>iFxACEhokDWR_ni>rf@sTx0UqIi_Sm( zbZY2lGesMvb;q0JZ>iSt@(n5IXt+CS%i9}=*|K}EF;xZ6WFWL_s1}cbTkFg;Jg4a8 zJx_flIb=6&VtTTPg-5bQ4%BGYhMQy0NaqMp=-I22XTA#|@VKOy;OCos#lxX+7g32I ze>QP&M<@dX?i0u+xXOLfjqkA(KA);is~xs-gw;QC?5Ily8sHd1YyYE+Yr2mn*odK| zq#`bE%^bDY<+STTv}uZc%OjmE`Yj&*%Dx*|fE(C$_}<8`_fJ1EDOB+rm-JD`woKxA zV6OX+6T|tL>sn+^s%hoIqetTz{oBw>arZuZd2^LG?#Z8qD5VdI2%1onv&$B%$oW_0 zjg4J9^Ata&{2dDXH|y6)SW+^q!+%-rLYOC{qttb8vOGnh zG`v4ZaE_XsqCFhu(yLxYOP2JpTVZ}oW(p%ILmG9C0N>-McP)F9(knNxOd>@In3@kd z)6fZ3X^APyfGcFJM{`$+{e6+zC-{VY9(j84Sl8+O^Jvy^Cz8x6|Judrl=^Y{wz*29 zPHbHTos;-q4)8%)#3BK91b6q}Ej8Ts$uJ z$s=rkAQ2?f0~+*NO-lYvRgk_z<{G-{m}_d|=5l1O24 zsZt7j?%fDGls4Q*n#q#ZF1s zR8bviGw6uCDf9Edz@$3B8>b;H|7xE^y^HGoCY^tnniP$|)ZFTfx zNq8JqZZHE_N*&LmSKL)sjQOSNOiuviq0m7aO8t?5#yun_fP)x2=Rlr?T*N(Eu7-w7 z9FsW6+^Ko}wR^GRPtGK=Dk3EtGNBJ&yPeif82z_)e+0SXs=5zZf~N_&kp;LpaCT18 zBlB$u(`X`6&CW!h1Gsa_rV6GP=-RpbAzWhN@6*cg#)~FefPxg=T=O4uae-dRUiTv$ z#D7M+AJN7maxVB?oGY(^tpSYKn{4V3OkN8iIUmTiBzXJaWnQDli*19GYhFIH zJz~Xk%f06O+H!ZWg|=_!T=?IcRRVRX0o^!p^YKvwgSo^z@8BQ1PgK@&m5jPA*@``e z$HRtwuZ~~+_5Nyj6t)}PG+x6t9KVe&pDlq;h4BIHdG_#})juKrhN8xzhM@kBPX>f$ zgPV^-2%?gB4^_l7UX^Y2_kR5F@q-Xzx3RTDIL!f>Hn8IPp5U&XJ*+iAU8!Og?P6{^ zGya{7F-}Wz>7}ldX0iIK(SlL!m>b8@_KrbK%rR=_BSoq1yu}UCTbg@@gtstWxAvNu zW-;&Ydq+a`NXRLVQ zWG~XUf8gj|`0BU6w%ETP_+Fi^ohCpM4@ruJ-dC98B;$&#K~#WH(wfLfKjTa-(2N8C zR&@V0YTNNCbQj{BpGZDX1@V~i?WKb2i%mOybV@C1~=g=O)Z0oC$4tkB_(X#Z=wZ6 zC!$DiEkaOFD!ThFCjAqP20g!VUT5(j?U)$a7=9hAk$3JTu zdB@E?;P1vA`vp@oG8{>D2PuV-Vh2N^DZ-&H>4lEP)mB2`V~QM$2UbC{5$qp|^|!+E zjbD<{g_W~cdP|r$NXD;ZA8M~&*GDKO+BA8WMB29X&YJO_e}1_)<-5=?cVyk3)-oTN zP5RfB^4#@W%I%Dsx7#DV>whGjha;8!|Hhj_$X-d3WE_$XAtNGN_Ff0a-Xby@9D9!w zhX~pG7}>H{l5xyrQzYw&B=vir@9z)jd5ZhKKkv`=zOL5=4G+UHb7n7vxG3a4A=!Gn ztFE9}C?167-iBNYu^@RYdva5ljf(6{7FR_7DE-J|C#AiC_^y=TO$iJ^IS{5N;?_ja ztPy&j=?=J+pB8Zs+gAH=dFTaLq!&i5o@eo69cg=-@FRx*tNxV&@i0`XO@pQlIxUjk zG6x}heNekuHg1y%RENuLmd%H!u|>;`fugx-i!cSMiZKHGU=JbOiHrD$g+Y+&z9UYwTtLswk@J04` zo8ij1*P+w;dYclo@WLAa+6+xMja$nRBa@){!kw%m1ks$Nvh~u~gC<|F>+xKC2?JTx zhx^d|i&Q3GW#}f8lZvgOH|8$qHzsFdWaJq3TO}Cqt1gDgx9DG|fcfflK8p4x87|-B zXE6UCi+}6?`e&-FVQF*w?p?*)5w5}R^Sco1KLS2}Cx8+DZCIRav&pn-G)WoM{9|LQCVr2ZrPp0gDP>N)VVQ(M?r<=gQ0~@hlo|99W^P7nH%# zt)HZ4+K336gewN|ptmKQ2}KDr|JU&Ai+`6^G#Y0$KZ;!9v65tUhni;yFzA`d zUDOD-cW`ez-i`%=GQ^%)LaoT>pI&17B{hzs4`jI2gcI2wcfS2GRS!)SJSlGnzNAra za3)FKUOw7W80_cKYuBbPU$bc zYRn{fsWNA#4E6!DC$v0U6XP6$q1!NP5EExaCBt0|LE<`yk3_fIR*R=R5fO>Mx_6l7 zJSo0tnKc*X_Nm1OBc?GzNv9s#x!xc~!sQ_^#QN!IA+WspC+DmAU+04_zY^+mH+_ZM z)ULQI1|@mmiYR9EkVb>O+-b5L62z)4T6V6kRAU)k+Fe>73}+mhS_I)BAck}&t;Ogu zBtb=fk0?p4Ohi?WBkujw;>M4+nHdzGN`Yj$z2>cij)7g_l16Qw*+1NG^|S-Zg7jOr z=-(PYn|aDZDyd+8UiN+l*H@hW2VbHm2h=P=s}72s;f3B}=Cxrj;xX+mX5;EwZg_j@ z^JfHAXeh7oCmup|kFs25X9V5s_+{_$;yHU{&a@*Da5FKn*1MOHlIIQ~Uoda_v$q|+ zp0`2!84Wxg>nOf~52ip7gjKN}$Q!W=)uEO2+!*Ip`bse7*>gV}Ya8H6o{>7-MuZ^)T zMuyma;16kbD66(dl&M3#Q_!PO@!2|v%J&LUNV-MmD|@O;_EY;z$d@NZ9G(*2A@@#k z<@p(^fh9wS_qnSoRqK*qun5eJO@-Uc9OYGyVf?fIY%T_51BXT#o ztQtaL2QoQND3WtT!ZEGmw_wv*M$4%M<+ zvl^`*l}E;@@Dqkl-X7IRCUW6Hdaen7{|DGj#(m25Pj7yhpgE+z)*D>gyh`vAkNny= zJ@2Tm?oBT)u4;ur^-~G|=5f-o`Pp~-%7I|ZV9epO{@N!N>jNgYcH7f$RUZB|2??eO{kY<% zx=Mga*lsxUH=B*RF(Nz7w~cTSQ8emm z{O7fYNt*d-Rm*6L9}aN|7?H1T4YF{Cy3(f^TXDR^Z9)@7*kClWoHlyl_V0)8 zsCgx_a55Tpy~(^5i`L5bD7$B6*YLt=zV)Pa=CAA3ETpo}-Dv|wso39=%oGg)N94I9 z;Yf9|m+>4FHzGbsXM>H|NC$xT*(C`Slx3L|+zS{0T%E|N5i`9>o#{cY}zwEMZ zah6lpD5V|?^wuGqd)qy@jm+RK4jLqT;D1`Up|zU_?<(Bg61d0!4hB9OGeOC_RS2h? z#z^azLS2{Rz8zlB_P&u~Fy~4$#UA=1`f`6%_jk_CA&FG4)kZ5@J{-v$%NawoS;|3P zQ7Qi*ALFcd!)U_b+7=Qz3S~`GOh^4E|MH{g}|)4S(uN1CVYC43n^d+ubs58^L9ze>n8RK1-^NsR0>M9epBMx z$`V`5D+`sZ)s2MT?4%dxMmx^fX=GXX`5mz}p3EPn>7TJ&2{X?6F9Dj^7vyD=A@Xzj%vmq5R5r7M-2irdQcwohK z9>zg%4Ich3d-`U_;UjCK0gnm!aq#IE+fk+n)v2@H-7WSnizgisf&!6pm?G@m|IN_; z%S&=!gk4~J6|}H?3<71=`du&xPESp7C~Nyzr@wck>n3YDd$kj9WNcq8Hc5T3a6LY% zKUhrTlQ;Au*_3=OJ!2>A1QkT{kCc+aw^sFQU8HR4=`OCIvXZz^5T?I;w>+vlnyY<3 z0A8KqFBxLWyPe^S?rKmAFu8r3?LQdffBiL_dK0KAA6RMZBw#x7QuALqLSN7fe)QycKzRV^x4D|(5zP|Kgl zm*AT4z=Q-PTv+%h@6&669?pWcjqkB#t<4@k} z(KnjR6DjWfn}|N`#wfBW-~)y7CpSF-R3m87+I0+2to7pzNpIZ4mU5~D=EjeI0@8tw z5r=$#V*3eM)>oi17R^H*g)&!miE?-Irg^)WllKWZa$hvQi%vv8BYrjQ117cfIo5<+ zz=7Af76;GR(uAXFYe1S^mLDS+5vHaJss27W1&&B0E4UX&64O|WzMYf4I3`p`FvY&Y zPEAWgO0Or-=o>&Y>t==2dX_!1%SVx~5loJy_&jR$&}LQeY{hU=8yk^dci>f{opv=G z=pIFvhx6Um)aQR&3w0=C&UKJ|1Oa9T>>AMe)(b1>AD5T5gL+Qt0t06>O9+N0CID$9 zc5^!i2@9nA_{R>#c#BTNF|22?CA}uO>Q?T-m14>fNzpti zJHgM}E&D7#*?ro+!%DT&QbpdD*E zMm`hgOM`8EVRihpQ)TM2=k*55XAB08!^oo_sdN#z3IlP!1dL86TYgEQO&rjZEY4j<$IF7hbK8BrOph9XPJNir)}V< zplIN*wld1+D7VGULvtqig9A~Zzu2ev{p5vY3(-y6ZmH>9qHr#_W{!8sR*Y?A z^YH8Adyns30msZqE1wAIMSin}+d5m<^_BhfxQhnLg6mwC2Xf9%dOM6?)=^QIZ19_4 zP#WbOQqr!{^rQFFYdxX2?fAmr!4P__6?lwETnWYeuRs-m7^7Z>0l#kjmH&M=sQ`lK z_HN`8&>B`1Wq#A#YTY?wa#I76B_B+kG@h1<=<6H!t^g>;$ZWN!AZUQdH;gC~fL(4} zh7=T^{FZ8(B6!0;Nx6EOi}Vb>Lpznp5usOYZrb(jp$F~hNCK4twM}>604j3nkO3<< z*5z?!W~+{48yWM;!Vd$5V!;5xi<7$a9Tk%AkeaVNa`@)Mv^mq>0XWNRUGlcrde9!=H^z_-2Bpkc~4Fz_ojgE zu*@Obu+-sx1mO&@M{~XuLN*3E|61GaWDboW2%9p%durG|K9y2d5?zUJ?(%FB=l#ud z?Un5ulIFO=x*tRHZINLd8;aUEhYEou zaY^z`ms4g?+uzE*EKf6bnAARCKWK72U_PZqUj=4Fn7N8Rla+iTn~fsm#6j%+<+$*i=UlPfMCSdqxWG?3` z-L0_IlP(`N=fQk^{@L?p&a(;APDyb^8TC(H2Fwe?g;pQ)GERu(D;3DsUF5#8xAA<# zv4^`*`qkB&6xUfkvD1cL)1rs*8|sAYkwzBt3*$veIvaiD46YZ5LO|`V_!0sweMO6C;!ZV2a-Lmy)EtUle6 ztGr3+0Sv3Li^nh^$b&^nS8!D=B_~hw%Y2=S@ep@ZREM_j>Hq^^5m=mOZ36>a@bvmT z2uwa|A*LnA^!}I#-ZatBvo^p-!FcROLf&Q1dqV~Lvxy<55;TK#7YW8Z-yq}kBI(c%6#@$$AMR}^k>F;rn!pc2+qO0gGi?1|R$2!oPY%=Xi zWG&}5pEB+J&N}r^|8edX|1lsuzMXMFD+GypMxz6S?4_{)A>4^?~0HgQv zNIZNNt*3=}ZfPg;8B7l_9Nj^`;G2FkATG6f>TtTQW{;zM@O+-+FtIYP&IKrP(?#tP zvDVO13d&KZ(8}-tqw&cbbY)+Qb}>JC+4JI{CBQf#Bh}09UmEH5D;Z21Ag@BA4OmiT z`uuf8_&uIvpV>uwrHa|y>Um-(8yq(7VnARX5#~wnJMYIwYUK2A)oxZ_)|B8_Z1zcD zJiPi?)g^T2wVv6P3E|YC8VcJxeg+$LnI{O}PQz3S;uF^0YMkBi z`hS<5yP7^7)pj4<*FLa#+?GlizJ3e&snP}JM3>AzG4l%}itKsQ&YumKMu4>d(N_oD zuS|>_>#3B)Q5j)Dudw=Q8003#x(mbMZc^J3 znG8SzxMQuw4T-g&_6ElD3lTTFa-tk?D@Ga_;TMC3_p6-Kt45ZL-98*|TVyx+zdi^^ zKk`wHKmDAw*^8yJgw)Ctb#r`xg)7fi^GI3S_50KXHO?_~gJq*}B`#~` z3$98X_fAZBNAIcYG|maa)z#B?$i{X!b;K~O@;(C3TZ@1p%{!gkybM3Hj zpQKNY`pOtC)9_&fNBjn0m z7?`+P7%tig$^9E=*UGdfQZ^f5z5wg_<;~3uxXu8X;t`=^uzJr ziD|KQi{S_B|Grtl4mgA$0@V8fh#N*-jQTMA&dAu%1`6GVhP-|1o=h290Q+w4-G%!w zjrXtBa*+1nYvQY;qLW7zGRxHwn9vB<@b8I8^@!^uf3R=K91;gUSM)15-o_;(Fe>Nk zgxXHMAH3DpaoMf49WDcWs;Kk#4atG;5V4dhL>fuLDr>bW%*3BCTSV?OSs=LQJ*}OJ z=2ey?^Bu24?y%D*Ro#^*5vKcger|)S=y$)s;fS{W=BqwZ_CB0ijmUc@}Fk%5~jF zk{wFSUPukQ4lmEy{lmS>I_6E&TmRnRl^V)RX_Rz^dQkZGYOA5W3Nqv;zxw&bQuU8X z`KWjZ(r$RVPuJ8t6-J8%E*@YL3jS*%je+ef?wh(acW_!a3b39<7IB3C|^cjOQ9mG12XF?;9* znHgad>{uXY3NoCz@8Wq-n6;)FPe~5=h9lFMe7db$Il<-j9_vBJzI5OWT7pE(5V z@cA#6>xntr>S{AYzQM67=2CFv`(pR`4j~Fa6cZeY8KaI4$^9+Sp@(N@>$XjniYe5` zAOR1lm_)7=tQVeDX#vKJ; z-LhCqE6D2c$r#W!JWZ|A4q+pT2fdf$x>XvkAznI2I}Fn}mYRxMM-n!a-#6KdeArhL z-3s4As*lP!6b{ZN8#EI(>Nq>p#@>5h`D}b;PRRG)lE37?j*B1O&1OlcE^7Va68y!7 znb>+ThJ=f0nQf8~hz^9wUr<4#6SVW{nJo3Wub%dq=}um2-;G9*XfbB!dL34xwFpIp zTl+KjKmShSP)^gJYM&pI{|$*#m)_5-_+TTs7D6ojHO!aIM+EQn7MqRZKji2!bXh42 zZkeL!)e}rY%X2SF$Y$i&@y4-dCG`e7B)-8H1?~M3GbUvyy2C~V_<-va5ALs6#I)S* zY!7dD@0;4+J&E6)Vp>VL%ef<&PWs8-?oLwOZ7?ThJ$J+=lROf0HX|(8R6>_}Cg&sp{!O5uv zj3SYMP;xvd+(~!?dYig+M^0V`lX z!y)-qc7}fUW3Y`ax+^i0G#{;{|Jj6K#;^VDf8w&teLhCeD73yg|4YITTRlI0^Fkt* z?UN^QP|HBy-iD%PWY`R%&KZh0LuD6)ag#hU)5x01?lV(#-qfOxdgE|@xpK*(xB&_A2v$d6Q?A^93`z$srAx3dd zCe|8GvljCTX4_678!^_~%oN`)g+=#B12+9gI&&Su!l(tH8F;V_?7!3uy*?|bK87H% zpRKx7s5pQcqg&eGc;P+85yb2#a!;+~nxwi;?3H_=+sDm29T)9K56YFjoAMoUwq}HE z44aJ3+3}Bl@L~Hr>g7^v3}&}IXhW;ST0RzHyZy6tx3&Keo4PO`()%{<_QXPd>Rrl$iQDGGEkl{~}6>k0~%dWAb=vPST+ z;70KX{?X;}H{QcJ+3UQR#yUWat39g&w{ocx?YZva0@1u4?Wc&8bm@vwE75_ zq~Bla;uyR7U&DWYk0F<5;zjo7`J#QFrI>t{Nq4yj&;nCdZ?KAl1*|RPMNZkA03c>kr z%JS6R+Nt7(`><~ao*6^l`y`xt6~*!)GNU2_tvN+`+F_WNF25dgOEN<&IGltL?}_zMyEX(hB7bSP$8aD&ETVUyZyc z%ruBVVAQdUOhp7oqB9DhL#*m!unjKN5MmHg*O}o%fS3~+>dZ@z?SLk^v}FF|baKiE zw*)irh?~mjbX$75;rKG02E);g?BW4+akcQ~WY!q{B*{U){jztyTLc55M*w^~XXoiu zo?rdD<9{(!%b|KIH$_5!@E=fdlE^C%>1LO!px+lQ3FS5*QDXkpg4uZK^W%g~=EIMed0 zYbuqhrAx33$C}IvqiZ)w5!u=_ZS^X`^g9Evpu=Ob70BpQ;2d&(^8P#|JMb?^k@58$r&diaN0%=nO9C86+*( zE10Lql%PzCY=O+^yHQlYJ@hGW;WtUOk6y@dRd+-B-<&l{Y$yHC{Diyf| zEFZ{Dl<7m!==AI4DCc%<%_h!@-@&c+EXi9Tor~1-`=p&pe1CaZ?+A?18@bncaqK%{ zn{l<{?6y_4&KC!3^25IbGtM^mmEb-$4#eu4s~45afA25d;GQ#OiLn%svKUdQr%uoot1^z@_*E)zGgL#b(l??o zMN4^hR=8-=Ms@KsTkHBRBoQ+Ve{mTI~dIEWu-Ba`ig`^J$gwZ<^)_%KFXEv&0c;?QqZFIO!p$0ij!(+gT@6_a~oB zL?wxxSY0J6F7(B!n6L3`jBQMHuQA4I-G^Q}i!mVa$YS;IPbW`1;H8P|1;Ng2Qb#6i zJL&M{JIti3^B_zeK>cCwrGS9>n-n1%eCk#xCWNyBUEVuK*-T1jgSz~PRR`gKR|3Hs zqLK0vkrvN@Tf5vN+4C?O^-H8l8Xdasp)56Z8WOCPT=`$%h zV97aEDXAKrpWk`xP%W%5sEY+Rp*C~xZRH3yo_F+X!WM(^hfl6dYu8skFW-bVg3A!& z8!Sas=wds_pED0IF)=EQ*^Fx2Gq2$6dDTXB6Ac}-&X(b;#_JrvCWU5lMMMBwSZ%cP z?3dF;E5cka(8Q(ByrEq=p(BAw2@H-zOi3;4zuy-BE}I7|o~ICxZaz7fC5FMl-UeQj zzxSO7pWI0e`Ybzx#(y6xuW7gf$nT=0o6ru|`T}hduS0P^AGLJh^lMk}Wqv}whMjB_ zlOR~Al&hn8qU)=gqL%AnBB8#4obai<5@wv+F6STH`S)C?>l-IyS?;LItB}vPHX4v(ibf;mBAfeg5Q8|g~Yh9AwK<8XYSzD z3%XoJ+!cQLXA4Eti4zQyx$g_0MX9A7+op0m;PADz%DE%)T{u!l3sX~Kxo3uyKlW*h z`IWO*t$0kfz?VYWNj>SEx1qvMV?akp8E9gq2m}2c#He$-gzY=*F=U;V#c!4GQn18X zT2G7Cp%=w|a5f&Ts8@Tyjj3NdTpp6&29QAwpwfpQO>)!?C#2g2xGvDdH^_N_W9?%;<4OZT#jTP_@_L{w6o%q2fOT9B;;^y&l zMg*yzYhF@aU$5lf8e={CE9gBYiV1K|HPea#?)na%7kSiuYwwHi zraOEb5g*=FMSsh_e}Z{zR`}T4uX$KltJ!jvv0;yFE$LpkqZj2Y&W4i<}Nx}Y~vnc%CwMF(EJ&Zf`G*2VPI%y@Jh-$*&ZM18K@Q4U(v%R ztZy*OXniVv?}Mh(wIS$c#trQ7qL0RH!*J(DMW7pD%S zhoXW^zVd{}a~wn3;B1F=JzUsF9EYIS(}PGw2QPrDpMdV_1?efJv1I6ieK!lVFjz(6 zN4d{wsL|fUpg-+PlHj%U6AVuNo*HJVB60Zkw68|ZVViD)zrcPq!*%`fTrjrXh}KE; zZA+e|V#hY9hTE(>CZ1kXHvd5Z8?pZv+Au?XihxfqcuP99a1 z3)JoI?`O%Fz@tL1iS5uYxv}Rl$~=qj!aOTacw3}vU3Bp}Aw;~tanw6yp4(X!lE)a- zHJRb+=EpRmQZ-_+59l%Hf;1(uF0*i6?fpBs`cDx$g!By=W%j%10)FgUyqR`9Ee_ap z9pWKGq#Yd{9r>TYzz{z2?J;p`sDJ!Tm^G=iQ@6-C0ab$$W^ff(k5T*?qNihban@D5Zrc>zAH>Hb$W+)^T**=WkjocuqOL6Fj!hjJcG`Fxvakaeqw$|Yn%(2azO0EMD$Vzw=(zEBkf%+eQRDn ze{4R6mY?Fml9EkH;p|J|)l`x_iHodrq_DF5tFZ3x{{c_t{|wDr^^w%oT02P|tt5di z1x%Y5+bH9qRhWnu;pRr;MI`vmUP`Vx(ZIX$F}!c-?2cjrBDLL4@O?HN7n7Af5gg|C zEe)#<4i2XN4KQ0oEZT>-0O(-Y3qC+OVvO%%tf84+7|Hl3qZ@z4`CX4`iB?GQt89jU zOrl@p>&#M8!iqjC3Uu<6ww$qQ@^Fsg3jWf!{sBLDRCZ&xFzb!W&!BEaf}C&DVS`?O z$9EUo*^AW(Ya}a!>{gEMb(nNUl115s*`i?wLZJvM!fog^FRnO~qlupF>eftOXTfn_ zr&tjQbHGhu^(a2q(#nb)Yw@21h_)4!HcG@l@jmA#Qr7&^Xw>mw6FI1~#QZ;dh~)A2 zY8#`-YkD?N;|E2TDYt+aMl2;dRKoxI@h*=1@Dd(jEye~<%A?Hnsk*@X-g>Sq(K*zx zcOwuWpxAWR=iB4P=!e&HcqHD)F&&5ZVfguJ3DVhprE)1e>7;gERkjgdf-=exxTJEn#{2ib+J)b4dOUgrG|z=1AUP-I($uO&*%s>qmiD>m2;<2T%HSi zY_8vb>>Zf6-PS*=N6)}ymhZ6l4hViPC@bno)Z=(!e;v(Fn2*hCE2yciPFxyah>-*@cYW>p2#m2%maH$Mg}KPTRBKeHQS zxW-#-U1uo56p1k7r>nR6N8b=ha#n^rO0L!0HAa6f4WGl*wkW8CyKwq&bF+TzL?(7Q z=X4pHE_=we+>umZ){vGihJ#FPDP)6Wg@$p+Kch=Otf*D%&XDXEVT~B%U9QNPr=%F5 z<(&4s6l>@QCXk(}AGdjv3^v$=OX?*CgnjE7RH#-Je2Dg}6)4Muh3pj*T9URs{hNf2<(T&D{;4GzRt7C{(@l6xYTl$@K4_yqAjZl4#jPO6{v{QcW%KilsG zccWW74a0#Nv<;k}bq&pspB^I$LiN&@U%e{dJ2*C&nv#y#8t==K&}w@WHkrQYnts}@ za~jM_SzVir7X2Z@4|8c?|IY@LJh)y$#WRw^H0__YlJ>hkwOy&^UBj9tKl5FQ;}$_k zUO-BmOxx*+f$e*irPfY%r-F|tL#jrHk;2I;wPg;!JjQX67@o-6Y6-8HyLmbK_+2(M zlGNmTg~^hlKfYhywWgG=)+ut`X8NoWllQkwuJ9faXh$Xz@u7+QW&Eyvmpc!RL~nV) zSF-1_|F2d>=q82Y&fZa~%;EzkSs~>m6^d1Tl)tBwNCwNGj*&xNUrFv>d6)GtpK^YR zL0DbBa_!(^nL`pvT0IXf6&aqBDi(Vx;qGD2Ww%j#(O(DeTDza^LkR%HeXjn#>#G^7 z%-~9;XUic>ngq%#C=Gs~sCeDM$hPycQM2fMP?gVNO z?;v^^{?UzD> zcVOQ8RqGZ+*IRdcg&d7VcQt4jo4hv^SGL~t&}Tp5oXt96jae>e7=PqjaoH0!yzF?( zlI@0JXspY|C5klfJKp+!3%Dz-Kb~Bi3U+sHc>0sC&G)Y#623+>A=g67qx5+P8Oe*0 zH^_%DI}t zCc!neH~#JF4y+!Dk@)lKif2D?rrQ|Tix+G>-$^4i0WZ`b6Vb(xvvHL%{D`#~{ zz1!w*CDZz4GLcV?_;y)}<;XC9x=H~Ck7&i~0mJ&C&=F1UR`lr(g|#E~ z6Emhsk0|Go^t%PqhSQQU9XOr=~Pka2ps{;5*HS2 z)y*?Bx>RR8t!g~v$`W#-@M z;lBN5Sc04i(RK&+6vR9QFm;%6up}84SLN%UQazkRwxkw}Aym^7VMlbmt&pdCvs#C4b8tY-f8~a1|^bU%wggor}pzxQc$1X&g z(%O2r==yPx7HnU*#TzQ!!>(m+FZ)>sJc7?w>#hD0%^3}0w#n1tni*5l?K2y!z`QW8 zFeq(3d{Uw9gmkEINw8(X35LFX*`?i_{6{ApGbGRJO5oSDSU>M~o^?*^KJEEG6Lh^s z>29A#C4Aqh2NUXkjmWmVT7BaK=8oES`J=n6aV#KaAD{glI3o7d&z$B1Tj&c8pTuOz z!Gf8ikQ_qdwQ+qE2B#gD+$NnPvQ_zqeVO|5xbB1=x9&T~zSfkD4b9_M&X07^*Nm{) zn-XmTI*swCahW|Y#mnbe;4UK)nL!AQ zdAMxeCc^OJHn}Rw3CcW`lbCyHrnwz5>250DmRvCsqgS zq!>%=D(tuqTuqmO4wPx{l;pb||M=)C-3m!LniN5!if?f0qAL9JQT_wB7J z$lK!H{*vWz8Wr%6#Hv?jb5`_R?@6rJ=ASLTAv!4h_yH4T@DR5VZb^)oI(K$;_Jro^ zfML3`ud>IQf+8@hA{ht5%DBYqCJPj2U3ypm%9-t&VHJHE8A&pO2>T)i&Vct)w`MHqVXQ{nxW-s&s47X0`5U(5IQl2(%JG{2H6 z54d8_YjIsLC!8s{Oaeko@;Hapln?o!rFeWG?L_&w;f5Vw;amqY=A{kYR^QT3Hr>QR zCtR?f0miY}nI+>|MUImBdY{v4-7oV<3NZWMyEh9k-s`|yQKwu9E7IHkZ`-HMZ8?kk zt%C~0z-PAxO4aQ6HXS2(qC<>Fh-w4P>sSiM`8kNI3$w<66OL^{5Kj`rYqEd}(L+%t zi?$oL_!PDrR5q93_Z;g!EeK(jw2s{Q9%&%#dxg`rY|St)GA??;j@|pp+WIW93K%Z< z8$X}cx){_~{O^J<$pKnnC|u;!jL9)iEJADV%>A)V4JB1cVQTS!p3{3pJ=$?nH`K9h zIwD2&<(;2Ro9uZ5_J`mYTzv(-307#oJc%kjSjdBr(YF`%dx4QX;$~aSBP%DQ}%9&KzQOWA?BIRuq0A z!jHJHHmAkU`>l#mf$$5K+$_!XuKhp2$Kg!4r}Ui{VC1p z4>2mN%kq?H`SMb|@UjZk7rxD6{Z|5xu3M+7L`s@*u4>~{E-cMPUkKTeiHWeT$aPS) z;TvD8Lj!uV53*Xof0WWy)^?e_bP4(<-JV@_lN79b;2ps4X4frE_v;2sUlpJryhVRX zA4nM5XPcuI_^>2lmq=zHcqerTkKba+vx2r*X1DxC?Y4c*Zap8N!oWRm2bqKwLdZgj zkwNPtHpOnIYJ`>?9^&$8cZe!M*=I(EAFBTo2`*6&2w)s=)FiUELB|yg_><;LX*K%W zmX)(t4i+M)MCwq^1u0$=ax_maG`04ly|T4nYodxO176mo-*3A|2A~t1hqhWbNk**P zpxh*-c3Lm@+e6N~a1xyHF)77`Rc z(mte_bB)un_#?XB_D8@`B&?N*E?-yW3LC`o9Wy{vL1d&p1_7)zrv?U?$1Pzw0Mhdi|v) zgLtqkwUEA%L1x(1bFdLDM5sCF^SsdwHfb?0AUNZp3}b0Dv64Z8YV-0Ys0#Zq9OrDl z{2tkH>h2}ORHrut`e-y|py8T<@&6toZ8I0mMtU`o|^@k@#BUB61 zb_jO{B|WUZ)t&V#+1l(}*56*#BCnSmCOf0`nC4u&u0Kw!;89)sqCF2HxRZD>+%+`5 z5d55n;)X}cMS~)4B~5fN9^u3nwO;A&qd0THsg@OdB~Q!DwQ*u%bukWUI%ga5H^)TI zD6SrUfVD4KmSCu7(T<)zkF0sOTwdyGYW|DOM&eNY`#%TcvWaX;SAx%p`~9M-rnz$6 zT8ZweGUrF?Ni}_n`;u|(mH-(?ySZfn1(DdfyM3q%Nw8m6239SN7_lza({-Bs5>&Ou zS0-QAo#9i++5A}Jg$1--)`vucFti!N)x>5vJ8k<*Ip3NYb9HKB*Urg7>#BIKhyCzS z6_80+TD7w~PG0_RBX>FkPmjYYFC5#ijB4{3FO0tAiWk5%mcGaGXN&jkJe>Y`9etqE zazi5{iEx=x_Ef5ZYIY_4)7IhPEdN+1g9>n|s(_rOeIvScMN2$>ncO5}XweD-yJ{6FZ3SH*3#$+-W%X0myO{wh|d5dXgE?(fnX z(>2GduJ>9A@yOW@?1%M^(760|#2gUW5$p z?+sOz@&o6^2l4hpwUIjxvvqL+ar~0MASMpA#*jiUzcH|)hqDzfl;Xvg!#=(RdYtWu zUWaMnDKwImCNx`;@ev}JZq_p5d+qle*~;dtJWIt>b}Gl8zPEZB4lZc9WGE&W7>TO? zSTlNvLvyB@ueBG2LV8wtEJX6c80}WwpsH$yv{z`%&!5*1Q(yJpne17qpyqG7wz;oTz>GeOTTd3uzXW^(iLhfz{E===1iLV z#{d)@kP=<0x7t3m{k{7ybo*pFs|xy3UBXb~~?JRmRU75BQ-X|cLNj{=iz<3j5>@{n~^|3=0frr~wCr1{Y!UBTZl)H&+ zW_OF4sD>JYU0A;2K7J2KTqo_QOKv~&^7Fvkp-je=TPL%MH`+OB4 zv|I@dx)S+lMine@l_S3R?2aU>l;Soc)d2He)%$VxVAc&H&YzHGx}av-X=L6%lvw!L zbtbf?@GDmR$4As%V`p}g?733wZ>;4-BgNAhhQ<5SWeOkNY8(h%@!AOnhd0OPxnLzc zN3{%M-(-~OpwXTqlKl>AEOYEbicp|>WNT6kxClq)SlKHSmk@+p2N;cx<24V2{ceQr z8q1m&F#@fiB>S(>WqJ-T$~$RZDIenvr*(h*ce?2f>%dqtR~nLnB(Yih;*%WRcG!HU zfrSNM^Z1y&ll&4p_<|+bt3fAa>&4_0v5jXkgxIM8&aTzMrf=)Vk17*@1O{6C;CJwF z);*WRQU0BG*0RMsy=rJ?+|lu$NB+TUqrDA%f#B+M+uvJ-RV|Ao>k&g;-ukq#Bv3Ff zqA)d^^k54EeH3D`#Ct$cQ0t5VpCtAF^a^%M5U|Sh=}HcO5=p{&NulFMy$&nEO=U4S=CETXGD7^pd!;ak;xNR>T~JWxB0)x zu5FjXx7;A&1!DX6jH$KR`6Gdi*{tgW>aG-lIl6T1xkD1(lMxuiZ2gkvH2C^{_@JY!G30e z+QZc=trx0%f^vt7QW&=y1!lUc}UpFhXJ(ITyufR(moFhDct zr!`Bcczc6}Qd3bVDy#6TxFX6c`SYVCG0tdCxrV|V#v=8xxB3;ZQ-#9i0_bn-@t$)` zuh@D2|F=$3IGurUVwfLs^_K#(6G@k{@xT=vwI<)b+}(4^DQ}CITVE=Np3{ssOt$&c z*INN*U}JUXS*!nJ=_~`P>bfu71f=WE^M3cIzfjL%@3rQ9o-sT5q0g4TSKJki!ZbGJ;hLerX`>h%0TX(p#VKrGf2xf6tXXPk8kZ`<%94ZILNy{OUi zRI%^i8xazVOr}1C|LgZv_4g&RAR2~A5oJW)CGC-^&mN&6>M~|kWxW%n&wF(mrBEtVY9agc0$X$87b98~E^3CLq7O=NWQK%wj*UGp?1O@;MeMfmeI1h!DMMdJ zX(KDk&8J{iYgnY8)>qGryI4c;3+JV|-u)CeZW|I+ksSx7t$amZdZxOWamsEafAI;# z;Vw@0XyOiBZANSQXjFwudWznK|CbAd+(J7C<0w)YFBK^}xdtOwXe>ZD$?5X!kY>wD z-~mZK%b2$1I)BcL0?wn-zVlX9-UbY(lCfNw^PQq2qQgY9X?%jZA3QSpF%`wpoMnt$ zfl)LM#C1o|y4ox0N$??A)BWog@4F)epeO@k$yIahg)@;8{Wp^Eu=)N1xTihkget3g zU6wp!85!Cb60HqPiIrTT@ZjKBXfsN*h>eIO*!w(MJc52j>=^19|Q z+x218-^gw8>c&_1qe=4{!Hsd<51w_~K`m-;h21M?p!Ag5GSUK-i68!k*{8%V-KaP? zbH)us+U*%OFZ0P3#b4>lnpZBbTS&Av=Df~Icwx8fU{<82>9R{Qz=Nlb@+;*bmYBZ# z3ew()RCECxofL-*3-z{H8r}J{GaW=t4VgHEj8gemSBcSU8B@__98aKhBs>ZWAR2Z zpGV^SS<$@l>#fd+j&mhiHTS@h>dc1jl*kdQdF&409I|*%VK03!Rs5{+ScICh1hwO) z&z0dYZ*H`PmA#ybqos)&U%VBy#xh8mx;}WsdyD54^`X4u%dIb@PpA?x)za5QHScA4 z{2^qZCht7@$@_aoWU9V;O2O2-B^0RK<4DhdANHnMe%o}J#r*c#n2>`VBoTq!2|xNS z*;i`AzGa03AVcgRaT86hp-9$GOAEUrwoEmDb~|zR{Dv{g2p8sJKK1*Q4MW##{lc-C zVWB0%>A{okk63m{IJYz0i$Yf+I{9GS=9se4t3mxzjgEsuwk?z7r z@&7WPc#tJtTbs_xLx0M>EXAo5E1LIh7>`vuU%RQ4aFx%2a0yLFgcQ$Dsmw96pW52R zVdMNklRgzVq{p`!&o*CQcwIGIhlzN7U<)W40_E1ls+(t2%$OQ{qL5Va0;)b+l8%m_ zT2A{{6lf9J);LfmLA)R~%Lb1cU6f7#eYkm=hkwh-fiQy!yH_bK{Xnkz z!M#pL95GAZ&yDCdwe$?D^AF+4u2&|r&G`I5fI;dBD6%=Re-6a@6pN5{Nk~@L;yT_@ zN0Ad7ryl1*)$ft+H%s69nO`boU3zBZqvoRY_8s)tkRvsaD8qlmjrHSmct54@Ggc+% ziS$4aF13$1(&}@0Uv{$Fm^Bx@yN0p{Sg7;HUr&GxT|NMtB|{XO$q3JQni#fC(5E=a zvJB3##0q$%KCTXj63U;p6Bb-2n;OmSQ3^u67Z(>F$KOrxI98zcTRl5_^<`A;zcd^J z@rP(rMgQ11B0BFzazJ-NsQ_YvWwST|Com}J>g=Wc(MVl{h0>phrx3Q((>9Y}MInHA zb5{E02=Xa?l=0-HbnY?HX#2y|o~>+*J{2QebaLXh5g1k^JdEk}w>acN089?pfAB=K zxy*{q>*QL0#N{WfYXH{rn!6wQCdZhXW;tfqi${>Ahp_SQsjAoTs`RlfVF<>iCCjf4 zEf-a~(+25|$VTQ}6u&7ecx&RkW{+wNZe`wOsS(qSIsUrgA+v2z@oP#^`}K%yGK=g; zhJHa=Bf@c^52Fi%=z+MZj-4L{?n6kvA%C@jq6+9XDdmk%0x2Bme=k1JN;%x8=)XtO z8*8I9zUfEhg?Pf{P5qgS9UPJUNQfCF&P|NTtM1eIx zvc-BWgCXoqJ;yEAg6)jr<6N@+iw6cL0xbv6TKdbXxD)0-6C~LXYr6=opH^CNYr9D3 z%RMsZtj)?(q?M2M{bIS8F;>Rf&XKb^CGkWfRV>j=Gv`IIC22kAz#HG0bPhTmh+&JS zy&^Ci(|yAQq0#|AOcJP+nZq%e8f)Y5?2~^cwCb?#d@RL~US!4+%K(N^X5IjR=SpQ& ziU%6FHnCv@T2x2u^qn}=Eb47j*b@JQx|WODpnz1M$zB6Ca!3j4!;8~{|5D9R6l$xK z9p+lNJf1fP&Y>kKf|dQC$j%d~Q>L=I%eTGz_LkG@I}DNR1UEAvW?+8q2TJ!Q-^SqOrX0j$ak^JSe;K z(H1n1N?|Pm`EyRy@f53u{)0xvji4C@vOnxPsOOhL=jR!wrNX4YL%aR%s9oyaaWFL| zeOo5SGOWQwSTtO1r^RFYopt-8m2g5Ot~`N;@keX=T)}7BDNqGup1v(ZwOJk9iXrVP zl1*P>on)5Tc2?h0P-HB?EP(aDYk@K_bKt%J!%HA_WZ?P(ZA5Z>PryLaWcc=Y1o17g zZcf(9dUfAMPRfN-{d55^%+iKUPVb@q=MkX7@XJB=zDfxjA(g9zBdO&nWSFtNRPU2|3hj50Vb_`IG3HAv=Cg!0 z)_x{%*C6C67{0~mpKg+XYDBoi@49y&i=*aWY_e&Xh&qmTQzTirV)yEw`_u0qYU+oS zHVdZJOlJ|-D@L!`WFvhcAr%5O-N`5B7CaQ6x*q`5anC{)&tJ5N8O7eGwfh)C!g1p2 z&q@6xgrrheEE3tOp*zFrqgrA1x>%xMGV7-Wu~?X;mLJif;h&(=Kqj4x@<+FjDI#P$ z$k!-viML%^au6bvr$;5%{80U@v58;~K%L*TgXkTV;OKdYXtqS2FQ0_PU?d++w>fZe zVDdb?N1&5(12Ym)X(8nV6;H3k?d#Zv`F6!oJ6_RL;+#BQ-|H(1@?ONnR^as10 zBWrvM|F(z-dYf~#ww4Fs?T5{~02={N9+>@jDP_5_%-q9p=-Q>(C(p4Ec^O1SKC7x` z$y@w1^Hwj4cxCj7!oS|-u6aAx3eX1A(`VWa+;X}xJ3G*4x{&DfT&!nq$@cG19%6_(D{f7Tv5;={P39h{VM6RuSs%(!*}URq8_tIvw>rD@$tA>Y(BR%u~v2onI=k9F92Pz_^1P#K3Q<*1YDL2K+I#(J%6_bh{wwPW8O3gG-HY0mnyv zRGa{@Z>bE#?l@!v{dMr~1QNo7pvb*#`2as&rT$F{W@N|uag1ImF4 zi?rXrE#r%1epH`y0i1)!UEBpqhpY{7P0aLnNC5;3b3|dT;#g7^#Np>TiRC@-Z%I3+WvmGKQw^gRKg+Gkb5` z+**Hx->iET_986zsh-uud$Y{0J=dKd+UpoZ%;+);|2;Oyb?cq;N(pgZ>h~(g|K?rn zEO<>GW`ZIoeqU$M^J_m4WM3wG=ji-H6Z7U+KC3FY=uNwL2TzrPZZahCm)GM+De{bS z>f$kH2i^DQL+R;T@j04%o1u^9-tL$p#Fi#jrH%sl?esU`nkrxXeedLL(vr6j4>`Ck!H`HKc7;>e;=@y7cSb81Y#NafcE%X^E`D=> zu<$ztT9N@GvDI=%-FA*Xr`iG z#O`(4zx`*YyrQXN{<6U<&hGsZ1@GW@r^zto#qW`FFYh!eU>iPtn9IDsx%%JD7sZHx zbut)7MN3>smr>gHzI23!AOvb}<&OO>km{<)*&=nsWA9-aPa*GQ2=%cwB5>Bje=ew` zH!JY|?bH=NJh#SZD{k&olvG)xU}g(G?eA2Yg$8pCP`ognJ$qKET_ncp6M&!lv_gD7 z_@thK9gXDKp&m<0wPRQ*;@8>8xGjx7fVmR8Mu89H@uQyos0 zj?SX7p58jw9sZ65^cr=Nu^B1ZSaE^NiZsZSxKK{hOBuV$r!H$W@6lqKH%mHs2J!mv z_CKcGz=|RkXT^PU?q@C~n)c-S9|9B^z>vA>S<1$I`ex0CO(9ux0h3{>^7UBrW$E*A zmtn4z{gwWU0II7Gh3MDXt27Rp=*oH$C)DXVSt zuBrdFIaS7_)rcc5rL1Ybulrd$xKa9*NqA33WPYJ8j!>c^E_AT}1bU-z+w&!oqPpmr zP|~}d58DM#mpRUEHoKj_+s)?OUV0I0iiDlu3Y~m_RW|ILA#Mgc`!Dm|2k&7)h3`N} zL`*n;@R!aZTU$#lHk_X5Ne(Tlm2wq;UJ{aC|Fo)tXD)WPgPkSWCzGogq$js8!<0B}dju(?(zr-nMq1RyQaZ zVCi-VL3B83HqaE9?NnJAFdao@j6O%)ppw{sV6lui3cZ`4rfx}O#UeGw#FB+N0pxLg za~Bsl0PKiO^RlSE(X=;^_f?AAJM&{{{JYridr85C$Zf!>wj^OV=M8H+{(B~7izPPa zbwD~>a>d+op8aIPY-O)Vae)KQ0f79hN<=Mb>FT zA343Op+<(VJ6>Is^h8{#=XFVQJH)c#u}2%GrT6Tc-Ib45yLt1T4r#1dcSxYJ>A1J9 z;$4fx+_!F&N$l6(cE7BVIoTL_LD>387qe!Sll0TcWKvw+)WON>BNpp{XJdCyABrTJ zHeO$yBR4N9Ulo9(AMUs@e2%nu!n1d;D{dXvKUw&iS1R(iyU@~JU@N)(g|DB>5v9Rt zm0fvxr6L|mm&sSH^qza|dTqvC!_^iE^cKcRvK60bYYE>A4@BCDn#jit^J3w&GXw&D}U5;ig^=(s z4c9wk3M>##SQx5dAc$5|v-7Nr31da3%Y%);k%O94WX81H*HxV&l|(rb+a{&ipsYuy zQm}88dovjIX}1Hg_?BK9oRh*n@#dLehZ9R>wv6nuMis$yc0L%gk_ia97#gvC` z(SnkB()=mKv?W>lea9iXjEB65Y|$Fhk2Ac#_HRPhHwX)%#HFYn5q(fBD}#8&G&ZKH z*--x6G@+-F*{g@Rt$Z_|bkOvLI%M0D)X9XTL=oVuG5x_Iu6Pb-KX}$cT$O0yXyv%- zB3USZNhUkvY#H9xDe_+}NLAIF1%^U&xylSWCGx(#5dZ=iu^;NCXN#g9lc_N?t4|_5 z@fX66YL(cDW=1#JRfF~`rs5#4k}mE1ntL;V3oCXkNFvjrm*(9`z?1?GYNZ0ZV>IVN z#+&>ftsGb|@q}FfbkCp%X_wanUqq2^kC%pBQhiU@TiV#?--htr+RtH4^pI7_e+qO? zx?mFlc0*oDj+tqb>mrSln%$P~j!S9#F;3H2T0C@4Y)iS+BPa}Fz|u@eqG8*&Q7Mss zMfBheL}ik6>;E;Q=kZ{nc06w0jqvyGQBE%chYkc+5&hzi7{Wy78s0=0TV2=QuzoA}>L7{;?VN)q}* zCngpK5rW~-Y)+{P#-pY8(MEoR46sP41>Jx#tY_@nBCI663t0mibpQixCGLPgXAw73 zk2Mo__++AE(Q3GSu)1aEWPQn7E$FrWx_)+Nzf>Tj!;|OyGU+lb317P++<{@p?&#vp z(~>=X;OFn1Z2>Nl=goGR(|UcI1y>HVxG8b=F29s+=k*=79(S&BB=;>SsVnQDUQSiZ z$xTTTx@RMNXm+JFt9-2_(zHINX`=8OoNA&ajnL=c zi$S3c=9YyRI$S%TW(;iE__qrEwbQO+(@ob+LScg2P$SxVBU>{5NKQp}ob@PzGyT~t z+xp`N;gIe5ckc1FDYYkxA{+>eiu4cFf|w0(DrpKm)S>Fi7G|Pwr<_IEji+$d!Iy5P zQZ~Vo5q+aW8awz>tlDAl4+C(cHZ{NWSmP^GMbMU6kaB$zb*TbE-qDe($i8~+-_oUK zn$mKCwU`<xE+zZ7`ha1The`Y=8(ZikNzI@@}^z$ zY0f}RkNph)^`6(B!NJb_)jQqY^KBe4$4aS+5H?mHMPD;>zU919JPTN3$SNJ!Y?Aw% z;l1X2o9S;!zP;mivcRHo^2hw?q<*2*2P#y6(j1JHcoHEC9=gkE7Yo8hEh8%o;K8mn z45jhh3t5wl@?D~!@O~A@|Eb$#JND75qpnO#=01#(^1w{=5w06W)D;+AViD2YWcp@m zy8h`=Jv{9H<+d6J)ux_xmkPa#8cLbavpsgDl89OeaNnMO_(MoaxBh(sfT3TRn54kI zbeJm>!ppn8L}$+^--hfG1+-A>Ei-9=~814U%Fge8npx0|OmFK1Amw$E~XNfPl9pAzzMulFt4B+6(UM z-zu?fKi|lofK_GjYPEq*@P9fBxIStJ|XpI~2_O%m4HTY>L z>b?By{A}_;12&@+wcKw0wT?K^Jl@5P%Naqd7 zh)2la`zH7JzOG7?pfGRpT&qilQ*3T+33}nyJH4KJVXWUBPWKh7ReNJZmV56w+{hp6 z>U!jOC?)ntj==MzgUS&YdCiAKb`WTz^-&M^S3kS{NVUv2aQ_k4be4OV|F zbq=!FkDmPC3dqiua6LXc?M)iD^lc>Z>Zcdd zBJ*Z}WGKRvhGYfAze|`}{!8_rUh2K*xOs5MBbC_t@Sr+!T~6?7B)OaK=}kC%40vWG9?=b3@+RxME0Q_S)8S?Gp5a zZ_amW;Hrr!5~QH_450y>Wt%944C% zlnOQkrqA^BmE*-7WPhK-vH&#UDVI32`f<(HJ)f2&Ck~cf%4p*I9*+7O87IQ21x}(< zFKoKoSn)LpK(b;LX<5^@Ag;>UwDUkj_dfA+J-k{=X|@s+EWJuBHrV0qFZa@Ptf?=L zen+2tcG+fR9`+s5^_?lN#W93j`=oK0q;bm zdwYNW`3^&34pA^uj7#=tkmyJ5hi_s`|K4y{qjB#K*YVUdT~SLflv7rkh%oamOu1{V z@FarbX+vxJK1n9@B@cqmYV^$=j3QD}Hh2c1_sEL;*0$LXl&!e4HC+ou3?w}t`QiNd z74_>OH6I_Ev}oV@`Q3x7Y#CZ9*@7{eSVUvvB$izE{r$`R&Bx3Bp*%HVraHXtsPUo> z**eZ>kD8AUY9{qj?WSVDFhNZb)RyTEY_E0hWn6E&apS`cDRB|ivixec zV72#;3F)){8cE(W!t_-xAphLY`b4hlZ?+^Wwj47$a>Wmc{n4F<=|6uuJ>42=gqbrp zMd;K25X1I;+`#L;-njdAS+~74#n5qx+S#6_|Jk?4MudQlr$+z#Ug5L05(0x+buK2I zq)s#p<4J0M#XEc#L))zxFjeQ=f0+NL@u3yn2(q=5F(%Hd!a`E z92e8R1gcBvmgJU+5T}OFPH{JfA?6%c=nSdf1&%|Qj?__n?oe-pKI&y-I9+y>OhjkKt%>|Km;YGp)TzeOdB!S@>d+^=hF;I9v;RnCO8$ ztS3Ml3+o9`04ieY$y?h%f5`2+Yi`5rvq*&JJ0j+)0pdZ+@HzxV!}D< zB`Qufl>NM4>icBUBwj_-{-{D6wAzdyK>AFM6Z!teIHx3q%LVoCv140%tE#q*6=}}P zF95%BxIA-tky+M57X0Xk^HGCf@$MgjfSdkCf8ivN0@=VL*W;ev5P{64tt~8DT{F{j zgb1nR*xdGJrs6X{3~$> z(OK`hsqU{=4U?^|73Y+Pq&4Tyy3QSsAMPKMBd2PIzjR=#R#8`WlN`Fd_}kB50o3GU zw8NPt2sM%eX>1Deo{!y(-tQ<5`43;W!h&A z<8=ktwL*B_gckWiajp7h^iUfg4o{h}M&oqGoJ)AQUA@RbBVjwb@{S8hll% z8bH6S{}U}(X$>gC&wFnK?hnsF%ol?0{rY{v&PnKv> z&xE@`%#)J7e}e^*D|NTOi3Qi4>=U#4m3KioSTow6&wmv4|YmC_w-x* zh?w771je>Yz>@dUGY$6o-~gT8+Jn&cK9%Q**dnj7yQyEx`MZ{Gla@1^##IMYBmb3J zC@CxMOQ%zpEeFj+x5a6(X;=4&ivzdJOb*4_S+1kZd38-&x1p@RAnu*@U<0q4sfcV#3u%KGQ+m$IAW=&=r()t5|*t|k2Kz}SFwT6 z5~bfP$h8nAa2N6`m-v-CF5|AjT-XGzrGjyL>#vFvAFRldms4}wvXHwhU7{@ii7W7W z!F{kBFmLCYb0tZpDEH0A6Fo{;D19-K)H__+cDm6JJ};N`u>Hl(njRo8&PT_7ri%G8 zqnDj7rH^}KxIUqX)p19;s8tIyZTy^a!im{g&NozrUW3W`*S-lm(k603T{U#(ixTnvrWknX0aLm~(_F zfybni0zJ+BU1;~z=P3A9vD~vN|4uP+l$EZ6uhEC0PhW!5@0Ud59!^s%O&jwjw5}4@ z3@tinQ*821lB|K#Taa{o~F2j`MVdOeZO^hMRhf)%klHuE~p~8$G5j z)pB^jA$t9;76ac8S}sGb$pnv(gm9%QVbwQ`U*zW!bKuhHzR(qS8YO&50IAq;fip(0 z-Q7#U!IWnTL)zcUtjjsF^qm~6vvU$B>Ig@-AJL8u6X(WgFYSNg#s9_X$JM{r;rrq{ zJwx{>xAip8#~c>4<7Rgxct~d6UAn5(-U0RzXuTQ3Ziae#wN4yJjwEwM`6wjfy?j`_ z^*i(>mj9!v9e3bhGrT!UFb{ctDF4;x>d#i8umhQ$Wei9{D%8a&-;VJxpixE;tGpNP zKggKVw#l|+_J2IWkt4(B2ojS1QK{i%4*9afX6}ZS zZ@wQrJ}pJ>`1};+Hyr41wrBWYAQa&?wu5megzEMkccR-L;o6pD*Yt<@NR^L|Y~tt6sGFY5S$g?J7=ALbk!E}Vp|@ZCx1msY z%cI&4k2z*6#ZcXa$lvHO$7|*GgqS4MgZE~N$N%lm^q}xQF+Xn(1iL#ZT8YHx4a%OR zIZOu=)|BR)Adqs7m>>C~t`c0Jy?0n>YHwV^w%ZT@a=sl`!WXgy}gXZb>1kTdF2uB5{%%9x?y5gnv2qF+aoJ6rVALUvT+X@A4L@gixP zcp^-qir6;Jbe(Ff{OLGh)wwvDlAeeoX~>v-U(K0Nh_0#@^;3BEhvJru-tF5W&ndel zI)Zag9@3Ohv~0V87mzls!X4@ zI^JzZ7yfjE!#Pw_t>76>V$M%Z?T1?>e}%7yu7!~%jjILWivX@9HF|Zw02KGsgMLhs z)4Aj3?iHChu$Q-V*(l=ZxV!h?;mNrc6?8{bTVb!UOADpj-g;?0n z3hR7)HhGmr+OBF@&Q8w>>rrSeuU&>|;A0gwWO9*X-;)%eekSfES|4Ph7R+W$oc=d7JN`tNT;^K6RWpf0|XSo$KQ zq)8W4tElR(VQN7>k;8laspB^5(1dPonb7s#l)8DZZ|?!0Hn&SdkxtDsdyi!704k!h zOCi8VA|n~ygDD+c*a9HR*#bfuS=b9-BkCPSeBd*o-b}5;`37y>mlCnKf!dA|w`(2M zJb7RshAQD#ZyT>X88@VfI)Z}jW7?$_yLKliCWi^mFg=gVkyJ3n5JNX(KEY4uMS%s= zVs%D}D+kN&LfM@vD8E)vP9&nR~Z@2&fX1A=RhT-nGNIF|@IhHh^20?o-g0loM z{jIui(MiigtwaHJ4@S@|KGXfNA`<#cltuN@!C#Inr?&v(Y5i?XHR>xuwA?y^yRx>l z6>?Xg_uw!6J}+(QGTMU6LQ$J?KD+HUYekW3&$}TPV)y-Uli%D4cpf8Vn{26RzlmvWU&7J7yXL_Y?Z zBN$1tvrWOl<7>KdTSQZ`NbSQr5oJq)e5+v|7t#be^un3p$E-S(&cm{E2JCFlo%I;P zOb{c#JCCHaxs#}_ml=R5#D2BLV!s;gJf)FrFh zAnAY;e$-pNDlF}F{~m26_$ukrMShku{>c$a)9}Qkh%wT zh~pE+Et37n&3xnr7P5osN+l$_ac}Ly+rJ0qCEdr}jlSJ5x%A+$QOI&-;}VPL&X;Y^ z`r;-2VqX0|8#x<;75_G^hTn!9uquFiqc6EbpES#uqOy(JT=AHY3L~*O!dF@g2E4^v zvJvWi`URufE0^L;)f=B`vUpdArciNt>|*|1fWrh)Jv%;yf@ zUaB<7!OV&jp1~|(Q9&MxoIkXsZsl)~Tc#4njKX0aGzU6*re4T5F%sFX-BH*sopd(m zJI-vLeWMOlJIpNDM}ubN3LMz$2b(&OsKJI`$1nojk&Is!KW3)dk3FtV!mn9{PZn@b zy{>DnS?AAwJuUE&_d|pG%De49bMURcnm70G@Imzd75uqOw1K&;KWqNmZ-ATPOJ1T| z-Ww)_kFntsY?0?HvXXbO-IYE>`+#2D60iF)s9bN*f<)MiH&!ZtYdsN$9M1kiON>S6 zh38mWu|!%L-_4@h3|r@}gnSmzhj0TICGj*J#0ep**FAB7?xR>d^|I@ZDc)`5)JkCJ z^y;`}=*kmKX1q5tKF;&suGZ8POo~^{T$+Bg`@0(J5sS z%bX01{r%NZ(J&Z(;J%E%d8knRX|Xi&Lni88zMuWsWpI|n*nxnv9(y9g*ia0s>Ll9O zjRJ&ElYTfH++obJ;mqH@x_R#17-=d(ZWy0~9$(E`c<&>3(z}&f+w^8-=18f!R_D1f zYyTlG_ZVWUw#;DEzJ-IR^8sztOz;Vt;*k57ihloIg~WWG?3uXD6uOf#3Cpz4N!Phl zq<#0iR_`2D>YhBmBt3JWk&5&VROYkqlh>j5RQ(mj%pR|%2Rssp`KPYQJ%h3Qc~1FZ z%rRzFC`)$6#7lZDhn459HLHvKoK%A@U7pU8b20R5?TDe^i+Y=_}Uk}R@XR!iMA-d># zR%B$K=DGdE{rwrIA&?`Y)5aUi|Xq2X3O<;XSukA zW5ZY{=iy!Vm=Kq{Jr33djN7~%t<-2Q-9J)xGC4#VS&P)$(_*8}d zJ>@Yg0Y%z!>8ksKl9nreeu^Y!0flr zWS$VZn|F=L;o+<*|rcj$sM z2z{B6$21~KbFCtxCP6G2m;T~{K-y#M^xJGtBUU0C`%FjT$$!D~88AsuAOWx*2&7>D zVm$di&rw}Xv%yk&MUtrj^s{9}^|p^oF}?fRTx8@D==S@{5wiWvjvxEFW3^b~%AKib zOQMM!jYAS`$CH=!B$PB~G{&(J(-60=C@*h^%q0kd0v-sP*?g!NI#4Ix$PANmo2GwL z6MkSRPLs5N=5y0BQ667|6z7vbo<4|`_5KTnx(2Fcl<>v$;W+ootbq1 z;srT~lM|KAFEhw{Q~bfa#WLjN-|?`d`HXo;-~bEMUIf^tIZXS7-XHcX#A8jNE$iU8 zMhg*V5mF9HY%MLV^wnRq?%aH(ZO$?yszTxF`VMJ0usi*UC=0eD=PzbGcw2~SuE73- z3TNZ?&9Eio1XOtAU97WTdqbp!>MBY&OTFMAlj@Qi$m34US5+k%Xz3WZlyGI=k70R# zeLlZdR5QPNVY2qqxvA$oFcQl|>2@(ieVC;@n&E45iHQQ!yjFRPl}z&G&dqIcK|01) zfJ?iR5Rs#-^r*d>yLFV?S+#u6J~d$GA(rJeHCBO}m$5TB%DG6sr!8Ks zdeJ0W9eh%+2r>!MEogK;QLARpK2uSAs)QjTEG;>VmGUW@FJLGw{_Dc~_h0*y@``L- z(w>#!&K2(cbxoa4nLEyGhkU4A%K=ZnOh1fK19ds=WNXI1PH%9M;=lyrp%Ha8J4}kz zzZzTgbUJi$d@}A~LiHm1C8VK=x>ajC$(h^B|8KwVOb&)rFH%>cZZb+imjSwtz7Sb_ z=V)VJk$ydr9OM#D!ypyezQ5-F0G0(PyUr#Cy*!L})3{_X%|%+~&A|Ww4aJ@>N6m`R zzIK<=%RpT#&k#3NXM*i631dM)AD_@>Cg48Q^ltjm*o*4ZNj#W&MXI4?L-R#2iEQ9e z!lO9Jl^B|~=*yo-c{(veb@c=|o0%DS3tug|5`Ns=+BccmczhtgXIXRS0cw@krxzKl z9Pn4lcsk9d$;O86jWrk;LD807RFlzirP};<6PgB zpM3RMk}V)GCko!=9$amRxm$?R88h<|BjdGyDf5)YiqI|Xvb6tA(;ll?D5i`0WjYwZ z6nJe9LaP8iQxH0(g(W5EH8YB6&{4ox{w;*PxkmwdQ77k9A?eZHu})Reb((%Yc&CDTj}%m#M_L*03+PREKIt^c)(RFrI$bch;u|l~UBJEi zje9a2=N031ynA&&Z0YYGcCTI;_NGpA;q%GOWsQZ8BB^U|27h*OE__M=IxF`hSGS-g zUkL6jg#r-lp-6I>Q4%z=6JI{K^eQXm5PlfCk{X>u=HC}&q@4AI4IRrp{qv)#1>mVg zlQ4WS(xEpZBq^}#^EBy0+|eTmPsvG3eYoW*k-7$(`bAzd=*RI&P3$^P%5)teqAXvzh3u4!r&#sjVgTnFQ1(ny@RGuFkQ82(^_DNBcH0o6;-qV@VVp z856~~4$1rbS)gbe2~un3+$K@K=}tk0QdO2Q*o_#RZ)*H>NlAZo;P-D*eB3##=>F37 z+9k4#+Y^>M!4BtbeccDQ`uTQk0 z&N^|Ee?jiIZsu-}FIH!Xt}N64#J|a7uI0_g`OBU8MK{kix0Bxai)i4sH(wo=IPGkr zT@+j|UH?X2#d;aiE;{qeASlYAxUj?C`1cmPZXnZNc0J>?Y*D$kD$XMkU3w2S3wY&z zbk^NUYCZ&fA?kfKqCNtTz7yW1E8-38_tG2Tz>e@RU4JXWH61HO$iQ1oN2R~iSLLDa zdC1ME!SeANvrU}Wb}wgcc3b62O~nu!G_$)_|PQh|V= zGr_zAwOfJnC@R=Ea(nJHw0uucnO63rMjz!O0FH9bM9yGl_v*>aF9EsZOg^~>W}$T{ z=QEpIle@FFP7AXabJI;j0q)_18H|fXHFF@edGK!gG5I0C66Ir3bQblJae_L_bj95~ z*_c*b@ue@SdRZQqV!&5yf|kH?`MxiII;`>sd-Y zsZp#14+?>tSw5nt3d^fRz02mao6KYfzNSiZj*!DGP>E> z)dN~%YJA-ck>~0WD71Icy36vOk{41555jQ8l8gLl)z>*GvM!@jH8+Z8&k2+F_pFN1 z@biIS-$)aepM0IO6-5)B_pOPGF03;nW*6;lg&xQ7V-+WRm$p z=d?&^&Oa}`!?L->lw{*B%tuQi&t$G9Zxl)E9T>dib1t3e7$2j%LuDB>pxpODZoHKC z;hZ(3PiJ1eJHK5u70^FksJJlV|4!b}RO{RDFio+}BbgEJM&{3AvE~xIS(e)GSDz>t zKI0KSX~TU3voz?C=O~e&gcV!1`$w*k-cf?;JI*~#j;N1*s9Li3K55{O-Fs4;y_f z+18my2w5hy__A_)z7mLePZ9L9yk-9OC&g`UWmCqhf66%IY@dHHz{0QK?*d*Q77Y>k zwtMP;`=m*WtiInvBi`P6jEm>`q~8b%KCs0+&Tbv^#~QKaNrb|?!}gfV>a@+(hVbRr z3*74tuc4}~@yA$3b{^;1=BJJw5BHw_)u`^Ra3AJs3uax!`c+dM$cdgw%8q{Lu@bo` zww#Ga^EZN|gJjLZ`@@B&y-Q}UtZg zl_0auQo0hNVvQ<9{rz7y7gDW*tiR9-E$I_1*F(+JV z9RsrRpDV-iOwyGNvMs%h;*F{!i5YZT3{=af;;g%{ng z@$nF|Z<##>oVGd4f}5TJ5jp`2>Q)6E#Kg8^pWX;lG6>5vhJ4vQhb=SVi{)hyxWZgK zo`4$$MxCL34g3F(8cIPtk1j9n+pVF2*N{f=E9Gf-_jelNFc!ON%TN7 zmQMQKr=Z&O3vwJ4JvvL~-kIL!bnAuuRpqUY;4HA66lL} zH{9XGghq6n+&b)%qAkbum(jhs^oBgCgNq`e`>po3Py#;vs@Ee?t8DtBNw{szN3i5h=xn4)W&mX!z6<*uDzM5YP>P~yJuHZ@ZKsGld z5b|ETmvi$#jyhrj=BQ01FT`t~ryi`=If$a?!Cnsy?#r%$=Z zv1gc2F0RPlk-gF;A&!ozkX8=!b!mfhcB z@7|W#&xbktW;_R$IA-!LK2Vv6USt^SEw=#U?IB9A1YILbQe`4%R4$WPmEL%ajlK}% z(ANGt0GeNKr-7|IvDjhb@|e$c`~Cw#^Lu(TbT+I6?1d_J>_)%VEU4yJ#f!chH%P^1 zaoY1`F2q|ScqX-M%bOKDs)SN)Hf?p#?bgc7Yz*B9MBfW1#{nb052E9f6PjxiAP-Lk zi_p63J7<19sB1UtmW5{oa^OAOVSYx(oF}@EKuKVFr5$BcpkF}ra0eimFPcP}9;&kD zSoR{S-VY1JF!%qiw4zfX(^&ay%Sgxuw?X8s0nQ5$F1v+>cGzLX$E~B!^{er+>C|G%2TZlth^UGEi%G;v%GF%>?*nzZyrDs+WI9Idt!Cw`0+B{t ze&<$Vx*dfTBfSXKD(#{PeHTd~8za@=zP)>r$ zI)BlN6mtA<&z+FbO&3V`wV9{A(XD(G)(x5pWGcWYb;#q7(*Qf-@4$${!ApR9U!2u= zrR=_6dlr*j+U^nh1bP4z3RkGRSNr$t-X`zQz1ua4N5#YpakkSnS?H{js+K(+l2*=Uit!I0+XqBeY=vaJH*|QiZlirVA@G~0A%L7+=)}8CQ?jM+7j~CnH zX~q8BJ?=e722mdu_P0#@hV%28+J}z%0t#HM5|O%pJ<_N@FN-2LgUY#J4r9VUpUsBw zfj)GdDA`DBQQbr=>GE?Et_OR-mQIBlO3mq#@YT{{UDHWBCNfh}UM~HkuJiYq#9RN+ zKRl0TP;+)TDK$TF-|w#Gb+d{p5xgSpKVVIWaj|olP;@DnW|^^CZy58~J*x901eJu_ zya&>ujx4^_OnY09hORp|fPBQiBVwXBqt-$~O)OHoSHT!xGNk~ENGr2g8+Gfjo?1dj zP8&+wFMPD+Rw(WkNXM>8XuhKfAjI!WdQgfbUp4gbPh8er7M22}kKt|8RYapO)g9Yx zdM3hGxas@Sg2&LZk{OF3kM7TkITIjjMfo;II**I-EI+@&jgmrdL@F{KlCL!*0E%<7 zl4K`GUAZMcNvuYnis)x1q_@JWx&QKWarQSZ5pAaFFHY1QFUOs^E)ByJwA36+P5*vg z5Rk*%Qq}F-Q}PkyTlfFC#0zYoYM!T)kTWv$tEZU$r}S!E>AIPq|3HZjl}hd1g3l*J zzjSD81g*x-;#3h9cgub1lHuqqas8Ns;`-TC1P7i?S%UQ|ZY&fo?958L=(~lJ)omNe zPYZgQm8}Xy9q8=7qL(na7;jKMgZoBLLn54=uN!CDnFgf@D9UpzC7Sh${&S#3J$pt8 zhT=2dX>;h)OxW8UQ@bz1F1vZ4A}~X;bSze@hq<3YyQ)1{z@mB@PBzK^$I@3uMfrVg z(=9oq!~i2L!Vn@qYA8wR6p(I|mhJ{gX$e8PLAtwJB$aLu5b1gj|My+XrC-Dm?)#j* z_qDJ1_S3Smsj2U}k101U*5)PE=oC8TG<*1~&z^d0spS|4_wTe5}(TRQWv#hDU z`1sxak|)036I-O^-#0f8ZSTThrq9G;ssZ-f3%a+uj~8(h>Kjh4(Avhmah!#N6BEr$ z;grCPc=+;XecLBs_4)Oiy*7baRk$2ya(9A~kUyQ!U#zy9Uq{EdSJxRX9Gn=jxXme5 zc5a#fHN@rB4@N90>N0$U;z_Vn2VjX2N>d*bqakPe@QiF^Br+r%qs`*_arvNmkfBBrUIc)lmn?=DM_DR`0Pf`&1v_8Xh9SeXva@5 z0(t{)0#OVd4Z>hry=LqJR|PeE)UfJ^wH*qPi}~&2`50jo{aLy>3y-9)H#%E?PWrzj z!e-k?e_g-LKv(@$u{Fx8xYXi;n*&{0m?@Eg@yzo zD0{{_XWlmF*Pjjt+c8d~Pc_hpSd$gf6L$@d_v=rZ^63#z9pgh%CE=-lNit9(d8Pdi zLpo;-)_=YHP?08 zZ@mF)4n-pB)7*Glyk(b*kbbPc=3RD@TxT(wFn_~_riMFGm(@WJ&!+_w^Fzdhr&o_Z z`}l=yESA|rh)R#nCf*7S9bNy>5RPNx5~c^o6C3R#4dKdp(q_M=a@^r+!+ElyO%wGJ zK0pIkl!vB|W@~dWB+Aiac?m?L%0lRearDM>o7M=Yd8Qj&&jia2+9UdDeIbYDkqW9c zuil&xu(pau&21#e;pTGH#Unu@RzhK$11>aSef06aDI7g8u(`#|d{IL`QAsX$jVz$( z9`a9F(QG=RCmn(hoA_QPlt>u6C9kHTp!9~}?4X7vI%)-T`9b9V;$hvlf81-+!XEfA z8U5|4q-~0aVJH9mc?^;|4V|1&-=@C}Lz;_@EIYK58N^#S!>PVv5EAvvAHoaW)08aK z=!pzeKbP8>U7|d767I(V2F|1xY{w2Ngz) zjfU{kED4@E;U4NY<9+*lEQtO=?FbKt!>uheR<1`%C4eJgMqfiCHe33Tm5p*lc_rdG zicB>cGD@N|kxoj!mAyUzieH7#q0QXl;_KZ8G|7(DPGlfhf9-b5sATWazI}t$jRh9B z2e(4^LrPxANZux>gXxNxdUP;wI5M)ZQ0$`$u5kpe{|MtY$C5>8kPgGG4Jy4 z(9nYq{C-E^wt1t>OKMYMLqSL9yOZ`AG3xo?P4^v5+#KQHl;&3}quc~SiM(x2{F&GJlKLw&~sCm|sLK%NoBvz#;{2*hT#J*6l@;p(;NVkrvMP}C=B`9Q^Z zSIT~_-`9;tq5V{p_KiHbvyPaI(2oum)&_ZX!Qx_QsserTW6y*POq3*MMk_;H==S}Q zv`5WJmaoR%8CqFU28$zqXgwnXOi146ozo1GDo`q`egr&Kk}1JI--=5S7b#W-78dm^ zN|^(4l2~!e3q-USsw?BVo0R`NAyRV-zxxP$jwL?Jy|(;yNeeA0{2X)g?&06l*k{;} zFtEO)iVTHj5oGTZhTg1H?bc*?t-K=VpzMoO1#t~h2oAc?{iO*D1jlVPnEV*57TP<}2gv`)fWpfT)vy-=q6!J@G#NSwhsxMZH8v=6a6%wtl(qcI!#hoAGW3 z>cWU9#Pq8zI5~Icd&oKe>c3j=1+SrM=QVfYVmt)IunE~+4`L`(U?Q08HbJ+D*_Oj1 zUNRGKbi+c16KhJ@cJ$TY!%CsLc%vSodHSn}R?q$r{J8)pDzzS((ZpGEyyY5M-g!ac zGDrp(Ft6#kVawRsRsewklUxKpl`#;0SboLDTneZO32K*rwb}w6y}E)-{=>?}dilEz zSvaF}V*>`5R}>)=s)DrM8!ERylzfOzop=boAvdPa3MsBRimGD0@K|omCo~9}udJyF z%*|y4Y43)n-@>3+lh!=#B~)o;Of>SGPf!dyNaL*C%3lW{-6E+#TsL*p;RAE*yA<}l zeM$K$gV`*{KZ-bUgZa#mlcRf{1=>C^TL1oYCGs~Ig|n=TK4EYv#>i30<>l05jo2uG zICcQi`03*Z)-U@!1?NOSNT_Et{pF)>o8{2hgOys4$`g%hb%Tumv(Te&1sW2Q1!|I!A!qP4UVmqo&MbTC^?PA{}}Kjf)49T53a2-0PiEW;w`I?J#w=^{OcPI zuKO0dKbzFU@KCqI;N(ckZcQ zb+L$haJ_^&w!V$Nhr1nb@+@bpEC`V*#+1-EH%9>`7%n&*4r9f$(Y|P;#qyhZUtiVM z=C8*Y`gpq}%Ao_ud4T+{ceMHj!Em*5NnFFsWR;3Qd8Bj=wro5RG6l`kUhoF^b&?l) z7RlS#44A_&$3C`4o}IZkFSxXvEy!~T(%g=W-*PZ96|4ww#t*_EQV9M8e-cM5~# zYKKM*?DkyDR36yJPn&!sjRrP(h|T&edCj=;3Swm~JmOb~!@;){0u2*R*ea(E;WlQF ziO1`&I*DV>?07ADj@Ndz{P5+#b7#HmG|q2lh*ZyIzgM_9qh@K z*Bp`Q8|T&67^t}*>8k&T4UteNiGw6bZ*+#v-CpAN@@^G-5L!bAU61!e;^E=ZHZa&4 zy$vjm$R0{WosBqS2@)U8Ejh75`%?+9+F()5OFC^+Wp|zt1YU z4>I`T7FII^lEdk4v=KA{4JY$v>FIMk)P+hpLMh~kQYeuX5*Ac$uwRerSp+eR)qLsA zrlP|+DP4QqNAsJgKIjABcn19Bl*oI56yJ&4g#FqJqGZg@bU30YionU!?E9+ zi6dQw1!hF)nCg&qaRrqZgqzkWae{TrG_T16i6{0}+>js4&#eG?B~$BQNtk5?ioa0o z-HCB<;bU%0-LNM6b0<+4A8swmN*+~H-cqjq>%zE{9Zq00GNjHHY|Htvn0cu(gs=2Q zZK~qo8vOFS%L$i62{tCmo8s2%2keMdIzTA{(s2nwNf9GcnItIT#QwXx65rtUbrYe} zaEpdl+1u{g+9~~D)o^mt6cYf2CJY)H`OpSHjX!)K2l7*PlHgN`l zrMlU1#UyoH7%k$zOn>&oQ;0z`pmbnDjWz013}gE6>iOZ~0kC|s-;2#madIir-}=jG4ZV>+ zhZLH|rq)E}46OH?$ufk$Iq46izVQ%8MkA_|Pm|Zc<4#gsV|04;{#c~+=3VqU=(*`r zVfnKtNW*oHEl6OXgnBV4Fz6wUv!l>sT2ZcX#egGaSNm}`#BQ+K>zLN)Y&gE!aMalm zH0mFy7Vl)o;QSY$CBjGHs!ve2-bLVrg%rV<+u**=1hl#!44Fb&hDoi#`HHRWR!uZ~ zTl9hQ8(sGDj5{Bekl+Uurm=60Eb{vd6~1x(@BVS0Sl2JQ?H|_1P4JeMm5Wbgw#Bor8cYoNM!^va;tbAV@YPGgBJ$8GyRAUFn+cR-plc-G|J6SZn-g z-n*fVo8sm#%7LarqawjQtH2-VEEwpl%ls9&2_LxG_fl%GQn7U0ddwYKf%QgS6Ki1U ztD|Izs-qVX3}|}zq#uUv{6(}JieNgX&mxd9R<1rzQuzDfrR6hZ3>x~pr+qZ%V+|yy ze0jHB83`92_rO1In_u1@EVd!_4l!E!S@yQUWuGiMI@*5!=X33( z;K@l9q#dKR`MM|FTwt1ce8jqCIEvFNHzEqd0h7Dgzy5$%;OmU_q)FJNK~wp#+9ib; zAImeY_YJfbROji{HLy3&ztYD+`w9LtpL61hz2MC~Z!nGJe&Xr1ib4G}DqI#t!q%fy z8On}TIL;ndY{5errKGSjl_#H)mF2sFO9ifb%tqRQD0vMH$X|DAYwVF1BkLdT${wC_ zTbzYai{*d!dH z@y+8d+!rekw;9Ww7MY&-z{OBVagpk0=iMDss7SB_auGK~GCrfZ9 zOB9$u@fh{m9MKVCYyI{0_4G3E0BFas@BQl(gVs0NJk==Azd9TjV-DnC=%}E1c#(V% zl!_lXyqzrlN*t?>9c$DmLOmPG5TtBI88fyOs~mDr^07ov8ne!fF?rZw*UyN8B~ea* zEpft<@ErrwQ{Lw!`Bo>1vdb6lU9l_?%BGZXc}fMQuLY_TE;OmONjLf@>MuOr2zNF` za90Q|hpsnOa$wR-2W>aW6yo$rN4Wjr83)AnRXPR`33P%jbRWljJnMT!ZofITAn|%# z6jxb*oj!5~n%^a*t#^@I)s(y~ASl@N^PJ2)--7EEH!>2JLg2MNQMhA2m*Lx<#UY1g zA1#M@j0BtToB{F}bqy(aoS59~E5F3CZ*f1TW%A;cHJ&F4yqr6V;Ny}km)qbKqjQr= z6(~~2v9U>3<{(>6ta51I;~@KusR*YCps{|CjXqTgl0jH?Do1`n0m%Faa~8Z)_P%<~)Mm z@n6k!lp&N@j0y@09pCcHdX4>gDN)1-IgFQVbjTuliK1c>WGgs^Q!;^fyKe7oGnQf1 ztOp1k<>C_tkpeE_WzmJpN)Y;QF(hJ^8%=NW;Hsf%z*GELMk=<2rQFxzVwpTu?fm#I zEdzH_-xG4*$DnD@&)st{?ZAAsyPL8|UvBf_p<;%<77!4SY*g)ZC<+384VMVN%}r8J zF0hawI(>{WLKw>zCr2Pl7clD(NoFadI6jxm?UA_`U*h^cQA;=)b^m7|meH(8f1m_ydHVB*&gg=b;=0w* z?)%>sglJ$#Etxyn0aC^OHc|t>)q2pSN!QGuDH!=^MWZfO%R14#eU6!oC#UDwJIA@} zoEB5&EI6ulB+DrEG%b4{`$wX#%hP*=ffnAszjsKWL(|sLL9it@U3C6M+WQWx7qC3` zIqfk%8g$YBZTU7yN(~vC&}^PeX!dojZm`{=@bVdO+`R8?za+o>o7^4+x~DNFqZQIq z9UeuJ%3D$RQPJYxje7%9Lu;I7y5M=of zl+;8mtiuuS)s=jyhpeMmj-g@15DouKxs!k2y+lL_FIx(aNSnQtwL7e;yCVGzK9Yzy zRImmeedGe1ZV*9d`{Bd-PUkwgetZHx(5ekRGD z%eI+?X4U)To(nYecCht3gnJ2N7+&#G`@7Y$Df5w9>A(J}+%YvpoS&cX=CS_R;C-y8 z4GSVf0&oEcHJq^I2VRK9wN&8Bfv4JDh|`=ItSAfzXr~i~I#D^E)XsE?S3^qA7QdjFR(7>$hWe0E)@TB#A_I9uv%PgIhR@!2Q zSbhDqn?3!f1O7z(@B$TI2Rw&;bN9FOf2kShbpu*|+7z*S0qN#}{f0$uuca!ao26yr-dri1nyxi#M* z`Bh)52M^1w#UtQtVNsE2$c3?{;YT2Sy8PDfMy)!eT~sI5uDcEu4bZnu66NTYm1dS# z2(F`-Kb+$68z@f0rl!q71qB$g>Wf+`Yv=c@a>Qw$0I<4Fi`0MN&71ywsnH1&`#JLR z#bow)x6pf(y&CgHek4$C@PozuVfp4VInPYusS2&3NS}#FAD-OO-|J3^ z9Y)!6KV><%x(;!3x>#hc;ZG1p*R%T1QbTH8&d%x7+5AH98H*Y}A%hlt| z)h%@!7N(@;H;VdS4H9{Mx{bpyLb!r2hfzSjJFXB}umw>QvAiGwDp|NqmctR*& zsZs0ASqD-n&`N&rIemKx7z2@j0wzYNT=Fwk#!^{5kvTz1C5Q`WwE>?k5l3|pqOS23 zBNYWc&jFC3xQm0F92Oi^=K#2%AdZv@(Ebb-b1hpa50&<4(GW@lx2JqFm1~cVqH3g> zFnQwdk|@36MC&FdV8sfOSlgeBpK^(cK1_Jn;_ct590YJqMS8VPc7RJ5xgwg?O`{_B zm+fD5%Klmvj%YAn9S@ek*tPX_{Gmv1)6;umHIpUfgd~GZp0d*XltY;f`Ytr|e=QLK8Xp zwY&^aVg*WU0Htx^4YlN~ByRV1pzj8yx(a4UGcBGq51GR!ikRa#hGFz!Wl2+#mG2YC z{-QyLT_?GpJ1@{MOxNKxWCCb7ZqSsQhcCFd7hTBlkS+6aV4WZX?}lMzLJG!tkp^|E z7~Pbj{cp#?)=V^c*vQ=-yEvz#`Z;f!qB^^Vy1cI6p_-n3yEu1Kh;mzI?Q&#^yW?bJEr zb6hpk7H|9=NSBwPSl~`jDbp;{s|=LR^=CT+!57wrFR6f%>{yR{SAix!t3^1cP1ykg^CqSBM8x!1cPO7RlPejgzge)*bm$$ze_3* z&+U899L11|YGQS;KQT3s5-yd<3iYl;uWOjq_~O#*$KJ(M?~X-ovJ;>AhTg}1mp7sp zMN?C=5|~3E|2BGD)aVOyA+bk@4^&417{ioDr!Y-UNYOS@f!2#I$*z-25WLTGK-mO3 zo~vN=Lhgty;5XP;c(vlG4?2_6Ro8+iiw;=fK^4D=T@y@pvl% zk(7xapd=(AAt96`dQ?SKwblj)2cz#0R3V>K(*9msNn~Nbl29+v09-SGF3|OFnlP*u z%>o2~HNCfhX`g;-mshFZR53G$1vm=tTh{B&EiP|w9iDaDL0q0#=ljVVNI&B_mV-#O z+^@wPclq9tz?`HY(h-ELxN&9hW*?+QdJ+PiFl7as%bmY0xaPArgtha{TmfI14G zbY)1eUp`TxlF~(JAvzqiYP;Op%+(#`)Dg%k@f?Vx0U>1-kIjGsU(O2RJQAc~=?tW?5ohMG2;a-h%^bz!vIywn6?XdFi=!@4aZ`lZA&H ztLomGkzbg1-f`al*)>o5)w&5=CTT*XHs%U7CJSF)uBo>gY)5IiMhgoFfEiNQR&x2G zs<}B5AQlQtqdJ}^k|K46ALhwSWu=)C=oRJ~ywc&uHRr(8x7SH=a(N!G;76vh zbVz)c(J!+q48?dD;M)P?hd_g!-)%A@zLY#4>NX3&WK`I&r*OrezQ4XO231cu??^UY~Sb@21 zHh>pYf|4xXsG~}@^dmg6YoiA()9sd9$nkDLVprB#Q^G0kM@eM#&Ar_p^X6uB?lBL7 z^8K~*jQ_yl)_$um^;OxA?$WaUzrvq;g{tF;{OIEAqY|QSq*EAgA+l2>35MJiC2j#` zf*D|z01fWaQADc6g@^u?{&9rAhHy5iJDq7WVS<_(xQqYZSfA|hR@6)jg}u2Ep{sM^ zUxewA_RR-s(>6Z=^g zB4hvMzwvx`WEO0Mm1_bn1^aMO6BbQ2QmP3Fv3LAr!<%r9VL|S4xjbUqerb{9ZB-%H z-y26Xurh(XeF{oS1X~_shOC;E9TVADj*EXGGSd6@i?9306yJiGSUlEeqp z-rJ?mwanosm+~m5j|Qq0LBLo5^o4H3+uaQ^{G~?T+I#-U+F&&|>+)UqIhcQLH{ac3 zg-mvKtuaVTzcyUNkCuP-ec^dwaR^8;GBGnFefi-x*yDknD|miAw@U{S4#X-D^xWKB zWerkr*@_5XRbf~Am48!CGKDh4i+A&af1?Y!Lgk1=_$-cjiSYE=0lax$`)`*6)&+o@ z$y0`hZo!&0)<7UJsk5V|rZ#r6d3tk$iPn;Xk&$F}KGXpN?S+`qt_&<;z?6rAlGX7Y z3_%FYWvf&19uIZ>Z!eOJH<&prIVKcXLgZ>!u-h$ep+#{tV?1^__!J|FjM4~W@;GBj z0n6M|WFstYoY>DOdTAqTsWT3GX#>zA{Jffr=Es(PhN0?^mphc33OLc(ySasVlto7) zkQlqUjC6k-MJOJ7wKFrM4>oB-y!e?YP2ng>Q_sRsVtfb!Isaq&jlu><^U`2&OJb-e!VG6SIFazd{3$h`Lcy(#bA;*uSSOJ>%n&W)!o$s7o}Io(pU zEDo4S)BuAC2#^7^(^T#=57fhGkW?;UFV*s6XQ=+^MRNp8Nrlai%%3jbrYScZ^|v$x z%NSGTR1H6mU}ABBg$8`3c=?F!UZ>C4?xQ-_Bkc#eiEgB=pQ!Wp zVVISc$mNOmYh`fs^$_<6q`&CvlPPck><8E8C*~akeg0;|TrRe@QJ6?Q$jnJ2x@?JD ze0;$w#V9+-S~-8*A_9jTy7&CIW`fF>_Az&Ol=onP_OV2Kr}Yeml@dC<_@WQ4QOdiNL`I@s?7ZxuU@FLe zr15v2>aA61lpvw{*BO1jSp8n?XCtPC2Ft_ppZ2%lU9DpmD~QT5T~8fW zb91&r@erqcL;O3K;a-CY%-y_->r<(!MM1w>g+I&nTk@yvP|$SQb79Yk3316VQUn{l z^a~h5;$_>HE8rP0=NZ_l9@zft^^89*dxXO8wcSVNByJFaJyMI^p)}Q_5SUVXlZh*p z1h^-aP1OMfnI6RJ>+4604)B45ozi?e!X4+hExXv;teTXU-skto_xtleYJ5BSV<{Bz=&7*gdBN(D-2$d%IJ1OH6o zI|bZG6Y}u+tuRwAGzc$cm=Ye@<4nxVbP?#)o@G8sLso{n-Fmjmc8gn21Wb~^y*I>B zl&x9>hHjVED}nt1Vfwhg-gHFZ3}enZOzwWaF;EM#A`brxcGDJt&i))-7$;r?iE^Y) zPBk(G)6C*X*ZsP;!cPRx*J6$^3)Y|<%`Y;!D9~C<*~gexp_!pv474fL3b&e0^Bh35 zWxt7Ya@rI|u<#2h`)=_IW*dQ^Qg3~8SpSSp=}*MsatZ7hA&j%7_`z{03BM6Rj%Km4y2ns-H2VqD?US8Bi>JbI)=TFNn z?qenQ66zzF{eEXcQHK`V7e9CYIhi!O)lC`|je$Z9wBk7=@_hQ|_3&$Wcp3zGt-&Fn zEhf$hH6&Yir*(C8wO`*-gcBvg2r*d+0}E5Q1-Um)PkyK=iEtg2M1D5YY4G002bbk) z11(Bc852p3>v`LgZn5TH0cP{c>gbHY41LUfU~wvbE2PRwJA813%rPyQtMVFjWWEnu zk5KvS18H^XO4eRNf;rF=UAP$5Djj; zLKmoe5_A0lh&!S!;wtepG$g9DI~Zrn*BX_CBdadBp(kAAJZu;Yndej?^dQyaarNZp z7Gzz9lWPJ-TkU-GgbD=@bvT8+uc(f>VN2I^fV2LQhhYzKXv%A<#Tb$m(nOo88I?r` zBONl#McZL?lA$o66(UYjfWH%45|o^Tc`qgU@FB&S$~t%Xvf1Hy(2DKL}q; z#G~^*Z`ud(3~ZWGG?)i9;h zW$-s;K-Qnd_LD+zm}8X|<496r5d{a$%-UTlFxM0APV#UeC$&_55mThZ|1 zfX~~A3iOU8{<;zO@oYDpaM-C$YX4X*ngbJ$GXrIAo zVzHM(uxD0N5_nO@_RT*zJbp8Pv7Uu3Hop-e-ch2C1KuuNTwKtfc)lCs11Kzkqp> z*)q1QIKXEQ4meZ?VOY++-#%`9%PFR+ZsY(>mHpiUpD9l&X6vE_Spvj5Ed-R)@q)O1 zLygQLyYqD?_gp&AU5ebcVuddP~8z;yT8&O|k-M;5& zWMHSDd)m*O<&BYbGvdSoi9A{y-00Q=6s>t%ho2=f>lOQFf&l2N0@E{S9B#`M7%0En z8e8r)aVi}lTXq!_C*Y~t`@=fS;)czdtIKJR*&_H199D{P4PKSMPSs*c##^XEmlP9B z==}EsM(caat*84ou(+7u+N8Ch>1mN%OJ@_^JrDVrcjM0eeBGzF_3y!a0#@e?8E?9s zgugG?{jhf7+yz^8JtoU}&6wrH*G~_*u!y(^v&HdzNStlW;FPA-Jxb5Pm@mnmc%4hA z`L4c5bhwaa$4tMjW0bjs8`y-Uby zSQ9P{jzU?V;%sVZ>+~+5N~h#^1_Dbqe!!iKj*0O!Rl#f7v(U@)E!{J;tk?;P8UV$o(^sOPLcFYe{hPpA*s9vv2+K6jE4L zbiFZlS@%KAI$93)_4~CHn3Y(D{i={um7B{;0Wj|W|6(!a!9t;Z*GpwQe%gQ+k$T;_ zymPAp0r8xxWlvu^=#_W5>IL}|$U?FQU@E9kLr@x|L3P;o09=y3zCJF#SK;7=-D!Fw zLQWNV+kX4v;X}*$0zfI89=E{sS>s@tgxY9J_U_?&_GHc^ruD^(k?yAYJvj_?tN^T8 z7Zq^)Yg<1B2BNZ6KpoZ;-~+dK0&cw&yy`g#h7sjJTh{!llgHksu;a?{x7f=c_}Yi zyd96Ums@~mqFc7Ma!i<~8tw<|*d&U!pJZu!T<&S;KI$bWjnsoSpR$DlABA<#8g*fmDPRj0~!tO&; zw15vNOVh;_SjNI$VMIxThc>b#7)40Grtqg>nTRqO86wpSNZa5i{`;d-lxNX&+jeB7 z<(TnlRbx7!@;M8FUzWAHOUes%hndbVxHK_5gk2y~og*W7=H})|*#(Fg&mtGW!_1ya zfm1dS+Ur*DruKwyvS17opylU(X-IKMTVtt{6ej~a2Hk;?nOR={NJieb!3aFXnPZSr zy!M!Hqc{7|cqX6Yw*H2MYyD>a1!>gsA2pu6_a=Xidof(!-d=Oc600jp@F#SF)C+K* zdQd$3c+*Nig-PCc#F4b)ZgTLR;@h@68va7t1NViRpqr?U0fLZlQ@Z3yze~fHI)jQ_ z&9bk$`?OE-CJrw`_6Tai0t*4b66}uX8pc6S|LDdL;rx|*tTN(hwI~QvcKg$~on365 z)xJ1*v{_2#9Q$$=x?KO~ReLkb7ACUSb>=$Ki?>2X+t>)guPi+u1mYAJ07L4%D;YRC z6E1fW+_Mybdl7S{jG|4~1GcsG@0a_w&N&71pDer3;}DsqrkL>rs^(530#$uTrTTVu zSeTfY-1P3|c36ClF7BVVU9=uCX8b(qec_EgTcIDi?P9byoBul^( z0~ivdeLNfp47ouow-e)KKeHiY^49ktLm2c95ZZLm)7$=CC$2-T5kuw ziROQOp`yg_DXn&&m1g&Qv;x08atMStyu38hA6GcxO=b$IV>^3jc{K6y&`Ks??Pe>p z7`j_wYnAIs3ugFC(Csz@-@nU0+x&Nn%ZL0(l^}XFR~7rTrUu{~^y@?LN!vQ*ikB0X zu@Hf2UZc1Cw*6bxPZnL>h}8)%g`Rvu%`Fa*6c2opfZ;+rTFw|JgO4QLjMwIKB{MsY zo=pWoF`vAky%ec#d@KQRqvmw~2pc}Qyd1rdLXNyVJh7uR>`mX%eNtwQ8)9XzM1vrN z$`PCH(a$_|!(@=Mt=Xg_7-cM`j)mz$tN>`_Si#=+1Fl$;Y}ecOgLNJH&7X*thr2Bu!GnSG$pmo*Mx2#wu6bJ_soqBRzq zdTGP^xnFSRrtD=a9E#+7php=(56m0EGZi{cc|jKGcD)riv*e6&seKnc;CAUJpYNs4;7<3Oy`;sUy}9-d>iIKRxP z#}V)Q_n_3&)UPzdl_6)bvxFTU1ngKSz}kESP2K7oKOwp@EUrR52!RCL`z(1U zZEFdo=ozq%TaXwT(U+P|_}lIdKS)gTf|%f}-hPpLJjiowEJ5Qh&v1R3WalCbFQg-~kg?~nOLddrnunV7 z{kzhCMvP6XOeE#J)Wh(5omf1}|7$evu&coSP}OrZBP`)W@JLxW-|2P(3%?spxSPSR zNKA!?^NwFvdcE}~E^&RMr$WF*p{vf0W17?&tb4z!BbH?;Mv;ZEIx$hT5Gx7arKm@?D-AiWs($9`0cbcN zSc_D~ciuO>Q%Hegtq2710gMGKa+QnJfhfWdtdo!T<;ACgmAD0a)pBZ7Dqj+ym-+b6 zs;Q}cCfYoP@iCFZo_IvU8{d4GX!av8(GB+Y+k&2lim5p(mM%Ab;=&UM>-`px%g6{S zc~)mn4_Y#HQCc4fJoUpEC@bn3!ZRHi+~XL?+IO^~XcG)k8Zju&<@>}FSv2p+u7t#` zZJ&psn92qeTg&XSjwmPr=rQ;m?igyC$NAZ32cAL<|J-f&a(&b0>At;Rne24xy{X~A z!pqgTVA|h`$kqBw>OkKUljq>fH8wWVN;42}7iy~H^<$id?|9}|#M zeYRN_5c>`kbd7YGNA93ic@#5ruF_l2PyvEql2xbcK*YEGh8|HCD4uXOJEb})X|Z$% zyLtX-0&7vJyu4-Xvs4dFXEXh~(h}%FTJ3-3^6@(u@ zzZWY;xX}Lh_2JdEw>c-95+G^;j0m)_+9_F~IV|>in1`;R6qul2;(u%TQ4kV#ActYM zxEhb>i>1$g88^w!+pDUS7n`&FO@T?GwLBiIgsV%%ASNA_F_IiBhUhkZYe$XCkuvd; z92^|R9v;`IS!{d*|Lq7>7C*QG?`X72yQeeOq`;3Jl;|!nL@7)Mu|)JpaATM=6JuLK zIv8Z*;I@m>2?1Y_VkdYv{<=qf`t((sW9o{)T_H~u(Wr`e<|Aw}Ld^7us-tNS)Bie^ z8p&f$>)$8G@fo?=kY5>goTRWeTO3Sc;MCNw!m`o$!8AawXugrFjARSCeWOpvVZN=1 z!PfKSm%GVWs+Kyw8F8H=B>2nxvtc;zC$}p=_BICIF{svodmM&0r4Ej1yXQJ$b2@+9 zroGC?sHO`Jr?c(GPJ5f)^&$ZtdgH&^Nz3eC*4^JnGOs8st_R^3EOJ#p+Dzf$j|20$ z#^Zvn$GR-UqYR^)*L`insYo$&LL5Cnx^)H$VuyDGWjSiOM!yZNL8W`I5o1c492O5vQd+rDZA?Id(rNSxfWMp6CQNi@){ zUnYF;LVeMCOAL69CnG%LE9~#?;pOkzMZQ_I%lCSj!&C7r^cU(r$>l`^cB6idmg~8k zfx?9snc7&}wn@|;{DP1wztP7N7l}`^bc@Zp3xYjZNTwWpoSe9t1{>wKPw(+6jaS5d zr?S@tD>>3D+ih_(w{n(@&qlao&ugKnBl>8F*-b4 z77K}EQMzPiFF*@yHu9w5$3rf9U3;fO_|Z5Fvg@0rZIUQ}%Vj0(-E}0Vp%K3%e^-vu zG&R-*Z8FeeeinF_sRjC^R0U%YZg|t+MX|@*C)e@@m3Gd;ngRoSiaqe00miqv1{D&7 zXtXO6iZqI1(;l7d<{<_pGk~=1Ec{826Ib72Y67iZ#ZcC|fU-8Lw@GkySK@A*f~%*? z-(#6kjHklWt2jD_9jG67t;SN-kFU@6!Cg!T;KNtQ22~fM6uE)g+7{kQcTpsL9P}$1 zv;Cp6z<~ir12_lI%i2~W-@Gf-)U|7Zct+K2)p83jJ=q5^r$NL&HT%>9#g zV+D@C_v#~KV{47uB2V;Zm8x;aQBp83-$~KS;vc>rhHW7G9-VydY%t}*La82jLDK%% zx_}v(qoULh&QwAJs>s=WAt)nA|Lds^S3kY{uu`e8({8*Wp=JhCC%w730Xv0cAiMJU zHzj{LP|)UAardeH$#Z?N?(alFBgxVMY{Rk7h>Rd#&E^CI%Cmo4f}ut{I0l%7KM=H> z-HCR;@VVQ+?0>kV%hl!(c`PQLEUw(-yRacHMbO28{T%M=*Ux?wYy7e5QN|LC{%K@n6fQq|&Nik|3D0jy3{@bBD zZMY8ssw5Fq^$4P)nO%$nC|RsSKjkmDOk`^ERXY+6UoS-l$YboS`y<4V|p7$H&+Xwt+Dt>US>`biHi%?7+3**H_HHj4l(MgQ<$sk zPQVb}`?YgLE523Gw=w*ACK)i<_gMiPz*Es=5_zT1P4M{`EjN3(VHcgHNi99>r640? z?*HSzdQ7}KYc}|}P6zR&zR5_mN(26m{p=Mj0U%EiRf0jqY;&dvZ;yFw*0`*>>_?$5*bKcJUMF-a zpQ`|sAU7A4C1NDq8AI9odOE8Qqzfq_{$rq1U`n7)0cuMWv3V5>#hQ5wnkN{QU4BUS zRZjU67z9rr6 zg=!RyMH&-e&^-wF;7AJN5&haCPO_=ihqMv>nr2X4wn0jD!_iJvje%;fTv^6#QUE#z#U$T zUaRQoHlxWVdHhZ%e)~mRU%xjuMnuk56$6b#53OU*BJ%9AYqEEyLH576pVi}^M{Iz4 z51uFvumk6;QdjNA@=@|wKFWarp6AOY`4-$VH#tgY^&F8tgMJs17m-}`W z5-xAG+VB@K@%jUyGC`bUE%*@1!5|#rui_e}0tR7@t--B#-dF))RmQZw=l?ytyWPyX z^Su50;*R)!`{C*#SYa#BChQi$fq_#cD+V0gw$Awh>F0kEmDcDtk#6H?{>!IsIx4Z* zK3YO%Tv^+3|A0;_2j(znNa4(kL90j$Q+*M6X*D?`DV!l4Esd|Fq(mPl!+?h>P>vg# zY9`(B?;ix7Iudw~B^nDfX5k)Mq&rRcemw^Dy3eU;X^7fO94X6OBLlTy83VZqdRZ?$ z?;I(O-={IeBi`p{Y>l!d;Mo_kqKfQN;B+JT*mA@H&_S^-ppdGOx}OJvqHi0 zU-l0VnG%Od#k#?cmoK73p_+(tIt{^goPFe??4fVimI zKLCD*$Vm$by!suw()d4`&I6k2|Nr9`*T}r~jEif0 zkq{+ilbw-S$d*khlD+pTvy4bqnPu-Si9*QCi0qNQ{;&Hx=YLM;dph6qJ@u`7Kkv`` z^?W^_kEd?j{?@JL-CNj)bmrp3??Sfu%-kgVm`u`VMyb{qL`V389cUH4f4{6)ALyavI-~q))^=#v9>JxoYX|{tvI7$?MmN#O4`! z-NmOrDN`QP*Ym|Z*DeS&K3$+OunRtl3T|Xm?m!YzNC)Ak`Tj6ct&(7^_w&^_8|c zwyb&n0LSFw^{D9!vYF$b)i8QPgN^X;fRz@kawH@oA@l}0MW#ua685#-Js&m%NY!2l z`Q#OF-k}izY+Ai~BoO3*Re4w#($%GUVu`yjV`~Se$1}T0BK)r9xqtI0wRCx~j5f#Y z`jzg0Rf);mSN_iA=M#P>F7S$Kg(LMB=Ua=-do+qrFI}3yCf0j(IbpK$q%NDk_A0qW zIa~4u@4feqB557Vya}Z6z>&Wq%_NY?FmPl1YvkB8)UqGdw9&ZsP#QhcTpHBnH{dbo z0VoJt6=rDhah`67fK3kU0%Q|07`tDVr}ukX?yGR@qt$(#{+Ch&5=`7Av>peW_cRLd z!-hqT>x-&D?svz*PPUX6Qsw@c=cu3|hP$U>4QT;cDyLN-pN)?jt*x)KNBjH?N zY=AqCx2$fiR9bXWkDTf4fgq;|7Q@S*T($uOCoT01L0KP|tt6q0OWq?4giDIV!97vw zJE5b2*oWd_d+aWIAxt~ntc|gdLyhTo`tVU;p4o4QN8EYbbD_H#_Xa{&#XqM9rC4bD zOaAUT&h4uTJnz2OEC2q}{~A@i%J9$!cOs8z5~lQvUl;xtPv)IYqx_DpZlCTB%>VlA zKymz$Vl{f@puWNh>uG`=UQ25$4&MlIdOscXWIV>@9!hvbtSyp+;eSEX@C6(Ftn?mv z^D(fSdhRy4sqg?9bF33PDej|7WaH{|A#$uxjnv-Tf>(4mA8+O$p>MHX(Q=7g1(C#xdWU>IZ@zakv2rldup`P* z{(=*Kz&baxriF?s=LGNb|EsYEXM-blq$xtA(0c4Ld-Z${>Nl?6tPcw?fK?h0MwA3o zILYdYWM~v5d{f;iSZXW=_#>#0+OxB&C{#20kB1_{1J{%>R5s>UePIEze~Lz|e>(YA?=yG?9hwlP@%)>Y;_B`Fwbi6a+>qB*zaG;Q$GDHFLF~vPdY+R4;{giCnn4A)FYMy49}})2g+qC-ARZ5FQL$#|^4f^pc1~Rfu}>2ioyh~qU|Dq$ z<*SqbrPHMJ+a%;yv>q-H%ecrH4~jYP05z%7Eu&o77i1rj;pOWwmJvA|n;#=0iJ3YgQl*YD8}*(qer} zpslX^g700|g)l*u)3_@Ovo=j)4cLGC`uYs-8?)#f*=3|;Kh>9?z8I6O?ymmpvgSS0 z{qrZC<3v~9h}b*#%T1f@LZpDjg0w>->!>~4f+pxlht?vTZKwGW=x`1ia3t}Wn29Q$ zl~gcV{Vhh`gg8TOMegxH+f7~|5m4Pwrj!#b~N9T zEz~3B-iE`;PqTxMx!0SjWK^vnykd@c8o=(4BbK?;Ug0?W-#yU{=8m(HV=L{TaV|>2 zm*I1~a{>*X@&f-F2hQ&_*2mG*tXNtsJ~o1(5xbBGmJR2n5?6-3VgLYQE+o&t&74o@ zwoRSftUNOt-IguAJX0->7sVKKi{=v%uV)@FpROMG-MV&mc4Tf2KldM2eCK{PkwsXL z)wNbn6z+b*u~>HC$<>OL`YS`C+t@_%=TTEQc){>uC1MBv=QL4@@B?068|!p4wgbE9 zNDh&4QbO->?(k4vDr;$$)-t8jx_#~1&DGn}l`dA@b!h!Har3W&LltJX z$Z==Fc!}b9quyZLuoy3M@c~%UNy&&I%UIiV^k6=I;ki&~TlO8f;k_GIzF$7TUhiJ$ zVS#wuMz5HlF^(RL(3=n{|5O7Quz20tD#dqf{d9D!XX4Z6zq96>{dSw@M}5~f$;hVI zDk2{aM$G8>L*Y|QjE19=(>>Rm*t_-Z_XyyMBV%nADHmOBB%v$VRi~Oiq*Zu^A9esOp7~wt6NcH!W0^jJ5F%SE2FaW zD|zXnYTWI}K(c3(*q=uCPCt)Zy*S~xv$2%M+FdP7iU&<;${4B|=*9(7$f`JqrYsHi z;IvB??NJX)`|w}(pH@;9>km>Pd89h}58*V||3eE%5%&QV$^U{#8zSfW8H9MXW6SmE z>FI?fCC>u>>C{h1@SC`50a*Y*Y#Qll$c!?N2)h>|irzkTf8!f9tXV!pu+5OhmtUd& ze4h-&im|Dw&hv9AsHIntUrA*YJNZ5Okyn8x5YKS!$Y{$-y|DXWQ=plDr+ILGn-fR_ z+DMeSw^|PH+@|7 zf{2h5eu%Y^EXP}{sldsJ43a85i1x!><4=Ob?wNnmo-q*#_wYLm9&LgH^6Z4(?`xxS z`R04TokU%248JksOwQRcr-NOHX*)+%hV_7>pRZK8DGi zKC|Te2j!ZwCPN&fn%s;mubO(-5Ix)9$%K{EM!-@C?kV! z_yd>55PH)?wbRpq3o)RFv35`%bXmq7_*|%)t#h1PMStw_Hp&&6%W_Z!f)@>}BVb3> zOEGoZ(y;wF8@prc;fv&eo6+wYUAYSJh%zGrT#6E>1IburE@h?+87pd7Bx2~fW+=>V z3U-kgAt^yOfdE{3jKseL6+mx{%}lg!Y;3?U6b>fhFT2Jpmy>`(8VkT1XGe$hg~0wa za@>eK1DYgd0&I+*4h&KuHC9>)?8F>7pjKi2^eC(>wz@guN{C;_h2+j`nma*XpIT~K z8sqg)ifjh6_`CVFlfX9zkqva#-++GltP_*=ncB7Wzz3;o0Smw^N4`kh5H$ko!Fv+! zSRmR@+FcCQf4kR6a~W3omXk8~xo~d|8;-msl{HF8xND2mGW${l;S=>MC^)6J`*i%e zeyHl^`ex<3u>3QVkNV}6^-;asZjdHN;F_h;0WMC=-X&+mITzaC-^oVhlh(zO3~Y*& za-{ELx&jeY0z}zyBTD*z^pq1PlY)YIVtyS_?1@T@M=QRfWB|DnT>Z427TfY-Rf0OU zX;qbxIpG8@?n4}(4G#%Vrgin!?S9NBR(s|$u+@L~UL`>C+3Pa)8$LPN0Xrt9m^&0v zr4Q+7HAUA&O1v6Nj`NhXhdqot47tw8yc#Y^fB)2do|*AF)b81!b2Y4B@fUE30>h+_ zbEVtBzm)m>PZ~qP%<2>!5@&&ddJ##Yh6paW<=lHT9JEP&vqXS@kcz3RyUX?O53X-5 zl4{8w2~48o8#b?ZzkVZ>Z1N+W=0~$hYi3qWDSpFWlH7pX;>3fA4jSX+=e&25RUInF z1r8c4x@Ah)3_7~4yuF2=C7Ux8XdPWZhzYPZprZ70SY#Os`FfM?)JZT}AP{FWb}6qt zS<9F&OcF6z>nUhBRZhF}VN(|$U3{oh1WnpBPdie?S5=d_h~ze(^j3UbDn09rdtgCx zW6Spsb(eQ(&s+$?hf)SnL=NKAcHBw`jmI(NDPN16iBgl86J*Sfy zA@TjX26g?57lzH1v1dU(kV1p7gCU);&ZY|EE4$#TOgZih+3OP;Okb@;V4nn(yL+z# zO|v+<8Xh|m#;&4?((XUUVI55Pf<*!yR zD`8lh3|U&i3Y6kTR{X&B`NhB2rXZQ-ED;l!{jH0oNkZ-g8MH9!2nW1>rL$FJT59Ry zN5Ra@3^sV+e!dGGW}Qq$j^v|nTHf!#`B2k6VmAAB;xH4krc|x62>mxcBR-_t#KtgN z_P?&4trHZRBu61}A>w$x*L*$-m-+6~)7#!Nw?MvkaFWO%Smw}*vm&uF*Fhl_mR0Sb zCEm<}BOvXs9e6|GzP>$xK7T$#;y)tIDkzb;K_`A|;K^#k(yh31u}3V^{V$}~Yjb(! zKAI}YERBABllAb%e-q)tF~_oEbRuvpJ+z9=DftxNdvUOwvvb~xlOEG0(~Ew9VM3Z_ zBsD#!LwIs~(o%?JSHqef`}OtkNIB6cXB*hv0z&=^7?8W}X-Yl~4C!s0<-pYndDTC5 zA^E0D$0qyp=81P~>oF@Bp6=!gU%RCioACR82XV_!I6sxYR5>*q{d{nEPT?C4y$^@% z@sDrUWQNc67<$lN<1nLbF5|FJiwR!2Yfz-9?avnM+KBMd@n^~Hl1Ih&)0>Un+q%6e z+q`FvBWb2f6M}UFO-{CTb#Y_w1En5ZK~0-(aiqyC-O&kf`5=e8D;&ijJ1AVg7Z)NF z?UhRI+w#s-Q0y0XOd*;``Mr)Z*Gq^6H4nJEDfrl?`rV9W}x_2PkgD*|Hz~^lQ6|A|9K_} zj*QM|LZ3}}Lq+saZEdD*1;ss+Pla{iH~ODfXC2&+od>cewM;PJ*WhLdl1=P)*~)Q_ z#8!P0SkxYxq;aeBF=Iro#)-&#uQbvpJfTc_!}SS?(|kfDP~XCvM9LvS-4L1M{KZUD zUXAevr6k3-{(ei?Z(gGgdkWPP1^wqX{nz1RDeMR%gi^-k?Ur|klhRed$`E}V9yb^2lmN8K{ z;3ANG2@<8kO9(oLVM5WhU`aXO(LEY{gHd1+k!?_Sr5^%K=@gbF*UzU*&zN+2t-j_L z9QfcYn}?EG7~L`NNvo_7kkw8Ea8Uc)4=UaCg{~^e%RQ@S-v;pNzg^Q~`+jaqOWc+p_1j&}e!7@HdqxMWO7Dv~8Ryv(j5>ih`zEIk z@v^Y@&I$2p_UnSR6FBIKiolF(>E=cWuIP4$R@g$}lv3F8Y{%(@1$!l zHtg^;JTfweUWUdxK96|C4VBPqG0r>t*)>qk79BH!3t~P-c1OX}GSvb5XwgyP>IftvAfJTD1MMuX-h zTnlN!Q>A&d1yIe!Fs{EL{NO$2pmp!dxs(I*{^eW4^~(a4zraEdr3*B~AS4WcR1TSh zXZ4C{23H_D=Pp4&2+W$m^>|U8fhRXf(8QcFh?wwARf2oH7(#_!3g!n)DK9&inaK6a z6#5EAy;GaMJKwr9U|aMajFi@?!Cn+kC4%t1-4xc$%@R7}eamvBw@cZCfJRZ}1dIg> zcA*->Cwh%!ZO9Kl7UAe2?~5kbECE@i4hA8<6x)S@ zHCu}zF%RyiISArnNh|r5TlfVV6t$V%rR_n857YEY6uw+<2u;awoe3xDnqA%*!Z#~P zbw(J2#fKgC&zx$Uw)-7YKnnM;{PMx}&TR^98d$zO$41jR%t9yV$RG)p09-cX@fUpZ_h7 zpKvP;QmqAe$n^wL0(PTXTKoj1M?5e8!!@-A`rA&=;**}v7zM=y?jP=4L0>;)c$(gH zy`1h!6Rf3&--}6j@$q8`h#^=t#9xFIuW6GL44R>x6#{Urd8NwrDi*#&_Tc6PIO==5 z)~A;bGd0!E3M2TDD@quCEh8#pK77d}xpXg+a=isB@WkmI5{qc&ue}x}6rSOq;VdqQ zZe5ZP3>3=V-cV83xNEWggUjks!wF&ShGN}gx(RzNywMBKeFg|?H#WxH^4Ku*aG@|~ zFmtzh#bf!mj(qef_TR$q_;5tU`CGmB z&s!`uY}iM_1Mzl=7=;P(-W0V%xqrWlLSjDAB#z^D+0eTkak2%ijuo(M{Qky&b@nI! zjC`fH3{D|~=SX+cic8b{+RK{q7YFwlfb&VZewSoKHLcn9J=qBq$Ok~W-+RrHjgy4f z_?Xu9kHz1DV5D_*XEC#tOe~?^kdRWEfLrDM;rzg{uV!&ndewo;weTx+ezAx1f)zf} zXfGy)XWy5aChB^gnfO(2w7pG6&s=`+&wR9hs4433#Hykd1VJqH1?*1nC}5`F>xwKt zk1qE}OdygC=5@drD}D#%>C$&srA&4isTL$V=>?yisz=9h zW~*=e-dwA0+PeaR=e&XMqJgJ{*=fyzch*<-+Z5vrsS^~3odbH1h?oVAgQ%V&tjkth znpd|}FYz!14nhgQMssHu#_5J`lWU#Evau2HJ9qOM&n{xXU z31YU!3SWtm6C*}jG;8T>k88<^Z}IEahl7Tk_~%{mm+b1NxXG4}B~+}6sH8c&%U>im zrdnwYQ4K!Dl@r?H%gRq|MH-PQ1ZTbycm8=-qiUSu0lpeW6hp;yN9j)4v%gf2K{sjA z2Y!{bxW6WkLkHSqHDUOFj6j&4vIg;G{Q(K{xHeknF9Y~A!8r-}zy&COX zgVx%-kw6cs{p$#P6p5GYcP`RI!RZrMYvcH>jId$FWPQe?zwb_Wf#I)E-+bQ145edy!Xk28Q5h{D&HW&1?C1% zrYG+DGeYng$TFb1Xz@#aUB)#{;}&+fab+(5PhH1{j9#5wq7DN9>Fen&n%b);ere&q zUZtRdbsgz8G*8ELo*jeA^n|D`dkN+>?r6qMWl zpde{~cAWdB>6oVtI(e+GZN-**zwgm}w*KU>kG(z9ix>4k1F{Oq@J9KfW)J)>4zPHw z0pI<~+XaC5o;t8kCqSUHu96~4$8715IL4z~Qe{mPX(FXS@P>`vu~ya)7FRSigMGP_ zjdglFe~u4Jj>GSexsNO|v-e_3ww^yUqgS(h0t_wO9%PuN#j>jCZhK@7Q34t<9EBT* zFyf$Rh!b(CP+?SYqOmwZb@sa5K3>k9Byu<0)aWdncKo4TJc5;a_hQIcF0;O!E@&4e z6)#bH*=V6om?rcNRBl0~hLW9H7HDgK`ABD=l$pzf!nad^PGRYYR^G|fP`7fnV9PMIjEp7ae9NjQ+tebT(|7C$if9IbzYK|vNk zA{+?_nQxZnH2a=I9a#^9!_ge-=D;d@B&zJiymwHj%Xga*x~hW{{L7EjYEJ(>Nv%H> z*Od%HN1G9{2Ll)TMn5cHhrnU{?b88xV`YO5wKj z?J~<6TZ<4G`3lnA8!1b41-u+>Twfm^5xu7~Ncb;WPDiw&hsN?fF@i8<=VfJT^FJci zi{ag}XmZtC%r$#E6lL4T52;WF%TmeZm2=S@zWe6VB*koFxCo7V!Z&ZKoW3Y5)l;yZ zUB64%eDt~*rh~B0YAIfA(zm;2pBck#8gRT)S!{<#*S5ZhMo{GPMnVD`Yd+}d={cEu zBZc)loG1NTZ9az|*&cK4`d^K|yBRadlYor{yQz?GGzBjPu>3rIgUdtIU^XR649@I% zu%m9)mE*X_(q?mS z(U)`W`7riBSr6)n3)Vyh8A*enNBX#9H!_A(B@rBZLQ>a59Y#yYBqIoh6}iWPzQ&(a zThD+4SgG)T5Mc-?uQ|F{`uVX{Z%%@`b7On0a=_x9VX%4Xpy&@rJJJ96u`t*~yYzyQ zmEh;r3_=<&dB`8f<@n?NMWK5;)ULecidW{2|2c%k1z1(~ELQZqzoz_GLRTYC7GXiJ z9LHrxxfO{a+CMhg>uOS>H2?74{W2iCzy#hA=Iq!w^yh=$Dd|o-PEXCP+nBfPK&wtu z&xyYZOf}T?M+|LMj^`{3Ko9a)>JowDLR?C!3;Z~+?G1rXXRJzNfDMQE<*w&Ww=aRF z_c=fBw-R(>k8vjjCsI4b^V^c>*H?|U%>kZsW;8hLmTg)sYDq|%NKQkag-Zp!qOk{6 zsAE>)Njk;w#2zkfTuX~fbBI5eUbLE`wT48MD7@nFVym=MD;pBt!>4cA<}Z*z1K`PkyV+Q z3*8;tt#t-AmeBPuF(D736O0N_$2u(%)K157HKjefyHI$ghQDUPS>rs_5CMz^hWD*k zF2i?%0VgB^-}qvIeyjYdH?4v6xl#1DEApz#uJSG0^5VWk(&(RP97)rjK(3?L!iKbZ z?aK?IKUrT87spAGiM`D=k_>ftfKrUOMm0W`q5wov$bK4F@MmyTbD>jO%`b7DQQXZ3KKk;;}(say^WVS?HnpaYXr8F3w>MA4hvE z=E0v?+QtWZv>58(9~(zFckWTWk&)qBHq#{mp&LtMms*aSm%ryNCx7)g+0FvsO;|eo z&l}ev%rfW*7*%eVckp^tYl;fsL4P+SQSqw$9xsg+FCEa7YZ`)7R9~C|n9-B8!ylS% zC_~r}Zv3}E0^KE8T!gfH%)6CkM5$=>lIUJA) zOhZdC6%_$OM>!`v)_iu$-`}9)L!+#9knYdLS_KX!;VmYJ1jo`tCDJ|7G!ZrbV#iP( zvZA6d)+XvUzZ_7^d;a&MZ??>B_{0f4hD}_iss(5=2BoHp{TpSndEZX%wNCL1QGFi#Ij%F6Ya2T%hzbsif<6Gw8U{@g6kh%<9oR9XBxPqTQ|M zAPwS;76O6*zd^}AOtsJ0itowE8ylprtE&u-03{%jYrR3iE?LciO?*fxZ}juz5R;?V zusG1=gYRxTR0Y5^sF65gOcCKu9_Mqc=D9-hu)XJ$NlsP{6}lxq_@|!aZuw0zyds5T z!mtG1vJi$AeE;Kjif>xEqHuNfS|@j`7nFG1%AOK7t;!^0rayHv@7I)zRXSvAl74#; zf%B{`Gtln-BheMfEEk4Q?C%M;7huU5dl`@49W5Ocf>pB2A8%ISeDZb__56H~l?YyU zt0LJ~&0BGAmdr<*outFXmdno$vIr7Q7lgs{`b#Qv&-CuenxNN*VD0d;GrUi?F2e;L zyhn0x{S`P`TMKJmRj?WF`amEsN2kzL#slJ*8F$0J_OcMlV$2+U$=Hr2Q??i4eDH@H z;^b6qW(g>brGx1e8tK@#FK`qn$)3!SAl9C>)qJ5RuKCxaB;@y3+Yo>ci(t5ueP>Rl z6P@JAH_vCY^6m6fsx2!5td9U7CdV(I%M1mx*X8z>#l932633*)BV2b%)O-Q}3EbW@ zO959|8XlXZzVDST4SsJ9QXT9#*?z5JwL0@sZ19Ngwa~BFpnhP%AFnug&I7BuYt;pK z?^5hxVPWuzY0=c<62A-Vtc+hp7U zBKcdb*{}S6axtn@S?ZuETRgs+ewPQ$@k2zfb72?*73q<{>1ClfC^xJeeKfrN=Yh-o z$f#+1*B|a@9v<6Y_)BLacrrWSOf?>m=a!c&{9#v6L>!V1`T4l}jiKO)Nf#Xpa2hYW z{F;H45Yi1^20g-Ckt%gyax(9N7mrQlWM$BaiDGyj^PZQ9+c;X2fHRYJ!H-QwA*Xmx zRA1kqT;f$Gxxh1HN})0X{rNCTmVvOPzhv7`ORNK9B*R)$@><2$AK zlbf-9)`jK_{yZ*)Q?Fz*f((qH?M+Zc14D%&l37XjJi${BzvMc?!-(8%VnWf?!fPE|3NnU!SUl&_qoSJcFdL4W=mcd8o6xa$ zhIAS=pPlL$=5urNx(lhe2g3_kjR_L7lmD%m^6-`D`TsB}2ff_V6HrWC9 za#$^oZbqsSr1?>*F%H8!j*(-acX7AJy3*t)ZN}`KSHkV@ZU(TqR?+S<6FuSs@m%>4 z6AbC)H8tX|NT-*G+fm8ZImU&vHM*hmsH(+p``6Py(!r^6zUXpFaK1lt-aHRg2+N-) zrc`n9b~!nG4H(~D!;r;x`tTRY zdEZCBQKn@rU^=1+BHRViT%gfaK~qw58K>q5%6-2|?d z&UVs23|1KsR3L->r`OR(oz2oxl`~7>twi`LA@XiR5ob6VHI8VPX zd>Uf)%dAEX?tS0IV{`3sf0iVm#FK%;e)vwFn`QCaz#4YtVT)!N4ZEOhqrC9J2TMo*%rOu zzj`A1tA8$u5+NcEQ!&z06GzRI05ygx5)o71zg(V~-Fem(05g^j&_Z#czT|UTmtp$x~=EuC0o&BzOU>mPq=0|Ee{N~Jg>|+on zjDAY0>8bz@6I#lp$_aAx@kh))>b$`yxd7?+h7ug|MsgTgj>lKHyQ;&%RyGVd}x)51zSO`QN&JW`*h{hcWDl4D3 zvb?@esTG32{{Vk%YpWl20LCPDuPq@lN)`q#I_T=Am(1fFVW0VP&UfcpskkdV-=TT!nVP(eR*lNAoXP+6%2V~DkA89(YXyZCGl z{7xs}wq3f!Wr)xb+4j>?nB}~uA~2wlZOFoyc{mfaLRiYu-FkkG<2>0AaZ6OB*0i`? zh^(eWEtTB(y*%PQjrHIH$q{RBcF8KRDz7(qF!I7Tru1}HNR4~p(Zk<1qx zLk$1Xv8!-^0t*8!k_dQ`X`f;hL~z=Lv?K&ucTY1ru4vp#u=-F;ZECMlV1Gm78mT-h zAIf$a^frrE{Le7(=J1w^12VY9KY9CaFDQTZKOedJU4q1a+16}i^(pVGGiJ>%K$~qj z6ju=>_v8(y7~rg^fqER(yuhvY^ z2=BkCZXkA?9lWq0+v&$m8s$$UGQzCA+Wvc!;Uo7K!U>dR=*X1q`k53%_(&t!a!dvu zStq5dv0%obAOJlf2?~CJn`I>Sp#v=?>Jl*#5fS$W3J;=8+|#p0&O~J5;yw>Gd?sl0 zWl?A#vRoA%TyGfI;FvYMI2oUr2{UI<#w5b<9FK`83nHcNwW_dX?eg_tA^fP1&EvtU zjB02<2=7ofSSj-yBXzd;u&rl@a|^BAMQikr$jg5UCz@a4{flnTwP*jNLd(mQBl#1C zRRjIY({4s}2ahD9|gGYJz-z!JW#)9)n1`j(O zN}EG7GEAUrsAP$*P{l(eq2;iH24u$B6CBtm%sv+c><+|oaYyAa4k)V-ZsiCVUXtfI zXrG~rE?Gt9D)Z1{tYlvLCq)QIRf$9vmUD<+*?#LtFufYd?1}4d$AIlcjCp;d{PX8d zF7ssT?N98o2wOlfs4TN|@Margq{r0>;4f{0cmKpBM3%IH<8i6~@o0~TijY7ojT=B6 zqwmE9m?u=2P=qeFx!!hnq#zrT&9k$OpMN~^c!?FXaZzrX z#We$ZSE-{g`o~f#Uw59jv7^-hzuXC~M_{1dRu|4&^ukGhPokocV_i3PvuLh=&!pjV zc~oPrE>gqzu%PK&KV9 zUd_+dKdn~Ld$083GFm!JwL9eZVVNXx%M*R224S9yC?AbmDgX8w=)1Hq(}sbbJ7*Q^ z3gi|zMFLdgpD`9z7EJZkGohBxTD}&%a4S4ykc_e(#;2^PC56UdiHv7)$idy)sqcYY z9>V&N9ha(DnVSkOuh38zD$uvd`*iE}&mTq;WFq=;7rx28UKfU|%@+ckheO_<=T3aS zm-{97G`uGM&)+(oJ5hxy93W(vTtCagv97<>bKbkXEcyb)~-FjRmZaRM$M12-=?+CSt~_ zz-o&A{@fk-i{JtK@%P`YV?pdf!biwnx!E%%(!|kcrX4!IO?}qI;0pV?uM2Pn3`o#@ zB307~snkkj^l45f2hLdF^~8U*Ihxs}Im9;eIbGsCrLqIQ5Br#$Ihw>Yj$kXQ`A(LG zuh&rcxc6J_Idb_A$MT-5$B{S2O!q~?(`OzI2!BYyV*eH{W)a}j0Z%`9(jn9s<}pR) zJVpa%7rS1_8hEnFp{K__IAWQJq6ayGd%~njT_(APy$^i$t^Y)El*T(O3}sNEk3MOL zY7i!0&31auD|So#Lsidua-4m)?7}ZCWR~a*4ULQf_nW`LkymejCJ^UvcDkGmclpY3 zxiIcJVSjUXcT$*@v1=oIX1vqZ%?lhj>b5?Y`qGxH;x6Bvyxbj70s-Zl5lSTwm5vS> zu<#|Sdr916@1I`wlIWL=g?er)4i%~j%q5hvg`sDtar}wN_fIt?9+Zqj6#|@)Jh6U` zf9=}PrNyzHm$3w3cZ^jGnHW? zgPuQSo;f4{B;k4Y!xJ%R$(03N0bfBo{8@bv#QtDc4F$0CTRv=ysv*h*FaMhhQCKV> zr5Sk?n8zC~`JpjBmN8R=;hJNdS9<33AEiVL)M0}j^-R2K>)Y#%sHQv8W|RlM#BHeT zC;_1O_YCL$_pM;dQc4UyMtBbaE;bdAHuS#xDQ5gPMM>%RVo9W<(GeB~bR*5u%hS`G zFIV=zPKDl%oFbPAhJqxohfinj(Ibi4h+^3|-YOFXp+df2GQL>O-#)uI-E7GVT)RZM zw^QtOyR2?t>Vydw1XgHZirnAJbqS|F1=#(M6R9StHn)q*ugn2E)-`Cc+s{AY&6OkT&3&u+@ z&AXaZFQr1Kyc!_|1;tHfw`b;z(nn7oDy3$$y7h%F5|lN@OMB1&5m7mlf2+8mhai%&WfOuCd(#G47*PSWX=pDRymM`t^&r5KB&(FXlxcb8IZygfFely&b?4v}Iq)Me8c-N`jof-omEyhB-Q#rRtN&KcNK z+PyADP%U)>w9VlY$sw@m18N?27|gbrx*{GMLxd4lAHsUoA0J^;w94FAM>T0*8wC65 zf!6}WOhD`h@nm@uN21zX*4pgX+O=QCi(alMqCAtpMN+vsIbF)~T(etvTuXT7=KZMX zp~&(HYiwK}B-rym6jQClNT|1GcV)02)LUc{M=!RJRzIO>Q000VPfMi~SMX3|Ow1wf z1q~&h6^HPUC>gf896;Zy1Sel8t>eeJE4oct3VBQ2d zlw$lL@>WNi73F|*Q}CyS`ETnJyas$MX3#$z>qKo6t!5||rKX1MqBrKCdI{&q%wfz- z3y6MFCusvM6#{(4lyIexxQusX451!1V8;TsCDfeCh+fQL^yy_g$r#7$?Jxg8J1VvX z<{})&K$c?F9_>kMYw}$N$0#wrZ^`xOM;`P9$kdjE2_?=FBI5-YexMXCeb#6GOt39^ zZ9+qQU1IIo<-7GbqmHegNe^Q~TArY~8v3!?RrC4cQrRc*IIqS4`;T2Qr({FHPL#bN z^HAlR!g_*(UxG)3>$>0<*p2sWOiLoFzaU65e4? zB5k4{8EBAb9N*+n2-xJLK^`{6LDK+a@_o-DEpRB3t)VLM?fs8AI{)R0-wd<8SQ-5; z!<3O6^LXMdIDId88pELzIs-F<6t=wiSlC5ZnQq|kMlYC=&^Ze|xsNm+G zqi+*4Q4K$*^iNOrBr95m{<=ew8I(_d=Q%#}iG<-+*dag$^7j``U?utO6+a@8;Bz9> z7z(1-DpOWC$X+(5>LM!}yW%z&DIMu$^%RfHpY?V`Q`m-h*(9O}ljzTb(DdHf9edau zkny1Oz<;cfwllMyuvKoL4mkzJF(9}@-7%KTzDYn<`+U2T9;VJv*re0lFZ`#aCx%J9 z^e7$b6QK$yE+HY|#ql(D9`zA&;AL-!qit4(sD8uIpV!zWb~!wKK-Si;$B(NJpizWE zPC3EX?LEsx++E$+en3!}-S01{xI;TVU{of?eocZl1lDODgSSEov-h{Ya!=m9{B}g) z4)yk0cV-(8*sT6hl%LKu3JNm5qxb2nfNF^-<{K^+K9*2q7gjLp04RN3JDltf{2}kW z{@Q`a2o07CB=|IiGkSbU9HD(?32oZgQg@t#I*We(*YA2Of*rYoV7Y@eW%SrD7xPBW zhEWzdQM^_XbG-b@&9Fp15&7;Vldye^Tu%Z85v4$1uqBhwFOAfX5+(g{^QGQvR2=m& zG5uFql2ozHuhqAf-AN7KU+S)c3Z@v%1B3$b=HZ?P{Tm#Jm^;+BZcRYPP@E+cDC5K| zgrZUR8_}p)bb|l9mk=plWDfe{YL8aSHMkMH?tlC&x~K?M_<>)dzd*99hl5m#I{>}b z$Qy}P<*-ue8Xl%8F{xLjS`9_WYvRii4Lzll38s%9Zpp|cp04vDWUij>`kgVVZQ@7P zzkb7<^<(=-HV)Ahe_J_HV`U~;15uHuaAc6JUXcz05k6%aPxU$fL3lpnLmprWh5|GCmxm<;#Ql_2{2vX=* z0Q*3!*QRhYze*yCeT6{jUyy-$IPY?7`O6Q*&O?$A_l6Y<=}Rrb;j=`Uj6IgK>J(L_ zf>CD4*^tc>!(L}_16fwv14;a+-CpwyM^(8vCr|AeO zm7lO?SXpM6neL^VUVHWd6TwSI0!OEiM$mC0F-q}Ltfl2+dt&}RfSK)JS?XYD5x;gU zP+Bq6)Evc-L4lj_?PXr(qTD33v{~oCrF4?)t&j{krqU{IwUe9qVIk%IyUU_$<-14h@#3pIKT-Y_?J|7 zf}y%&!IuOL^BZ4~z2vPG0&omMy&16a9z`HO4=TgA>8-d<$CsU*!B0NeJc0k3a_&*&BE$`y|XTBkt?qjRDLN16f@ph#uOzl8}Ff6gOG8B-?^ z#ydAFKWQ6~_Q_-ZZ=rM|#?sr7Wwi7mvxv<%-cbte8GnclH>%Y|oe35>OwfWzR0P*V?{H$JHGTfV-yQW0Gl|QAziby6~ zt8mNh>rfHgl));FWwOAuFLf9B#W&vS61+#P_#${QQu=oGKQsHSYrpCaiAuHF=!87&PaYL*_0*VNTZ1gu)u%oM>YEcL=WYI_vLxY41y=jaw$V zn+>?l4fx-SWMhn}3fNUpdCs?=V~9{(jP@Kc2@#C&a@=`&_#;l50!JqAzU)VRrOJ^| z^INXCXq1(Vip)DE#;=fn5X@sSv zXNDRm99$cRb`Om1{Nlm+KxMyopTd9fxm4Bl8{k>Fq^EbYufxp?@b=r~#}QX$1;1ub zeli#Ltrp(IDeGV@<0H4(CU}FZ&Th?j;A!2t|5~z?h&b`>#Fj(Fm{>_Na^nWiAORZ! zs*Yys4gGeLQq_gJ7}n0hu2~uJy~ac!v!Oo=sgl?${0bXWq0g3jC4eKEad*Bl>r4Q6 z+HT?MejAmfLz`Vg>&`Kwo3>Dc2jT0~n6XC*gHirnD_>wyhWKn<;5E7P(9Uo_erxLdFkf(b8o*S#iK+X*A zxlH;Ep|`e?x`PBtY?<5^;G{V5yJIWY)6WxpN0BcB+O3U+2S1 zqTx69mI`Zc$F>pvUh+F%+OEGC-JHv#_X`#xg&PNf5%VZHXx}qX4GC+x;S?I zd>588!1l`tT|t`h(GWxZgp6QHkg_Bt;J>e5zfoRWtCIM}{wc#92!(NM`5@dE4U*pq zW3ObrHds4>l~(=-ehY-!JFssK&1)~57}rt%P^rd5#?vzHKEcWeb8Z9e5=M?WAHQ@w z^6=RtT4jE)tV{9x^Or4&r=B(>O_uEkL?|(E6+S##eAq?J_MGMO{maSLvf5V5UXl6F zj!dDts6|xc)5H}~=mz*DzG$~Vy{{*PKSnmxD z9S(PAb*wEAL4UAz(RHnA+%Y-a1fAgQeDr@z3QV)DhHQx_*$CWsa`cMTL52GGd$}eo zYwOvj#jU$|z%(#!e2fokGl{^KFy3%1WKsHL>4IgRni@=t{!X_`JTiz@H9leL` zHp*^${ou&*`<>g_f9uQ{wz<>A&c5a<-NV%Q_Aq-^3^LgM3ubtoF3XV=`n`x#kbQ09 za|s(I9xa0>w|gtUQ8N0+OiD5xxLyKd_HMm#%K+jyP_lmmFL6QrXejoj?999!_v+ci zziY|I%}X`wt%_X}&*xp^Z~QcxXt;NM7b;2n9Og|Hsi)hE>^Z!B3?@T12{Aq&p;}5$W#k?vieh?rxCg&>hlJ z(%mB6eYl(Zo98*edEdSES~Ig|K$9y^@Bz3B1m~6fXDItE=QTzS9TG}@z}Xq1jI5kK z@OuZTvPSCNAY&oxsgD}?QTqVnlMNwX0^*lIHQpz*3CQ#6fW% zgjhKJtvW)51>pHpKVt_2=ZUP7H(=p!2V|py#bi-GHyvvmYkeyx>^b6QqBVIKQgd8( z<)F&qALBbfXDe8B>517NzlLBp1Ck)ov}#Ne2T>?qyt{xaA}%4Jw=NqlTJ0lKPowWG z%j)gOiJ>z~gaKm!2}Nl32f-3hbp()vgOYA^rGx#Aju04RfYhsEu#a`dVF3M@1pDfBtb=*e# z_Q8vF9#n=U;o=pzdWPMsM?MXXi3UD0Rp4|Hx=AvtT;=p5faDU=pR(_n4Cz@#&KVs2 zT!Ktz?-KrBNgP7Btx#Mb(RI>iO08OojoE`wxho~tY)3U{B?r#1NLpcJ6u(;H5bX+S zSoG)V=-$prkY<0<^R&dTWze^>Lg~CO?+ov}YJ}n>|LsWL+P3j7WHe~=Sv4GgUAh{v z_3ZQANFI9w1Otc__u7^#(Xkb>cX!h-k)3yo<-g)ZuQ|Pp=}nsA0_EkgIz5H94~u1- z3w6R67jyR=N!V*s++UQC&sru+-b7UU(?*Cw^WM>10n*Xd$udQD4^hdIEYu#|Wvgos zAHuY=nW*ezp3TyN0nyc)FOnyQ(Hbc_VE>Xp3E&(|)hexSU?$BU^5NxN-rN1D?rk3c zNyPtMX}q=Vc;Z-f+jH z4}s|-{XmiT8w1U(KrBDqDvpdcnsPGB*gY)bn@pw8@VvAV{+_C>(+Yx6d-B2mo- zQR#fPIEJBu7DQwq^#%2L7e`yD@j|3GYH(N7<<*$w zdX==O)-EpE0~-^$y%{{twbdv-V#^(!eZx;nkLPo`28M?5VDKSH-9-l0c_FBTzizyf zhy=DD`$q_P98k~`yxxx|E^967x&I|8gDaZ^v>5*_H+1W1C2irW#Ih|ETJvAx84r9&y+4=`5c5+~kyS%8k(M<11F>n|Dws;qTzsD2z9z0} zVRdAPRpbx*qhhA?PwfD!^qtg#yLuA5(YhL?CA7xyvs!u1UUJEwe+D&~TS?!&cAy1c^&Nh?se>NfXxs>_uAbaH+zmWIFIG>A+22c%3D+yokkro}co8kz zu@$VHOcSG|azEp>@C^M^iBa=ApbEd2dwkDK)SYFlL7DzKI-%LJZq8WhHCtAKXahUf zGw$$ib0S{|lfr`G68;ydE$-c>s>a1p0>07fMUjKo5)6>Lxx2p?F$)2X?sil5b_F%_ zL|k?NY|Gv{B7UObx2YwV#~T-XeqEsgB=|Tq-_{56^aOlfQxN~KCpbIZU^!{OAyTc< zHUw5gM;{I86&5w%o-k)LqEzaJ0EVJC%Q9cWNt4Jjvfe~TCNG*2R8sGf1$fF&Pg9@H zhDSaXBl~TNK2HxkJ=`>V-Z0Kp>h3Mhlmp}JQ%AuYM+6vsY_h;UX9BpVSNQ2v8Q%K( ze*J}%Et#nKlc6-`uM>6~I&5A3SxEkMX_YNs$eXl^To4zEDK|0rf*r#dxl^Gdj6^`o z?RH91ESFuRQ6X^Lcv9NE(*I6usXRkqLXWwU^{?}PLWK&uryIQ>5nT!bS10~8m(Ch` zJBvDXW&YQW)LlTtXx{2TPkDZgg&3~ls=M2v=w`*ES%HP7i7%%9XWblAL~$6LGM zcK$~}Eth4)grvqkrtQlO;rQNN|H`2p5A{ zTg{SK-rmi8CJ@0DL-Ff4K&QjCszjHLxmtOp+w2xTazUMP`!{6S{p3Nb!z*>eu5WRX zZYmZ=sOtoJeBy9Ds;=X4M>#t;iwpZoAAKHn0b#(Nn~7JXLM4Ch0P{;Mzj#!*C{|nffZ30v%4KLM zd|+h{m3(V{cvELw#TFch`Fc}rYsrc}szzBdePfF|PHjIDZr-p|N=K}xMnfK10ZD7T zE+)}~5QBS54|D!lf?G_dxiVcRZv0N6G=rn>tBlO4?lYtl*w^ZA^o3!?w5>g`zd4@! z)0}L#=$ZXw(@7kAVQ%g3d2-_(mXlo|drGZr>b+1_$ybA%V>Kz6HTu^7`=psfDZjWO zl!0E;J6I@kk0%CQ)l=$WN+?Ybpn`cSTO7UH_w|3j6PVKzwF~0>CJ=5F@5;_D+qzPuQoh-u)52;X5ze(T=2Ort**kiOviCbPU%pC^z4?_K zQo>Z9rDu%Vn(poy_m=Iduei!#$Isbpxml57+-O4O}hzy~*Hn z_ctk*rI7v^B7jWp7fRNq0K4DhB&O0`FksD83ZXRRv=7YDqOF_xK&JG$Sa7pzTb}Xh zoYo||y>~$H5w&v9eq)nT!0ox+Y3hy|*e^cj1L51F>+{O<8+R_+VX`|7yT$v57IDo5Z?THbKoEdz#N7<6FW$T2w!sJgskT;UhJy_4DKCl%b+@(w$?zmGe6&W z-K>z{N8S>p(Pdj3n`r4|#;6^H-9&}#tCI_JcZa(Z!H=O&b$q5!djT*tjn}cs$*!s@ z+Qn6iF2>z)vv7uo8jNk9Njr&69EFtj8a%cSbwKAE2X`Tov;(MkwEb#HnwWiAUfE5e z6b6Uf1hfo8>6s;o!D<23)Tg`K^_hDH`r69M4v1RaUAbA^T5b2V z`dKx7cV@%lxZwYu%=ex@;xK*Oj}ut3E@ZFSk$u~@oMP>%}`5!w zT9m+JpET1rFPkZvv6wPr1O5{#`((c~;gn}tQWjwyD|F^jqCF~pE!6F$WPYqQ^1&oX z$ttL8x1s(XXE+e;aDAu_4sH3$kCJPTI+Zf_&}h2$9*gQ*CDJw69Y}0^091WS0y{fW*L?= zHC<2?q**!gOJzlD4T}FtTD@TRQwUET!f6#}%zN-QDbhd@dv&16TaU+H6rIss1u1!4 z7eo(yW$X3)K=W=(A_U}4U%dDWKSp()ah~$U02P^7cj%QLQ+Zn5rAJJqXS zdHlEqRiC$Cmn!aTk%!Y8UR?35jovZ1D_5wL&K-d6JN#mAT(N3yVD;pwI{V8>-LlPz zbN00>)V^`ykl>b-#m$Q)D?IT`{`8a zzE>w*^`Qt>mW?c#E0*VMt!vCAZh?ey({sEh%pHd?sY0oCovonv9X`}~=s1aCr!cQj*VNp4IdTDLtET$;lY#80qdoFG zaSElP6&m>q76ASpy8Oe26_3UCQJ=J6h)D80suqXaa8Gh^`#&HWG#$^-_wng4v$)Tg z(5RciKRfYtidcJ?{J88UK>+L06YG^D%}Bu8^?Zk)oLbq;z~`oi*QKH|iI7KQ;OH1X zX*PI;&w2acdvbEo2-WqCFcgnj>}Lad%UD4e+heJ^yKLy8s% z!m{>QaOX$aq;+-@RbxtcVBIPQCJn{8?H{?afG?ZikRnVo<%DnX7;)kOgD zJL$`0f0HHk-XEfKHqJg#EW6cNmPA$P0WnWt}&)-lDE>+ST_1(#Bdkn z4t1?j;Og4nx`_1evJhu`>i)qLX~t>!huW0;>fYCX%l*>R8{E141>~{9=fJTo0{K1T z=^k`B+YqFB2z8Fzu^F)8*@GkxxPVs!(S*{D@(EL?h{->fm{9a9{=>ton#RG zRECWf5ro=xOdTCrlU<9#41-ilx0Ezdcw@&x>)-Qc$GW5#ZN^6a#N_@WIXftZ^R0c) zMJgZw(MAsERPtL}ZK`@@eB@&w>a;m@#%DPO+h305ESjJ)Qn^K3~$NY`cVR3X1>Y*}G zCH23s;!>=%4xg}gmD@DpiO9nWuQ6t_2U#}Gw=1`riuy?8sTQ{=YEY6!-bw4cv~i=O zqYh`AuwbVGc}5v@e?A7-9|LhTEXDFMI&U62$2*@IpQCS9J+paTPr#-BC4Ullq8_ib z4&d9ib+?{$SoSP7Hbk}y(`(HEx#e^TXKF@fD_tLd6hzi@-(5|DTd0Ef|3WpP?a1kX&fis0n;kn9u2uMO0|**^Al~c&tCj^sL7a@elVSzYlLKf0m#r z1YU7)>)T;i1Sy$2i<@w+vkz{GaGW?QP0(G}1+}%!_1OGBmh8hFrb^7&TPfIPixqHV zVTeW4X<+J>$7Mz$_nOO9u${=@4UQB~C;-B_5AOy5h`**gH&d_r~9`+#mu?h3|EZe0)~1nYNFjvzg^APL2d3YU!Gfs231?Giv`$Gknj! zd=#|oo9*2R0Rbw0vs}>>;bb5uyF!JYo-Gu6M&$iGBA-9a*YR})lMlhWO?p2wSwA?& z5Fnf5c78mn?wrFTSo)o6)I|vkuQ&4c=dAQD(Ri%CTD*Xc53(?V-+=_*ocoruFTzXWwMm4n+ zqci=GsF`;zbIGMmX`PSR&+a~FGkfzZ3nu#;B18gOCdSS|QBiMQ8eIQ6wJMdpGciH4 zdzk&0FdL}fCkR-A49C6S=bFIUz@$5r!$AFCEcX_OTJDq z5YD$Wx6v0m3LP=qV@JW>#l)h%rrTiwh{#v!0a)nP4;X7=P>91^(#vmD-Kx3u%2u{_ z@Bb5*YSBzb*|HA2=P`bsPS3vjH)~-gPvN6l-_+f}6zIg5$c-iZug6$M_913G|e%d7r8QJ*M?8zc)ZZF_lIWt)O67 zRi=p0y&YK7*06Lm@I(z9Q(#Izx;Z$oP}YK?<6aLp?%3Sf(pv!`O8!b<;9Weh#EJ7a z#$XZ4TIU(^oIryDlnJF4FtXMZZIjKl|FtC8{v4Z<+s@cYtm^=l2AFL zz4kPU#nHEp6Ggh@k_39N;E+~66xtw;=x~s*@u>*7W?S_Gso}Oj!M}?3}Bj;p|Fc+EYsK#qXd5Ybm`mE$K zthYm&d0HGUiy+c^dmCo&lh*oejbRX3<7dCug6|$jvDBn!ZPq%*Zq{xEfV8LW@q7fV zB`vKWge1nhiEzISK&yra9bStxB~ zb5aeNHb(C=Gsja*P(TTJ0~a6wI{Lp8d|=n^(CXwnQB`z%tmccxvE*_ku{yQ?Ghhiks zoEZy+3MFuSHy5XH9H-;GPVyfPQQtW_I%?hRJ|kAV8*_<}i=kM3SZ`RMjuwoylBrc~ zaPgG+FHs|aT=$O3o~vN#$l+=W?da|ebW-q9JcGwQZZF$6%XQT|MvslGzO|$M${DWr z`~JS@|9ho{Jya*tp~U<-Sv_@_O-`0cS8ED3!khT`{rGEk^Pu?H)(%O|{7n zfo-0yQOE;(VFvwZ0v+PT#NX(W<)x-AAa>UCC%Enq&Qd}KcjLj=g;7x>&Kcgnkv%0C z%KH`vQVpN(yX?v&A=h^u*qpe`87V$ z$3R5?uhxN*W*&?%Jc>G$Qq+S>FazO8Q)h((3biDpZ$ulKsOd2zRQAkytvF-`v@{eD z;GT#$1>E2nxZ~MMQ{mX>;OdtcvK45RlR-kc#T5^{iD|RbKFh@g{D2Z=c9JUOhC}eH z`IS4iX7*0A&$6{|+}s%h`JHQsz67oqtsg9a&=ku{G)pm%-#c-se9ie;sFIG*eQ1xd zMNyfEwmbBb?TrmFO`#%4s_QSU|Ak=?*(OCqqbOlAAa_17l$*bqGE)dU%1m81m$2Qn z@c2nYgOc0sdh;Pc+C)Tf$e-8YmI)xhbi0+XNZ7Zfo2iZHc!?3}m@xV>w%D~x_*29| zZqdNYH2%crruC8ddEmMG=K1nLVqoL(&JlEeEZpp0T332*yul(W6trm|#ffdqBm%5|kQ271EN8b3`~Fb2RA$s^8;s5CfePZu|8&1tq228p}Vd!Nqspb^jX^{D6FJsgd*;tVeO(#jv)K8jk0TX+V8Y(}Iv_bZH2 zmRfVh-rl|Qw1Ik#h5=t2dyzl2ea>I4o;v%nVHUXOKFc^SCLy_?@wPz5|KW;U=t!Ob zV?cfpHMxp0S=ixpogkS}rvTJOtnb-mFd(4sX(Lqd?k`aY+UV)=kueTuOH)V8fjdEl z;NYK8l;b@gdQuZ`0nmfn9d^ksVg zS6($`0|6F2tdJFb3G_e|IBzmdvRE42YbdW=Hcvm8MW@4D{jyQ(XGQe`4_d&@jFX)7 z_sT=7&FxhMHo|Q;KwbBzB8y?shw)?Q_cf09bom|=@O#&@}rxN4DjCe}pGwzM3H zpF5{LAnc0Mkr#y=l9zv!A`8wLnA*e~vUmoFQGMD+5UlBbyxQDLgAy8_RKaB6U@)bY z!rqkCTN+=?<@`^HxgqNn2rhKI*p&sl+qjnxMfH6g;oOx&;TimP|9z*4q>&?}I$sL3 z&!CmXbdHC7<(`_4XW`8qRL|>6!9zZ`s2CMa{3{s$#j*H`}K(1|7h)C`0&Pz^UpX=_-{)S3zY$A)Ct6 zwf<#Q1pEpW3S1T=t)!yEmYb-^@dskU>RC911Gn{;a7nOl&U}r8O>?T) z&-(EqEOGaVcf=`#97nZLU2Db2u~EF@@WN7;Uv7MExye4D_2$^&=pQ=~pPHWML$<@_ zEuxO^lVxe(@=X-qH30OA<_&+-?qQc__F%;wdC#WJ|EoXd# z5>WNAF~u=nlxb{Myjql$9aA}SS3^Qaci)UiVX_V!9&Zt&i9Z?5>B1Cjp*Q>9CvC0N_LkZX=4gBvY4m&Y-9CcLAGUf91(vEnTGO`v~#i0lQK+gMt= zM|0vOEO2UaJrVGIuzj|M?yfzi19taR&pwtZa>~9Q0tuUCep?RXK=>X8OuWA{`5(d} ze!hM_JJsT}rfc=yLj_m{s|xa*vAJ`4)N$xs6~RWkru4E`b@&g=@r%*~sRX{8SiS3~ zK-ER6|IFFse_G+sdN4Pm(at~y8>N+|_D>jN1Dla`TFbf8=znGrJ1DibV6mbd)8x!46&~c&r zUqRT5ii)R~0veEQ{m}7p8&kB zYvr4f(ts zof?_I(x#NOV`4J`Wf49+OS4=f@SO~n;iwWceYGNDL^)895C`9ATMfBpTKO!Ct?E9a zXYfvjvCv_m1hZTj^cXMALW@`Gn=i93BYp=7-!#%sCIwKBHdpX(?rwj-jwr_;m1Vn? z>+m2FJUoNK6Q7<95Z5);_kk-|-J_}R{vNJ(<9n6w(+ggprrRi2K0^^nmPEw3;VE#W z0#>uYMUi4`;*t~=hG;QES9uV-t=(^*SIInF-VO#65?6Uv=(HbP$JGj_nFsSx>KnEg zo$d1xUBlgVQkP(6v_=mrC%D5)F(>#}2t!9PtET%aC+MxpMW$%$o{T#h0kg~YCehjX zhYy2pefNuWy&M1066P@(019}zSkCeCF9tBx3O4|lMgHUusY2npNeTp!;DA^58L_Id z$}ERq*!LF>LezIZVpWH@UZT?asOX6FhQK)tAWf2!x zfGxaUu$@Rsw5jI(kFgnjekldrO5SEY+NJcC5g19Aa0w#}fxRZ+E(|PQ3_?d(J^Sl(P>eowEbUjHuD=4FU>tPF>v94u1C!0>1hjX(ja79W zOU0m)R;ZLH({p)J-EzY#S*%I;+8*U9gfbV};Pj=lbDy)2Wp(@WfMGtsAcj)jt5RC<<2^4*A?@Vx;)z#Dp zRV~Rn`V{=Qr6d-YA`UWF!P$GlbAHIA~FzDcjxs$ks&`QD)vDNm^Vhyfg zc~byF7~Q_OJ&(RMFuWS%d*6Q7j_qH&ce;VUw$V%M13$+s^e6hDX!r$LE!6@N9l#kJ z77l^0*=@i7J@+GQ>CVjvAANMyKuic4vBS-=Hc&?)_{Y}FsFb~A&oF|6qMk`YCyOa+ zZ!ssWRyvwxu?xTJ_QNo|PxNDANj0XWbspVld^U^kA;kc^Cmy`xTJh1+_06@-(AcRq zd@flB2nV9XM?1mqFSK5C`T38|eC1M_((s*(|DxqDMy^R4N9dzF2;vDc_$?2JnNQf` zY<}bR&OAfbBF z>W}+=;rlawtVo8!-agUvNjp*8U>VJk_0dbV3X=$_X8*0UHu}Vdq5l0%1@#$a2Z2wC zQW=7-(SXat`InYW=FhbGdj+;E9{xuKw+ZU+y6VZDUsG`St=?j}h|5j|eTkUkj(?Aj zYwzvCQpu@LN8a7{VhG`G@x*E55B-^}lOg8wCvtYTy8&=4!5nzl)$Q$L3Xgc!ke0p7*IJ<9S481SFA7tzIzF%VvHz=bd-bfUpAGY|O z0A%R>PR4G4SfZk);`W8|Sy~zgp!c0NoGWcpbB@@b9EkMs6A zUT6IVAx|HAfkWY3)ta86VSr85fE^bFiY#;B78e`7tjgT19f4%CmRQmO*BE!6n&yl$ z6}BWkEG2DhBIE4NY7)QY(=_*MI#=z6rg6>>$B2I8SXzb@vrR|Uhpj&ao5oz9j|53k zWqb-PHQ`2#>zF^QElVY}Qpv&(mw#KBU`53*xD9Gr95IvD&i;;!$225<+-!9+lvG;d{s*JU5^}?H$b{ zOxlNu+db29g$gxtbt)ER^7zgRX51|7e*QF`nAM0`qtaZaz=SemTFO-Z_<{6|HaRpC zb8=Q>v4UsCCK+vAeh369uI_>g3MOpgzt5+W8lJ*-Ad z5ai?ok72$dg5=LXYS1Aa3T}-nsW7$M$cCiSmLhL!eS1>xV|Zlb3@&?ra`EWuh87bX zwyXiiasC0o3KQQf>8=+?&deykOwQnzZr4fPFcZavGtcoXec^Fy0VoR=ex|NYsbg}S z8medAN3xg(#M0hS$Q;Xw{f?v;Q`q)xl&jV(lUgWWUKCL&R8>z5Kj8_?wC=d5@<~2| zQ1S^XCMAqe8itf90lt7O{Vj-qgx^Iy?Ya1Ln0|5X?)Xyx`J7ul8@8YCJYryK3KMLT zfvD{WpDJ;5nC~F>1ym_(2U}_9k}>rDUmWGmalDjMDxc#KsR#b33WqZX>8BZUyKtot zW7b+e+Gf>iEsQt!nw*^d@V1R^kK03k>+#tAeB!#G?wb;)nyOuGbX4DwN*W}M5bM#$1ziD z!Z~g_w?swC&;nLGB_nFXZt#8=aK95gb}524s?XVNw-8&6^pt@ApgWzn?;p=xJ4e9N z(#K^cK;6H201SAtC8y2Q!Bv>Goo8OhaHy=p(tOax9=GqYR*mNsrM|g$vPpZ-O5#VJ zfG(Lod}wPU@kq@`75o}WeZP$d#Z%L*!o6)zBvKbqZkl<uB3r9Ml zNf^HObbLH~TQBcS&u z>HCy?mR3ho!R2~P0MwxpN7ef1r&Z50oi8qgx2O8k69+9|f&k=Zd)IpyV@;WSE-EAu z(9N~mBm+_D?5qmyotPi+{F0bh5{uz!Qc;hiD>yXZ8-j)z#;@S?hfC1nm**%#^n_1~ z^Ldl=6N!5y>vE+|Oj~)Kp*}Iu?yuaUMPu&0o^PPAmS{He=TUhSh`E(YGQn~H30$!O z%d11Fti^X=MaO=7Fj=uWKK6Td{#8TQ`{?aDUL+A9bOQ_ypbx5zhsv+6ob%-0=Nj@t zYm%)Dh0Qe?3L&(YlUvPdKWIydqUxp$KSB&G`j}x=paPMEXoe!gI{Q+7)NHoCH#hEX zH$0V3Ru0x)QbT1JQDik=%NGE6F=^4rWw-v{r}j(CPaU_3WW6sqr!HNVBYEh1FH6@W?`N51lUW zjL;NXEzNzGD(t!ZgPlJ)C~;sIFKEaZTrwdQJM7Zq+UQGeK{U zt8SW_>;0Sv$`VoEZ+C*H^Rvv44V(4cvPAG+8_$9)!fwBPSqRdvY(Iy!~x zRCdNJ(dPd}MN+ITwp=S~?u62c=ukS(u(*0N`gmrG+K|FZd3!u0%;K#%+wsTHs6@`b zx6=+88lojy?v!J~BMmbDwz9IYk*KO;0?5E1(#pMWba!A6!+v)()qu|%QQ|itkct!* zz9<`m(ESs~P>~N>GXy=pyV`zqI9f%TvbV-{f?Z>e*l25z+fz~};6bfDwH7MWdiga!*TlhYRfdtdee8x^XhNJ$l{juNa4@h0aW-2` zj8z@?7Bv_bC?G4j-$c)P3i3g1C|IkOdr!h#;9z$42QaY1@ww=l*ZYk#!hI#)!T!k< zIj{|pgP19E1S*M5emGs7^dR8csO5rw8!g)R%GT#V*YV+rc>RH>W30JMtyQnxrnVAL zEv&3{TFvJK?-{jjr>y1$Y0Z^ssyp03i)w$d`!W8lX$3?G7juC5$|Im#Pmf_?Iz)bI z9OLH@`Fu?Z8)}h@Mk;xZgL}wbwX;Jw?Rh6wbI9)nw1M-w`DYH?1HA>u=8JC4wlmLX z%-nZb2OD=;ADNl9ZTjO>qr@`B>Ll|gU%>db%gqRYxxXLVe}NvS&SWsuq%0d+L~Qt$ zcLN>{mX~l(&yL{vn(i6V8sWc{rCd{yo_S?^So*)A{_S`>O6i0>xu904P@zz&1Ymly zaI&Q22+NI@5(pEw zfxN4JslovBp3(qYY*|C2`0&B&dFz3OVy27~=iEprIMRUWA54A;rUIYC(>$3?3_FAR zw?c|pfjjZVI3$Qvm^{kHELnGsc)L!qLgndt_nZ9a8vS9Ahy_ybJf4W66K*@k0ig!8 z^Jh(KyV;0l6_Zkv`-ipd?Y%XI1OGKa>Z7Op7hD1aeV%d3m$V<_fG`;RS{>sU+|vcmLzxWXjQE;XMZA zV(FrjwRKc)NQ~X#ygVqjFK@5Dyf<7dhT1RTl)$ERzVQ^UaD-ljwHt7@O{|@xG=_3n z*kewmw%N$c-)Pj@eGQn6N5ousEhwK{Ab7x#!|$EIY^gk~Q5a?IF3iAfRe+wrhd3G9 z_`L4B_iM@5|HKpMIrCd;lS(K`+Gi{r4sY#sJoYJ3y~83dvIE=h$qpl6uLpX1$Up~S z1SA=Cvv9BEar68<@`X%I)9?FGY`lke(|1j>ni}Ior~Ay9FGM}Z_}6&MpW|S7-aH*-!+`0;m{Ge$G=Gxj zmoDgwiIB5Cyq2aNJ9kMYURB%lB<5e=ox*uyGHI&o|GOb;&?)3;0at;okIjrE>^}(O z+(=c#?X=5cQ#$&4m<;QPL&LHqQ@dq_v6Z*=Wvz=V+HfhQ#mdTNvzf@AfE7t>7O!ZE zXUQnU&cq`PtjlBjE$cGbe5`PEbxyuHsmwtSZYxv0sYsQpN3NObvj<2r0_mj2LXJlB zn)bx(^*6>lHq+fwo^Vf20dP_ZD6w2zUEGf#bAPWMtgKJagGv1$dQH&!(ruVop8da%o@eb7&^eM~Ff+a;+{7S>|UH1R@X^Fj8A(ea`d|a;|XC~?^irRh>yk;P&SuxSgn&`&B^{#oTFngBL{D;$7n%)HHAPw;5K6=iF1gFG;| zMwm#@CnEqJ4G7)uOkZnQDiPGw)rnNi?VaX|{O9Fnn(9&q0$Lx39vVNu=v(yDL`Bs_ zMq>VGh&y&Y9{y;|;+dP!%K`Iun5sSVCi zIAU)o2||eyz09}_7K#VkfpXg}148QAEtzTXBI~o{`0v+bpylACu@5hbX7Tc9Gv%n zrB5QQzUSZS3MIoL#0+YRmM+}}Qh#$oKEx?mM0IQBTK64q9gM{Bj$xD?PiTj`0Y{aD zOiaw7i(%l58jea)8=X6&=E%+6@6P)WC(gN3>9Eb=#v}hZ%^K3`HLRlvxO+gR z>)>R*c!bL#=ymy2_^@D-X44Xnh}L}e7;UvYKMQ^XG8np!5ZzLYTkE1d)Xj&itAdd~ zcpSK}fiqs=j!MspSO>O(I z8OW04u*5Nd7{SED;~tD|f>;w$7+*+vd0Q{<`GIilGj0Eat7=MiYK|b1+r>ZrdK{pX ze^eOq!J$Ns8+~2KE@~fn!1GXcf!QaOU*F?wq=EF~N8Sf}y`JS7zljkb~FUB3u`@-^sZa(y#pR>$W zen8f*nj=RLo4rR3YmuS{sXQpbZ-xuwxaR`B0g+U@xXQ`Sge4ayN>n>w{Z!)Z%kX^> zs%un!F^ZYkh`(4~$b=NHZ<^i+?d{y|o@t~_^rG7duQ{8w0L&DS5{;R}1A*?@`N${x z!}%KOYsY4iN+M$5U)bb+fRmmcJpcA5M5Uiu9~%RPT&j>oA%w)+LU92uZdK&(F=hHS z(I?4k&3o_j&kxbwX9(()eNCB6#GA)bLPL)89=G35pyj@UzZc^c)N0C>914Xibc*#w z7Sp4s6crT#Ar?!onuTw<&hQN&a05Zq7mD|ed4l1$y*J0FyHT)OwLbu$e?LA|6iy`1qRO5i3;9C`f-RRoXmEt<%-`yEo3$!28C<<5k1~FF2b3=7l+@TUe>Z zPU83%c&HJtj1!n!!PYQ$G<5YBEx6vBxRH6xQTK_8R};VO;`frCbtw2c|UzT$I1N$~jgVY|8xRIl4Zmp~!DwuDs=H0A&b4R_qvE+~Hp4j88 ziM$#o{ql*arf3=4f{MP+^DAnkV>UnQNtcS;Cn9CVr5apYxp*V$(PUYW$O}}z_Ua_6 z06`Eq@1j+6#-5(={I19LkqF5fJG zpZe?@wwQhJ^2nL)d1W{hooG%N!@Q^UE`9e*;AXBA-*rU5?=Lk`3s zw5`Bu7G#z}SOvi{rcurri`c9@zsSy&=OEKLcZGFNR4@u&Jo!GvENJ^m6e{FyC!b0S z?8McesFc04B>ZXrcY>5rx211%REF8~MP-Z?P@L5@g}2&L(}z~|k%TbWqayso`1xmn z@z)>T5)!d;svOV6QDTROF6IzC0^be%NEc3o#w7Q%9o5?nw2pB-uIRofRX%JG`v z06#s_|2qi+Lhtvx0C*7Y2wI~`z8eBo)*$245n)sG>b4nubWvb5WBF#uP*s9FhE>0z zb~vy`6A|Qd(1a^2jjoow!dfOKEfBFjhEdJ(_0y>ufLN+xeD!V9{+ zF`i*w(Mi5p^Uc;qf)AMV;becn~B7 zso=#DO9`dnF0ikLd+CWl+T^xR)_HB}8wF&**x9z@d=BnP*PLX&7$z73e{Y&yPly06 zu2}pPa{wc%m-MRC5Jdzx7(>4xERLhz2$K2Ze0V#K?yWF=0S?Vaq0}>mscQ&@qV!&< zw%;Izs#(+lPZJH1*CVQ`@99VXRn#c4UJY02RQ@uZy}vd2T5WcIAoS^zH=i%gc^TKQ zEG7yVoS}J$ATn56v+$%I>#=6=`n;osJWgAPufLGdZH1Y_AoC@|6Un$vp^yn@-Ux~A z$Xy_}hK+}^K|w(^-LTIpX-CkKEsOk&pt}ch<9;FdC=Hh>OE*)7Xn7+IWO-$YNMLEi zqCyI&zLyv3G6WohrE1h)cnxY4IetG#%gPSgYP(Pg8`hZpIi26HMHYf&uIR2>C;?V?@C~tf&chMFWm$!XyiJ@zcjn7BArobIOb47b1jRpx+ zorFhB0Nd!fxa`_@eiUTI4Z_G2>e{?#RFIPDh}lbF{vl%t$vmW@5O&C%!dqK}XZ2Ss zesuuc4ydInW&V8^V#bqgjdZ9j|)K2PsPsN=p-Y`tz;y4|R>t`H3}`QRP3K=oaMOy>=lx7(CPZsdQv& zJz|fYAN18xBd$L=K`d;iCD_eOiSH``zi5R*o)+We5u#>iMeT|f_Vn~Ln40-GZC7&^ z%(_iBmMk@p&^1D^dCSo^qBsm1?#%MNpd)GH@GT?RwA~X$SFPldk`d5 zH0WZ3=gCpFc$Qv-xe&E%uv;)>msDcaP%{qqBd63SpzKZIinb4AdXM;bKI;wp>#zh& zkZS@A&*QPM9`AsJlH2Fet)|*1I94tFNX}4K;ogG5O9S%@1|ai*))$qSd(_G_dEap9 z51MY@jTDN1ihN0^fpwzVqKVEzBuU})nI$8V^$@f^oW$AjM7_=OVg}VHsD)JZ-&wpPljP#3-p@5{1KGiww;ty|Xsby|-^+wDFzp>O zA?-WyEVsMHkf1dGO-$jtpmQTaNEb;_B+nb;6G4pnmZnC-hWX9Ryg{=NU7~jnkJ2Ek zPnIqAn*FcQw5(yMcB}esE2{7pE#HH;0{7F;p9xR_LQLzPnD7DI8hBT5A*jTgn?Vtv zguZv2d1+W<-Too|Y_wshZCEK*vHf;FU~MR7K|g74#S%^sZ;dU^+_O~tN=BqpFlYNg ziE1x3MNsl)Ll*oS<7QmjPdBR|RyL^fK@h49{il0ZPQYjP9W3X@C+D!Ywzhtu8cdGt zrrG}Y^v=cejZ{a-N%OBf<0`p9-~wlro;2#@8Z8q>PyQS&E0Bhbu&?I8^7XmH9Y!D2 zez?X!MN7qFtFsp}mkSs8t@|guuuDES#7`p7b6sdBuw9pC!t+D_QwA|mI87lf1g{4v zy2SqcdC+zothQxgq=uByTlLqOHW9ySQU^`8kTB1swv+ta2lN@whnK%1v4$z*k;2+z z z^uhl~I?J#sx2_8d2as+gq`Ra=TIudi>F#c%ySsCPbhmUP-6;(s-5}w&c)vgX@bWrG z+51_~TyuL4`wnJZ=7x(tZGl89my}fDhX@&glgmd}lbJoXwss9#U-1k%+GXsV_9pg$doK6B-pQH``%}TKoBD>rFgL?keb>M9l`f$)G z37Pv6frmkrqLqEBYiucU6-oJrp6K60v7DFAALo?#OcnF^ad{32aRo;rv2~)V&I=o2 z9iR8&UmAbqsf;eemE!a10+?e|aWcxaqp za}K?#Iz5W+i?D(>`G$mtabFPzYwJA3p-X1S)gr_?depyqMW1;e!~%OZ@S~-utKHN5 z+wkkPdm6L@K2x&4&%S~zd{DF=Osnf;f$+9Ku&!C%8kJ^d_c|v%=8nXh8Oh=`#M$AA zLD~Pbo3J#i_1y`nvSYL}N=H_PmD`p>+!_K^@dh{+YR4z0EMS{=xWFyvbsMAS@qokh zwez|^1nu)tSOGZE&V6zLx9`Za1=H0_SQ(Y|xRCSI(aWg&xQDyg%=CnNfV|`hOKEe( zo1<`rkl9{ZVA0T|;zII06=iQ{RNACSuo%_%q+XZowX=GC^L)c?{jem=MHjjUDv-0$qunG3cReB>YgyBkr>pOb_DN6T3dN3kPFQz&%YxdsTwSV^?no>?TCBSS|tXQc7 z!uSg13qYI(LAM0pWan=}DVkj6(m>ag$GlYiuNCb?MO9WVnKo=E4XpTo{XK2g(DoQ^ zt$sng`ESTUc!V}89Q!*VMoNrFrGgegPYPXv=x@qLdb^|XH{RTwz_pa3t1`^y7E!|I9Q4;%nB2p>}JSkYWRt!rCnZ(@~} z!=wCoBlbOW$*TyRHe1s*0k#*f;i696irCgDLa9S^X}$N#8#ovkL=^j@j}|qxbaqLA zX2tGz!Tf>?Mt}?!_%~7XCEclT5P#addgsKKW5UZRMK9UGH)&mdVlt3KiAvd*xbC2r z)uG58yv2AfrGO)_HlM+=_|VasO&yVx&Yol`wwy-}J`|6edG&{vT;JR+djOHJuCP0| zd%5Y_TJ(Ef|OJ9wj@Jk;5#(LZLBUrJhy^J1@;3iq=aCgZ?7d)M>QI4DHu8A$- z&KAx!Q+jpvUW=Z)XL zvbJ*~eM8P`xA(b=Z9qm&+Wf;Ly&5&)s%hn3?&K0C75#6_xBux(76Q4+-Zlo{prT(_ z4JMSIg(XypjV$@&nP#qAW{H}%F_BtP0jhYkr5Kd^CkS^n4FTe z9P!qVhVS?Eo%Og$tmz#jb9>90D61$gsD|A|>@33P+tru#Jl;4+6zcta_j`|RPYGf2 zZf31qsq}hjA~84h$KQ&(4-=1Hi7$ChcKtMI@*XmVOA<`Gx9q#e(KbwdJp9?2y|axb zeWH~b2Ur@Kv`oTlWo*;vNyi7iw>8Yce{c#{FA{|tDGvFvDIvI=7{#N#=Kk+3qn_7W z74ZKYl8=dW90_Vrw*q4#2*|uDE+~OuKksgNu7aguwW=FHTda2B*h(5w6j2C&C;`*k zz=R-Kk@V1!#1)gcGJ1PD2x}lBYZY{~Gfxfg`YG)A`Sm*ozqwzT32GWH<^L^z-c$Fx zQ3ozhW=H)Am{#2TONCoqxhy_OKfI|7UN+(c3llhe<~R;)O=$X|*c8X_)h6eEwTGMhtj0H1k!x~3k8{{Qki(=~*ENy5Ez zXyWwMEof$1JS^e02E_CvY2p*D@D`rFF^BPM|Nla+f0?-nAoRHshH4Cm)DlpXjzwcT zRM-=>hT7Mt)BLMXoS>YQl6sJMQA-(tgok9ycmQMM*{n53i~9vMsM{epaeZ{?%Km&c zrNxei?4X;PolUe&Ygq87zKuuUw+s}8VORa*0~v|(MeF_aTHeStEuzd)@}LIS{fY;A z3&@OG{`PL&OVSM8bVf?z((0gtwTiB*4$W=l?%MAq}OcWbo@@R^G=Hdw_f5#MoVk8U({+`sIdoUwmoAG+R3}xhT=jwV&k5-?hb4}8muRVqlm|;E-PjnLYXNC$#Bp~KqjKO)KJa9Ic*dti_rEwtccWu|=cA_iC z|BvUb{MURnTQ+1I1LKv*V7a<2N8^+_4~-S;JTmqp5696(yhx8_Cxt#Hq{YwsFXEpK zmzIHL0pN{uC#sHvfCWioU*KvtQ5++;(dc=_>^X;Bgw8JhH3 z=+cxE-|@w=AYR-a+cTKFD-e=0ZngEpEr}dIsM5&?PwLr=kIvB6X*RF-P5IY75cFd7 z-ucQVl_OlKWcueE;YrDYv7d{qs)&QEJ|>BjGJeJ!XNNmRah}p3?GTzJu;xy^mOP4_ zkCz)YATEbci78bkP$@&v_+92(a1>9wyqa9t>)D@Xn4dBK9ae*XIVz$1nw=(86m+@T z1vkh1?(Q;sR)=%AXNT>as)fQlR}_xs3bkOnFnvQ~6CNg+;!jHB`K4Z}+Fu%vxN(_W zG0Ygskf;cFFW!_Nn1BvTO;h6ju$St-^>Bcsy@(Y+X~v8!48l@v{M1J{y%60mQ?@Eg z$Jg;nd4|DCwVJ!D1F{qRmL&3;0|$k|to1llUHEo}(ylM60{6NRS(c=amV?QG6dZx; zE*a50ll*SM>R){tm!clhgD2kKIHnu~)!;^5+&(y^$}ujcIE!M?yi&FR}1^OZiZv2BpY6df5M)Ca7)xd_Q%Rrq2D=ZfffyLVMl z;r7yK9E4DH#(l6f5d*^*DWPIO@ zC??4?AkPLXbwakpW#-sqr2!LqG`aWmI>WVD2F}*nU+bu0+_AzNfxQZ@595>XwNFN3 zB4Ot}c@<|+TExzElaK@|k-!*O!FzzW`P1^}N3+P|avJz5igfFR-?#r+CS%q%A-!;k zwVrCsY7?)-&?)S2tKPPWjML4Ch6l^6?$3RfpF7*+LWMY{3twIR zc)3{wJSr7~BTu0?#@ogPXC7U`A#AQ!>rdNR%_<4oYSop#OQ?p0Ax&fI7Lz%q z233z@s6TY)65f_Y)%7A~ufJ7d(=*y8SWr`6TG99vq}(V4I6G?Pid8C61*2E?$EM0N zKi<)ac5Tog3-_{s2xYmHGwp)_#F5);d|CN3C+tE==PE45&9#1)(!{QIycOF!{BX!L zI#SYVi9Ed_)%fXir%%|FnRPX^9nVFf?<7-`2^NMs<%okUQ{p(KIzBa0EPA^yma=H7vDS?4|b@+T)Io4^DUDSfJR zDj~$tJ;cyh!mZSQW6VH_g%qfsvi7(UX*IId7->hU*zQ|9!a5rQ^n5QZXS73UHA^`~ zOaUIS(^FMrL+9ftViz_d_`lV5A`$0uHLNa(*Htln__*ho9{Bd)esHm?XCM+c!v2H? z{R+$Fl-Z6=k)ghh_e<&0lGF~@c!no-QwGn764r8oMB;N+q;x$xZDwrpzHao%vMI|S z#c*tNXU^&AFyKTwR4#dS_)hr$_clUwGBGHtfeu+1?!Us`KR2F)>1B>yg+E7HCBff1 za~*0lLEQlxgBLZ1Lg2)IsDs>Cs>|mrU$Sp~U7o7Cp>d|2OKHj(N4@icU?`S|LEtB1 zlu-peJ4KL48Q*kl#ka)R&8NkSu`lua&}}i1J8kgoBXcKr_^?oV%~l9%G*pg_6BUbb zjV5hXkq52tTc!u6NgVHE*L`OcG~VQ*8rPn9t?G)3=|z9Er947$GWuY>TBC9Z*N%>U z*N%MV-T!C3Jc(X)MVVcOh)cxl@0-Sbm_17(&|j;BSqNYF&3uUh&lw?<-x+(GD?zO? zYSmUFH5?(H1U1y!)|v$mby{l6vx+X`^64Ty)R%2!9bDwF?ux z2!>q3d*f&kQRtGjJfl7;SVbRX=!SE}%%-qjwMZ(HN#vtIC0JEr#ej4(JL`1u>Io=9 zk3jfm6tp9;PfhTHMvYNWpQ-fnjSLnU=FrEU7iwePbpm0b?mR8nC00MuznHx{k!060GT_R6gOkkpefEA5+w4SdzARr$n?JNCG9IKRb*BF=~GzhPjbyT1SqAUAl}zN=4&cj&u0(B zRt9%`R}qf`jq!lyaCSGX^_ugU$ZGE%pC^u28k7I{8(D0h59fWIidg)3+h2}>T-_j= zlN7bXX1AVvN7(7k^l0m;hyb03M5+wdv*ZSLWx!-B!Yg? z$$@CmTFISQiXo(rtml-eZz~Q={CIGtV6Z#aS&Y*cGTl90x@U0KcpYEc&gU>S-n?CL z(V?pgVH%QDRjN9|9ICBN1&T7o>YA}-zbsb165?dYVL|@tkuqH>$XyeDASH}576M{V z`8rVgB7hZ$^Al(1l>G#BE{eF>Y7$?lBKCW)7$u8uemoEyYVj`;;liAy(MF;bNsXxy z)&^bSVlvcE9Ha2db(SrSX(T#aTVRP=;M&BXvm8&^ zQ*_=Ub#+4`aVv51x)Z}?h}aOJ3tm@0O6BuhYdHoEKB;}PvMHRr$G86_v3+QfWpf)374Il)O{Hjs~jTY$^)+nEQHew;mmU(9S8!`WDu zTU1?rEgjKJJl_kyI|$sr)374B^U?;#G;}VOe53R4O_fB~%BUt7wWcYR(gZ;%1T8GF zc#AcA9gYB6L`A9P5FsbWGqey!zo&PZXjQW(H-e(y4Hjwbbz(sS5GqlInVVbc-rk<` zg~H~Ap>18y)?x7jY3z8fLOK6viVmuHfgb{eusy+%|CeQ}q{bxAoJbi0M5p&EGY&H= z+gx}Be|hhH!%Gk8=#$wh)yhe$bD+&37OA9!C}|e+_Sr?%gg zqG=|{OgvHa;jePL!uoIsn?n%AZ9<|-wLj$iQs=gI@~Ln*xFV(;6JnGc&J?p#Jf1^m zk=!Dju&Vtwd`b9aKX*GZHr&t~%vqa}I!;98@BQr^?Z|Im1ah4wlWx3SDoSe>Y|4prZVDK*-P`!WOJq|p)AP7Qs zoeq}>sU}%rM6j1H@`jRFdaM2zRwDGllSyd9CQ}t9uxMX346s%Vt4+CHU@ zK?PPL>IiaMovsOe7BG%W`cJ+=;WB@+$89jI)2pTYPL7BY4pB`>ZQh_T7F^v~EK*Z@ zKM0Tl8s^9zusx?dTMNRd6C{j`qw-LL6CYnMb-$f?umAe|dYR62e^w=~uw`AZU|TIC z3ubXO%?!p7!%!rQrt`dVRmraTjewB5%AG0{HJ^7DK12K%jg9Z2>PV#?Bg3M|kl}>1 z8?UW&FkIRZc~hI~gmhjj%9X&XMBn%?T%5!$Dr~gbbU#@~(lw=l{sXsI%1KA1$Eabv z-e!qEquaPIyDLVkHbi_%Z(vq{veJDQZ!{+MnmqBR@2(2lgo)I7@sQ*t&xoeg>|+1D z75)FF8hH7eQ3ruT6}yDu)B_cr4zuyIM}ZY1NrF7 zm)Cv~7w(y!ah8{C!G!XmR$rn*{!7L~f~<9;31L+B5!NZNG2*L-yC{STSN+>ut>Dwi zOVbb#ol3WsVvucKH33g>_6b~&HT4ivA5M6gNQ$^kV707Tu+)*pC!%bM}K&}u;6S2v%XIo9S@UDNv9Y$lv}w|VbV)#6EQeYE1k;-Q4%kT=W_;>I3q4C%SjfAse<&atTG`GlR}$bjm17c zoeU;xawGlGFc35~8cS5yWGL{6wixM6gD4z74}pa$pnwII@bnW!`D`ELeC`{ROI^1@ zGF9h|8Q*5+7qlvRlfKkDNNP_Me$*zWS!kq?VZTGXJ}(Ng(jcx4V#wRWyGeYQD2kim z-QXc%v~_kr+GmSb5>Z6P6IJCTPIzYUpUG2!S^0ilgr3{dwJ$-_h{_{`5lYq<9IMgh z5*-~aYq+YGcG8C9P7wE9SB1my==PDct5>FeT+2+tT9T24Vo;Xt=Jw$ck+ritoxk%r zL-d_L`t{rYPS-mo0p#K;bRPrSyHvB|nG8+fzH{7~VK}%1LDPiC2(ulGMqL|2cRpf^ zeiB94q4GJPIeA%xB|;{o5IW3=+(xBt*hE; z-OEMp%-L(E25earq^4sZcSv-wEi-8lI*-n8q{R=f#dZ8z_{F}o#3XWJL5nF;HKaeS zjMT~@bE6?0 zjU%{*V8ko+k5o2tij*YMq7Zu&>HJi1)y0IQL@^G<1JiZ=<0gTvdzfi`&$UQm<=e&9 ztNrHiUX0FzRSy%^v>a#i%-|Hun#-ooj~^q*fzdW*2i^C{M}?5x?HKu^I;lM#-Hg88 zx1PM8d7tz6r-5XB_8u6gHTrsUq zfL?63W@u&>`l3H<&OshAZW<>uFC%9uKK}KxmH#34s#PFdiay5Ft85WMa)4_<3y%n0-hD85pO%9EKra!# z$PtR@2%O)mQa`YkO z;hh?7wJ|guahQ$|KzCFH2RsE z=&ioM(-rrSQ0$2%6&75ym?gWxFU=M?zr&2y)}_LBNw;=HzC#7660A;RSMDXPy#=(c z@wEZ<^t5azH0-T#1$KvCF0EQnEqMe^{EUdJfQj{#*Q6xpB8_5!g#X$sCf7SDo9fgUvKpPC zS0=+`-<^;5M#(Oi#ZzsW=-ctZaN~fD#W2f}H3e;2$>fkQ7Q|z<)ql|Aki!TLkTLYh$n*#6;-J1KJAJH^C@8hs&Nso%Owal~C~$0a)WyWK{{ek$C>(1h>B#*NeKGv(-AJAWA(B zIt`q>+u;HH<6M}nXy2jbvHwtoD$B}p1dLA+)&DlH9CD3JESxs=W*iyWxKxj{8NMxy$;q-gwd@HBad8y)*mzhy?4Qx;dNwv6ij!hn7SfQ}46{VbFq_jk#@xdSaTL z)7GC>ZlyA=k>%tDbaO%u%o|DE_`L_bkkJTnLg8-~789#<+|)MsAst**fzG-`4ez5J z>cW`!tziX7g3v3fDldM$B>`wxV7844U}11d=#i#Kc<7ue4zCd)}9Gt*1$UI+#i66-j59T`X`}06il!1BU#{ zue&$6No;>ukkU_$A=&I-gR%23NP-d$qsXRu|^N&y{6nKuNYD2RteA^C; z>CVloq<0_3@zz(Hls6><5&wQ~Tvd7EgbWIbNnz5}8x<$-10uwIj;6U0RCJt;p#dRC9YfA8@?~4KtsHGiF)pNw+DPHu zK}rd<6dlNWy<%qJ2O}tMn`9ul@09`;t`~^y?aZ=ow*Zo(;|pY3=r2Z{fTWS$tR<(t zj@w3X@HVXx+$fV$jEo7^lst7MiT6VM%|bz==w1t@NW&0seA8hDs&Z! zk-UWUxGmbt)euF3)akdlCf6F8yHlacL)b<|3X`ID@F3*cPi6H+WGHI?E;dSbjW?|X=Z~<0 zydpq2p$Bl$@BWr20A~Q0SMN4_G6x2zq{b~`bUmUEDa_FI(tpv4xGds__=KETSdK4n zjpQ|s4D}jMSNv-4F@Jz->$0h{4!{6Eevqx|S~O$%jTL12scPO93vO%27YWfDE=r67 z1TFfe!GhXHv3_H}-7hKK@{aa=#GdH2CG}j2%Qvcjz{Rj==6eUF zB~yaIXTF)S^j{z9_mRW{oV#7RZ>C~GQv|d;X%8`^X+Ee=D+SKLSH`t=22o~8P`7GT zS>gWSERjxgDi0$ks6>$RjsK^%dDR!Cj(g}S@kxw+s#lV7Ej@dFjZ0a5Ik%o!6E4Na z*ow8`eTfjBNkQCj76GdwgC*Jc6?Loj(mP`^j8Vbjg%zE51>>2CO*ZS2Bf7IK*5sJR z`Le*X4aRG;lx}EX+1n~a`@GxXwqfFBHpDrA|6tvue6Zcdlyj7>i?BE#NpQ%~@6d0K z4Ysv-*C3)Tyv;S}qC1f#aMkiJ9QGC zH=g{-uDI@X7(;*wN_>9Gdv>Y61@-=Y=Cv1p0E-9}?^C$R(I4@o_ckk`a%^5t&=3k5 zdn$Kd1V?-9z0=>ynnw@MxemE=4^K9} zmRJ;QVR9#SCtkUlstR=-+a@x|<@B)4j_;X)Q_bYg&ZL*|o*cU42ZO?u&Ywp5$u4`S z>fw93bF42C79$KKhxpo+F*`o1pOn4s(qf;c)BI~yDt22WpjRM)HABJnd_hNaRjAFs;+0smZbG{^h33yB8wkkQqawDgbCl1w}N3FHV2ch9wy}tAlv{<1%MVU z+;S@7HQKJ!?Ty`4}U?tw~(F?)%ZhiZ8O3hm?eOv*wZ#Vm*ewTF)4c-q> z64aYQQL@8Ge7a%1VZai-KS*89zyOvQG4ZGmDGbpe&A#8%>8CRUhL5+fWJq`>`i}`; zRR}5A#T#^U6>OG2Zp-T$CRbbkaT5P3Y43=M7~`gl!2#GYI8b*1X;rT}QmULk*NK&a zT()fFK<7efS(Q(rC^xDKG-yeMOG%Sf%=R-K2QSb*s!}e0G3Z{n^l3^tbJ_{@lW5f{ z)Us2u;V4zHY)J`IQk38#WFff5Lwyu6&==U*##?mgiJ@6^u_-rk@TEWBakzXEeYt$1 zYjSP3K5<@JKAAdkK6C{;b)S%DfkMSEECef0S#h+;DES0K)W-Y~71@#)tC+~M1QH9D zaT@=u3-ifxe$=wKEt+bW3?;0)HyE7cq<`NE3xwy+7&CZ{0m&cd@n|9shIC#{y@cqe2LM!hKNnbUDE zu~ENlE2l;YLGhr%n&BdIw`mnLlyugmsmEwT#VnMgj6k;)JpTXvBD=JHdYfmcXNO#? z&fp#2l$cAtP06#yy_pj130^OGX&BsbRZe2aq1vbkFd?Po<}zbr%9946gWEZ{3sg~& z+nBK`g2u$Q{=v(F*2?jTVYA_u7%TR--a!YNdpVkEWgK_iPgzmvj-@gkz~gI)W3)}@ zzu;LB!w){51L$Cr_X(Dkg;zAF!r-GdGCE`ul2U#?^=Q$v?Fm-YmrP*Y#)J6p1dLD2 zXccDRH5i4t)T#Y^UhPEW3kR++%SI{Cb)i(M(YqSMT&du|Imjj&(Nvk7i~eHwIkjOS zsE}-(MSp31&}FUSFW-msDbBlo4#k1n)&vwhItbNrgmou)tl3RJQf(M{dM1RIN~-+2 zOhR&897$6v-W6H(R%HLR(|{wpd{rS=Cq8?XA%~+gVj8z2!8g?7MrpF)txB-XaWu+w zY~t#b{l8%EpQ$I|-xi z0h>bS^S6j*xLSPhq$Y;Sl?WVC-dFRooRcTqzkK0n`2{+IZ5TO%sxw!o&d+@&dE^M` z_b_QDa+xl-UWbCY&2)ZkItZ8JE<7N>c8xqB;cDn;u&`WhYtv>(-=tbS#=rH0Js>yREe%rq2EfCqN^=66h()zI88ok1>c50jXd*~$s?tu zL(h}U=lJMDth4N|jO5zZMiXqfJ}7c{#^pE$@2S`peMZ4=Ba;#20n_N8YN>gvRL$Ff z*0(hL@5i!?-I#Xa$H|NLz6{6i)Lx{--i71sHfhm4#IG*AO`0MzPA|uy2yiy$MsQWMMiV(RxXD3=mrjy$)>J0Y8Vb~+ z&NO-ppqW2$Dt%+<#@LkhXOMlg`hJhSEm?xCEwml6<|OrnHW;1)21ASYivuI}{qdBR z)7ArSDM?rNzFg>dr7mEiES)(2c4TbOsTY~QYz&pWyx$e zmgyO)v?-%h^)IFOqE`;D=R5)5?6EXN$-vY#1aNKP^|=V3icW~Dp7lX(M2LG@mZ7U@ zhH1SdCjsb-a}my*-Qc0Z#Xjb0>Z26_Em=0J4^F&-$=ki4ZZ;1mTmc}YBwD%;oBmkj;p+h{D z_=ELVc?6JB0{sM@g>qg1mCTPvk^)|stgUCx zP=A9zmrp(eZG9Va&6lO(lCc-cqsC1>;~20jWZKg#Rc@W1qx@CUpN47%qb1x%0ZF;6 zjz(U(NGdg|f-OSbhWKZKe#{$x@+jfIfyA{DVOnD8x_RAZ!3%l7)2=EtPhaokL_3%~ z6OPEh-OK<1mi$k>z)7c|RtdqJuTW}z2;$t~p<{1|t}~?&-sZvFa5(1=jX2npkWA8; zN#x@e-=>TZu@ZKkso-|{0U65mKqN1hlaVSHDBr7nod<|%ax9?Br_F0#)4{7ofH=+5 z-dc?L=D-6l z{~_+R5<}$@qxb1UAgO+{(Isy$Z9}`Rp^VzeqX0xHy-ex86HTk6XQ=ZmlirJWnI(U` z)}r?4=C_L%;CG6>615bVlJ6gK|8ZlXf87iR#zXMJfH1=UG)YnlG6>pf1EEon*%nbW zK7k@|{Nvy6YFT&XDAIDKT&iZl`5tsM{BbE9mbR=8jx(BC3REhVn3CTV{vtvK_wjD@b#7>+L0sah z#!9aoyHBc7W%c~ipbMdR*;=Vm?ZPIxEe;dJ&hgmrP{YU*A)LSOmeNMi^WC89Wt;Fs#xBmI8~0%e%Wk5O$R6oRCL+eNSnF=j*=wZC`g z{2m#w5}6+=Dy}&nX|Y6O;%B4hPE~pvJh6vaqBBPpveLZ1bNfu83SUChmw5)``@PuR`2fQJp^lAToQIR{V++m^B-xHyfiMRE^%*Z7~9|H>Cj`gp;=p70gVQ?4qZgB z0#H(=NyrjmWnfkI2Ck1RTP_p;*H{Q3tsX*gD~*^5ykuNI_t?s`2Cn#d;i7RqHs-D{ zHfhjVNuz$rEC_$m?>?>a==9xaz=RX*?h8eGNdEeeOg{FEAZCp_A8z380;jUSS`qyITt0~0}Mr|;Ae7TaJvzM zF)+q1)uMm|9<{0gtRvMZ(;uS4rKivBI&!KZ`%jve(m^-$dR&6Xfmo{Nv^(2d=H)31 z1P~(y44xR-5dA703e7DBvN)~0A`S)@X(mcnd+?P-uW4+QZC_@5T|}`P;t0DTbu>y> ze=6dQz#oi&M~FdDb+h42Hmif^EcUr%bI5<P!yBLLUo5&Q<&dx>XoXU z^MBTj3K2|;i3EJKT0qR4>7xQWenq^xhKAwj_n#1DfsJ5$lUrO*Ai< z(wGuYA;f_vT!g4x(xoy48JIi$t$?1=Qs^ZGaIWHqsFC~VowThfbYq0&vSW>LERD~9 zr?sE{0!wUSVq)y04Z}H%Aq(Ejp(|k1I+g~NWwN+7u#J~Fh;R{L!U>ZT$DHMEoeu06*rf}`T%qnad28<~p>lb!R-8CjWb8y=~PUALa`2G>F4WHpy8yUsG;!gQsx`pYyda7*8uQ43GH_Q0$4 zxSlcZV+^Jey&((Xly#a=SP`axqCs>>$PWp&*grP}eLdZ9U1CA`iasx!p`Ukg{Vs4X z_|6=8mfr%LOl zZ7@_!4ln$tks#R-cH_=oXDH#&)mrPaLao{fFqJ_y?<1dk&71DtZSut`-5sm1k1MZk zH9iAyY07N2h4lQB#B*Li{Y~0H9YYbM#w8ROfggiBQf4^i>TkV``-Rqj4zu(`N1CP# zE17A92qtIB!oIzxEKbBAIj(jk$4rqR;W}TZtepirQ!~X1fxK03$(qc*2!=xty{4^B ztWb~ncp280v0(wQ5(veMi^ zG$pvsQiz}OsL38JrF2_DWR|`wPtS(6MV5@-i@0+Y2YmUDwjlz8K7fn*;w&b<9XcsK zmLiyJENOTyeE&WoydVx>5vfbN>QRjKP-vQHOA`dYV6|&x*D`? zu8G}8Fy8}KBgjaGqNU0XYDzh4Ir2Wpzb{ZOL1Ij%FYRS9<{-dl(60sn1IX&p9>H&D zAuDmXY|Nb*2QC)gzMsrp#)$tNw~E5|%$KWcYG}Or;r)H$yo>KUb6=R6j4aGQ$$NI> zkO|o6+r7KYWMsQMq$%2=8BkZPp%7l}#D_Rx7d7TeM5SYTRxq{=kGt z;d|dlQv9F|i%8kxH93}CHjhXJAmW#RAu?x0JzKqQ$-+8qXlfZS;u`7MCeg8@Xo-yQs_-hwRje;vgFw`lvy8zy&xJ5k4gBMsg;~`-^PHeg zq4^ej9At=fjB&z7Ge6YW7J(1yrK`*cp{q*-m^JW5> zrc9Z}%mzyw`p!TG4y7UV=&(Mht-PVUcImEm;jZ?+nr3N^Kf>6gESn9z0zdeWB!1&ewOwW|qB<}R+tR9_Q!BnB|D zZ9`A8*N2`{a9=G8u>D8OuiQYZ21jl$VO zbkXo&21U*I`hsKCc@tS}Nm4hlAR4IA!ofy+98Z<8NF&oI1$}naR%1=4e^>9&gszhf{;@Svrtst4jE08E@Mi$IHB| zL#9m)@Mh-Vf-Ihvk=4tWxc~ZAGcf_}H7>9@q{pYO_dB0oK;LJ$XJv}%qerLs2(w~k zQmJY=$C1m*IQ6(#v{s|g^4*2*TX7-Ct}@*N*9^y-6uwy3Lb+u(6axs(cf3mE@L(nQ z%INjU1np6J^}?krH)Yjwe%Cr!&jL19SHF#`vEE-yGm!CLqhSV#LK42a+-0 zXEeo9emSigvkOF!FDxv`h?#+R5h7oY`#wA)1Y1bzbfar>dj_+|Jjo=G^3$m7(>VQ? z{kc!+>U?A^MJT!pQac_@z(O(`ToRWsUismd&mH)d$^T0at-X^}A#^(V>yqdeBFAuS zq)nIW({1){X4j02O*D|K`gS4Uz2VO#Kbhx9rHF?I53NemjE|se=dA1B%Z{%!;;|sx zgEX}@fR)o4dzb_RDnKtOxPfRg=qH&X?wLIB_>q%s3D`7=lr7X7nag~n7?fZX=V?iC zM(@=aH8nGhLi`!hS@_Ye^MU%=_uuQMdP@oqJ-X-kx4!9J7npJf2gS<9j$GUO>3^w9 z7TgrZGC0y#1aZh~SM3r5APDqNCtdHZq_SR}$sJIwD`5e@nw*RyaG%G;jKiWJb+LZt z6B|4Lh;ZBi2aioKRNS9TP|EilM|7m93TH0)M>~fuKt~;yTX&Q)sC%Ks$yc%NEm4h< zldNzcmma_{Ku3px62wD)C5;v17fOc9W&K2!i6LufvdJRnjj8xP?LcT~^&l6EA-?@s z%&G|g`=*Vtnh`gmA37IwMA!kisVu-38x1ilmL`Fv1Son1-%8~~tT8!xHty*H#rjbZ zbuH}*MJhRt_k^F>CZCRxtFZIPrPl}^a{zxO>N|XR?e7dEbD~0(EILf1$NJH*b!%Tk z99452@s)AbOcQavqs;j3khPD^(I=+A{tk+%CA``Lq2)<)xS<&k7JWe>HbMZf;=%_g z@@!$m9@`!ysj+pnXD@&H0{Tayoz*R32zmPF=2TXyD87+&J^-@j^v=t{KN$*(L#>Ua z&57*xLpfzj5}6ZNW5kfP=b@2uk%u@6j*)kf`t=LPX&{LQA}E;g`vl!@NxZ+5%zCWZ zN&6GtuDoqjy7u&WJvRskf)t1KxmcvW(P}eV+-8oMD2rX;rY?I>;tRLl=3h8PD_XQx zMVi&uCaHm+5aw6K5!})e98#TSJ9h zaeI47Dn|MYN=x|`?<{hHie?()p~N#U_mu7#DTnJN*5YF7S;NFn8{YLx2F!1|ht#Vt zU%Pk#h1&l2d46pQ0J{||G)DW6w2oelsc$%WY=P*`8mQ%I)v1dFgo#m4}7)qwj_q& zj34iFV$~uV=RY)R-4kPKJ~tLZQkKXu%gRyUIltgTqeC`u0R3;LpWV+}HUe@rDf?l%!OI`W z4Eu<(1ZCO#1j~;_w}J_rc#ePg9>RRk{cA6{*y^DL+t54gU%=0Zz2l^}7aEuwz1Hkx z{Rv;yKK4ib3Pa#A1M@R`-IE4JQ~>|2;PbGpacAqw9}~yM#q>*h3c^82MhjtWBJKL@ zxdCZ$$Ll3U@R%ojfA0C#{LAy`^`LOXLxxiuiLXZ!V+AdgUUwucztLuDv7!PTZsuv? z3cN%pzoh*9bgL@xm-}OJ?i;u#pvV3(GbHbHL%ry}-c z@6{wAlt*pz5q)i~cGN+j4c?q9O?(<<{)Z1%dTbU$f+YuRl?|HSp=5!AlR5Hjnkj#?SY~|TYlpH*XePB|CB2>q6egC2OUf=T4A!MQd=seru zVlu$4YpEHw*U&&fGKTMq`}|b+SqQ#o&A&Bi*rh0NhZ?3z@hX`?ELoKX^kiyTk;VlYZ{xTSXLl&2vS1M6aYT*Yt*R^|6@T

N9~)Yjb4>l5Q=fOMzX~x)91oFw{KOTd6iv82G~XQ@p%>cdCxlg%(?0W9I}_c z)gT4-PZ;?ne*L!Z)&xshWXwfSjFr{z<$JrP2^N?M317itquK8oxP#t3jR{%Jb~o17 z_sv@^DoVCX2{7o(!yhj_lYO#~|I=-A*_{T#w!%Q3S%ZS$I8>zNq;IXY)_=oS1(6Ok z#P?fRfyR84uJkPP7wXk|M#eNQQgpp6H8%DaOGPZP7p(?4zZ;CiBWjP!=PI+%_M13` zhT=89{7@R3Br>+OWzv->_-NPl%*o5k3+7x#eGC|=u6o*Oe5F@KAGU^wYPd*@~3^vUSMNRK1`qCnFF@(<@jOi%%0Ub(#dYd;%Y zv)1ek{D;D(&HG7Srb%jl`~b1Op_$1Kbcql0re3BbG3JH^~Kg&2V^z`iH%H)X~_NKi))bc{GszXQl~=h9t-o9Jq=l=IA+Hd$`CE|LfH^ zRtZ;2#|wf|G-uoH9o8vWqmn;v^Dr?ixNan20!wD^^J(!QMe~DJQ{@FG{!wre9TX-R z`q*^P^1RNYSdnHC-9lEc^`3y(FXLi8b8WoJ^UWF~F2v2O>!()kpj~r)y)<4(X|MvF zC`4z=s=7lAqEuUyx?kD+i@wg17)$1=X!Fm!m9?!6fgv5PWBN$N2@!Gjjj8&HqTWd( zJ~>Qa&l?EG=qU%y*+hd*?Ql_ExD;vs$By5PQas zot7F!?O9d3s9h^|%-X7?C`u4&*ND;B+k4vY@Bg~u%HfPz=k zrtGh&)RO`7830Cv%0ozN8fUejA6>uft;zPb62FhC5h*T`+R^0~kiq0UX#v#dD%b1= z*1Dj9wdOTpAiVlrxGeabf(^j4JOl`r9)M8MeBkMQq*N4lwz*u6*7}_?_W%v_`g~knzXvF#yPfjF%|sen!h{ZG|yC2lOTo_6K&*EPC`helXWEOyxw17cCVOG5x;g zZ3^`F&zirSzY+u5w5HBV-4+}<^eB7_G?x2H&Q~!(jP}QZDF%@y+?R`!Y>#Q{#?^SwI60Vq=Cc~;mO)=5XGD0SJy-#?5d}YgsJIG z*7xj3#+7%2yZ;o((d@r+0BM@tF0~MZ@`Ru?3|A zea}up5|h(JYzuxrBg5e~o?r8}|2Y*=%^o{`bJ$KfqESM8tVENRmUe=B9u(S1G3oYp z@N76ZN}jtf!trPT5~+JisV-a$iOsNy1x(cM_I2N4x{c!D^Zj4^-Iw-v0~9uce|21Q zvdO=$-!@gnyV*|RA{v#tR(H4k`YpRvvx(bHk_4u=VlH>-1e8-kPb$Km-2sP8B_l$g ziWyWIg{ly1SlhzH&aygi%)aN_jYXf`I^iq<$F1{4DUT^2g7nN?7<`p*uQ%6$ z)`3OpeXH)B--s95t-a|U*?gB0b(>~L9CB>qw=o{m9u%*1tX2!m3R-&=MCAVEkUo^7 zvnuEif4R*31xtTdSJzF;i*5#7|MgBH&a~suv^K$D9{DGw<8g!k1>W(m02=o;TuX&8 z`W$Z$%g8Td%$~4pRg?aNE7gOOb_pR6F7VvMdT7mCt0b+djrPs{soZ80Del=t^H`rK znL+STdKB}}O_wgFD2@Ywr776uI^Ue3I=T<`^mKegX}MD6-%W}tu*n5P@jcJg>uu@Q zD$&2#1tfWDEKmE@c?bI)T~d^)mG_GNSCJ0{w~nlWtAbXK|D4UW5)(La-oI6#(e{4c z=EW}ui12SO4;2&Lfx8dGeH*&HYI+02`dy`aY-*xxdYchMPudj`1!00>x;9KTU8js( zv*9O;Ey4gA)P?0q$D8Y8@q@0{e|p%+fg*3~OnUpeyKHX`r~>Baj|w=$-rYHR)_L}) zhr-kHE6bi7m97k#TJW}S^1Z#wgy!4D*1&$m@w+-B!(5B}Y!62zwF54hE&BnPM~Ig` z!f>K6NBoG7_y#03Jog&av2aQ%7PEPpkE;k35~y2ORqFgYE>k_N5FMT2nU+1_9KPYh z?+`(~10hbUf7j{rGRl`tj7K4aq% zx%2A6m;-*=fnI+ivk-m5FJkZKX(D04Rs_$o0%3eU-rDh>v>mG9U)Gi%40iG`R8Pm`{T!tuIFM&LO@gG zD;)bZNykZ_$e-c0`K}Vh%MC|*ll<#j%O9Lcfze~&;UFFls+6n~#+6OVh;*G2-{ZOCYLgh90!Nnbz(k2}u)o@Aqt9|?tXen3%`+bv zezm{dBkJ+;WyHoRtr85Fm2Hw+2O>Z#9BtJLMIw{zBPC7CMb+CTjG6kup@F6sB44Ch>@ z)cg`GT?8Hi0M&X4dBV=x6M?u8bMBip){CB3?F4wfXDbha&c<_>0P_OVo^2Fr_jXQH z)$9?9sk3$x>_8cDf=hf82gJc1$4s-4J@6V?lQ7dM5#LE*70~Y#kf7wf?(Z%0jr;0K zrAb(ZtoZh&S0$zbv`JX_s&kkR2 zWcI(H`B+hjSfUS5c4Q)RZSy^)MsP2!Jxqx0Ph?*{+QvLoQ1}Wo8vV0AYAa{?<(=m( zl{h}zFg##?GFi`KMvcV>v~_kZIi%iDD<~!@N~#*hxq^`<8;`4)zoT-qgS>}wd_zl^ zNZdXzaylRZs18{E^M@${8DAB+?Q*hd)WH=BOYDCrCr3-qpBldSBVsqP*PqKl-mKEl z_s;?+kTN2tplH1Ortu`~FRMoM6sQF3GtYOXwI8%5t$qDnt;|?NVV7|b$Q~Jq_SpTE zRnrwQbf)4L_PB*Yn4YvEm6U_bGa!J)c%W=RUQ0F_0PN_sQRod2uBhf+76Xc0VHi=n z^bZ_lR$;+T8C8?4HC+_?+HBko+>+Wf3=C^0sE!MP+2%l^+>>7Un@Uk3tXAuOe_WZ{ z`2I30FHY*gR9t*c7ez64v^g0IyG*5zp$Ll1>BBfJNe=}slCHlTOME;_kIGmV8n{No; z^PC0Ta{tNp{MGiPx}XIs)r`pCFPR?EF#iN=D^T{}i8`mw^XDExFB7H%A^@t?;-v}r zD}&B=O&_oK9XZ71Ikn}VC_-Uo9lL#KC`Z4 zd4M;~EOe|f1OPImt$v%ybD8vSQv!VcQd82CHRHhzg!Y;02ir^#f`^FMJ{u~M6+kP_ zpZt~qB-Iu5NRIs5-Sd-Q$L*1SLGV^N5#f!e$36atx1nfS88-yoR(P4r{xNOb0|`MGp{yIU9xGpNL;x` zOE^3-vKn@a_wNdw9|@5~av=vC6wi(SIuuE$<+P5A)%8|`64$NQel7fFW@c7E`+}JU zm!#DsYbGpXfD$oxT=VTd!Ril>4o^>IcXD&BLD@FV5SwNbwYL%N^{*9Lg2Fh6#WGl2 zweoK~ZjlYIO?K-%R&zQQA`PLPN=4oJz0XPZttmY9)?s^k1ZS9FRJ3<$IS--uZ%ilk zb~S);ZFS$){Enb3s$8%@>At=C&E9i47ILwSs0FkKi}jt~6&}DIeV}!FjjJVow`g40 z+$)7+S;hzwOai)UiIkb)mC9WsbXw>*b5#evzi8BJO6B|1hT7eF^KX|Qijt`yWy4%5 zcF+Hq5phxux!%ExfJWW@$x0NvdV_R2_bw{K{YgPmweQWs*8Cc(=i?AdmQao`tgOdJ zx~)aZx@lU(vMPNXyP{v{^_9$poGcJ9j^x@(XOYO{ zIa2WG-cPb&o&Rbe5jjBh4DaO7@?0ulud>l9Gry+Jtn$xNAL+&BTMEyhpoIN>Z!HmF zK!sVf`ZM(R_XA=cPxpa^c1ncauS<+Nk*X0f`WBKIa?R2wZErUQd+=20N<(3#+dI}|{!s--*6hIZ@ zAZ_D0SR1Q5f1;ny_5jFXVJH--nZ@mz#e)OdS39#^*_cM4)GD&Zi>l-4rllFa`5XQB zp>L^Z5W(qFR+)gg>wCJ#^L1H_P0lyi;dyS%gVi)rGC|VVa7vVrW?XvE0j~eyBgK9I zUPc_Hm*D{Upx!SQ%HQ;;PMYDSNV#F0vPdT7j?BfM00KBmjSiy9_;gbH#p z!C1eO_2on{ruh8o2Y`wYGGPFCL$7Sh_S@aX9C?4jamjF}Rv;Cdp#BHyp@XXTxLnuJ zGIuwAK^8XP8#dqwgkb=d177#8zS^>|vMvtE{KDg4f&fC0ucTzu5xQ{BNDiBoQy}Ef zTB$OB6lKG2P=hSBfg2nKO-`5G2C0?u_v?*Z0mK&>8QFblC7rC4toHVm99z%6oSfgD zfx$@xOP=1Hr7paly!br%VEO9aT$r^ZhH-FD^nJXU*mzv@NZ?VOhdIOeG#MXXiSm{t z86=H?aYmY)oP5Erd(KCWYE=V*f2&Ash(EhUJiEU(zr?M)3uL1_ap;Hn8MW4TD(foC z#U6&=4%nOvhv?my}R{;8YmcZvo#Qy(FDm3fa*#~xTPRTHp+e3yr0JY}<&j5^L96N*}N?gzHL zJQfDD=+10=d|yDq!q@npon`Q_ure&lP2?@&Ebm!{lU_TZ4Qe2Q9w@k#F#(SC9qtby z0W%R1+9M!W zU%>4Q#n7ktopELevQx|Nyx2h!3u+pd-eK5XLNbgxU?X`4_IAd*kf>-hw~d--QHh)y{;WZcSoN^8)S8vYBQr zgupZXpGtv8TX*pQQ-E3p^K}kw(KEUT?7j%!tqeq^sD&{(QSz?Puvk0_cFN4phg4cI zE;Tw^`R7FT*^oFiC`VBij8YbR-c)SjRru4XZbl+irXPV+MRAVLQxyuU8K5*W*9PaU?e0Y5UY!I)~)K3y3Fn^b81wg zQOf@=!`*BV$gc2uPmCUQOP!n3F$WOR8{-au9=Mq{t|@3F;M<F=@=n=4ZG;U{Nz+8> zW3FXqz2Hf002$1**D8ti35xcP>jb4?$h&fd=3Yf^A zBEvN%LaSSi`3g}tmdPUlAJdUS?MIMeRE1pFVHKq;%s&d}8#mw>h67}kT^#UwJ8%=2 zhG+(hmH6E!!dB1j(+S^a6GX@H;xoqgt)Jm=aI&qCC<4ClhEWKMesj#dT&I-P{5}1( zDJNY2`;kHlE+a#Q^Jv`yE&;nRW(j-3khm_sN57xB*8Z#rN@cpJQp1Z#V_M(#G(9$wI+64y^NrD7UE z^jH#G6(hBFs&L~p@K*r6%jkDeZCTS%kiv_ZFC@#y5rhzU$ zhu>4Q+S=Iuz^%N+NLzT}p#Z1hQ%>}8%EbHFA}t!ipp{Jr6Ru*@h1h|JfDz5_9&Dq?;3S|Uj1O)z+S(3ccFXF5_MFV6Vu{{)Ij5$p&B}5AX4anpk zoA3=TC-Nmb8mgiXL0A<^Wev85TNV7-@q(Pr@_I&Y<}*helw5BegGrJtdL*qWB5i1A zX(VDuCUK5GE3{Lkq7;6%ui3UkI_tGgau~p7Wp&MFmDOH<%kiv3YTV?)#T5r>zdY^# z^xbQ+1?1#2TF7m(+6b*A*z`v*Fniu|^$*7RlA&rBPTM~&3PBn*p#&DqUdF`_)C8$) ztyUkV4;OdC9NT6*T!?RQIwDxaB;Hre^5!#2UcEk$rJQ`7u&gRZF_!a`xnn=aAI(}> zn{PMa{$$i0P;)NdY@#JT_S6=4b7A+W8PXX3$Svyla+ILh5`iKS(0iqj)vd?QyxqFS z!{2tFxXx?HD^-fomH1$@75h}iUrIkK z?Z9%m=<*riW9iG@#HJ8q@x1ysN*oUQ zas6l0FCPh1eqT$0>m_gyi)Kapmf9R?QfZ>$tWF`UUkN)_bzb;k0!n_?^35H8c+6A5 zkPIiC#L8IU4$1m}NDZ>Dfq=!bBf(V0ec|MU5YX|WOws8PsZcfgC}-o#Qv8G_jaC1A zdBHP2dxPW8*WK?&-=&?g?(iZI}f4lagrjFg`g0tMxR9})X?>`#_POh1cJ3tpGx z*MDg#74x$mDMl)|IL5;yQ7jTLSddQMPN7I_6@ef3*ibSg3PU-l{z<&VXydJD6w@PT zRR!Wn?0fqyXY-6}zYbs*&~@3)=^iLY4O*y`A*xLid&-it+fy6hbV{q5|AIC^da^ny z;g(d_Cw%=Fnh2-P{YpoJ>HP~wRiP`E2}k4m%u~2Mj$&nUuJX1{vV3t*Pfx0hf|8W* z`c?kb!m@Wo<1JNN`_E0Qu$Ux4?%SNa0@z1RtQ*m5g<(%nwW9C2FMAe6nMkw+s`%C8 z9;j7>K)aBz2Otue>ulCoW()_7i8}2}2)%6Sv6f8!;FK9$tCb{C`XDy=kaoLEJtwbsF6HfpPs`{) z^qP#jY}H3-N~t&(#9U11>Jdt>Jnoj!gt+NpI;?4k_f0?1iGjxDm*M!L90s{~4K9G5Ay(s?9@Lu<7 zOOB?0Q_kC48c_x$1N_a5gNhu~g2N-jR(MT8muC^8X-3Gp!C>-ov^WM^46}WcU7yXc zI$Y9ytAZ$P_H*E_UyjG!xCT0HZy{MJ{qSEjWw?;&S7g`WL=l$A6 zcY31KtGab>P8_&85$;r>-qMjgw?4Q?DgWer(HpK`(?P2hp)fo=EXtNxFuKJL&Ho%= z(BSH5!aGALvKf=^H&1bBIkd$fpE$MNP7O-=^V#Op&6-_8n^m5m5rXlsqQQ5wBZ-%O zIgT18HR|@WWy&A2!tj{BcEEzY_DOmuBSeY^+MAj>Js!rX&X&!ml;x|8@BKVDA6NZT zVG>chnbibO7MjELa%fbaGV~Gctp-_aF|W7>NQ8Ot>?VC&G$1h>yd}07_02YFH?EdU z(mIUOf@-{wbjrT{;xj?<9&1Ei-14hhdMfcjeUs@y0e!IQ1i!K&tCCwo~?stsqwU`lIlm0$`w+eK=9t-oprV)~IN=^dTw zcD`M|tY^)}{AX3!7@p^>8X7N)?=;L&(p%I!X0qGsqi$8wwvob7BLvX&#~4G5H-FgmpLG2wk1%oy{*ZUm zV2To&?f5O4v|G3S7HfZ3XYIl>7lj^535Q5Ljt-2{{q~X6QdMhqC9C$mJIDDD?{?Y@ z+sg;syuHwifmr(M$yeGj6A>38-7fcjb^h#PIgB4Q&nZhKRsJ?n_#qhFw^{a$D?bjB z!VBqTw#~{`T?9!pkuNqOMBN*;oN9M^;H)o{)Z89V5#MvhAQ{EPgtWfe`sPGs6n*cn z?0VdrheLBu0bw+nyIN>bGDvawqHa?>3k%D_!UD(PG6M9`TAcv#IfUJk{Yk%L)?hOE z9+Qa^cOMj#oB{3Jx5`M3dP>I(-;<+2EO#5rCb?Jx+iz0{#_O#p)Y`}}7O@#2B2UtV zEaO_bAhB#>bso?@?(bERqE?+qqIBRce`cgu*x0%~Ki&^g8k@_HiJD0LQ5sttzbn3^ zGTCUW68D{|DR92ut2vCbGOyc%(wOyR@2Z29fCo^# z(z-qU@}3o;n3!Btu~%a3Cl@g};joAhk0Gi%Q=*wWCcVyCRyB}?tt~+?$MY7ld$*!| zn@ja`e4>rCK@fN)qHI#d=`9bsid_w^!^p)X`hu0i`o&tOXYUqlw2`lY+m6G_R$7&X zW}KFl0nScHpqbilwQW&UVRwTj#JV$XE;3&6LG8I$%PVM6MMW#%JQ5<~Q7F_mWzkBx z)o2Lx)_B_<*y!h2Qn8j_Y+7A@?Qz-37{bNHIO(M%)8cmHJdiJFtI6>^+#)OC<9pcA z)aeT9Q*P--e58{@$KM9#1 zY`|NTt9zzGV(pSwM*GtM+3AiZfT>pxsB`#i8fDArSkTcos?Wz-xr7JR(HqR73*4e; zM7a8Wt&$0a(O^hE!pN{ONiFTWgBhj%>I1jt_&5+LCl_h09KPnyhrZCqI%a9Kb<_ke z2bKlX1mprvD1nT2!e(6Cm8Rk8XYQHF2kxM=C+12@3GepmL8R6uJnupL!CPOmxvs>F z;+-@zKLOS_3p;xc+`KL5*p1foYf6Y($`2r4Z8nnZ2EqbuK?pv~Ac=)R)!_n3w-bnM z0}(wvJ>QK;)#io9;cH9(j?IBl;mALjBq&~s zk^zCLuQ`c5E@+RnBN&jjNMX^YTS_HGdoB_wn4x2t$b%LLI447ziv-fslhoVT_=i)W z#(PYYP(L{)Yrv(O9LlO*iSsVg>SgA_1*{oMerT>5fIFS@qS4K}+PTIVhfaR3&YlgU zRuW{uE-9*Io!cf6)>aQ$mKLnI9v!>n>1CYwN9!2hugp_6HYAhPZhbvG7^SN_X!BPYF8E3%UdYe%A8xvg7Y>t6t%KULh0W z^y|RaZ5n?4L2)vP+Aa9q=6Xw39!Oq^Bg_yDx2*ZC??(~(II0HW@v26UCi(5a>rXt= z=ZLf6Qsc&-xcABywSv%;%6jn>!<@m31jXdq&@%E6f#-!o&Q*oc&;1CbjnCIu>&l{1 zkUEz+TD<96yiNYc!ol#z&Jz}1EPS_hzPzVN`TS|?*;Hcd{Zi@F<+3g=BGklfz#9;b zDN6to_#Wvt-60ngQ^~x)!-d2IDD?d4POyK)OdiR6__^9+w*JFBOL|Of_XbqLB4VPZ z?;a`E{cRcF;D;jq{5Sek^8rvOBQzW4e#&ho1LbMR&;^}OSjv!gtE>{qc^ZuLs z_L1%jkOss~@bW`!R}qI>#^+5U=tSYL0Pn5aAx45t0e54R!#@Ia&EwZWCBl%e^SPB`g?L!@$+-RPXySA3zO8CqTf?ZwK^ zCZ%}aV9(gE&80iwig+ywEMS31-_?u&r16OSw!0(~R2m{Ku>WDTqAj)b-FT3LRDLqb zFT0FCevN-b5B*5@_mtD>LrpCWjNxxg-qDNsc;C0+Xa#->=b!Szkm!U=kteoaAZ_XC zeYtV4;^OQ`YgGy3%wkGnLgdH1AGHfa3M>w{M!XBw8g?8>j0hMBBarE*-++vbis%c3 z`M{c~8eaSxfn=v;E{!%S=IiXq&Y{;1F`v0zQ%}G0qWkt)EYps^09|s`|*Sl!U)0d zwgOrkS>L%KmPcq1MYT)!O7)Oom4_Br->sU>SwU}Wdv|m{daKj6gUZ;R?$@p^MDMH} zl#_clJHA=XK@0?>DenZ}MQ!HggE-s)cf}Z6JNCgGQ7h~oIEn;qyx+*GN4HW(3=$9d zZC^>B--9Iw=+G|D^b>2Qrss#=wG=LUJSfOe^z=OYNKquW!QCWY2jbN{_@r^L&gpEd zUab2a@{5+kr_J43%=mC_N@KoD>CC8`{)!-Xz@*T*HVQH)ZvOjHgj@Z?CF;?W8D#x6 zct>T@%XqXd;bEDk<2M0rFe+FFU!a@?DvxPft7xr|dY}*Q(1$*v28U<2tbQK2&UYzK zM&93bI+ohaSd9(_g;lh{;A7JA7Bh#1LJpNEQ_K3wDDmuZ-t3j)8y|*;eY1xTr5_=U zvE^+dP93p>@E3uVH;tf4pKaJ<6p4W7q96r#xhkE5DE;}^ei$?#ODqzc!fl2M_eWGe z12VRps#{>|F83}bV$Jyh-#DCIXpc+e-`Gt&bAMA%KpYUW(OS{!BarP83%(QE+wiE$ z2Y=Xi2e;cwov>_i1IOrr^EWKfPC{BvBI^U_iw4fk9hzM;^Dmc`1E(*23M-R?O#3Um zuMlDR;v*gm!!?PL)YW5?GIyySWbrn)-)C1t>mFue6YM6yhpoCr@Bmd5TY+95-!U3UZ&UpIAc8Gh9mRo~L-_xIX5~wQiG0Kl(m6 zsjuc#KAElEh?dp)wOhYhi`mpeZtFElm?C@1mmx5pCb+&)6Tivi;SO!3KntQ?DTXUn z6$;JLVqis!hCvPQkw>4nJEhj+DCzK|kp#Xxlg^nbT)JjD@cJiZ7gbrj+a^9FX4>eK zIg6t&KeG|rw)K8(3YM=hu+?%cCw$FO)o(G^h&mmiG}ujWv!r=^QA_qQ|M@HJ6!jNO z;3v)~Y2R|mI4to)=%8xyT4lkg$@&m&la)SeA3s3=GzhyMhowiw zjHP_}TECiqsD>GfQe%E$wAp%e*Q8O#rqJ?dB@bM(g?->{T?Z`Sd81ziFM7_d!@S6l^0-Y$c``Q3bru>Q+`yymnk=nA z3A;b0&A%jl4D-L{KQE33!DOi637hpP{q_Ff`q@-y&hUPrkdZN(utjYcDFmIFGE}qD zIL~g>e$~Q{8A~m%5NII+I~L#|6V9p*1s#KDZPGfEpaz9gw-2n88YmUaxjjrDTesPo z4+DSZ_W-lr6RHbh_-rFP3D2z9(@o`t^16Q+zET|rDW1YU^QTT;2KA+7{oK{=EfimK z1HGF>`WERoZRWH6toh=aS>}ZK4$$A*m9yH*F7e&gnH(d_wWO``oktCV)wMs2{kFYS zxCf*a@SN7S{;WHDtp6$*2*N1$OYA=Texs!>y&Utx33Vpo9yq-X8U?e>R6{nDe-7q5 z-yH=H1LoxC+Apq5bM^9GP4P+N^=p~-@r73g4qBIRn5W6=L(rbSj0gseRq&!3bK88!63k##$~(MuarMsimG^~_J(k)dv-kxCXiLU zb5x8*V5irq1u!kc{Fw4$3{U-Sh+jQCvzA*C_oBxxXC|n+)x@JLLAb&10)Z$X2jx_` zCFvVwj88;ujpKY^=!WO!NKQccpQcSCR6Mo@!wciRFvsG?s?4c9;A0Uc5+ST%8jnrs z{=LfEdkJ%2cO_qZ9>&!sfS&}Hd4J4rqbnMjDRDF%Re;W9w+MD%YqyaO7v`v1az}pR zjasC@z80L^RjLM}$yPGhQn72vN>x7CuGU}SKije~DA)*(V15UI6H2|C7@tMBnJ7FR1mtXcRQxQXTSc77i@w?5^ zw1cr)uWP3I@xD+NGL9pcCm&7cvZS2rR&(FoG{t*D{u(Lta&JeI+39>G#;D#5>@x;i zEZJ{NSOp!oI${t?__35@cVSW5Fw@&F{p3D95}-3r4KO!|(%$uEUNV{s^l?SQhhXpQ zjdhC)iuTMJfzhxoPldZS8#nsQIt6GN-{}7=P-a@y|(k z?o3l8>~{Mj3FS*{@z6IW$TXjv)@t~9Tlq;-jh_LgN37>aV<`Ru9#GhLd{M$%vn=umTB7s zoJS|6`Ij&f>qS+e!c6cS3^ScL{?lfqROhk}cVJ3CK zV+~2|F^|V07!B1vI$@cAq*@tEXOmltJe?yi5f&?RHkmVIgGDI*2(&CK-W^-|0>kN| zn`i33^6$60&G2IPgRl@`?|GE#{H^;|RLaB~cWA3y7&3qvte;<2a8Io?cS5D?P%Gsy zqf$`+nBNXEaeQS42oXv|fQ=AwuwS|P^)O=Pz?PjBprTKjj%&v2$=HKJyCQcCbx|yK zmn$&M3Es+Z^mM%}D;I#J#d)RzUOFki^xV_{SgL()H=J*!?k{(}E5QBPfU4RD{-f24 z0n5c6SlvENC-a!~bQq*#imN>H$lcs2!1}`ao5n^xi>w+Hd*@dbNbKN)P7IUA@Wzb< z+X;iu`N05Tgt;au+Xf_S`tza)%z`9MH5?!vciD&_4!~~%9`La1ItYt)8mHHqEF=5iZYb8 z*=6R(l8u(OLulhJHElI;!-E85Uz7q%iO9q*81;lXd%o!#_@@T!eJ-r!$6;5DJtp;o zc}~ZOvYFSsw9U%Kps8tZVm58P42qsgzK#vfRs0R-hpMsa8Vy z1Hf|}L(i3bmvV~@iKD$R86##txe<^np}?U6kXlAG&ak*Q^Z4P7AP4`A#i!sohfXG_mA)R^(- z;on^$Jg}^MNHX?I%o5$>f5VPAwPwzwkY|E|aw~H(&5YOw292gKkg)KH2DKkZAy|tr zpLv^mEB~g?VI{VwG4HADRMFi9pEb)@a@7i>kzUP->(wl-s5>=-Vm>Q*1Asg8lH@id zj8ggah%mhO%&_uENU=3YyVdG+yl}rm8}%7s`;kX28b-{ENx&j0)@FXoVje&Fu`gWN z=#%3=Kb0mvO$P%sCgu#;{%^E9|Bd!E%^uh4Xr3ovd2ThD@>1U1O#c_IjwvCK(5_AG~F0XcI z`sh&qNcjeK$mR8`^2+`9069$ywFRQ3A3*}W!bkmt&b_pa(bJNF6A=Z7y*VOJCx*FO zsNW@3tL-9wo0)3B%gx!Wz@Y1Y zLr*_wslPWB>Ft_Tk?^bCthFUUx>8_l7`=McVygrj|Ke&i2+XQ+_f!+*o)d1DS)`Q; zNttzEcJqM|I|RneP4KiDrXHstml|LyTh1-++5WYpyCyXM8~f;K=isAVVIQ;B;*n$C zjNCRtyDU#Ma@BC^2zPeWHoliiPxQI!^cR|h^F2BhS+T58_{G6**CK7w7#95;bNicx z&v2kX$GvQ6`$1Rz51Sxuxw&?o97=P(f5N6!HEqWw&?^O7=R5vtY-#WFJWx)uj&Xdr zS^Ihn{PN5zPI|-tYH#n0d$&Q7z&v6M?%>T3E)lAi|Jh{c{QOhvcWm6PiAG8AnADsD z`qN(#W4AVCFIcPq&H~?{b(kwLcRbj+jj3;M=Es#EX@8oIbcwRmH0j)vJehkiBHTAV z^ZWF88{?7UBu?YNywON!kbT4OtCU_R7f?8ba>Y#S@+UcvP+1O#W=~3)`ykI0mgfWZF$tKD#!x?? z@xSHue)%O+vrck=G`JOu){NPBMmqytbY=h6A`>w3RDX(uH?ZiAXCp=TDDrro@4t_j zo;@_R9>@M@uuSbUGMP;mB#q`j_GH*SM~sGJ7o~H!QA029pY8l_ z84N1C3*Pb0p|i-$ax^;K?eX*>acDhodxigxc#X&n1Gn{f6Q2G;w#_@O3{f-Ai8VJ zCd0Rd0!X^8w(^C33~~MJD_?dEOY4&KtsAhkae#ckCibO!ZRq|bOyzqO)C1B@&IrGN zkrtkzLm3qK;mBp=2<*I?Tk|Nx+(*JyU_Jm{m-kQQ_F6S)Acv&QXOYHNjXWz<)R8#* z13hVVy~!Z>uv+Z{iB@NmOu4j+w!0tbFhNy5x&CQ_JxBjZM}(X){p|{_0pv9DQ{npf zxvrEt6K5e4)V>8ulywk~xY6Hed~|9-r}9_i6AxHf+Kb&gS7RTvWZ(PoyCEebj03gw zY52?Ht8jz7Z*vj@$VyA%QSG$4{p~WB<@SI2hq#ouTxW~{X-?l57^Ig|KWt$kS5fcd zhI=2R3fITMZITUe{b&!IytCaY7>V^r2+LtK_IJyh*6>y8tA{xaWt)i`P;`bF3~ z?Xx|%1Et59|JZ=j|8Yvhi|LH2y_?9k%i5#FU46Ch`Wt1pgK?MR2`_$n4#$e=9ks6j zN?t%)^s66tp~6-@^_YU%;SP9YMB%R&1XzfLe3CU~7(gef_6Lw6LBrkKZQHUZ%aUV`#FcK$^II(VeeRZE4yZoPmIADu{9}e zlNE5>W!+IJHA=t_QGb_r+)TYTCw_)+*UaxYZ}^Kq3$m=={dF92LqBKpcM-~ET|6=H zwKQn`>=X$fNuIB6b9eO0t#@~s^i1xb=cz?_GgLv*pKbwGI;HZr951@LgTb#XPm8f$ z9V^}gAd3kfC#U@chWQe$nf%M8>*UjD{g>um{(B~wY#FTi;Ip)b=c90*#3ZCyL^(Zn zgWud`{-62-)Ru!CJak|uuRy}s$PP7A;s)ZF^WugD&K$KZ(~&3|@5sY%_R8V-w$JK@ zbNO_C&lPZuatl0%4l3y@A#a0wGeCY7UKH>g&3<{I)-OVf>t!T*;Dx|x;eYltrScJ@ z^dT{4%L9S32KbJ2B@fBKTc~5}e>_G!tzXvSL^Z}kOAB}sd_(b>^Of6O96P|W5Oey6 z-sVDl^FnhKQdHAu5KpT?(%k-|ci^0ACWu^?d!9LE2IYSbPeA#F zs0(nkQuc1u@OemC2O08zlr|;=Ey?2phCfOvLDTkuG}uT(IJ5#0?w40Z` zLd=K2$(JFuhbdlnSAvIjx*7kw#XYWH)rlj95Z);v;L(rq)!P5!X(bW*>v#Z`weY}K z#XbRGCV}_vj)+-U*6hp#{*U^VEjUqUF~BT0Xq*mdg{qEdO#XVUz^u%cxM#MA|D7=w zt9;nHbM-&ATZz%<{p>#p0Lr5QH`$i?-y=ah^otMVaVyQpD%%1IS67_%O58qk zDHIvs8lMZi{!a~1D(ek+v3}pQ@>t0NM%R6=rANRs&{F6+*L~)2ZB6-?3&SYiKQ(ks zI(f2j8%r`VTU6AA;bTGrWqX0POZTe`nH1CMfr?z&jCw4IwtCxZ7z4TuHL1NQeI z2E55iKSO-5b8X9O%@ox6pGZ0XE;(_jYSP2L->Xb5#9&*79iuEiEfe8X*|cZL(8Kh# zh?JMZ6_-nXPaoOKv8%0>EjfQo>##ek^%I=o^P9u1QSrHVRA7hwEx@x43%fvCzULnX zXZW5PkMe7#m%c^_hLpv1zHfM*;$1`{0^K(Y2c1jNIr*$LXa)3$+dxL8kPiZq%Kvk| z0UBa5&PK|iLd5CW)ePC-$kn1zp-&%%Y?-^Y$ItZ-%^rJ~w}FmT*BT7u9l)byTmECb zP(imr$m@xLH*?quuGi4)as=Zkmp29D5hp&95H`|N&RI0fhVf0j@fWqy1aYhSGdZ7N-9ZEtjor(f+i>bo(5jXqyj2fW9h zVXC&ilx`vo@3nl0pVL3e0mEIM6(F*Vr!O~&HQ-g@^+amY%4dC6n7craaexrdRkDqL z3>Ks6Vg{&{2S3Va3O-;S;d3vpEQD$Yu)}BTy`j-kPIcZXRFFOU3x4hxslZ~VPykXm zK7}r;EJ_zHn6Vk-N-KJ%mNxQsB3%@|HnQ5So(E*^ETPv3I3ZUz%Kvy*#7-%%;ie4 z%kEm2Ytx<%4-ZcV3VCX;t&PVI924W+#Am|01svf6zY6%w|NmGW|2`hUzyIIB!@EKA jzvI7G{r95*y#4*_-@E$&H&9WEhxb%XM-`!L75e`Gt=s2U literal 0 HcmV?d00001 diff --git a/src/rtde/data_package.cpp b/src/rtde/data_package.cpp index bb3ba6799..efa5b6699 100644 --- a/src/rtde/data_package.cpp +++ b/src/rtde/data_package.cpp @@ -42,9 +42,8 @@ std::unordered_map DataPackage::g_ { "target_moment", vector6d_t() }, { "actual_q", vector6d_t() }, { "actual_qd", vector6d_t() }, - { "actual_qdd", vector6d_t() }, { "actual_current", vector6d_t() }, - { "actual_moment", vector6d_t() }, + { "actual_current_window", vector6d_t() }, { "joint_control_output", vector6d_t() }, { "actual_TCP_pose", vector6d_t() }, { "actual_TCP_speed", vector6d_t() }, @@ -57,6 +56,7 @@ std::unordered_map DataPackage::g_ { "robot_mode", int32_t() }, { "joint_mode", vector6int32_t() }, { "safety_mode", int32_t() }, + { "safety_status", int32_t() }, { "actual_tool_accelerometer", vector3d_t() }, { "speed_scaling", double() }, { "target_speed_fraction", double() }, @@ -88,7 +88,7 @@ std::unordered_map DataPackage::g_ { "tool_output_voltage", int32_t() }, { "tool_output_current", double() }, { "tool_temperature", double() }, - { "tool_force_scalar", double() }, + { "tcp_force_scalar", double() }, { "output_bit_registers0_to_31", uint32_t() }, { "output_bit_registers32_to_63", uint32_t() }, { "output_bit_register_0", bool() }, @@ -548,7 +548,18 @@ std::unordered_map DataPackage::g_ { "configurable_digital_output_mask", uint8_t() }, { "configurable_digital_output", uint8_t() }, { "tool_digital_output_mask", uint8_t() }, + { "tool_output_mode", uint8_t() }, + { "tool_digital_output0_mode", uint8_t() }, + { "tool_digital_output1_mode", uint8_t() }, { "tool_digital_output", uint8_t() }, + { "payload", double() }, + { "payload_cog", vector3d_t() }, + { "payload_inertia", vector6d_t() }, + { "script_control_line", uint32_t() }, + { "ft_raw_wrench", vector6d_t() }, + { "joint_position_deviation_ratio", double() }, + { "collision_detection_ratio", double() }, + { "time_scale_source", int32_t() }, { "standard_analog_output_mask", uint8_t() }, { "standard_analog_output_type", uint8_t() }, { "standard_analog_output_0", double() }, diff --git a/src/rtde/rtde_client.cpp b/src/rtde/rtde_client.cpp index 404276db5..f31587988 100644 --- a/src/rtde/rtde_client.cpp +++ b/src/rtde/rtde_client.cpp @@ -254,7 +254,7 @@ void RTDEClient::setupOutputs(const uint16_t protocol_version) unsigned int num_retries = 0; size_t size; size_t written; - uint8_t buffer[4096]; + uint8_t buffer[8192]; URCL_LOG_INFO("Setting up RTDE communication with frequency %f", target_frequency_); if (protocol_version == 2) { diff --git a/tests/test_rtde_client.cpp b/tests/test_rtde_client.cpp index b52c44116..8158dac9d 100644 --- a/tests/test_rtde_client.cpp +++ b/tests/test_rtde_client.cpp @@ -26,16 +26,371 @@ */ //---------------------------------------------------------------------- +#include #include +#include #include +#include +#include +#include #include "ur_client_library/exceptions.h" #include +#include using namespace urcl; std::string ROBOT_IP = "192.168.56.101"; +// Based on https://www.universal-robots.com/articles/ur/interface-communication/real-time-data-exchange-rtde-guide/ +using MinCbSeriesVersion = std::optional; +using MinESeriesVersion = std::optional; +using OutputNamesWithCompatibility = std::unordered_map>; +const OutputNamesWithCompatibility EXHAUSTIVE_OUTPUTS_WITH_COMPATIBILITY = { + { "timestamp", { std::nullopt, std::nullopt } }, + { "target_q", { std::nullopt, std::nullopt } }, + { "target_qd", { std::nullopt, std::nullopt } }, + { "target_qdd", { std::nullopt, std::nullopt } }, + { "target_current", { std::nullopt, std::nullopt } }, + { "target_moment", { std::nullopt, std::nullopt } }, + { "actual_q", { std::nullopt, std::nullopt } }, + { "actual_qd", { std::nullopt, std::nullopt } }, + { "actual_current", { std::nullopt, std::nullopt } }, + { "actual_current_window", { std::nullopt, std::nullopt } }, + { "joint_control_output", { std::nullopt, std::nullopt } }, + { "actual_TCP_pose", { std::nullopt, std::nullopt } }, + { "actual_TCP_speed", { std::nullopt, std::nullopt } }, + { "actual_TCP_force", { std::nullopt, std::nullopt } }, + { "target_TCP_pose", { std::nullopt, std::nullopt } }, + { "target_TCP_speed", { std::nullopt, std::nullopt } }, + { "actual_digital_input_bits", { std::nullopt, std::nullopt } }, + { "joint_temperatures", { std::nullopt, std::nullopt } }, + { "actual_execution_time", { std::nullopt, std::nullopt } }, + { "robot_mode", { std::nullopt, std::nullopt } }, + { "joint_mode", { std::nullopt, std::nullopt } }, + { "safety_mode", { std::nullopt, std::nullopt } }, + { "safety_status", { "3.10.0", "5.4.0" } }, + { "actual_tool_accelerometer", { std::nullopt, std::nullopt } }, + { "speed_scaling", { std::nullopt, std::nullopt } }, + { "target_speed_fraction", { std::nullopt, std::nullopt } }, + { "actual_momentum", { std::nullopt, std::nullopt } }, + { "actual_main_voltage", { std::nullopt, std::nullopt } }, + { "actual_robot_voltage", { std::nullopt, std::nullopt } }, + { "actual_robot_current", { std::nullopt, std::nullopt } }, + { "actual_joint_voltage", { std::nullopt, std::nullopt } }, + { "actual_digital_output_bits", { std::nullopt, std::nullopt } }, + { "runtime_state", { std::nullopt, std::nullopt } }, + { "elbow_position", { "3.5.0", "5.0.0" } }, + { "elbow_velocity", { "3.5.0", "5.0.0" } }, + { "robot_status_bits", { std::nullopt, std::nullopt } }, + { "safety_status_bits", { std::nullopt, std::nullopt } }, + { "analog_io_types", { std::nullopt, std::nullopt } }, + { "standard_analog_input0", { std::nullopt, std::nullopt } }, + { "standard_analog_input1", { std::nullopt, std::nullopt } }, + { "standard_analog_output0", { std::nullopt, std::nullopt } }, + { "standard_analog_output1", { std::nullopt, std::nullopt } }, + { "io_current", { std::nullopt, std::nullopt } }, + { "euromap67_input_bits", { std::nullopt, std::nullopt } }, + { "euromap67_output_bits", { std::nullopt, std::nullopt } }, + { "euromap67_24V_voltage", { std::nullopt, std::nullopt } }, + { "euromap67_24V_current", { std::nullopt, std::nullopt } }, + { "tool_mode", { std::nullopt, std::nullopt } }, + { "tool_analog_input_types", { std::nullopt, std::nullopt } }, + { "tool_analog_input0", { std::nullopt, std::nullopt } }, + { "tool_analog_input1", { std::nullopt, std::nullopt } }, + { "tool_output_voltage", { std::nullopt, std::nullopt } }, + { "tool_output_current", { std::nullopt, std::nullopt } }, + { "tool_temperature", { std::nullopt, std::nullopt } }, + { "tcp_force_scalar", { std::nullopt, std::nullopt } }, + { "output_bit_registers0_to_31", { std::nullopt, std::nullopt } }, + { "output_bit_registers32_to_63", { std::nullopt, std::nullopt } }, + { "output_bit_register_64", { "3.9.0", "5.3.0" } }, + { "output_bit_register_65", { "3.9.0", "5.3.0" } }, + { "output_bit_register_66", { "3.9.0", "5.3.0" } }, + { "output_bit_register_67", { "3.9.0", "5.3.0" } }, + { "output_bit_register_68", { "3.9.0", "5.3.0" } }, + { "output_bit_register_69", { "3.9.0", "5.3.0" } }, + { "output_bit_register_70", { "3.9.0", "5.3.0" } }, + { "output_bit_register_71", { "3.9.0", "5.3.0" } }, + { "output_bit_register_72", { "3.9.0", "5.3.0" } }, + { "output_bit_register_73", { "3.9.0", "5.3.0" } }, + { "output_bit_register_74", { "3.9.0", "5.3.0" } }, + { "output_bit_register_75", { "3.9.0", "5.3.0" } }, + { "output_bit_register_76", { "3.9.0", "5.3.0" } }, + { "output_bit_register_77", { "3.9.0", "5.3.0" } }, + { "output_bit_register_78", { "3.9.0", "5.3.0" } }, + { "output_bit_register_79", { "3.9.0", "5.3.0" } }, + { "output_bit_register_80", { "3.9.0", "5.3.0" } }, + { "output_bit_register_81", { "3.9.0", "5.3.0" } }, + { "output_bit_register_82", { "3.9.0", "5.3.0" } }, + { "output_bit_register_83", { "3.9.0", "5.3.0" } }, + { "output_bit_register_84", { "3.9.0", "5.3.0" } }, + { "output_bit_register_85", { "3.9.0", "5.3.0" } }, + { "output_bit_register_86", { "3.9.0", "5.3.0" } }, + { "output_bit_register_87", { "3.9.0", "5.3.0" } }, + { "output_bit_register_88", { "3.9.0", "5.3.0" } }, + { "output_bit_register_89", { "3.9.0", "5.3.0" } }, + { "output_bit_register_90", { "3.9.0", "5.3.0" } }, + { "output_bit_register_91", { "3.9.0", "5.3.0" } }, + { "output_bit_register_92", { "3.9.0", "5.3.0" } }, + { "output_bit_register_93", { "3.9.0", "5.3.0" } }, + { "output_bit_register_94", { "3.9.0", "5.3.0" } }, + { "output_bit_register_95", { "3.9.0", "5.3.0" } }, + { "output_bit_register_96", { "3.9.0", "5.3.0" } }, + { "output_bit_register_97", { "3.9.0", "5.3.0" } }, + { "output_bit_register_98", { "3.9.0", "5.3.0" } }, + { "output_bit_register_99", { "3.9.0", "5.3.0" } }, + { "output_bit_register_100", { "3.9.0", "5.3.0" } }, + { "output_bit_register_101", { "3.9.0", "5.3.0" } }, + { "output_bit_register_102", { "3.9.0", "5.3.0" } }, + { "output_bit_register_103", { "3.9.0", "5.3.0" } }, + { "output_bit_register_104", { "3.9.0", "5.3.0" } }, + { "output_bit_register_105", { "3.9.0", "5.3.0" } }, + { "output_bit_register_106", { "3.9.0", "5.3.0" } }, + { "output_bit_register_107", { "3.9.0", "5.3.0" } }, + { "output_bit_register_108", { "3.9.0", "5.3.0" } }, + { "output_bit_register_109", { "3.9.0", "5.3.0" } }, + { "output_bit_register_110", { "3.9.0", "5.3.0" } }, + { "output_bit_register_111", { "3.9.0", "5.3.0" } }, + { "output_bit_register_112", { "3.9.0", "5.3.0" } }, + { "output_bit_register_113", { "3.9.0", "5.3.0" } }, + { "output_bit_register_114", { "3.9.0", "5.3.0" } }, + { "output_bit_register_115", { "3.9.0", "5.3.0" } }, + { "output_bit_register_116", { "3.9.0", "5.3.0" } }, + { "output_bit_register_117", { "3.9.0", "5.3.0" } }, + { "output_bit_register_118", { "3.9.0", "5.3.0" } }, + { "output_bit_register_119", { "3.9.0", "5.3.0" } }, + { "output_bit_register_120", { "3.9.0", "5.3.0" } }, + { "output_bit_register_121", { "3.9.0", "5.3.0" } }, + { "output_bit_register_122", { "3.9.0", "5.3.0" } }, + { "output_bit_register_123", { "3.9.0", "5.3.0" } }, + { "output_bit_register_124", { "3.9.0", "5.3.0" } }, + { "output_bit_register_125", { "3.9.0", "5.3.0" } }, + { "output_bit_register_126", { "3.9.0", "5.3.0" } }, + { "output_bit_register_127", { "3.9.0", "5.3.0" } }, + { "output_int_register_0", { "3.4.0", std::nullopt } }, + { "output_int_register_1", { "3.4.0", std::nullopt } }, + { "output_int_register_2", { "3.4.0", std::nullopt } }, + { "output_int_register_3", { "3.4.0", std::nullopt } }, + { "output_int_register_4", { "3.4.0", std::nullopt } }, + { "output_int_register_5", { "3.4.0", std::nullopt } }, + { "output_int_register_6", { "3.4.0", std::nullopt } }, + { "output_int_register_7", { "3.4.0", std::nullopt } }, + { "output_int_register_8", { "3.4.0", std::nullopt } }, + { "output_int_register_9", { "3.4.0", std::nullopt } }, + { "output_int_register_10", { "3.4.0", std::nullopt } }, + { "output_int_register_11", { "3.4.0", std::nullopt } }, + { "output_int_register_12", { "3.4.0", std::nullopt } }, + { "output_int_register_13", { "3.4.0", std::nullopt } }, + { "output_int_register_14", { "3.4.0", std::nullopt } }, + { "output_int_register_15", { "3.4.0", std::nullopt } }, + { "output_int_register_16", { "3.4.0", std::nullopt } }, + { "output_int_register_17", { "3.4.0", std::nullopt } }, + { "output_int_register_18", { "3.4.0", std::nullopt } }, + { "output_int_register_19", { "3.4.0", std::nullopt } }, + { "output_int_register_20", { "3.4.0", std::nullopt } }, + { "output_int_register_21", { "3.4.0", std::nullopt } }, + { "output_int_register_22", { "3.4.0", std::nullopt } }, + { "output_int_register_23", { "3.4.0", std::nullopt } }, + { "output_int_register_24", { "3.9.0", "5.3.0" } }, + { "output_int_register_25", { "3.9.0", "5.3.0" } }, + { "output_int_register_26", { "3.9.0", "5.3.0" } }, + { "output_int_register_27", { "3.9.0", "5.3.0" } }, + { "output_int_register_28", { "3.9.0", "5.3.0" } }, + { "output_int_register_29", { "3.9.0", "5.3.0" } }, + { "output_int_register_30", { "3.9.0", "5.3.0" } }, + { "output_int_register_31", { "3.9.0", "5.3.0" } }, + { "output_int_register_32", { "3.9.0", "5.3.0" } }, + { "output_int_register_33", { "3.9.0", "5.3.0" } }, + { "output_int_register_34", { "3.9.0", "5.3.0" } }, + { "output_int_register_35", { "3.9.0", "5.3.0" } }, + { "output_int_register_36", { "3.9.0", "5.3.0" } }, + { "output_int_register_37", { "3.9.0", "5.3.0" } }, + { "output_int_register_38", { "3.9.0", "5.3.0" } }, + { "output_int_register_39", { "3.9.0", "5.3.0" } }, + { "output_int_register_40", { "3.9.0", "5.3.0" } }, + { "output_int_register_41", { "3.9.0", "5.3.0" } }, + { "output_int_register_42", { "3.9.0", "5.3.0" } }, + { "output_int_register_43", { "3.9.0", "5.3.0" } }, + { "output_int_register_44", { "3.9.0", "5.3.0" } }, + { "output_int_register_45", { "3.9.0", "5.3.0" } }, + { "output_int_register_46", { "3.9.0", "5.3.0" } }, + { "output_int_register_47", { "3.9.0", "5.3.0" } }, + { "output_double_register_0", { "3.4.0", std::nullopt } }, + { "output_double_register_1", { "3.4.0", std::nullopt } }, + { "output_double_register_2", { "3.4.0", std::nullopt } }, + { "output_double_register_3", { "3.4.0", std::nullopt } }, + { "output_double_register_4", { "3.4.0", std::nullopt } }, + { "output_double_register_5", { "3.4.0", std::nullopt } }, + { "output_double_register_6", { "3.4.0", std::nullopt } }, + { "output_double_register_7", { "3.4.0", std::nullopt } }, + { "output_double_register_8", { "3.4.0", std::nullopt } }, + { "output_double_register_9", { "3.4.0", std::nullopt } }, + { "output_double_register_10", { "3.4.0", std::nullopt } }, + { "output_double_register_11", { "3.4.0", std::nullopt } }, + { "output_double_register_12", { "3.4.0", std::nullopt } }, + { "output_double_register_13", { "3.4.0", std::nullopt } }, + { "output_double_register_14", { "3.4.0", std::nullopt } }, + { "output_double_register_15", { "3.4.0", std::nullopt } }, + { "output_double_register_16", { "3.4.0", std::nullopt } }, + { "output_double_register_17", { "3.4.0", std::nullopt } }, + { "output_double_register_18", { "3.4.0", std::nullopt } }, + { "output_double_register_19", { "3.4.0", std::nullopt } }, + { "output_double_register_20", { "3.4.0", std::nullopt } }, + { "output_double_register_21", { "3.4.0", std::nullopt } }, + { "output_double_register_22", { "3.4.0", std::nullopt } }, + { "output_double_register_23", { "3.4.0", std::nullopt } }, + { "output_double_register_24", { "3.9.0", "5.3.0" } }, + { "output_double_register_25", { "3.9.0", "5.3.0" } }, + { "output_double_register_26", { "3.9.0", "5.3.0" } }, + { "output_double_register_27", { "3.9.0", "5.3.0" } }, + { "output_double_register_28", { "3.9.0", "5.3.0" } }, + { "output_double_register_29", { "3.9.0", "5.3.0" } }, + { "output_double_register_30", { "3.9.0", "5.3.0" } }, + { "output_double_register_31", { "3.9.0", "5.3.0" } }, + { "output_double_register_32", { "3.9.0", "5.3.0" } }, + { "output_double_register_33", { "3.9.0", "5.3.0" } }, + { "output_double_register_34", { "3.9.0", "5.3.0" } }, + { "output_double_register_35", { "3.9.0", "5.3.0" } }, + { "output_double_register_36", { "3.9.0", "5.3.0" } }, + { "output_double_register_37", { "3.9.0", "5.3.0" } }, + { "output_double_register_38", { "3.9.0", "5.3.0" } }, + { "output_double_register_39", { "3.9.0", "5.3.0" } }, + { "output_double_register_40", { "3.9.0", "5.3.0" } }, + { "output_double_register_41", { "3.9.0", "5.3.0" } }, + { "output_double_register_42", { "3.9.0", "5.3.0" } }, + { "output_double_register_43", { "3.9.0", "5.3.0" } }, + { "output_double_register_44", { "3.9.0", "5.3.0" } }, + { "output_double_register_45", { "3.9.0", "5.3.0" } }, + { "output_double_register_46", { "3.9.0", "5.3.0" } }, + { "output_double_register_47", { "3.9.0", "5.3.0" } }, + { "input_bit_registers0_to_31", { "3.4.0", std::nullopt } }, + { "input_bit_registers32_to_63", { "3.4.0", std::nullopt } }, + { "input_bit_register_64", { "3.9.0", "5.3.0" } }, + { "input_bit_register_65", { "3.9.0", "5.3.0" } }, + { "input_bit_register_66", { "3.9.0", "5.3.0" } }, + { "input_bit_register_67", { "3.9.0", "5.3.0" } }, + { "input_bit_register_68", { "3.9.0", "5.3.0" } }, + { "input_bit_register_69", { "3.9.0", "5.3.0" } }, + { "input_bit_register_70", { "3.9.0", "5.3.0" } }, + { "input_bit_register_71", { "3.9.0", "5.3.0" } }, + { "input_bit_register_72", { "3.9.0", "5.3.0" } }, + { "input_bit_register_73", { "3.9.0", "5.3.0" } }, + { "input_bit_register_74", { "3.9.0", "5.3.0" } }, + { "input_bit_register_75", { "3.9.0", "5.3.0" } }, + { "input_bit_register_76", { "3.9.0", "5.3.0" } }, + { "input_bit_register_77", { "3.9.0", "5.3.0" } }, + { "input_bit_register_78", { "3.9.0", "5.3.0" } }, + { "input_bit_register_79", { "3.9.0", "5.3.0" } }, + { "input_bit_register_80", { "3.9.0", "5.3.0" } }, + { "input_bit_register_81", { "3.9.0", "5.3.0" } }, + { "input_bit_register_82", { "3.9.0", "5.3.0" } }, + { "input_bit_register_83", { "3.9.0", "5.3.0" } }, + { "input_bit_register_84", { "3.9.0", "5.3.0" } }, + { "input_bit_register_85", { "3.9.0", "5.3.0" } }, + { "input_bit_register_86", { "3.9.0", "5.3.0" } }, + { "input_bit_register_87", { "3.9.0", "5.3.0" } }, + { "input_bit_register_88", { "3.9.0", "5.3.0" } }, + { "input_bit_register_89", { "3.9.0", "5.3.0" } }, + { "input_bit_register_90", { "3.9.0", "5.3.0" } }, + { "input_bit_register_91", { "3.9.0", "5.3.0" } }, + { "input_bit_register_92", { "3.9.0", "5.3.0" } }, + { "input_bit_register_93", { "3.9.0", "5.3.0" } }, + { "input_bit_register_94", { "3.9.0", "5.3.0" } }, + { "input_bit_register_95", { "3.9.0", "5.3.0" } }, + { "input_bit_register_96", { "3.9.0", "5.3.0" } }, + { "input_bit_register_97", { "3.9.0", "5.3.0" } }, + { "input_bit_register_98", { "3.9.0", "5.3.0" } }, + { "input_bit_register_99", { "3.9.0", "5.3.0" } }, + { "input_bit_register_100", { "3.9.0", "5.3.0" } }, + { "input_bit_register_101", { "3.9.0", "5.3.0" } }, + { "input_bit_register_102", { "3.9.0", "5.3.0" } }, + { "input_bit_register_103", { "3.9.0", "5.3.0" } }, + { "input_bit_register_104", { "3.9.0", "5.3.0" } }, + { "input_bit_register_105", { "3.9.0", "5.3.0" } }, + { "input_bit_register_106", { "3.9.0", "5.3.0" } }, + { "input_bit_register_107", { "3.9.0", "5.3.0" } }, + { "input_bit_register_108", { "3.9.0", "5.3.0" } }, + { "input_bit_register_109", { "3.9.0", "5.3.0" } }, + { "input_bit_register_110", { "3.9.0", "5.3.0" } }, + { "input_bit_register_111", { "3.9.0", "5.3.0" } }, + { "input_bit_register_112", { "3.9.0", "5.3.0" } }, + { "input_bit_register_113", { "3.9.0", "5.3.0" } }, + { "input_bit_register_114", { "3.9.0", "5.3.0" } }, + { "input_bit_register_115", { "3.9.0", "5.3.0" } }, + { "input_bit_register_116", { "3.9.0", "5.3.0" } }, + { "input_bit_register_117", { "3.9.0", "5.3.0" } }, + { "input_bit_register_118", { "3.9.0", "5.3.0" } }, + { "input_bit_register_119", { "3.9.0", "5.3.0" } }, + { "input_bit_register_120", { "3.9.0", "5.3.0" } }, + { "input_bit_register_121", { "3.9.0", "5.3.0" } }, + { "input_bit_register_122", { "3.9.0", "5.3.0" } }, + { "input_bit_register_123", { "3.9.0", "5.3.0" } }, + { "input_bit_register_124", { "3.9.0", "5.3.0" } }, + { "input_bit_register_125", { "3.9.0", "5.3.0" } }, + { "input_bit_register_126", { "3.9.0", "5.3.0" } }, + { "input_bit_register_127", { "3.9.0", "5.3.0" } }, + { "input_double_register_0", { "3.4.0", std::nullopt } }, + { "input_double_register_1", { "3.4.0", std::nullopt } }, + { "input_double_register_2", { "3.4.0", std::nullopt } }, + { "input_double_register_3", { "3.4.0", std::nullopt } }, + { "input_double_register_4", { "3.4.0", std::nullopt } }, + { "input_double_register_5", { "3.4.0", std::nullopt } }, + { "input_double_register_6", { "3.4.0", std::nullopt } }, + { "input_double_register_7", { "3.4.0", std::nullopt } }, + { "input_double_register_8", { "3.4.0", std::nullopt } }, + { "input_double_register_9", { "3.4.0", std::nullopt } }, + { "input_double_register_10", { "3.4.0", std::nullopt } }, + { "input_double_register_11", { "3.4.0", std::nullopt } }, + { "input_double_register_12", { "3.4.0", std::nullopt } }, + { "input_double_register_13", { "3.4.0", std::nullopt } }, + { "input_double_register_14", { "3.4.0", std::nullopt } }, + { "input_double_register_15", { "3.4.0", std::nullopt } }, + { "input_double_register_16", { "3.4.0", std::nullopt } }, + { "input_double_register_17", { "3.4.0", std::nullopt } }, + { "input_double_register_18", { "3.4.0", std::nullopt } }, + { "input_double_register_19", { "3.4.0", std::nullopt } }, + { "input_double_register_20", { "3.4.0", std::nullopt } }, + { "input_double_register_21", { "3.4.0", std::nullopt } }, + { "input_double_register_22", { "3.4.0", std::nullopt } }, + { "input_double_register_23", { "3.4.0", std::nullopt } }, + { "input_double_register_24", { "3.9.0", "5.3.0" } }, + { "input_double_register_25", { "3.9.0", "5.3.0" } }, + { "input_double_register_26", { "3.9.0", "5.3.0" } }, + { "input_double_register_27", { "3.9.0", "5.3.0" } }, + { "input_double_register_28", { "3.9.0", "5.3.0" } }, + { "input_double_register_29", { "3.9.0", "5.3.0" } }, + { "input_double_register_30", { "3.9.0", "5.3.0" } }, + { "input_double_register_31", { "3.9.0", "5.3.0" } }, + { "input_double_register_32", { "3.9.0", "5.3.0" } }, + { "input_double_register_33", { "3.9.0", "5.3.0" } }, + { "input_double_register_34", { "3.9.0", "5.3.0" } }, + { "input_double_register_35", { "3.9.0", "5.3.0" } }, + { "input_double_register_36", { "3.9.0", "5.3.0" } }, + { "input_double_register_37", { "3.9.0", "5.3.0" } }, + { "input_double_register_38", { "3.9.0", "5.3.0" } }, + { "input_double_register_39", { "3.9.0", "5.3.0" } }, + { "input_double_register_40", { "3.9.0", "5.3.0" } }, + { "input_double_register_41", { "3.9.0", "5.3.0" } }, + { "input_double_register_42", { "3.9.0", "5.3.0" } }, + { "input_double_register_43", { "3.9.0", "5.3.0" } }, + { "input_double_register_44", { "3.9.0", "5.3.0" } }, + { "input_double_register_45", { "3.9.0", "5.3.0" } }, + { "input_double_register_46", { "3.9.0", "5.3.0" } }, + { "input_double_register_47", { "3.9.0", "5.3.0" } }, + { "tool_output_mode", { std::nullopt, std::nullopt } }, + { "tool_digital_output0_mode", { std::nullopt, std::nullopt } }, + { "tool_digital_output1_mode", { std::nullopt, std::nullopt } }, + { "payload", { "3.11.0", "5.5.1" } }, + { "payload_cog", { "3.11.0", "5.5.1" } }, + { "payload_inertia", { std::nullopt, std::nullopt } }, + { "script_control_line", { std::nullopt, std::nullopt } }, + { "ft_raw_wrench", { "5.9.0", "5.9.0" } }, + { "joint_position_deviation_ratio", { std::nullopt, std::nullopt } }, + { "collision_detection_ratio", { "5.15.0", "5.15.0" } }, + { "time_scale_source", { "5.17.0", "5.17.0" } } +}; + class RTDEClientTest : public ::testing::Test { protected: @@ -51,6 +406,22 @@ class RTDEClientTest : public ::testing::Test std::this_thread::sleep_for(std::chrono::seconds(1)); } + void filterOutputRecipeToBeCompatibleWith(std::vector& output_recipe, VersionInformation sw_version) + { + const auto get_min_version = [&sw_version](const std::string& output_name) -> std::optional { + return sw_version.isESeries() ? EXHAUSTIVE_OUTPUTS_WITH_COMPATIBILITY.at(output_name).second : + EXHAUSTIVE_OUTPUTS_WITH_COMPATIBILITY.at(output_name).first; + }; + const auto output_incompatible_with_version = [get_min_version, + &sw_version](const std::string& output_name) -> bool { + const auto min_version = get_min_version(output_name); + return min_version.has_value() && sw_version < VersionInformation::fromString(min_version.value()); + }; + + output_recipe.erase(std::remove_if(output_recipe.begin(), output_recipe.end(), output_incompatible_with_version), + output_recipe.end()); + } + std::string output_recipe_file_ = "resources/rtde_output_recipe.txt"; std::string input_recipe_file_ = "resources/rtde_input_recipe.txt"; comm::INotifier notifier_; @@ -362,6 +733,42 @@ TEST_F(RTDEClientTest, connect_non_running_robot) EXPECT_LT(elapsed, 2 * comm::TCPSocket::DEFAULT_RECONNECTION_TIME); } +TEST_F(RTDEClientTest, check_all_rtde_output_variables_exist) +{ + client_->init(); + + // Create an output recipe as exhaustive as possible but compatible with the current version + std::vector exhaustive_compatible_output_recipe; + + const VersionInformation sw_version = client_->getVersion(); + std::transform( + EXHAUSTIVE_OUTPUTS_WITH_COMPATIBILITY.begin(), EXHAUSTIVE_OUTPUTS_WITH_COMPATIBILITY.end(), + std::back_inserter(exhaustive_compatible_output_recipe), + [](OutputNamesWithCompatibility::const_reference data_name) -> std::string { return data_name.first; }); + filterOutputRecipeToBeCompatibleWith(exhaustive_compatible_output_recipe, sw_version); + + client_.reset(new rtde_interface::RTDEClient(ROBOT_IP, notifier_, exhaustive_compatible_output_recipe, + resources_input_recipe_)); + + EXPECT_NO_THROW(client_->init()); + client_->start(); + + // Test that we can receive and parse the timestamp from the received package to prove the setup was successful + const std::chrono::milliseconds read_timeout{ 100 }; + std::unique_ptr data_pkg = client_->getDataPackage(read_timeout); + + if (data_pkg == nullptr) + { + std::cout << "Failed to get data package from robot" << std::endl; + GTEST_FAIL(); + } + + double timestamp; + EXPECT_TRUE(data_pkg->getData("timestamp", timestamp)); + + client_->pause(); +} + int main(int argc, char* argv[]) { ::testing::InitGoogleTest(&argc, argv); From 060a493a4590bae58ba18d298c9500d4763ee41a Mon Sep 17 00:00:00 2001 From: URJala <159417921+URJala@users.noreply.github.com> Date: Wed, 6 Nov 2024 14:23:28 +1100 Subject: [PATCH 10/11] Apply suggestions from code review Co-authored-by: Felix Exner --- include/ur_client_library/exceptions.h | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/include/ur_client_library/exceptions.h b/include/ur_client_library/exceptions.h index 9adbc04c0..48e602d53 100644 --- a/include/ur_client_library/exceptions.h +++ b/include/ur_client_library/exceptions.h @@ -129,12 +129,12 @@ class IncompatibleRobotVersion : public UrException { public: explicit IncompatibleRobotVersion() = delete; - explicit IncompatibleRobotVersion(std::string text, int required_robot_version, int actual_robot_version) + explicit IncompatibleRobotVersion(const std::string& text, const VersionInformation& minimum_robot_version, const VersionInformation& actual_robot_version) : std::runtime_error(text) { std::stringstream ss; ss << text << "\n" - << "The requested feature is incompatible with the connected robot. Required Polyscope version: " + << "The requested feature is incompatible with the connected robot. Minimum required Polyscope version: " << required_robot_version << ", actual Polyscope version: " << actual_robot_version; text_ = ss.str(); } From 8ff93ae594840ea8be8dd352b5430af3411fa73b Mon Sep 17 00:00:00 2001 From: URJala Date: Wed, 6 Nov 2024 04:33:58 +0000 Subject: [PATCH 11/11] Created new exception MissingArgument After further thought, I dont think the Incompatible version exception is appropriate for one of the exception calls, as the robot is not actually incompatible, the function just needs more information. The new exception conveys that, i think. I can't quite make my mind up about whether it should mention that this is due to the robot version, though, so I have left it out for now. --- include/ur_client_library/exceptions.h | 28 ++++++++++++++++++++++++-- src/ur/ur_driver.cpp | 5 +++-- 2 files changed, 29 insertions(+), 4 deletions(-) diff --git a/include/ur_client_library/exceptions.h b/include/ur_client_library/exceptions.h index 48e602d53..5145a75d8 100644 --- a/include/ur_client_library/exceptions.h +++ b/include/ur_client_library/exceptions.h @@ -32,6 +32,7 @@ #include #include #include +#include "ur/version_information.h" namespace urcl { @@ -129,13 +130,14 @@ class IncompatibleRobotVersion : public UrException { public: explicit IncompatibleRobotVersion() = delete; - explicit IncompatibleRobotVersion(const std::string& text, const VersionInformation& minimum_robot_version, const VersionInformation& actual_robot_version) + explicit IncompatibleRobotVersion(const std::string& text, const VersionInformation& minimum_robot_version, + const VersionInformation& actual_robot_version) : std::runtime_error(text) { std::stringstream ss; ss << text << "\n" << "The requested feature is incompatible with the connected robot. Minimum required Polyscope version: " - << required_robot_version << ", actual Polyscope version: " << actual_robot_version; + << minimum_robot_version << ", actual Polyscope version: " << actual_robot_version; text_ = ss.str(); } virtual const char* what() const noexcept override @@ -163,5 +165,27 @@ class InvalidRange : public UrException return text_.c_str(); } }; + +class MissingArgument : public UrException +{ +private: + std::string text_; + +public: + explicit MissingArgument() = delete; + explicit MissingArgument(std::string text, std::string function_name, std::string argument_name, float default_value) + : std::runtime_error("") + { + std::stringstream ss; + ss << text << "\nMissing argument when calling function: " << function_name + << ". \nArgument missing: " << argument_name + << ". \nSet to default value if not important, default value is: " << default_value; + text_ = ss.str(); + } + virtual const char* what() const noexcept override + { + return text_.c_str(); + } +}; } // namespace urcl #endif // ifndef UR_CLIENT_LIBRARY_EXCEPTIONS_H_INCLUDED diff --git a/src/ur/ur_driver.cpp b/src/ur/ur_driver.cpp index 717bde4e4..23301f714 100644 --- a/src/ur/ur_driver.cpp +++ b/src/ur/ur_driver.cpp @@ -364,7 +364,8 @@ bool UrDriver::startForceMode(const vector6d_t& task_frame, const vector6uint32_ std::stringstream ss; ss << "Force mode gain scaling factor cannot be set on a CB3 robot."; URCL_LOG_ERROR(ss.str().c_str()); - throw IncompatibleRobotVersion(ss.str(), 5, robot_version_.major); + VersionInformation req_version = VersionInformation::fromString("5.0.0.0"); + throw IncompatibleRobotVersion(ss.str(), req_version, robot_version_); } // Test that the type is either 1, 2 or 3. switch (type) @@ -430,7 +431,7 @@ bool UrDriver::startForceMode(const vector6d_t& task_frame, const vector6uint32_ std::stringstream ss; ss << "You should also specify a force mode gain scaling factor to activate force mode on an e-series robot."; URCL_LOG_ERROR(ss.str().c_str()); - throw IncompatibleRobotVersion(ss.str(), 3, robot_version_.major); + throw MissingArgument(ss.str(), "startForceMode", "gain_scaling_factor", 0.5); } // Test that the type is either 1, 2 or 3. switch (type)