From 1e2a751e7b889ac8a46850447759eedc66309021 Mon Sep 17 00:00:00 2001 From: gfigneczi1 Date: Wed, 22 Jan 2025 17:01:57 +0100 Subject: [PATCH 01/13] adding new feedforward and feedback logic, not tested --- .../compensatory_model/compensatory_model.hpp | 19 +- .../controller_inputs.hpp | 2 + .../compensatory_model/compensatory_model.cpp | 286 ++++++++---------- 3 files changed, 141 insertions(+), 166 deletions(-) diff --git a/crp_APL/controllers/ctrl_vehicle_control_lat_compensatory/include/compensatory_model/compensatory_model.hpp b/crp_APL/controllers/ctrl_vehicle_control_lat_compensatory/include/compensatory_model/compensatory_model.hpp index 7327a33f..373b096e 100644 --- a/crp_APL/controllers/ctrl_vehicle_control_lat_compensatory/include/compensatory_model/compensatory_model.hpp +++ b/crp_APL/controllers/ctrl_vehicle_control_lat_compensatory/include/compensatory_model/compensatory_model.hpp @@ -36,14 +36,11 @@ namespace crp bool m_trajInvalid{false}; // FEEDFORWARD - double m_lookAheadDistance{0.0f}; - double m_targetCurvature{0.0f}; double m_targetAccelerationFF{0.0f}; - double m_targetSteeringAngleFF{0.0f}; // FEEDBACK double m_targetAccelerationFB{0.0f}; - double m_targetSteeringAngleFB{0.0f}; + double m_lookAheadDistanceFb{0.0f}; double m_posErr{0.0f}; double m_posIntegralError{0.0f}; @@ -52,6 +49,11 @@ namespace crp double m_posErrPrev{0.0f}; double m_orientationErr{0.0f}; + // RESULT + double m_targetAcceleration{0.0f}; + double m_targetSteeringAngle{0.0f}; + double m_k_superPosition{0.5f}; + double m_targetSteeringAngle_prev{0.0f}; double m_actualSteeringAngleLog[2]{0.0f, 0.0f}; @@ -59,16 +61,10 @@ namespace crp double m_steeringTarget_prev{0.0f}; double m_derivativeError_prev{0.0f}; - // KPIs - for debug - double m_KPI_c0RMS{0.0f}; - double m_KPI_c0Mean{0.0f}; - double m_KPI_c0MS{0.0f}; - double m_KPI_c0Max{4e8}; - unsigned long int N{0}; - // METHODS void calculateFeedforward(const ControlInput& input, const ControlParams& params); void calculateFeedback(const ControlInput& input, const ControlParams& params); + void superPoseFeedforwardAndFeedback (); void calculateSteeringAngle(const ControlInput& input, const ControlParams& params); @@ -76,7 +72,6 @@ namespace crp void calculateLookAheadPose(const ControlInput& input, const ControlParams& params); - double steeringInverseDynamics(const double& steeringAngle, const ControlParams& params); }; } } diff --git a/crp_APL/controllers/ctrl_vehicle_control_lat_compensatory/include/ctrl_vehicle_control/controller_inputs.hpp b/crp_APL/controllers/ctrl_vehicle_control_lat_compensatory/include/ctrl_vehicle_control/controller_inputs.hpp index 42b1aaa6..3eb68844 100644 --- a/crp_APL/controllers/ctrl_vehicle_control_lat_compensatory/include/ctrl_vehicle_control/controller_inputs.hpp +++ b/crp_APL/controllers/ctrl_vehicle_control_lat_compensatory/include/ctrl_vehicle_control/controller_inputs.hpp @@ -42,6 +42,8 @@ namespace crp double dT{0.0333f}; double vxMin{3.0f}; double trajectory_distance{50.0f}; + double sigma_thetaFP{0.25f}; + double maxThetaFP{0.3f}; bool debugKPIs{true}; }; } diff --git a/crp_APL/controllers/ctrl_vehicle_control_lat_compensatory/src/compensatory_model/compensatory_model.cpp b/crp_APL/controllers/ctrl_vehicle_control_lat_compensatory/src/compensatory_model/compensatory_model.cpp index e94c25ce..d35823d3 100644 --- a/crp_APL/controllers/ctrl_vehicle_control_lat_compensatory/src/compensatory_model/compensatory_model.cpp +++ b/crp_APL/controllers/ctrl_vehicle_control_lat_compensatory/src/compensatory_model/compensatory_model.cpp @@ -4,19 +4,20 @@ namespace crp { namespace apl { - void CompensatoryModel::run (ControlInput& input, ControlOutput& output, const ControlParams& params) + void CompensatoryModel::run(ControlInput &input, ControlOutput &output, const ControlParams ¶ms) { // this method is the main method of the compensatory model. It calculates the feedforward and feedback double point[3]; - m_localPath_x.clear(); m_localPath_y.clear(); - for (unsigned long int i=0; i= 4) { - + printf("Trajectory length is %d\n", input.path_x.size()); m_coefficients = m_polynomialCalculator.calculateThirdOrderPolynomial(m_localPathCut_x, m_localPathCut_y); - - calculateLookAheadPose(input, params); - - // feedforward control + + // feedforward based on preview point - output: target feedforward acceleration calculateFeedforward(input, params); // feedback control calculateFeedback(input, params); + // superposition of the feedforward and feedback lateral acceleration + superPoseFeedforwardAndFeedback(); + + // summing the target values to produce the target + output.accelerationTarget = (1.0f-m_k_superPosition)*m_targetAccelerationFF + + m_k_superPosition*m_targetAccelerationFB; + // output calculation calculateSteeringAngle(input, params); - // summing the target values to produce the target - output.accelerationTarget = m_targetAccelerationFF + m_targetAccelerationFB; - output.steeringAngleTarget = m_targetSteeringAngleFF + m_targetSteeringAngleFB; + // finally, filter the output steering angle, too output.steeringAngleTarget = m_steeringAngleFilter.lowPassFilter(output.steeringAngleTarget, m_targetSteeringAngle_prev, params.steeringAngleLPFilter); - // output.steeringAngleTarget = steeringInverseDynamics(output.steeringAngleTarget, params); - - // KPI calculation - if (N<=65535) - { - N++; - } - m_KPI_c0Mean = ((N-1)*m_KPI_c0Mean+m_coefficients[0])/N; - m_KPI_c0MS = ((N-1)*m_KPI_c0MS+std::pow(m_coefficients[0],2))/N; - m_KPI_c0RMS = std::sqrt(m_KPI_c0MS); - m_KPI_c0Max = std::min(m_KPI_c0Max, m_coefficients[0]); - m_targetSteeringAngle_prev = output.steeringAngleTarget; - - m_actualSteeringAngleLog[1] = m_actualSteeringAngleLog[0]; - m_actualSteeringAngleLog[0] = input.egoSteeringAngle; - - printf("The following KPIs have been calculated\n"); - printf("\t c0 RMS = %f\n\tc0 mean = %f\n\t c0 max = %f\n\t cycle numbers %d\n", m_KPI_c0RMS, m_KPI_c0Mean, m_KPI_c0Max, N); } } - void CompensatoryModel::calculateFeedforward(const ControlInput& input, const ControlParams& params) + void CompensatoryModel::superPoseFeedforwardAndFeedback() + { + // the superposition is the calculation of the superposition factor between the + // feedforward and the feedback targets. The factor lies between 0 and 1. + // k = 0: only feedforward, + // k = 1: only feedback + m_k_superPosition = 0.5; + } + + void CompensatoryModel::calculateFeedforward(const ControlInput &input, const ControlParams ¶ms) { // this method calculates the feedforward target steering angle. - // First, the curvature is calculated in the preview distance. - // Secondly, the curvature is transformed to a steering angle, with a velocity dependent - // gain. This gain is planned to be used to imitate slip compensation. - // Third, the resulting feedforward steering angle is filtered using a simple low pass - // filter. - - m_lookAheadDistance = std::max(params.ffMinLookAheadDistance, params.ffLookAheadTime*input.vxEgo); - // second derivative of the 3rd order polynomial, filtered - printf("relevant coefficients are %f, %f\n", m_coefficients[2], m_coefficients[3]); - m_targetCurvature = 0.99f*m_targetCurvature + - 0.01f*(2.0f*m_coefficients[2]+6.0f*m_coefficients[3]*m_lookAheadDistance); - - if(params.debugKPIs) - {printf("data before limitation: c0=%f, lad=%f, kappa=%f\n", m_coefficients[0], m_lookAheadDistance, m_targetCurvature);} - - // finally, lateral feedforward acceleration is calculated - this is done to be in harmony - // with the feedback path later (out of scope of this method) - m_targetAccelerationFF = params.ffGainOffsetGround*std::min(std::max(-params.maxFFAcceleration, m_targetCurvature * std::pow(input.vxEgo,2)), params.maxFFAcceleration); - - if(params.debugKPIs) - {printf("ayTarFF %f\n", m_targetAccelerationFF);} + // First, a look ahead point is calculated. This is based on the preview time defined + // as a parameter. Then, this preview time is used to calculate the feedforward + // acceleration. + + calculateLookAheadPose(input, params); + + double targetAccelerationUnfiltered = 2*m_lookAheadPose[1] / (std::pow(params.fbLookAheadTime,2)); + + // strong filtering + m_targetAccelerationFF = 0.99f * m_targetAccelerationFF + + 0.01f * targetAccelerationUnfiltered; + + m_targetAccelerationFF = std::min(std::max(-params.maxAcceleration, m_targetAccelerationFF), params.maxAcceleration); } - void CompensatoryModel::calculateFeedback(const ControlInput& input, const ControlParams& params) + void CompensatoryModel::calculateFeedback(const ControlInput &input, const ControlParams ¶ms) { - // this method calculates the feedback target steering angle. - // First, control error is defined. A separate FB look ahead distance is calculated for this. - // orientation and position error are calculated. - // Secondly, the integral and derival parts are calculated. - // Third, the orientation error is calculated. - // Fourth, the errors are weighted and summed with the corresponding control coefficients. - // Finally, lateral acceleration target is mapped to steering angle target. + // This method calculates the feedback based acceleration target. + // Elements: + // 1. An adaptive proportional gain based on the focus point angle + // 2. Highly filtered derivative gain, + // 3. Integral + + // calculate focus point angle + m_lookAheadDistanceFb = std::max(params.fbMinLookAheadDistance, params.fbLookAheadTime * input.vxEgo); + // from coefficients + double thetaFP = atan(m_coefficients[1] + + 2.0f*m_coefficients[2]*m_lookAheadDistanceFb + + 3.0f*m_coefficients[3]*std::pow(m_lookAheadDistanceFb,2)); + + double thetaFPNormalized = thetaFP / params.maxThetaFP; + thetaFPNormalized = std::min(1.0, std::max(-1.0, thetaFPNormalized)); - m_lookAheadDistanceFb = std::max(params.fbMinLookAheadDistance, params.fbLookAheadTime*input.vxEgo); + // now, calculate the gain schedule based on theta FP + double k = 1-exp(-std::pow(thetaFPNormalized,2)/(2.0f*std::pow(params.sigma_thetaFP,2))); - m_posErr = m_lookAheadPose[1]; - m_orientationErr = m_lookAheadPose[2]; + m_posErr = k*(m_coefficients[0]+m_coefficients[1]*m_lookAheadDistanceFb+ + m_coefficients[2]*std::pow(m_lookAheadDistanceFb,2) + + m_coefficients[3]*std::pow(m_lookAheadDistanceFb,3)); - m_posIntegralError = m_posIntegralError+m_posErr*params.dT; - m_posIntegralError = std::min(std::max(-params.fbIntegralLimit, m_posIntegralError), - params.fbIntegralLimit); + m_posIntegralError = m_posIntegralError + m_posErr * params.dT; + m_posIntegralError = std::min(std::max(-params.fbIntegralLimit, m_posIntegralError), + params.fbIntegralLimit); - m_posDerivativeError = (m_posErr-m_posErrPrev)/params.dT; - m_posDerivativeError = m_posDerivativeFilter.lowPassFilter(m_posDerivativeError, m_posDerivativeError_prev, 0.9f); + m_posDerivativeError = (m_posErr - m_posErrPrev) / params.dT; + m_posDerivativeError = m_posDerivativeFilter.lowPassFilter(m_posDerivativeError, m_posDerivativeError_prev, 0.999f); - m_targetAccelerationFB = params.fbPGain*m_posErr*std::abs(6*m_posErr) + - params.fbDGain*m_posDerivativeError; + double targetFbAccelerationUnfiltered = params.fbPGain * m_posErr + + params.fbDGain * m_posDerivativeError; + + params.fbIGain * m_posIntegralError; - m_targetAccelerationFB = m_targetAccelerationFB + - params.fbIGain*m_posIntegralError; - m_targetAccelerationFB = m_targetAccelerationFB + - params.fbThetaGain * m_orientationErr; + // strong filtering + m_targetAccelerationFB = 0.99f * m_targetAccelerationFB + + 0.01f * targetFbAccelerationUnfiltered; m_targetAccelerationFB = std::min(std::max(-params.maxAcceleration, m_targetAccelerationFB), params.maxAcceleration); - - if(params.debugKPIs){printf("errors %f, %f, %f, %f\n", m_posErr, m_posIntegralError, m_posDerivativeError, m_orientationErr); printf("ayTarFB %f\n", m_targetAccelerationFB);} m_posErrPrev = m_posErr; } void CompensatoryModel::cutRelevantLocalSnippet() { - // this method cuts a relevant length of the total trajectory, based on the complete + // this method cuts a relevant length of the total trajectory, based on the complete // path transformed to the ego coordinate frame // step 1: searching for nearest point in trajectory unsigned long int startIdx = -1; unsigned long int stopIdx = -1; m_trajInvalid = false; double maxDistance = 50; // meters - m_localPathCut_x.clear(); m_localPathCut_y.clear(); + m_localPathCut_x.clear(); + m_localPathCut_y.clear(); - for (unsigned long int i = 0; i 0) { - if (i==0) + if (i == 0) startIdx = i; else startIdx = i - 1; - + break; } } @@ -172,10 +161,10 @@ namespace crp else { // find stop index - for (unsigned long int i=startIdx; imaxDistance) + double pointDistance = std::sqrt(std::pow(m_localPath_x.at(i), 2) + std::pow(m_localPath_y.at(i), 2)); + if (pointDistance > maxDistance) { stopIdx = i; break; @@ -186,88 +175,77 @@ namespace crp { m_trajInvalid = true; } - else{ + else + { // valid snippet is found, calculate real path - for (unsigned long int i=startIdx; i Date: Thu, 23 Jan 2025 10:38:41 +0100 Subject: [PATCH 02/13] adding new parameters --- .../compensatory_model/compensatory_model.hpp | 2 +- .../controller_inputs.hpp | 11 +-- ...vehicle_control_lat_compensatory.launch.py | 9 +-- .../compensatory_model/compensatory_model.cpp | 18 ++--- .../ctrl_vehicle_control_lat_compensatory.cpp | 24 +++---- .../crp_launcher/launch/core_test.launch.py | 69 ++++++++++++++----- 6 files changed, 81 insertions(+), 52 deletions(-) diff --git a/crp_APL/controllers/ctrl_vehicle_control_lat_compensatory/include/compensatory_model/compensatory_model.hpp b/crp_APL/controllers/ctrl_vehicle_control_lat_compensatory/include/compensatory_model/compensatory_model.hpp index 373b096e..6e3f7cb3 100644 --- a/crp_APL/controllers/ctrl_vehicle_control_lat_compensatory/include/compensatory_model/compensatory_model.hpp +++ b/crp_APL/controllers/ctrl_vehicle_control_lat_compensatory/include/compensatory_model/compensatory_model.hpp @@ -68,7 +68,7 @@ namespace crp void calculateSteeringAngle(const ControlInput& input, const ControlParams& params); - void cutRelevantLocalSnippet(); + void cutRelevantLocalSnippet(const ControlParams ¶ms); void calculateLookAheadPose(const ControlInput& input, const ControlParams& params); diff --git a/crp_APL/controllers/ctrl_vehicle_control_lat_compensatory/include/ctrl_vehicle_control/controller_inputs.hpp b/crp_APL/controllers/ctrl_vehicle_control_lat_compensatory/include/ctrl_vehicle_control/controller_inputs.hpp index 3eb68844..8a037524 100644 --- a/crp_APL/controllers/ctrl_vehicle_control_lat_compensatory/include/ctrl_vehicle_control/controller_inputs.hpp +++ b/crp_APL/controllers/ctrl_vehicle_control_lat_compensatory/include/ctrl_vehicle_control/controller_inputs.hpp @@ -22,29 +22,22 @@ namespace crp }; struct ControlParams{ - double ffGainOffsetGround{1.0f}; - double ffGainSlope{0.1f}; double ffLookAheadTime{1.5f}; - double ffMinLookAheadDistance{0.1f}; double vehAxleDistance{2.9f}; double maxAcceleration{3.0f}; - double maxFFAcceleration{1.0f}; double steeringAngleLPFilter{0.7f}; double fbLookAheadTime{0.0f}; double fbPGain{0.5f}; double fbDGain{0.1f}; double fbIGain{0.01f}; - double fbThetaGain{0.0f}; - double fbMinLookAheadDistance{0.0f}; double fbIntegralLimit{3.0f}; - double invSteerTimeConstant{0.0f}; // todo - double invSteerDamping{0.0f}; // todo double dT{0.0333f}; double vxMin{3.0f}; double trajectory_distance{50.0f}; double sigma_thetaFP{0.25f}; double maxThetaFP{0.3f}; - bool debugKPIs{true}; + double targetAccelerationFF_lpFilterCoeff{0.99f}; + double targetAccelerationFB_lpFilterCoeff{0.99f}; }; } } diff --git a/crp_APL/controllers/ctrl_vehicle_control_lat_compensatory/launch/ctrl_vehicle_control_lat_compensatory.launch.py b/crp_APL/controllers/ctrl_vehicle_control_lat_compensatory/launch/ctrl_vehicle_control_lat_compensatory.launch.py index 894e946f..9c9e3598 100644 --- a/crp_APL/controllers/ctrl_vehicle_control_lat_compensatory/launch/ctrl_vehicle_control_lat_compensatory.launch.py +++ b/crp_APL/controllers/ctrl_vehicle_control_lat_compensatory/launch/ctrl_vehicle_control_lat_compensatory.launch.py @@ -8,17 +8,18 @@ def generate_launch_description(): package="ctrl_vehicle_control_lat_compensatory", executable="ctrl_vehicle_control_lat_compensatory", parameters=[ - {"/ctrl/ffGainOffsetGround": 1.0}, - {"/ctrl/ffGainSlope": 0.0}, {"/ctrl/ffLookAheadTime": 0.68}, {"/ctrl/steeringAngleLPFilter": 0.2}, {"/ctrl/fbLookAheadTime": 0.6}, {"/ctrl/fbPGain": 0.5}, {"/ctrl/fbDGain": 0.1}, {"/ctrl/fbIGain": 0.0}, - {"/ctrl/fbMinLookAheadDistance": 0.0}, {"/ctrl/fbIntegralLimit": 3.0}, - {"/ctrl/fbThetaGain": 0.0}, + {"/ctrl/trajectory_distance": 50.0}, + {"/ctrl/sigma_thetaFP": 0.25}, + {"/ctrl/maxThetaFP": 0.3}, + {"/ctrl/targetAccelerationFF_lpFilterCoeff": 0.99}, + {"/ctrl/targetAccelerationFB_lpFilterCoeff": 0.99}, ] ) diff --git a/crp_APL/controllers/ctrl_vehicle_control_lat_compensatory/src/compensatory_model/compensatory_model.cpp b/crp_APL/controllers/ctrl_vehicle_control_lat_compensatory/src/compensatory_model/compensatory_model.cpp index d35823d3..e62eea0b 100644 --- a/crp_APL/controllers/ctrl_vehicle_control_lat_compensatory/src/compensatory_model/compensatory_model.cpp +++ b/crp_APL/controllers/ctrl_vehicle_control_lat_compensatory/src/compensatory_model/compensatory_model.cpp @@ -24,7 +24,7 @@ namespace crp } // cut snippet - cutRelevantLocalSnippet(); + cutRelevantLocalSnippet(params); if (input.path_x.size() >= 4) { @@ -73,11 +73,11 @@ namespace crp calculateLookAheadPose(input, params); - double targetAccelerationUnfiltered = 2*m_lookAheadPose[1] / (std::pow(params.fbLookAheadTime,2)); + double targetAccelerationUnfiltered = 2.0f*m_lookAheadPose[1] / (std::pow(params.fbLookAheadTime,2)); // strong filtering - m_targetAccelerationFF = 0.99f * m_targetAccelerationFF + - 0.01f * targetAccelerationUnfiltered; + m_targetAccelerationFF = params.targetAccelerationFF_lpFilterCoeff * m_targetAccelerationFF + + (1.0f-params.targetAccelerationFF_lpFilterCoeff) * targetAccelerationUnfiltered; m_targetAccelerationFF = std::min(std::max(-params.maxAcceleration, m_targetAccelerationFF), params.maxAcceleration); } @@ -91,7 +91,7 @@ namespace crp // 3. Integral // calculate focus point angle - m_lookAheadDistanceFb = std::max(params.fbMinLookAheadDistance, params.fbLookAheadTime * input.vxEgo); + m_lookAheadDistanceFb = params.fbLookAheadTime * input.vxEgo; // from coefficients double thetaFP = atan(m_coefficients[1] + 2.0f*m_coefficients[2]*m_lookAheadDistanceFb + @@ -121,15 +121,15 @@ namespace crp // strong filtering - m_targetAccelerationFB = 0.99f * m_targetAccelerationFB + - 0.01f * targetFbAccelerationUnfiltered; + m_targetAccelerationFB = params.targetAccelerationFB_lpFilterCoeff * m_targetAccelerationFB + + (1.0f - params.targetAccelerationFB_lpFilterCoeff) * targetFbAccelerationUnfiltered; m_targetAccelerationFB = std::min(std::max(-params.maxAcceleration, m_targetAccelerationFB), params.maxAcceleration); m_posErrPrev = m_posErr; } - void CompensatoryModel::cutRelevantLocalSnippet() + void CompensatoryModel::cutRelevantLocalSnippet(const ControlParams ¶ms) { // this method cuts a relevant length of the total trajectory, based on the complete // path transformed to the ego coordinate frame @@ -137,7 +137,7 @@ namespace crp unsigned long int startIdx = -1; unsigned long int stopIdx = -1; m_trajInvalid = false; - double maxDistance = 50; // meters + double maxDistance = params.trajectory_distance; // meters m_localPathCut_x.clear(); m_localPathCut_y.clear(); diff --git a/crp_APL/controllers/ctrl_vehicle_control_lat_compensatory/src/ctrl_vehicle_control_lat_compensatory.cpp b/crp_APL/controllers/ctrl_vehicle_control_lat_compensatory/src/ctrl_vehicle_control_lat_compensatory.cpp index ffe30c80..45fb28f2 100644 --- a/crp_APL/controllers/ctrl_vehicle_control_lat_compensatory/src/ctrl_vehicle_control_lat_compensatory.cpp +++ b/crp_APL/controllers/ctrl_vehicle_control_lat_compensatory/src/ctrl_vehicle_control_lat_compensatory.cpp @@ -12,20 +12,21 @@ crp::apl::CtrlVehicleControlLat::CtrlVehicleControlLat() : Node("CtrlVehicleCont m_traj_sub_ = this->create_subscription("/plan/trajectory", 10, std::bind(&CtrlVehicleControlLat::trajCallback, this, std::placeholders::_1)); m_egoVehicle_sub_ = this->create_subscription("/ego", 10, std::bind(&CtrlVehicleControlLat::egoVehicleCallback, this, std::placeholders::_1)); - this->declare_parameter("/ctrl/ffGainOffsetGround", 0.66f); - this->declare_parameter("/ctrl/ffGainSlope", 0.0f); this->declare_parameter("/ctrl/ffLookAheadTime", 0.68f); - this->declare_parameter("/ctrl/ffMinLookAheadDistance", 0.0f); this->declare_parameter("/ctrl/steeringAngleLPFilter", 0.2f); this->declare_parameter("/ctrl/fbLookAheadTime", 0.0f); this->declare_parameter("/ctrl/fbPGain", 0.8f); this->declare_parameter("/ctrl/fbDGain", 1.1f); this->declare_parameter("/ctrl/fbIGain", 0.0f); - this->declare_parameter("/ctrl/fbThetaGain", 0.05f); - this->declare_parameter("/ctrl/fbMinLookAheadDistance", 0.0f); this->declare_parameter("/ctrl/fbIntegralLimit", 3.0f); this->declare_parameter("/ctrl/trajectory_distance", 50.0f); - this->declare_parameter("/ctrl/debugKPIs", true); + + this->declare_parameter("/ctrl/sigma_thetaFP", 0.25f); + this->declare_parameter("/ctrl/maxThetaFP", 0.3f); + this->declare_parameter("/ctrl/targetAccelerationFF_lpFilterCoeff", 0.99f); + this->declare_parameter("/ctrl/targetAccelerationFB_lpFilterCoeff", 0.99f); + + RCLCPP_INFO(this->get_logger(), "ctrl_vehicle_control has been started"); } @@ -75,20 +76,19 @@ void crp::apl::CtrlVehicleControlLat::egoVehicleCallback(const crp_msgs::msg::Eg void crp::apl::CtrlVehicleControlLat::loop() { // parameter assignments - m_params.ffGainOffsetGround = this->get_parameter("/ctrl/ffGainOffsetGround").as_double(); - m_params.ffGainSlope = this->get_parameter("/ctrl/ffGainSlope").as_double(); m_params.ffLookAheadTime = this->get_parameter("/ctrl/ffLookAheadTime").as_double(); - m_params.ffMinLookAheadDistance = this->get_parameter("/ctrl/ffMinLookAheadDistance").as_double(); m_params.steeringAngleLPFilter = this->get_parameter("/ctrl/steeringAngleLPFilter").as_double(); m_params.fbLookAheadTime = this->get_parameter("/ctrl/fbLookAheadTime").as_double(); m_params.fbPGain = this->get_parameter("/ctrl/fbPGain").as_double(); m_params.fbDGain = this->get_parameter("/ctrl/fbDGain").as_double(); m_params.fbIGain = this->get_parameter("/ctrl/fbIGain").as_double(); - m_params.fbThetaGain = this->get_parameter("/ctrl/fbThetaGain").as_double(); - m_params.fbMinLookAheadDistance = this->get_parameter("/ctrl/fbMinLookAheadDistance").as_double(); m_params.fbIntegralLimit = this->get_parameter("/ctrl/fbIntegralLimit").as_double(); m_params.trajectory_distance = this->get_parameter("/ctrl/trajectory_distance").as_double(); - m_params.debugKPIs = this->get_parameter("/ctrl/debugKPIs").as_bool(); + + m_params.sigma_thetaFP = this->get_parameter("/ctrl/sigma_thetaFP").as_double(); + m_params.maxThetaFP = this->get_parameter("/ctrl/maxThetaFP").as_double(); + m_params.targetAccelerationFF_lpFilterCoeff = this->get_parameter("/ctrl/targetAccelerationFF_lpFilterCoeff").as_double(); + m_params.targetAccelerationFB_lpFilterCoeff = this->get_parameter("/ctrl/targetAccelerationFB_lpFilterCoeff").as_double(); m_compensatoryModel.run(m_input, m_output, m_params); diff --git a/launch/crp_launcher/launch/core_test.launch.py b/launch/crp_launcher/launch/core_test.launch.py index e4b6e039..53749488 100644 --- a/launch/crp_launcher/launch/core_test.launch.py +++ b/launch/crp_launcher/launch/core_test.launch.py @@ -42,46 +42,77 @@ def generate_launch_description(): shell=True ) - change_controller_ThetaGain = ExecuteProcess( + change_controller_fbLookAheadTime = ExecuteProcess( cmd=[[ 'ros2 param set ', '/CtrlVehicleControlLat ', - '/ctrl/fbThetaGain ', - '0.0' + '/ctrl/fbLookAheadTime ', + '0.1' ]], shell=True ) - - change_controller_fbLookAheadTime = ExecuteProcess( + + change_controller_ffLookAheadTime = ExecuteProcess( cmd=[[ 'ros2 param set ', '/CtrlVehicleControlLat ', - '/ctrl/fbLookAheadTime ', - '0.1' + '/ctrl/ffLookAheadTime ', + '1.0' ]], shell=True ) - change_controller_steeringLpFilter = ExecuteProcess( + change_controller_sigma_thetaFP = ExecuteProcess( cmd=[[ 'ros2 param set ', '/CtrlVehicleControlLat ', - '/ctrl/steeringAngleLPFilter ', - '0.8' + '/ctrl/sigma_thetaFP ', + '0.25' ]], shell=True ) - - change_controller_ffGainOffsetGround = ExecuteProcess( + + change_controller_maxThetaFP = ExecuteProcess( + cmd=[[ + 'ros2 param set ', + '/CtrlVehicleControlLat ', + '/ctrl/maxThetaFP ', + '0.3' + ]], + shell=True + ) + + change_controller_targetAccelerationFF_lpFilterCoeff = ExecuteProcess( cmd=[[ 'ros2 param set ', '/CtrlVehicleControlLat ', - '/ctrl/ffGainOffsetGround ', - '0.0' + '/ctrl/targetAccelerationFF_lpFilterCoeff ', + '0.99' ]], shell=True ) + change_controller_targetAccelerationFB_lpFilterCoeff = ExecuteProcess( + cmd=[[ + 'ros2 param set ', + '/CtrlVehicleControlLat ', + '/ctrl/targetAccelerationFB_lpFilterCoeff ', + '0.99' + ]], + shell=True + ) + + change_controller_steeringLpFilter = ExecuteProcess( + cmd=[[ + 'ros2 param set ', + '/CtrlVehicleControlLat ', + '/ctrl/steeringAngleLPFilter ', + '0.8' + ]], + shell=True + ) + + # CORE crp_core = IncludeLaunchDescription( @@ -114,8 +145,12 @@ def generate_launch_description(): change_controller_PGain, change_controller_IGain, change_controller_DGain, - change_controller_ThetaGain, change_controller_steeringLpFilter, - change_controller_ffGainOffsetGround, - change_controller_fbLookAheadTime + change_controller_ffLookAheadTime, + change_controller_fbLookAheadTime, + change_controller_sigma_thetaFP, + change_controller_maxThetaFP, + change_controller_targetAccelerationFF_lpFilterCoeff, + change_controller_targetAccelerationFB_lpFilterCoeff + ]) From e9c9bb27a13b7f885004f8fd4202c298c0b65c0b Mon Sep 17 00:00:00 2001 From: "Igneczi Gergo Ferenc (XC-AS/EDM1-Bp)" Date: Thu, 23 Jan 2025 11:42:22 +0100 Subject: [PATCH 03/13] adding control document part --- doc/CRP_arch.pptx | Bin 125494 -> 170403 bytes doc/SystemSpecification.tex | 23 +++++++++++++++++++++++ doc/figures/compensatory_arch.png | Bin 0 -> 206564 bytes 3 files changed, 23 insertions(+) create mode 100644 doc/figures/compensatory_arch.png diff --git a/doc/CRP_arch.pptx b/doc/CRP_arch.pptx index 5cb6b5522fac4c77fcff0ad7cc8567de77523e7e..b686ec52d438e1261a76a821a1869af317a8a6b5 100644 GIT binary patch delta 52068 zcmX_n18`>1(rs+#i*4JsZF6GV$rsx;CicWmCN?I?#I|j|x%bxpYFF*5-uqPTgYH$Q zSFdhegf4D^!&a69hX8;;fxv)(fRKRjSNBuPfPsKG;WS{AfdLI1*NFk)*Ho86+8c^2 z&Ta0OfO4$&_BE+e523&{Dp))y2y)x6Pi95ldKa{|z!e36;8q5-Nr9`~Y~2-Jy1lS9 ztyfgEUo`7ZS_O?!`pM|!@i^o}Gf6k4yc6{wO!m&~K0lVOP1(6D4OfGoX)JdFBb~Y; zVs4D&PJE3hRX~yv&cA4Ks-L8CzbzL|dFmjzeoqfI6Iuzr!@xIMP`-jy$a}nx)y_}^#{PkIuiHTQ3Iz~A%+2B}otE8Oo|^=~coKTA3B z;EguV#G!OWJEt)38TYk5q_wEjVhKWq{54j!J4oG+9q>ylT|Dx;)A`FK`n&!}EgLh}0DPEGWU z6Q*2#nPf?V4CzmHf;gL{vtcr^Ugt(P4DCW^GT2EWj=bKl4=mK=yMot{L@Y8*U=r2X zaKOQ+;R!gOpbA-`vDs|d6UTE^y84IX6bzb&O5LmQ!M%r`yp`rI?YAorvspcpRQSd7 z;ap-!K7M9n-KRchh?M_o4gb}#2ZHy;Ghxm{UN0Y~`{#4+d0nLu=yBE?hKuFv`w3~2 zU(IUE!y0P$as?HR- z4of#q3LCqI9fNb{eg?_KG9yPxp?r6aGT3$2jX(vN7qMVsNRxUeV`j6UX>@O$FF~_V z9hou(YVV4p4+VRCIs4hF^Wf%ibtfo#P7TWSIQJS+VRHOxZpYMWHdx9!pu0*FsS^B% zo7AP%Tbi@29C6M@%lr9&tYynVZ_ufwlaD`5HEPO4vOIMM3bl2Zygp18_pX;Z_XSx3 zQk<{oK6DbT*G_Sfn_oA20eEOoLh$_Ut&-m_tX(G%x59Z)I0WGayz?_?;b>WCYJO0c zP3}dbAkf60^PtfP!b#VNK+A`ue>;Mps&3(8Z_=gU?3^HBBJB9{QnYVJYkj7i=vJPd zI#xP(hU6!+Z4ZojUHM!tqD%y@SNzz+H-GTruGN?jZ$6OtJb{1Z;Gxf;KK#`V0KxcM zZrmq5XA`9REfrdKl+}}0-d0?Xe1{4KCs?E&>s$uDqv5(peVx2e?;i|&@6ahh27u%* zgp}8J+!WCJm8LEDlSBCOO$%jbS`d(GB=D5{Mob{ve`CR4FM&+PW2+1F8~SIyMNM37 zyAkdgDk~|QCDzKMSEugU*9+Mb^Tjj+pE_+9#Vb* zFzI@)Nm1|wiODB~Yj*bQ#yt8#$C7m#3QGsbJyuZQKSpHjkXl0oQvzZnJ-MWsGMR&z|D}bD1{S zr>gKbrcdX5c$tJg-xP$-EsK$Osz>fZ#+wQMKDIx9Tqw<_>L!)omwut|t+<$>J1EO$ zDOSi5nBUC~tcnYs$KRWl_6ZeZlREO3RvUWq=OP#>^{o>aY9w@(;eH3g)LT);J}8;y zag**t43lz7$7mDF;Y-l}oTm{3qLJ(gRb%!ibObP2I2%rPWPhw3a~RdMC`HpmL#7S0 z5sS+@Ox>xGX|q&%zp_JE1k(#8U#wd3X9Z*-*YoZU-ZwdKU z*Kadj{UHin9{;u71+$F-4CRogQp~=c_H%@HKrN-dSfarZh%< zPqwUlINJet7qNRYgZ&=|)mz5ghMqxRA2WxyhhS;&Y(AX+juBWy1K#x?U6v`g&DY_d z!LyAb&n_nt%gugwpW_ce3GUjLAL`vN`%PbXOj=zF&fdx*azDQPh2X)S?r{CDk$VC^ zPnJhw3Y%sm9Qhem+ENlmn;_SpW#0R}Jn-Dgh$LUnYw)l;J=2tUg(kM$dkGEA^P?nJ zjk#}yjL*JPGEIUyzNJ2?l$wjTntih@w0Z&x9s3~Nn3`_M3uYjJGY5Yd0}Sbv+s7Yb z*k_r#7Xvclm-!pZMgG zeY194DO`6Zm-hr0Ffr(j|2@7Js9ITRqw~5b3)Z@No>sdNKTC~H6`r>V+f%nLDOM+~ zE182$(q1`0#o#9ee%_<51NbLWmjD2M))>%z^ zxI+HIZt#=-!7UJgabfo$lM&asXT4kmkC)ojslw{))gIR+e?<=q__=~#Hb+}&KCm{r2xK>XMayE<=DYQ|q^Or@g zlIRR*;&$HHbraFYxj|3A!~swb3A`>1oeL*EeE+n%=H3UpIaR4I(@kFNZ)zm0JYYBy z9gQTX4B|9XH?&6*g-X|SW<1_zqDPezWmlGUST0P0Z6;D*Q@j06tZJSWf~96r3zLgJEcKF3@68F6mbbK9E%EA5HDs=Lc#%#?_<-&sNH48GGOnwH!{W@1v?wt z8DEUBwswxMG#15PI*yVmNIUJIkpEOK8iR>KSVoPJUYRSFGP9%T`6(YTF_!1M2ON(9_xhAul^d`=?9jPO* zhScaIT69pu65MjinTak<<|4Wi5j^#Kn>M>+`94~3Ec<>~nAsUD?>m2P3W#8D365@O z_xR%6LTiJK=7>Sbm`EVQoHzLy=VS_$dMaR0)?{2q4&QX7d}O;3T4K40W|sqP@Y-tJ z(SGq!OUv7T5w+Sb>(p%?EkIy=%g>$h-i8c&r0IU zIqmal=A;4v^C7aIPc;!>NYD||y%JQu3?D-9@;WzQ+$(MyDncBe{9e~N`|}IPPK4ZO zeN`~CxZOuFx50e3abLB3tsn$w$+sMC**u(c9g8h`*+K}T3xDJN z-ap^sE_g{J=`Zb75F=*e`iMy=2)O42y0Z9je5}yS*p`?OQ8AJXk&>#$s1iy@(_W1x z8D~-VMWuKZh<_+1cC=uxFmV7wy)KQ^3=YGo`wtPx3Rs6_^Qp4sbV5xDi8;)I*c>m^ zu18i+UjM<#*evhoH8SOJJV&ii>^XA1#rD)wOE8n|=S5{YG8RA2r1>VKj<#R}3M}^=-bAt<3XTHM$VSGv$v|Meu!1VQcEcAK* z3n{2I2DHs|@w?7n>MCugb6PO-6d~*_ z(c<%~y5=46;+gOA`4H%#wE~sbe{;UuJT!~lDfcaYXT^Hg<^1>;Il}S&Y=8N+IW06g+r~_~&73;5&OL}jMANf}wlRR0scb{(g~L-Et2}G-J9LM{HYCCh zQ(SK;6Aw>X4nihO8r70sf^`W%p{krJONCbCmOSzxObBGHZ!=M)s57k(p2x_i`dVJ2 zQ-oM}!yJJ|*3siP8tI?(FR(lM9hww zMiLcQiCPY;P2LqZn5!j=)3ZYG$U-(|tD5a&lQ|%^utZTTzpHz0OKGrVI_vygQ62e3 z`)LwGKMstnvI8h<2y5^NpA`S8f{V;vP}V?Vz-p_a)zJJ)sSyTi<5gKTchiADq%3q+ z3`>Mxy2LtIYlKG8oZ35$PBAqyAc^ocBiT{GO3$)d);-M&?Bh z$v(;cF++X$H0OgN*V*96;7%u2N=E-xVZc)g{j!6=D}IKSdKq-~&xl99+%Ga3B#M;q z!a(3>xOA{u30eM#q~7T^auB~IGi6EHyX5}NAD#6qZxw!fyX`FT(fJXYMpe2{2DV6C z)1(DXQc2!AB89@bEAz^O}IcdI=`bq+sGhLE=NWFS=`sq`Y+$*KM%YN=l_%Q8Ge^*9 z7@5%+=Xujmi*J8KM@sIV{r_uKGdNr7mdh$-v-(*2QAIe9aC!1s$t##~fqaUko1+vP zHlczjsKliCP^V0Rycep&@;SQ0vFJE-{XJzOqHKt}rjD^gNGu|u9#Kp9*R+y^V1&YI z7GOT4f#A99+`?m+TT!*yx-nS8tbe0XO8_#cN8}|q7uabrsXr(Buz|*V_Aswiv zy57coK)?JtJbIzwaXVdZ1iWyk9CW127ux1OH~YNENmy+j%+CIfrICqRg2;-5FR7rA zrXEa`=h&rK?IT%$=cZOIOi#t1bec8`k79iBKlcdI{k(@*hyx|o(|nQ~;T z8eJejf=bz9|1RDElJ=Zg{>!`mdP93|xmWS2m)GKdI$|X-UT=5Q2->1y~$={CKZQBZE%nzp7-ers_M31^kRw_c3xmkcR5Ta9QsJS zdaO2FJ|enEEqvN*OO8J8VB9plM5HM% z3ShGH(zi7Ps%W`ORfVx=xRCwnu1cf^(p&e5?jp1I+zVtSr=~TfiZA|UKXlBMtD7{V z=}U?#6trV6eQLiMivF>rO)}?vbD)~$0H4z6Z9cTbOk-=)0)fGJhaZ#V zK`P3Ni7>ok1^7pn#omvtzK6?%D0Zw_{CYZ=#zScYLfZ*br)rH=FIFI4LbEK*1)z{t z#JMWWpb=*XKq*WIxed_K2Ah(%?~iGpnoHxN0{*CXjaeTj`>!QzZ*tHyjPz%yKR&Z~ zg&oEvQ&v#S`JrSZ3ufEi9bel1eOm1yam!{-=@LC*kM!v6Aq!PhD+|01Dp**AO8SlP z8^JRh2nK2a@^4U=3kTr@{u>iCzsQWkXV(|Da6V|t6N8+sj%Sw;VrfTOS-?X=t2Pdg zX3XU($u2Ja@WzO9FdXZ^am*ALR@rgcl$5cp>1k9|C16qjWN9a%L!=ay(a4~zV=$w- zOZ}Pzk_+moBAoS9xf)MRWlKo9HXX)8#6Y_mQPDN*KjL`enJrO&=Bx5TOaobA(mqjC zwqZX)W}|&D#l?TTTS`dUqUrU;sKu3F4#@!{P~#dR_oOLQnw6@RgmEBHK}q*KP+8T z3L#?vD9SXAbE`rp$1j&25_c74NHQy6%>8#K|AEF!Qd5Od@U6vYBGS@JVa5VR3%S3F2***#a)k*@98V=nm0r$s!7*V(KW3Sg?0qhO8BW zpaT+RD4cZtiAJ=@WRzh2TW6pk$;hfe34+i$UNR@qn`!!KD2#|^TM^WNoAoWM9H)fm8o4+KI$NDD)Q(}%|Y zoon#%Tzg%A@~r6%TJFe|U9&QyU-4EVVY=V38CV*cns8Z7%{+B9>^BL^Jt#hX@Jsc1 zf2(oWTC8!X5&K~}nj|Z~H$GWPP0P%MK)K|_i0W5RH~c)ej$tCJRSQ{h6kJ0d3l>au zav8V-n|w6%kSZ24TnqG(EhV#`SF6}95>f-*)d`>{=6^*!rPt$e(PV8T7)ar2@gm=A z;DoiHZkQk?Q;0J~i@+=a!?|L;^DvkRLgoJh~T z%(Vnyyeq?Gbism;);aqt5}rgw7!M-{lf0xetuYbjKjjBB9pSIulXb#oGBInJC7{-G z`Z)RU!0LBd&?XN1~+LmthiZ~3O)s9=>T;o zP6|u;hORGmu5!H`PMxfK^vRr+J4KPs4|#}sdH?#d6I~z#vK1bGp(jiQv|C6k)FK}9 z(|qOorQP?FNf+i%5$)73PWnhB(YpIS+4Z`4}> z)=_0k649yBQkk(2Y0g`v!Y3U=NXSHSIWtD}7sTQLEO1&uNa zmSmM4Fc=IknTm-=*%rnmFfLccKCYEBFaJeFD`lvT_(2Prh4o2d2{qRW^kGET#X@oo zTpVjemn2z~goYTeT$>M&8cs(JO)fy!s!gn*aWzX-SQ+Sun_4}~tabio;a_Zk5GQ>o zG0>9lDOr{wr&EotoH>bKLeVug^pPo6Hl&1;CZ_fXwMWnOu4h*V(d4IvH~j&BI#=!S-LI3Su#TNvbwWw&z@vJJ1VGXZ_<+mD<|2hI;n z)Gem?teXKn5&c^9;b8>0>xW#a8M;r8XAbBWnLIbMX*Yd zTBrnjl_Z850a}5Cq2Hhv1^Xh2Mp zpGYZpa+Uq2( z*BKgxf%-R#n^8|xaOJ7g(?}Py~fX`dQFXljGk)0`B#;%y8Fi)T0DAdqUJf?;3tv~%hr&mB!P29!ppsw zMyA`GMK76;%ZAYM9=E(MMm%Lh?KX#{Yr}{R1ZX<=4h;<`IDPE`du8gjLm&w>ezz*Y z>%;Q>$G&AA7_hcL=`+(@t&0;c2vLn(WN{DRZ5~Q&S1P8GeWuQqgwjIyv?dC7$A6sZ zIK_h`yAeV`03TLamEBl7$%8bkt*s?YC(br)^=H+&DgA!pda0>-pH*7pgikK=$Lg?> zMZ0yr9B;NSUv;O0JNp4O7qC58cp4$<5(A>Das={F9*zuOwp~{FtX+bW69D_O_C{Ag ziHFA+y=f<$vLuwx6zblXf~%AV?dC7&s|^xrYhHae9NtJWwJiFv=&NZg8Xn6~$|7l> z^G>MtA?em4l({&ai0G+vh3);Ba-a$XVdz`V(dhl7e1hR!U3J;n3=p+6`!Z|SWGEifz!5Zs9Ncf*l8JpHwA&HSD;`N)hT?H@j0X3Jvmufp78 z=nAD~!;v)yU-9Jy$dPDSWCX}{Rx0~($}+cTlZkqVvd5{K(HBRqP%EUd$Tq#8vL#m( zkXJKbW+npapspJHw{~j9bR)` zR+ynEP(zR8h9S_g2(>q?dJXDnpw@83hleiAJ7av8s%hhU8wkEUsMbYjJj)HcJXpll zepwemE8fRqoj;@cCtBMhD&$bgo&EH_P0t|w5>tTF+(sDORgwlZ-XK#SN1Vbo%~w((ab{G^Q0W9>iAG-w`yQHO@Ex}QC1m8Ct+F>DSv`$OTbD_A)O5H zb;ega`!!Tzbjb@ zFwfdXet`}emMpZ8`w*96#bl_bB_TJ80yPSyVF%et(N3}*o_2GAc!Q-bt|;vDb`Hif zIPH)(&}rEzBzPyQ&%r?@u}Z%rC{j;Tw%9Z_Hy$F|G@tmGTS8R=RzYE^#7{ocjxsd4 zNJ+^hM7ijrX*7^Rs_`x@uAZk*uyw|AG340VZdi-IE>CkEBJo)eoL4Rsk}4I z;kTS)2=*w@C<7nr>H10;AZvIFx(2?+_j1>>I+*|+%4O6s>j`(Tb)`(=6^`2|Ad5HE zI$|1!clj+wZi=a556KE!EL|ecVjVk2?<3qdQ6uzQVN}*+O;8x-8OpB%Gh1^L7=wd> z7L(SVTtHE-0og!}M+540$70c#5*X$j1D*=N>5h}HFqT~vX9ieHqG0J4vYX(dCgIYd z(~^2@SH+ixMz76w#Hme|JV@=T2cUlvH~2*VRQA(0<0J? zs?BHU$D`>csu|WMLHzO7#l8eUBCql$dU8knA1{7-S=;sqbKI~N6P^(je(jE*5$Up| z2^p9K1d@5<2EXO>@uy`M7NTn9$itUC;=dH54n1B9H5Uj41VFqGUw@ebakx%r@KvUM zA|3$8f&?LIi2}OY&|87XR|$JP!>UcV@2G*f7)r%ydq?iK^O~epP=f7@{6s+lN4cni ztvaRJM+r6SwOds@2JyB(9>2fJor*XWT{(01TZbpJ2=g%JDf^`yX9_DC@+V{Ov#>kH zplfsgI>QS)@qr8qu@7Paa|stC|B_80PlxFRQSU~9)Zz1&bPza~o?SJfI)_E1yMa1M zIIHf~G8+aD33ttxQR3G`IKYvXW&Io?mxRN29fE-09Jh;Z_WW5xc}` zof%^H@h_RK-@Z0@%_}3EdED6>b%bXR67_yDye6#&;v${ZOP%*_30Uu(x-Y(7eBz(W zU|dV(dcfIu{kW3_CQylW5g;F8o&PAYA2)emdpSMQNhR&sZ6%;Kqe2znZhmUtY^`2f zv~Ru)RjxX5PlzlbZw4ZV6K06tR5{{nG}{Rxml>)l^x$lLM4MUD_I9hot*_9E|74et zl!Q2?-WzkaQIkQp*{J&s`ONW{Ss0r>MO&F(P3)>`OsWtE+@)sE^g)pap*!+0xUAQ8 z9QJ!pC^sL*S5tKPVZhu%0S>9NW5;7P)#R?znsf0PcG0gnwa@qaY`U=QY55%Z-se#- z=g>}vfUvaS6h^Spxpf6c*E#Fx5ysF=r*6&!?c~Mrcb9^5EWybF{V*aP?IJ4gr}i4a z`U<8|abivx7-X#|aG7GjSGa*y7o$2Lmrf4Aqtwz?mD%kJztC~=3i9blaClmOs?O*W zK;y2M{e55)KK>}T1M4IPqC|f?R3Au{&6+l=bv$R50ISVkuHxfod~a7h8mh^)eZXQO z9>r=T&FUb#9R+M3RrBf2qgZ~3K=xZxMz#ngvrd%&##aMqaA;D|=#nr{|B%P!qP}}E zKR@zG4{#$+D+_F@)*w(q77KGpogBez;uF>J%um{VP!@>(pgFPfcyaJqF81TcRrGmp zjfBSaE5y7Fy_h47VsDX1=1j*G!;a1z4uD~ol!OV!r=W??Ez{qHwo78a4rwlvQdPbr zERsS4Y6VDwa#2%@h^mQbr4f^*E^62Zs>}b<UT4Izdk%iE&IPAcc|cn8~m{GMYjC4Kig zR7{+9LOWE9Q0iGRyjCy$QCICri<+DT{H_m|z?5Aa)(S*h7)zz@6^Z;64u{$YZ$%R; ziAsrt^N*&T2arvYk$BlOxLgU-sKjRd_6TB1L(A0=khc7+OeLiSd}FvrX2Q_eM&1k_ zif?jkTNlkxkM--p$EC~pCRCX1%PINzs`t>>51Rg+OsbJ$A}@{Wre=D1tAlq1io@U4 zfI~F46D~~RSC|%vb`+OKI&gv}-;lHTZH`0b%?7e!a;9uGXFLXR_rBmmjQFv9#D@PM zjutgdocZe+$SK?d@@PsXaS?S4BJK<(j(SG^{)!#D7|rgJf^nuzYvuckl(k|%kQb?9 zpZhOwyr%r266j$ID#Rm~l=5>Y(9(WERI{HxVF%EXbRAsAYlQF)`k=;akj{_a1Dgnu zIP{Z)4>vAC=NWBm58f#}m<>QaJkqiP!U$&uipmjLQF|Yf&#oiisUy?}(g~u|@C$R9 zj2MPEGOWeRGb=<8lpHi1T6yTG#Vg0?snfp@ZjMDO{ReaC2EG!Y*e>@G`0h<4{lf$c z2h998C72DQ^3X^N_Hq5av)~Dsfmi3rGZYWXsOi!5j)Gty9GY}h`=5Pe(~}mOWKaY8 zR8pjRLvIo|M#ni;;y$o3unRTf$j`I1uFrG$UlM_|n9HWzSKf3GveUE^V^CPa1c^zI zqTsBJfs{{dV#KOY5TLgxz`{rdoSapR|2%1O;t8nCMl6t@d5QD)K|a*dQ$LG;TZsL_ zwDCIRZ%#Hy>=%~bw(pit0XIKQMgA3k4@6a5P414w1aE>5791&45?;9q0@yyw3p}8R z1V0V>3Lg1_406WPqj{#ui>PH5uuB8T$Fj*qr%>^992Urv_!;%gcKHWJO9oK(~ zWx=-``a*(K0{feLjhr8HKdaE`lrQb6G)J-EU*1}bLj4u<^Zv1BY!es%Co6eH(-_TY zVzMNVEEcbVD>^FF@oArK|+a&^fNFG!_-2SKb2_-1%RPi54&zwW*FA*CJeY@w|j)kqg z?V9a5$+Mg5!H@qm%}@%^%h9e6-&&(cx0@R75L>yHzSI24=U$~_IKE)mFOb|H2y(4; z2xSIs_N+WcICuf(oyNZn-VHj2Ja%1V!ypT>{E_FviMss>V@MYK%MczS@{K;{h zNdAigA_ci=?tAn5-S+$1QYtZ|=?y{{BnZR@8+1`IKwB}=-a`=vn}aF|-Ngys&R0>| z{ob92WdGPQ61x^oQIh`SIYCAPd_HL#10Zw*BWj3vTpt zbKh(^w^pi(l~dGMY~q8uf)xtOEJr_)4J9~jv$HZ2Jn8raTMCLs(sT$dw#Vr?1U0!t zzJwd|gIQxFMqa5zITjOdBlnb}m{NM1^hNlD{}xU^QP~_p^VlNg((-#Hp!&W(zUah# z82B48o*R* zp5w9;a&9^q5r-NLU(|lXy~8zQsqg=fxho5BCb-!A$K2`oar(h@^83$GbYq164VIb9 zVWZA%bp3*{kulEtC9sr07PpMY^h6Bdo7<=w&qAw`U@cmYpJX z5laPVoJdw=F}+v7`>xj11Qh+s;Akn^Vo9P7M^BX8 z>w$0;OZ}-~USEh?FK(1h=Nra6By7&4{v;ap$B;tOXqI+kuG5CB!Zn1KtKtf>k#FKK zNB$n@ci~P%EJ)lN!bGH=27V}_@mi^oR&B7rDfXs~z6qu+`_q031&dKa(KM(eomf!%IvM#IwzFcrer6v4c0rSc5;0YuluR0Xis>E7LznO(G-p>*CmG37B+c_)iiZ4 z8^6qL!`0tPSK~2sAX!%Bw?y4@D0^LpW9PYDxM;!Mbc0# zaKpIvPhHuS)e9q00$3iSZdaJWj*J*ybaivSsnz3qY>43l6CBi80x&Z!;GlPD!$|K`41snt<1|Hol8>RL579o9Jky-dG6QQTS# zsoydviWO0LG`R|Gn<)K3(tpx}0%Q_nf7G9VU-CSe@{vW%bEV4hkJve)_=?V_aiSF#?`73U$N`xZ|9e!DBjsvlDQvjlEk zmTq+jeAbOI$EMv#L9K*mgbC@1pG39Rp0Hn$eE`vw!lhJE4<*CR6dIpA9=or@W9~S5 z2_To}qexaR>398$EIPe5-PFG)Vu5zdn12LcD8Evw&hMSWnhd_tyk{K=qOm=4Y z#)_F>pA-#|l#)YA9rkl_hF9RQ59K~`U|F)VQZSQ zqOoGER5UrEos%gfGz4aJb4y|x<@Gu5sHgWwX+-2m(gMU@PO`=)G9YYYIM#wv;@vG+ z%tms8RBc08?=^CfYKvCG`V(s^A3P#~b$&ewRJKOWVT!D|A;Bs{)XumyjTc%cJ zyzsFzjsbHi=A+jjF25s7x0bsFusf8P2UwD_>v&p@5m+`{+dG>l`8D2_B3HwJzle6E z+~A*Sm*!bkb(4k5$Mk=F`rk}SwHtpkLxL;&ToShk^b#iB!K?tM*}1_-P2rK^L zIxK=5!~T=Ol}m_C1TBuZnr8|P+;w&S=)Jw~#b_luv~)@_gSQX1jtfZL=1SY1bp!%m zVR-K=R`EP~wJ&Yi5nY=&`W8Gm-SONFFvdG;LU?DgiM#4B`!&=KL{iFiTI(jO-8)$} z!y}u@H=$4pmhEA_giCfpE}8bNY`E>p=G)~bB{bBt;^yBt6GrPy&+u4q()vhl11wEI zeq@ieP{1xsa4(_9L=hZ(LH$RS-ZXNH0ot_kh7Q*Fg#iZFm?WKR3km`fg_HvKMesjK zI-`rZoojbSzfFiRO89kHZ^%VYU6YKw>d%f;(Zcd%!QVfN8UGqMbCve`W5H2~@;)dZ zom8C0FRcjkXGKSu&$Qro=xvdI1QSG}I+O6kE3>9nf-5=}pQfVh$cnp?N4u4v> zRKc_4ovnQHC%j~=)mh7jDb;l%SPjNu&LcE<(pQvYijmB#BWdG(`u8eHt;2cafos~~ z|DqImfdExSO=}9OV1OJrMzD?r6BGbIHk$9RB!yJHK)Fi<-@t;EklG9axkz|m2S!Bj z1~Z6-DI+IdVnJ1tz7KACDsLrbuh1~rwT@#VTCMGF@o)+>O4NR1H42B<=-$Uog@f%* z0$5c86TnaG_Vu6vJr%cMaC1eC$7%bg_+K3T@5hLp?XekTMuEQRne#+x(`saEF4dk< zg$tLb@DCK@T_U~0hDm@rcKQx98|LF$Z%7b%WpV$ruqOr^+LIdCWO za!glG_=3NM&_Gp_Ah$v~Z=!vU#_yjX_)9i10w#!1qkEd%`Wfm<8#AeBaZ5Iyk>wm4 zB?Hg++`ZbqA^+=h=N}lLa16I3`2TS=Zulm_7bZ~Pr0ftgApAM_TDh^!n$I)KgOhYh z6or6@xV0S1E+u*BPj8P&YBth-zr+|TFeN47I#;-@YqkzCo>+s-OLmW$6!b1=@M1v!oWZ>c7;vbxD?JE6Op&m>vtU7g3_qi>#syjTsQu*QcbcX6! zymb>W72{IpYlOB?2Eb6+Y@2AO%C>?E(60jjcpTW zqp_+uo$Y5^?9LF_A8}VDt0RR}U&ZvAmAvo$N+rN@K*x&+ZBm)vE7xggpKtpLLVzg^ zw-^wo(Ts>~T?(Lj;LuM=76W96I&B0hpyHr#5Zj)^8jv6$R2Uik3ZSGJ%G;ojz^Tkh zhYikuaRT{<6x>-RMJ{0w8w+kAsQ_{u%;q|m+=b;6+tB!Kaxm!kIa)j{h-v6!b-aD(Qc{+o`)=UV-5+g0zh<-vbw%GkW zcFCD?k-6-7RN7^;(h72th(&iL-Fi%`3T{n`_UWU9wkCY3YVRO8U&WaPXep$X^W5Q0 z+liISVql{wbaz$aJEKruUVXel3okG>x0;WD9By&cs*^Qvp!>YgAdNhG+`XjLg1hv( zsQI(@@mhSj!PWZE-@Lba8f(_UDu>B}t2sXwUA|7fs`zYI5D_|Vmpo_NR<1s=pBvK! zLif(arf-}TkfL)GET0w#JRf3=v~+-B4GqD$Yl1MjuDwF+8O&uPo7^{T#(EG;YG!oZ ziuPbczH24yX3>?egxwTTKzxOQv_5zffm5ZL5ypl>l6JxejZ~K0Aa?mFKfN_tpE+6` zWy%`LHzaUI+_}#wgs!U^hj*T9{pG-|ea?>U364dqWdkIuTQ z3Ic9#69WyPdEK#Cbqn6~8rS+xrtsg_R?ud9kSb%VwJ1P00YZ2#eAr7YxA}1_cfs zC7Bu`(@R7)a-S??qnEA)l|8X_{+p#-E_m+oCSwXVYX7&fqieuSlBU9I15evTnX+X& zW47UB`I&^dj{yt4OWs$5RdwUoL=`KSE_1s2hVCC(`|0~H;7RgCmVca*hvYWr)wRdI z{79DI7IImnM+xI?l3_@X(_^z|STzo`e)k|^QT4JNlRowaNu340(xOPq3^%hj7W5m7o!F%zrvYj2NlRjfgHv-d2V5y}#2VTVE zP7wS`R8!>nphBvZQCOvfGAZk`N^sVAR18)eME9v%xCIL8Q{{_TO|Y&%a#^&DTq$*h z+y{s7l+&wmvrk2hNAcy}ILtg7O|*5gf}waC*- z=G0yvpt_*&{KEG#Ch_~lmO8*Z&o%5iQMo0socn5YAt~8qA5i=CRlBC&i;I7}r8ZhB zl0Cy53-XT*EJW!dmY8rxQdHg(L968YbIIqx=uL7E%ZCa83b+g85Ch2g1m`7E)QoWn7q@!K|+JyV2SH2 z&S5td_7kOCF#fMiId(gZ=C)svs&RM}uZMDI(y_e~PLZK|jf&elAtTY&=j&jEC(u9S z$FTlLU*m`dS7|?=GrkWstSO2Zmzs7^s9+>(LSU@%vcev*?2Wu{dB|1ymP*>Yce$+* z+g3~IYacRih`)SvAgWtogvJ&7*rKnQRCSoppWABN;exrV)rm}Tg)(tPd5!Y8Rjy5r zKMe^$C&JJFwk*RH6)LfgLx6x7qW=$a3;scF8>KdAJUH|^i(U5*6w9_QJy20lh*dPJ zn+#9`Pyt{Ho8(2{Y-`{T=$3m>b_pH37h0L|^bn9$k5z>yLysi;Ko7bHsXK~1oaA(( zMg~4-lftb?GMl5RJf7qHjuOLe{&CeGm|E_t2YTS`CP=Z|3DGLaMD~bV_z;1}v7NB@ zDw&wx-5i;tk2{A?&)YrJT<31h=rb|aKcr*3w-A7BP$^|JToHr3*+V+ojsWxA$?Xw| zw6M4jT>?ZY4KMnJCbvlW6vQUxap=t#o4ng$uUzp4E%62VnH~)kwR=J*f5o15%iU^%Mu$;v-NWzA)$<8yNw^AdY=kbNPKP&J!G*Zpv|TBG zwhew9t*p)o0~WT-g`3CwK}U7(Ef65QFe3RT?e*21ZC{ z8T*Wa=HY7;1S9{Cxwim{E9%w-X(SLdc<|s5g1fuBySuwfV}S&B4G`Sjo#5`S2^!qp zrb&K#_a^sE&6}y3u3Av^K4+h1$+y3?);_0YRxSY2#YUDVG%!(ukG{S@zB({^JaF6$ zm^bf+y^Ww~IuBa05f)68dQ#FeL|cd7HH%m$2r0{BZkQ0iuaY5dohB)caw;i$x3*9> z_SN_8Jm3r`Bsg9U&I&3R6HvjU&fd{YiP@uCl>Pi+f!}K(o{_~W()mQQ&3gDdlJ)*TQ?$oQK z1;_^f*L-ZIaT@R(!#-ZZlo-l<641KDANtt>ORW+HWA>{**wl8e!@zx-ory=@p2&$h z@|hR7LYX>LhuxwhhAYOi<`L(K2`Wj!)@!1Y#pAX>iv&jF?JJry3Q;~(=x(!1Kz~Z` z4b%|3)P|dBi75KYp#*FZLXY|hGt2++fuqQOPi_DO-2iTHS{qK~x&^+tf^)fgA}mK;@);#X9hpfpzc?u>+6H6|lwD zy8W*Yn=DWkemn%WO?})SrED)nj$QqP)L9fwsyE9{?^6Vn8Maz8^n;>EB%E*C0A#4W zr9bQn^)$MBa{j38rfm+djNJ2vHyuBz>3FDb1J_1u!o2Xv+!W$)-A8t4H zU^^tlut4FlG0UT@Af2k{SyH&irl8;_>ZS2eeV{EpX2bL;pnkKOx(*zAzPk%QyZihk zyN$Z>sOOHty8?4fPFee8eWz%zv8ajOyOhVfwMQMuco>_=J+UdAFob(#_npuTBGmxq z?diMkY!#HQ1*C$W4_Ow|HKa2ip^4|)^xEh@U)~=xGg^O%;3!5Bfc4+Vh_uqG?7EIeXM)mF&ah=HR7Jli)qT8j}DY zte|1OQTJVd%S5|*^@OKdD5E1CyU}_O%y?_2_cWH0WWsydCs2=`omh*q0JDtl&%VGH zm_zt;1Go&}-dQC=ASVr5YzO2#f_GAu8m*?RT!Ae;7?wR0Td#+T5GlKZ7Ln8#P z7)k$vN3rdpMy5%*|x_bW#~r3`%s~0b+{23o@%-DRVh7+O{2#y z3TLWl0(v=M%F3pXh-n~ZSP{GCM(c=dj+}IKpETTUzrzdRfZYgA*eLE z3HNJ#spSVWg9At4my)sGj70dyn49e_oqeG@8`4&P!fb4eUA}6c0Y2&++pdL&2#zV+ z>m#P21-*kKhHROa~R}=~PX++=i#Qb|>{NUZI4mx1?*Lan%bW};L=l0AmD%Q`oHg*WwydKVx z2SaS~>gS#InpiE!BPx+%>0VWCY@@&+^2Ocb_j7MHiQ|gA9*lGG=xZ&;GxthzxjW)E z_Ez1UD>7t^JX?s;z+h#)_!@~=?-12buikV2(VuoHrIqM$LBvw%h?HHXrckvBS1XbR z_U?j%_ZH_RjfJ)H(bG%;Df8&{FJ;!-KmxSEfwubdqn#Z`0?t+kIB}VUwjqvW^R&7o z*q+Pg1&lP77>mH6k+dzBht|9O$UQetc1lEGc1V{zntt$NzoU4Vf`w=Qh?(yLQyvMz z3Yg-~K9vn|4@ILcG#LqI_1^Zpsocu>nbc9Q#K6~+4QuZf>-kHey8G}L1gUcI^+t+Q zAh^HR5}bTOBi5k6x;|~!#Nrb{FPvAjF4AST*G4&=an?JBIlolC`Z*dROIBfdNO+?% zXhY~enybfV$|+UjZ#V@ z6nSmI6fI38(w%J1jJau}gh;gzz4_+(JeF(r6ScWd*7gVDJe(>3?ru1G#0pGlrf}@W zausA?=1G^v=L~h%x+x;RF5gY1R1VVNiOW@C{fy@+ncpQr$cR_kO7#RVfIdjzTh5dS zS0(}1GDs+!{%OpC;)0047S*`hH;u^>HbZOGz^DEMO!C(CF!CZc3KHV&w{)B{)M$6p zd@>zYfz(4M5X2-Lk4PRj4W*m|k1QXFNy_8*Sa4&GvYTvEP4}xxa*)~DTKW?)g`H-} zm%OqDuDsTQ0PWx5~io_*t8^@bhp=rExtGBkleRwJ-;Awxp$B9FCS6ri;(M(h+ z$D4DOT3;APp@SoQ(yWr`n{}(;BIP@uEnNUH_~;953(|?sR9Wd7Rf?v^Lw+~#@Ml99qM>uJE96&b3-~YsNWsX2E>cfG=&EKSPaZ1U z&HIS4I?u+iolo1i2cgY)27CgzV6tZTLP@Yo{Dxsx_k+ewM407#@+)QAXSZFtFCKY~ zZzX&fv=-H+tx8;qw{~rX*1&T@_*s}Z9iq2VnqP{Z(C;_`0$2QyDN1WDB57HgQ~EKX zRywViw{Cp$ESX&R*^gS3(wS>Sfi~K?GUi%wp=}=XusX+`UKJa84h0w5qA0rQKyZ$* z>hcHDhP18s^Md67jf=XU1Ov3YQ86v0htn>45N)5(gxivTcrt?6x0Z5l zrI8kzbgSt)-V&2q8f$D;`eCxIEF%*G0--r~rm&6=8d6!pp~L zXxS@$m0<}RUhSEoC~NOaGgbs+V0OKTb&|^lU;npEDB7!GB=v0}9bgJ_96u5=ClQ5& z_$P)wyj+>6o``+jf|>cX5%wvP)^vD-t|tWlVxpaJvpffK+aevxfbYJVQXV$(u>@bn zUmr46%18BL5$Pf7OLZW9$@MvKAD|$^^nUn$KE6j$!n4eCk~QZs6d9a)l@CzoTHduTbvcx;EX$-yMP!w~7<$)+a`UrRqEvg$Ugpa84nc8c z(0#W*XO_=~~PgzyPhJ|+U)3`B!0F65?w;sWwy_U$)Ul=o%Vs+YhVx+sVyY469Q`Bq^Bbva zn_)o~&FWyim}Yv`_Q8?-=Poa`_c4U%u_L)!O5SIUV@$USOI_UvxJa(3v0 zIg<#GAbu@y3;a6n`px5jgg=h-^FEZUEXxB49!-(v?d;Axv1&3M%nFGep&6$=viS1b zkA!qlP55zmK+^+`HlVVxkh+u_!s<$WgV)ndpKAv1(=Cj#Fl(3XM8$s7oF#dPz}ja~ zI%+|SnR~S zFx(8duhK;7R^PA7Dm{!RJRn#{CTNi8!HY#)$`uDLz)7#j$X6n@kKRB3f+pDLwhwz9 zppt>{n?xiu0CD~OTRyR{`}Qp!cpa*t8?Awqn|@WT zZc|hdTnarO0kz(JguZvtn_$E^d_wO!e9#nrzEfSb!`HEA{03SzTcjHFyyRBW4L50u znsw86x9VcZ_j>K*ZD@-&Ysi;;O0JbLHF$_vzK#cVWM{S%-4TK#0|i{rdhPb6%K7RZ z-gs4hu-(+mFuZOVa*GHihK6QXLViWkNqE9F(1Et(u*A$8*60^GE;&^-W zG_Pmc@hrR-z;UzfhTs|lB#trSG4cO)iO@f~r;)$U}zV?m7TA zanu|z`}>$xYtZ~3IRVCi-`BI*01X!z0tO+kQ4L`0UCIF?;4qO_ALf>-AN1-as{l6u z2tj`QdXXA{FrYrl4X{C;_;CmDrrs|fumddz3wplY%Zm_fZP@SF9@N`<5p>WyFHgO* zHa0TXr!}|MH#Mebrm?dz{VXRViU5oKau$NPn2-YKHx5V$U_hJ}j4)NiJ~5*K@D55< zPD)8QnqL)&m>6pf8o_l^kWmDKgn>oJBV^&=QZw)kPb;r#ZtoeH{IR}sbaC6*gBS!l z?zNqmx+54ECi05_2FcEOL2r7B3-K$l$sUf)A^Ot6K*{ZO$QL`)K0R~xL>EN&nxc*g zrpAEPpLqJAZ+V$#InjQpxER3&P;f$t?kc}m=ZvF{*g=TEB7k7!b=TeqKwbhHM$@CU zHuQ*~jzlL_I#&U0Q+)sM{A?x$9?+zC5e7}* zp$iK^V=lmMX=3uk3v{sS2=Sbv;Jw`U^W@!qbnBqnI;s4csY^HB* z-B{aqVhRlQ?_%QVGmNoRt^?U3beiEr=Hd|$WfqV^RA`XtJP+*juM=nw~r=bf0PZr!cy4MzUm@}A-0VJXs-ZJen@ zvYD>Q#{!Va{^epX-SmHjrU=;Uuzq!QP+Y#qADoKmFHVI4ni1=lQ-O2QEdTF96Q7WU zOBCc%pxDeRuWEmBrkBt(ynXjF&!4;r%<#pVC=|CwB@un!!9$Lp27mpuPH^xzW==9A z=5*LwZ(&N0^&ojzhazV)$OdB+OM?+p@Z-CIS0xuvfX{YA6848i8&SvyT~`PEb#y-s z$wNmU8U5rOiSEno`P7SPZp${nfeZ&kS>pZf$Y1pXCPCz}W(QKui~K=7e?%@2#QcJ; zcfa&AU4Q=if2W`S2hip5KSG!5hP#;}%6AMO+KQ|%w9;`$A5jz9l8M2L^S@JQ14%7| zt9njbzR_2_+r1-^v&CUYx|)C_{D7x`~$qcAmQ`HNebf~F+-rM7Iv>3^ur z`8QTM1KriV)j;E9|HdkOLMjmEzj)RQR>j1KFEhkuL6m&iIpq0n%O+C?Q|R!NiJmeOO zbO*p@dnYlx2l@6&gVY;NNanapGOYVEu~UPNpvAntfZeEuMYYyihA4>)Ze~EdphR-I zA2C}!Dc1MqnT8}b`#?mM(Y>S3>Guu|nuViEio4+BvLRZG_?I{5G@YRaL- z5%{_|f%;mx7~$vVYr>&1E+dT5*WA!RFWwr7GJ?4(5>9mi0fEl;5QA$&!WaIz-C`Pm0=qk3J=acQGY7?YTBF!VE8N{kke2b#vS$Z#}QYy zHKQKnCfPlDE2=06H{*Mn?zxusO`nftYX_>rQ!C#cq1Ko(!P}NhND1Cbp85p>UyI!| z^|hz0_lQc%ob~waH@(#rDON+Mxs6H4VWxVZS;XAP_M<}NkP$2Ou8`cR#3eX1PZZF( zw4nNQ*caoaRQlSYbgKB0(9bpl%m-2CB&silVR6P6vz}H@B0{tu*uD7uwm<`w*SJ`V ztF+EXGgM#u^^E~EzhQuH;zMJx??JecFwS>{_AhWz@F!Y;Jil^~$)Hb1xKUM)Qe?|4%^sx(rIfDdw>G}CZCWxL0Ja_en0Zb2&_q;gJbLfYAsKf)= zo|(YG43LBVnJ9s=nqOC9f>tx`mmhx!CiXuC6KFPikl_AW(Vp${dw<80&+l0B0s7Yk z9Dv3t{}oGkFDu$VL&^1JO-suv1_e@c`%4@x{$fq<2AhjPC;cgqzz+Yx3Sw3q{OR6& zO#Jk!4yGWy?nX0|-u)T#z~)nuxPGtYW%Il`;%n1uApFU;b79Q@0QQmb6r8WBZYR$2 z>&mxyGaNokRUNRTBL-uK%Au%s=D?=W#e4VQraYyI8Gwaj2n~rQYh=hKej#gH^S1zn zM?5T8*r8*=9Ftu9>W*{5QAl>^MgoZt3L1Aj+fQ{l-C}6aiVA0$$)WLxVmi5!{e@e7 z^w}oSz@k^I!V3e4Jx>F(K8;p3x02QgJ|s2v9|&7TeOtnyL_V=N9gEH8KO2mhZl$JM zJf#(je0bb|I58;LE%(9)djf+TM|77`xUK`~<1coj(2RThCxQE~x##6#4pN+2^@GUY^_FQU6UYZzH(unw>P?>#q&ND%=q(B~ zC)qED$Aw#8|LyR8za8EWXpK&73>ts`PlrbYW$piRct>A9(9)5VmY!8yR$kTclEVM? zcvrYMX3$xG@_2BR7mt6*IyF5P>EMIxn|`oV{7^`!R7}7Z=y-mHR*8w9$BJ2SYncDI zmI~}2z?4kb>dKO%crg6{Jf3d?q|V7&4KSs%`)snBHcSPTrdI4-xmrmimHWU&7Tu#S z?leq6XtHMQDeH=%J}|#c5IW?oc4j>I$_^n_Jce$tn5gAno;`3=Be<&X!ZfF#nA|^J zzb8!{Tj)OvLD?+HXvP^SSR-hXyjj$r2?5N1;v6w+eFh`zj?MVdbGC!${F-(5&S-_)!In3->O3wMty4IwRvgR0)s{Gcqk^G5H_iw#+$u@C_su_00q6 z)QvuxphR(d;q+uNfkzwya*JdTK1qD4?0U<4iIHN@&F8sTLuy`CKd+Bjq;P;TuDY;D zkS}N7r+z#Dep>}s_`|!PSHkzOi%VZIh76$0O{>``i6-Tq0b%oy)KUTX{-&SfG~O^v+xU6yH?oo$PcAoorTEHOoQnTu>bzm?N*lLSf#yvKilb6TrN3AH744U1L%)$)irRxK)*STS@+!TGAILH4Bv5vU3meEmTVXm&i`bjoF~Ag& zxKj|aFR+t$rsip%+L_^Q^4)t^$1^MzN3X|Zo%fckB6AEkH88i-$e@7)qljefo%Vey z|+_F-xK z>oxBbuYE@Hne}mcxNlI+oEU*!av`2U5#np@%U&j&ef;$iJ?KL{WiF)}=T2b=gsaEz z%KTI?@?^WcqWC`%%!r^HE|Eco{@chZ|20F<&^!y82IcNA@+TwzEfJ*v&58fZ$mS3w z$G?s2@EgS(fGO+e>7a4af1(% oSK0-{nc6!^u;;W00n=&!2TOQECvoSqMK!k+*P ztmz*Hj$T6Xr-K(l6+%<0fkoekf;@X}H%mn`-BZg*n>Zgg?uuc7dh+7lr;-OUo|7S_ zR6+`C+HRO7QWl)CNX%v&6!mIZ;m+CF*C513BoPX4T(n%g_6tqy#Rw&oZi0DXOf z_P>p>IV(mmy2gd|RLlR``ED?n6JG$Jt7t^}0z5}AQ5ggPJjtW8l++Wt;U~Yr3ZIJR` zk?4jT8NcHU7gG zziXJyzp{`QQ;4Ec-GGk%qbcV9VTzc26#sW`K4LP*(nyGCBp2R4AuWJQMr?$gfcfxp zeKMu}&?&>UgSmboc1s-yG|Q*zfj8{M0Wc+qkhEpL-wZgHPwupVj8bdM5xF|FWwCO=v=i4?fyf(995AV<7yvlJ&L&F%-iVclglHJ~Xzy~EO%u>#FZd*~H zim#U)Woyva*VIhD;|EjPak`nQv2$rKU_Sf=Z?wqShF>b?e=!uA{_&3PD=@GZ`IDjk zm@R_Lg7`v)Ie&#pIPpi^-=Q+|+c+~oL}P`Qj8f#E#(9JO77OnkC|u}R*f_ZO1VqJN zVnz>?H`+P6x`9&1;PA+pxWu%Kto-t-dQj!Lqo;3pWNdP7aScR%k1wuoZSgqTK{Niz zfRNu_4CtnFn1Y}Ry1O#SI2h;>1y(9a0aZG*NyEib9>Av6AG=N9_wAN%gW+nw$yJJPoxPt`X>=R6%6o?w( zr=UNJNLIvX7hShQNk^G^G#1yHy3&44hm=loYDFqv*@D!0a?5No^=bspbnxvW&3wPS zs6v&tM+djpKnlsa^x)0DMSW+K^OZuIP79x^#hu-<^qVim&4F5n!*c6_D%OEgh1EIF z=-WfN+!KgcGst#wx!%yL5ER-YJ@M_+EQW<-3-tG8hZk6l)0=6FpOm1M$A zLxwcp6u`kX#4F*!7SKb1`X!`baM1^*(pYA!UflpPiTCmS&ES5}fd|gXQLQd-s^&0K zjLSD-_o)kc02!mMIah`gA3R$fy(eNV5I%1U3Xz`f9u_LKWAcV4cyLGQ1~whke%N&g zT24vz)*-;vpjkXc5iV3MUZk_=q~GcEGV#d1F}u?wA7oL4yj<7^y1hF7w0d54ZGb=3 zW7fn2uAhLOPbMory=x(BA+w&`TPBr&YMmtCP)kVUO1c)Zpi}y&=CCs)@M!am8RU26^)|nP)A>p zj5?Ni-!0T4!-pQ&5OfN;YbGhoF+6CAp_&aMMoiuwH_x;khKPoSi{$k@Luk2$);H2m zPSkgAL)-$V^0ce%KEOK7JT^{Xypl{&!qr3l-kv4B;Vq|{9*6klbQ(=VI3uYm-uY?A zg_^W8%SsP!sfmTdlfMaLO;>R0M%2EFBU%GFRa;Z2GO+c_$es)j&iLmMwODBB4T8QO z2jvRe)C{^|40Yjg!k`11u~>#SNcRot5S}A!v7dozt77hvGi5_rYMoapc`Q?x46eik zDZRX+VaoTDOi$_pJNK`c!hs1S(lSGQQ#X7s@B_}vCh-Uz+HoQ=FQ3H&!n(g8cGX%C z-ZZG!{vv-uY*0yp_>X{~NFM zUjW+)1lU2rVIaUxO!|%2ziRLQ3D%hpfiDaBpTHVI;vZnWpsl#bhvxgkDg;&|r<5Xh zu|_3a+7i8@FdhR^|M@v%&qugwc+)?bqq^bPkzWN9S60TwQARA9p91(DI8T+^Vz)t& z18g=xQ||5=M=+R3_O{DbGa4!br8sWO_Mqp?O|6wL)1joPd*P^BAz!b*=ZX8!^eGgE zIHCj$IeUcIrrjRG*>x@JClP4w<+m+bK`klh)5UDUOwj{^c|;$(3=oFF*%k z!3UUDvlXWGS#NV_Sp=Y%Zka+ET3#Sr1NZJQOX!W#(c-rv0G8A;A1blpIOKA=74|7X z;(F_@B7_6Uy-kjj$(@O6DuRq@-BWvObL?4OVIy12&bFG^$kn^u<=H}_jDb^3Z}9!< zZ@c2W2J{+N%6PLiuw%K+j0;*CTLC`OLwx~zkh7+O)%cZ^Vktn&L#jqw=+;GXEQwZ6 zOpfNV>yoh`6KaDcapq&r`YL1S%N>}xJEnQrJVnQk!4GknJG886>yO9pdv>Qwgq?Yu z-9sJ+ee2LpCa9_AKifxAjhbk)bEe|aSTLEg*sL(leeDr3 zBHL%OHn42KB&sPvN^T=L+1z-uhq1q@15{|IYG)j{G!cvyKL(#x&F!~#q7i$9)b({}sWJuVr0m4AyYHUobn{cXSJ?tbZ9l64Vr1i5%+k(1-GXwPBt zUbEa2US~s)KwcTSXMW9JW;?MAcH%D9p&49-s*G@5Y7t!rPt}F?LdLi@*r&HEA3HeD z|Lo)9P39QQtfR1k(2dFI7F^Rd5QC7n#0_5=h!$DI8zRCHewd}RkD|ji^Bf|tM2XmB z4IRzTW<@U^1Kf;Pp9I#P&i_5KPo~!|u0R_lU*r#w&G5IHRV-*qj$eTtK#>ag9oS>P z1A7dZY?ucE3NWF61~wvyi~Zk=Y*4;h|8FMtPa>8LAa?mnY(wh3#I~8>VY0d*s4C-& zXM4c|1l6m46+G>eaV5)93nv`t|!)w;fgP13pB#Xef?>d5UeiGdb%u8__t#*3~MK)Wk;UUq%$1`!*l;6Qw>2xDepxn$U zxW;OVJ&%p@^$wV|O!z{iwW|7?`7q!pj+B%%M*%^_c}XS77l@j6*)A0txb=u4oTO?+ z2Z^+$8Ov8va+2I+8BpO1*?Zte0RyY20M4-$4R+Jmr!Qmv508r2uat{1o>+QmF5fk> zhZA}pv(E3!iDNkR70en$LLn^#vd>=Lo;P~X1#DhLFh=;ZZ$X$Cw-kS8!y?Bsw^)4 z+Tm76Azk@%Zn0{tb~7Aa#^hiW&^cuRMN*Exs1Nk$4z21$JZ}w3k9?WMVDX7=)~U@f zE>(lVVP_UOs>V7c#f`9WHs!#YKnl?+}N z%^+m7DD*zACpDtLd93^l%@DWtjQ2nbFzDf1P}DGx_XshNRo1?91J61kNgrpVX2Wx$f#nErsDivmq1G_&-@t{opvy z|B593{T@Csc3e{fMJH&GSoGURnA1IvL85M52F(2AMk9lhzk}&kGk_A*B-nW-xXxc#!a*h z2P)Bkx_zVt)ta_drB} zw8{A1GW_M$jm%zo^o+fyz z+AQ1(;p2_jkmSM8I7ZDkf^sW!o-W$D3Xw(NQ5{V}dmmCy1T|%8sH0}e)Tn?-@C<{R z+!A-$6&t3>j*I-x&)WuT$^9&#V>1f*t-Z(R`n&q|JzE#-wP)>5y4%=muHBW?rJ<_^ z34D=m|B}_$N~xweWS8I-B19tkZPyTo0f|n8sRcn}DnL+dDY= zGBk>0FqSYIVBKu&N_OC)xuY_&bBJ?UPC3RY){0?TSA#EAOx^k!XZn&9NKKqC)c_j1{wbZy_gJ`)@V+inRdt562D&-fWRiltxrG#_ng zM>QX{x$Elh@?5pakw#-@T@jAw@@mT=yaTEaT!fnPSMfuNS8`~}5I2QaG1q@UuT0rw zsEr-&HIfC5(MQ{6%ntnUx~cey$G;#D?#YF-zfKIxj={U25Vpkr1!xX^ns1uaFWYAm zkU8DE>-J4`6P`OgbS6?v+pzj$0gJ35EjOmJYN=M~4!*ZGA?Q1VzM)EOdYnWHPL7d< z$P#Ec5Nn-w4m6a8-MRHOCb==DX{M1`)VdAle79|&?;ckA@UW8k&>qvWDwmbNMoWmyKFwW)Do~%L z_fRFIMwcTVRv)gKO8Ra5ba?_M(wa_Oq?&V5DUD;tb6tJF?v?5;_nBs*a8W!q4O4A> zpUG5&dhTVD8Z^)YpT)Ew)GVc8l&83-vx2;S0W&h)6X*Q80pH`wmN+~AO=WTawn?fM zhJ%T?v5x60tm+@kRRpy$cq`n%czDFAN*bf3<-%zx1k990PjOW@ZXNmZ&>5YflyHjF zhAZAI1^BKSVU92H2u-1Hot^n6xb(edK@;v|nJPBgO#zu3pW>$)T0Tcf?%JqF*7ulR z$}ut@u-3AMV|un^tuishwoYmZCHD?+fj*v?=;b88tL+oMDxlUU9B+mqfr!<#EX{x0 zAc)@4vFh-wx~Ok#D_q1qlKf63%f@2f*5cXe^4C1GTA0Q}RpA@1dLQ8HohaKwFzl{L zAQpjx?y1)P5dUfx|p zpuaENJz;}h;9WB@C7S}VBtMaDdOXT%AGczwFQZxzR#1?9isw-CF z*9*%31ea4^$T?r4QjbD51rl*Z?vP2ia_s^yO7pMPMqLG&nHn*>8NSx)DPL7Ua`=vYJ?!}fz zS9r#)U@~wk4_smnqshV5#=J5<)tn|aReE(z$9ho03Zm(tB*LNiZ0h{heE+<4p*{{X zDT2~ESa0-N4!7~DG#dLVrHM`#qwF*U^tt!4tR7dmY>5?kjd95DOH|lSoviU@f|AR- zY$>zT?~kOQ;t;u-&X&vBV32_W&;yJUTPB=q`%{&+x?};Ck3}+y&g6GdE4}cGW3}gg zoVSatd%4F4xjfvPTBFzJLc;kXV;nF4(z)%2TULK%kQ;9aPwg!gNx!%Wcd@(v&)#QA zUIenku>Q>9)eV=|h4`E1m&&@zg=^jW_L?Wgj@5VXq-cw)4$KsRkz7^dLK)dd-gH!yF$60AD)YyG_p-xN? zbSKPu%knI4=v>WrAUEiuJ~OsGcJ_f$J1Mi&vp9gkHU@8Ie-!(S>)^pEWY1&H*!u@G z#`zXv*FcAp!qBWMkmU+!$#Y{U(^eQNQFq;WiD5`BqNIc@qK|!zn9CHakWzYXi%P2K z&U&8JlpME8p!+zalGvt|Z~Ax`Y(b8CPhW!Ut%HHs%E7E9Vp|C%yg$-|9a2E=YHN~0yOchgtbx-TSnVvrTalw+dqy)SD!SXI zz}~zZ#hq?qd^zH}OO9=@DEblKwKlJID3*S_$&a8|R>r>)KXNWLoEc4C(4@7fzdq)O z1T$CMpEz43R?nBPR0s2{0~D_-`%LRR z33@h)YhD+sJ7ZN-3h?Kyd)SdRVg3irxo+>Y+&jKu1{d12@2}QTIN)po_DI`Slq}k` zWDcjl^y&t7;xET=z>d_I5TXyvGQTN#$dzDiPFQv^1MZp}t%oi&<;mrH`h1v zYU_Q&2gLnc&>P^)?OK`EJEYE94=4KOb!By}wRfHXMpE5$(fhOLqxYk<#2GN{`-O?T{mqH!b)K7pzzEFb?!jHl~ zX!mGYpXS19yPm@!qWSHB9jKBq&k&oTQ=}BLl?;Dpo_+l6RC4%WU@!6~=J}TvJfIIW zW$`a&PGXqFI2RW9}NH$L%EOu4QT$Gi=v>uG@|fdI#C~J z=@?m9+5SOE6+qo6eFGyiOHe}!#7ezh_M`-V3XgheN~LFH<${ANAsZ}%-a93lai zjc%PtCfMox`B}7RwWzGzm8*_VvU$H#I28O1RsR8rW9N@i2E>O{%@`PQx~6)Dbf4fEBk8ahFE1Lgn4|`BsQ5 z3$ijI2@1mW`iHmP9X&St4H*s$uy+#{#r}JpGID*l0f(3?U1vm<$-p)rJZti#5QEOe z^ZPfLW0?`5=h0D@AI0%Z?`6vj9TV9GAV%ANHVw%Z`Z=CGTpDmXh9f0;)!tDi4JMo=zfJt2J%(whhF*^>@)VDud7oUFqiWas``aZ)+WZTjFg3j?S z({|BR)mO9o@iFl9`u@+oc@P_BK&cV!rSMm?yq4u%% z5UtnIBJ6=l7NRv@6GWqL_t2&6_}+KH?!|R~yw;%5d-8p~JTqKDjTj7f$Gsgy-*N}} z#S+=go<@>NeZWO6$y3bvOPZSY;B+oLM{-=J{ej`J{s);{=KPJ=9wm>X!kOmr&z&*Ofp0yn#E}bM?O)1u@DzYiZu8G^XL+7>(gn%ZK$`3PbNYC8gf+iF8DLbo z7}*8`%pzf2#B{W+ma&PrtlUK>6P|t;e6M+zPh{>#;R*YzqGkSUOcl9Y5}J}ZK>)Vz zcdDgq$ zv16ldu=QGs>i>Y07UsIIEVKkoPUl13;RYq;@yHdgBJnK?K2@ z+t(pTZX$yn4$=#Tq)Ynx#xg*6SS+}(z+6OKKPibH76;y^5Vv;`A?&Gm+FDQPN0gC2 z@ACI~wu%cm`z|s!?^|n7$De9MuUmB|sj)BZbt0O1zf6vPvr@?F_Qy_&%IYU;K~Z1K zZW`jXJLKXkFiba-BG{U`~ftx(D~x=aU! z&4(e%vCqJ<0fn8{Lk`Hp8I*QW?w9m;*E7gk18b_~;N{|YtloB&=8qZ7KQGQ=4(v3E zw92LW9**j1MX~Jne7IrRIn|y|DJ5aB|Me<^wDrDft8?+y%xEbrP212*d8i9Yll05y zujMZ87>f`AR!;h!E^Nrw)Pn!0+@V{2I5<77X*4uCTXKCq40b*Omv#97mHw(pJx#$E zVgFORjSG<*k=NA?wbvM;&&lX}vKf1p`m3Lwaz7#M{0z(etI1@(FQ5+tW--;O5vI>OR~3W?=)<2bqQaCD;7J zGzbcOXKC*<;dWsb+(P1Ba{VS_f1W9v?mK*lOTie-@|@#Djk=t_Ji%Bumrhui9-8yw_YqmLrYCf90^epalF28bb{J_-3**dcsDbF z|M{GFp0ZsUm;LTcQ>0EjksjD09Aui&XW9%-4|Jlmqdbkb&-xjnlQ3Jgd`@=Abq$wX z)p_8K$r+R3$IJ!3r`GRYeh+GkD{??s@b&45#UaQ~-)$H=+239r$A${3Xdv%fKR32hWAl8OrOtZsGqgc4A~)GRE}P#{HN2US90DETh*sL z37};rOH8B@fnbyO8&peTAwIkSh=zztH!+viidjAkUqA6U)F|bqVSZBlXNoi@k3h9R z9@UxCz^lAz{Eo5w#Wy)rv*g1{=J+^6`g-45h@L{!Nj6jMD7Q%&>8Gd17g3UHq#WZ4 zBaP=a)NOR>59JI`>_@Hc*~ zO1Me}J+&(PNhE_oVG(okobsZS%ozY<(>shlzBe|!0c(d>;;Rf81%hX1`12gObhhe7EjN0HD1SaIOR zP~{X6;y7rbKi6@R@_uMdv=Bv&pZSE9d9Qn`lEX2%>OXK{nC_sK>;9dVkXqXRWp@9t zG;{7x=RHFq`Mm_0g>(&bfr@ygiCj+G>FoubeAB~ z-3W+E^X&y+^~Lx9?epw&@64Y4&Fs!OGqV%F)7@&R`V`}BgAou2zK&>gLac}7pIA%W zGo!RRHBC|(2oH|?_tIuOCr`HQceV0=L)jeupVZ z%S*;4i^Y{)e9^C*{f83aCJbVANmJ4qqP#5JmCZFYQFV9+!HaRi@Qb6Ht$1;TX`7vF zbFsn(A0DV7una4^Z@ISS=mot-u7JZ_md`F4nBZwG6*>j3*DyOeuJ;ewN_eun*}uB6 zT#BzS+8e?5O_wL7_v~b!WBNtzgTPi6lli{YX`N!G2zr#oH?>KrYUoyx!(NB9E9YnP zeq%3~kT@9{ai}fBjnmn1cUHa`<`+4=t_TZj$l{v~kbB@VZRdc4s2ksRzesEQtrY3( z$8~|7g_+kpK$GI~vnV%a3o@1dMStD(P^UG=Yd0##=Per_RSB749*BBpOr^Q$O(CCK zyH8>s?**j0Q31F+8wDQ=bk@WuusZIxV}kM-z++tlNxhRBoASE;#Z>e-L*MpMz9V=I z?$#AF4eCf~9Ll~1@}h23s-~CtvOoIhb9j<-lHmOapzu72wtwtuaHk(9x{?Wq6?_E zuQoMz3@{r%7vf}G-@q%(~V_F^hLo)O)z2FNEN`!60KKhmqFsxIdlgsGFD5kCPp`k@8a75;Pa>5sYso4XbZ`m&&buds9;x zK9(Kd(pu~m9z4rjrF~238$dFg%FYX@M8$8sgkoXmid7HAe#&FlSTCgQn60{fZ29VX z+P4GkEZ^-23_7QkxQ&y@IO;CV%8bx6iD25gDCdUn*rZmCq`m5iCp7+&0lphy~qI6K;^7VF!@i)IaF0i^8pdF$9?2gx(8E~6l<+scJd+<2!CiAtm>F&$P2jmaq(cQHUtH}i{d$ic-;U884rTGpjU5Nl;&6-%@ZiV z3qfN=tQlwX<7qXRry1sZQ+{;WO5gdn;0`nr5&h*1QNtK_$#GQerQ|d3Q@P zG~PW@Mw;KV=(|Xlwb-C4B;bvmd^&z{PH;57y%Uo%cLkE^6S2C1JEz~sa0TW|6zIZ( zB57M<(Bu>tJA%+e1JN?N8uC(?M*3WPQlq}UBrCy>O%l}t3Zdp@ixXk-?wB$SR@(6{ zHzj=tP6={34Dc8`*rilybCKsNwNJephR zp=&kt62`<=2B<0VID2jgr{goc%oP%(x@wwAkWsjG6 zqL(vKRfLerW2wP)FYO&-N*`NgB`B98#k_PYMkP(^WARo4-C#?c`SJO91GQhD`X7?@ z3=qhf7H#^I*>%gK*xjznZTi1M&0-zxYu%hRTY$>le!lD>D5S3oO5M*|x~Ldom^Vu)@ctK3TCC zdUWy}>^F=oHAH4s2jQt9wzoR;$0WNPb}+clYIoQGO%}#Jk~t7cwQRQ)w{I$Q5Z7X zSNcK(nN4`Y=E9fv>aULul4@;`&4yd;=1yM($Z<*AofW_wck7jLp!s2!DTq@g;hKNQ z-7NPoLYI;_c9!b@1rphg{~Q1y#qFr4&}7AnNLJ`g1O!@hez6Fg?QnqQrvqt*)to;` zPqst)9!(muUYi`2GjH-Ad7`8pp+MPQz(gKch>9n)EQ@0r%Zl2A!6|33r63sdXVui- zLWEWZl>N}gxYr_!jM!S3>;;31e$RT3^txb6Ct$_N|A0i|nd1-4p0t(1WdSE@OYSHB zw~g3$ElR@tkdCK-4r*~5bbTykls$Su#Ko8Q@QH}Tj_o^5rXTtqb6lZF`x9bw>0~=)-2OKUC!1=H;*+R zFY*T7$$_sf_&7U{(SqA+w_Mef&R7?2!`)CCkAk!#Uy>q3E()ziZY=7iRMPDFCy)N- zDg7v$s2AODOABQv7tHPjo!&8hh^~*zsfnd>*cYZjoAQW@SA#hf?Hw`UP)koV$p^7n zI%93P3EOxKd8c6AdoM=30VV1IGZb&G7z< zbklR%^Van9lT(@o$VNDipxndyD*XNIlB8i?NB=W7eIOzAb@S+?#7Sg3N)$_cJ$zaudCrl& zn%gclw{J98XLoy1j16}$j|VxgPeh@brjI<$Vwd&SCces`^)m$R{;G!jBo-zO~6EOIP!mxobM9d=of8bTuEHmo*)OlJ`4LAn*GMh z+_~E0kxBWjn)s&MLsyc?7 zMkZ|<+ z^my2c5qAnOVl1#`va*++6BPh;)$NA<9mBE~$v9=56-nl0QEs1~9qZ@ypYj&vQ8_n1 z8CIZN!^h$%0t_t>1gbI{Q3dCun^=?* zH-K#cM3M^#MzzTd3>iTQ4<(z+A@D%0d$4wl%WrH{zeP^B>DGOXGH=ifP7Z z?j7>dV0r0e3h0L_RjyDsSZWwUn}?8i7pS2A;j*xKHF4S0Tz#54Q}p7Xj^n*Ispec=udoCY;j<275zZr1cl=I;jlJt*-G#Te8ze)5QyKt~lP)^B zG!ur8UzLRxJZ2h1n`8{t<-SQ&X8k(mY?`qjosZuNhMY&a{T!-dJ#>WzfuTvN`fXk+qEw7;( zEn2vU*D)H7TK9@Cx+QyduYA%Ff8(Qbo!&xdV_w56A!CLOs_a7ISc4cuCP>lR1B^}= zPU*h-#J&Vv?Z*738}S?gvRdaG4uBUGedi{SrYDg^yeFe7QG{S-T!disIbVp1USeJ& zT3}79rT_jwl6Tv~NjH=ysB~cu^<9n?VW@Tkz4J_qyoPo!p9uWGld5?@b%a67{jBh8 zYzpN0WawN6G>YVsi1vsN(ecbEn?HOrqeQpHZot(SY`w9>yDD*mLa&q;m?9JBc$G{T zmctZ&uxvgcp)(MBBf@=W{yXNaA7>J%?ALb|9F$_&&zM?yyJ~Sx*Gr?-OC)Kw#I$d= z(m1n@(xcP!^L_RI_I9lrj)^g?5SPZ=>=c59QOm3#My5Mn;t>AY$Js|(>(HfXQAF_i zy}&yGE*^2wH#V~$U!=H zaoXJ>MJo#Jadx-LB8@91@p$98estFpL_WdY4h8dOIO@!;!*XM^^fS7j8Re6zUVB=E zn=0eU^#XY|dLm=%0!H_Quhl9PS`7Qs8@#|tXCqyyyITd{y~@yS&kekJoK#RrN|F`z zVYQ9E6TyA6-KEQh!{jv~ZITmL*9AHqXilXFR zCEVM^&AbmgUC4WiO;j{kNFdjJ$s!z3>Et;#1W3ABUcL7Hs3W&pj1XO2;|@jZd7-Dt zuHsOVzTwU;;)o{r5s=_WAqsrU_~e_RY5f5=IKyh~)Ma1B9*fT@$nF1%+H)axu_Ee2 zd1S@i4PA>MME+ArT6@ow&L{Xx8Ay^`Dh>|mw(ji8Z;;cR;_m7YDS0moFg|ggVlQS_ zNGNB~SX^ZwUaGYjI|enwo@ubOjz_-YAcLTrc|&6VRg*+8K7c>-0{U6fQA#CsKG}uT z?Lm4a75}x=Y6-@5hNf%}Q(ledM znIU!gPK1`uj`)xq3RT5T1UO3FOmZ{SG>JF?^ z0sQJ#{OgY~ThD`YZ0e?v;_vpHE8xWC|JY~ZS{Xk;1JVG%&i|UF{a;J~;UMA#nG+J6 zsj5cD<@&(?Nd-U%74%AMhn}y2_wG%HvwL3q`hEt`r$>r@n2J{;0!Bd4>rRJ zqXL+^`yQkM0LKso^0}P~BA>o*@}r3vx%OlG zh4-o#C_KZ_8;bIQLF0E!a!FAennZgalquZ;GwEf6jCC3o`OUv844t@-@19z!+6}B9 z!`-Rp@qz#Uil>b=Fi zgs@jReR!C8KN14jifp8$CEw7WYcVt_4|v~iKZf^Jv#{|y0m8O#UccTRHtbfLQR6MX z5>s{ic6P@|wemzbakS9GcXF8{gIz>X*nDYb0u;y-44DX+Mq*Fs5vo358dUWe*>L&N zkToG z3p5ol7#R+Gj00xt4-LF2b&`tVYBrMl#QJig-BcBiy0Y*blpd#n4#juyA84nUuARFN zxxu-$wjFYGFZ(JRE7bbj+qnB4U`9a(k26TlAhChM?NW~p=-2*dlFfNM=A|%+BR#T8a z5nR$53bK+VrR86$aWhPh$39>3QWn@q{Vz>MaQ?Y{B6%wz8RRBIdu1j)Q8A)my-`wC z`*D=0_jJa93E&flmw^ytuGpnh+s;0zS7N08QWVu{R<1Wq#jbF;%X7$#ee7Q+8cE3| zqO$005*kG3+4Ly7UF4l2@y^&(>1x@ndvC>z`iCMILTG&hllNWDNt6T=LR(zGm0WU# zf}XdSjR(1uN@=F9QD)>&B{;!7go3OAm82D+Tv^_4_<_I^vqAF;v%!`W^JM9LyM#~( zExZts_%+74FOCZb4%VwBhYs^nzCR#XfkfYxtQkV!zdvB7Z$m!5VJtWuo7}jm61})B z4QQP7;5eYD^0M;uRWYNPFQ4)W2%mni9Q2X6wu-(ya97~nkFD8mgw}o><8XN{x89)z zie%b5$i@IVi`*_>;17K2?b911DSYocpWhdZd8Z}Bw5%9lWKphH!hNdlTD>C(b#*B7 z3CW;*A3K$JH%H--Xfa;18;9;`N#>&>E8qEeA{A#8Bl1K$e3843FN^cmv3$$hw<0%R zkK?m{imx4^TwobU%aqB~AXc1Zc<@5$Y;#mMfmp&6;G(aAy8$0xJ3y8}ahr6>p$j9Z zLM)FnMq^WO!lIj?x$ZM37lDj+9w+KH`^^2g1W>?bLZPtMtszQU zU+I``)YQl{62_N56kPF$QV{P9cthIY=uVCStEmH)!^SeSVXZo@o^A|oqgbcZThHE* zjE;BvjKA#7dsM~2#owGj%$}edbNe_QJRc8wrF{vmJhzyvPqTvZ8NDpMA*ZkVZk+t2 zK};XIzNvg>oLQvk{@p4B9eM5Xb9a`$Msi6L<@idbAB9P`6oN%7Ly9%Rp`lT3mESOd z2D>U1dFcG6E%}iO^O{ELBM!+@+$k&uqnDMX=Bt%58wBozsgEcnxyZLP!^bQ*Nsl&j zS*n7K`E{do zd3uAp<0GG5)FrUZSYTChS&^8?gl(N*QL@ zl<0gfb^%$`LZ8E17|ogIg^zxtwP5CM6psohIiVP{=D}w??FDU9CMr6H}8rHeq;fHek%#a(BnaL z@$Z8oA^yBr1xjsm$(&IthKU?p-S+h5h}pQvuZ_0sBlW`uP<0@*SSTB8l?i-p$k``W zU&*yXa%Llw80k2GZ@Z&f5wk7FHb%r@oMI%DB2=~^WC(bLEVJv2FQu%k_Uswf0@MOb z8?8dN*Mhy_dA1U5!m^k~?vrqm_=q3Pe5N{<5Wx~Y-hV0qXiAtWZSsO)JRF~x>18gu zsSXqczmfZ<93!Kv?S!NF!w2c~(;FWc74*Z9_GL%oxJH1}A9)=BCnA%FW#)BSXJp~5 zYU1Ph#cJ~P)8RNYH;xg@`=0%Mye}HfA)yglPFW5k(WOntq6*$9+aVb4Mv_Ml-?Rpq z-~^Yu+>rYAwdAIWlC@%pYznzCrr-_FmvvE=?$6wit3O0xoKRclZgH=Ed?++KHKeE6 zOm>s>!G?-7kWK!@Lp+L5nBac;0n!|{d(kXHB{2&pxVQp|TF;i~P^=xj0M)I?3BJhy z4ZOHh8^5FER5U<;QZ5lUH`UeC11J%kBDfG~8YM)azz8A!M^}iQSC@m5VFozQ z+1kcSrx(DeU;N>pAES8oBl>zBkUde$QQ7y{g6BXh*Vy&IM=!t8)6gMzYM&TxhvbY0KZzD7rf$sm z3=X5!IlNzG&Az;k_)Y**K|5(gYw0(jMTy(mPmff`pUa0ioQd3*Bl?ivvy!Ir&|!I1 zw@xYLb^H+3iqp`7npHCv)oP6FTKl<(&>dlxljn44QF#Tg9bORCycpp?qIE&6_+lcb zVO@lNecx4G!EUcI8Zy2mVobZXv!etF29qZj=ZZ=XglSld)F|WO|BnVo)Ly>-Gi^Wi$=7 z@0*fI^?8UVx!Ql(M--WJm)CBa2d=45QfsGJ-PL`nEzma?hLfR*63+I18~yX7R;pp* z0qFw8869Dl_Pr##G?e##Dro_A=1N}hTtkv7G0fUTH#WkZ%e|PYc;1{5FQJkaUJkg(mN>FA-WZNcNKNs*h|3zKSsPrlc(+8kF2@mI$xkVAhdL; zkA&$2W3PxX;<~G{CQbkAYctw6k@B1sB^p}}wedFE<>zdbW4WER_MAAG)Pz;>lg)UH z36h_;wFz(e#3K@ge6i7LKeEyp`iSWaacptN#Y`nCqolCpg0Uk*27lYSTf7um`y@l-O zp5dP>W?}3t7i<6^eG9CG3JHY~0z8K%rDa@f;`(!?ER4kE=QggWmmh;b=>IY}B*dS+ zUm*EhcU}gkInK-G70VE^pb{5R|4`M_?=}+%rLA@NEYDGs&d;0HHn-vAdl>cgrYC%! z^<#U-g$iu<^z}jYe7kw-BqVG+Y^(`FYP9@9khrU`VkI3?J5|4c$B_Bu6 zCwNGX=^-|GU4HoKv70$fA+=FY%Tph(Z%+WDr&4w}rsl^XBubU9MP_$ZnL{Bw-1ZD< zEV|JtpOVN(u(u!)+$ZbpUi2w%bm0we_Yi&h?EOGSvf2sz8sjeC_`OZP@+_Izw%`@a z^f{If#Iyd$Oqh|?<3!acVXE`#A|}j6A%VSuKFaSoSFgR%-EphFeXTA|GPXMF+XG}R=@T}sXg&-byBAwm(p!bdbyOu zv1ODfsb6=0Tw9&pJzbW5H5~BU)z((?T8Edv(RW^Z1sOCEy4uAb4jGY~)`yoyt^F!*!0gZ)S0*Fcdnb@D_ zQp9JlQnm>_Th*AwIp7WFkqsU+kwyZxQi{6qz}y2jF%MrMNiUnbw8A`bJb9ZxfcM|5 zW}GBtmByIO_ri>s>iraByTXnVe3+yL^X4}?3?A3ycbhy+bJF_ig-vC0D!)O07t!!m zWB4|E<%_xF+8%Z+O zW>)+4sj8_2o@4?kVy|mf24O-ft<-n6h{I(fd_jK6775l_Y9mpneD3oj-Uqt@qDhB0 z$Lks3gS_`ydgROy4Uyihk3`OPxfEuQ$f?xRjlDTcQH)}!J<$R9_2mRd>Q6z;#CVrpGCdn+XVfl47D>&Nm6F-p&pz)qBT&o4^*) z=1y?=7l>v@Yv!choqKC=FH;rJN52b@^2!>YOGSwstTh{x(moqf*HvcJR}&W!&`=?O9+{dN8n!#g*i4%fzy6iSlAk zp5QVpOLsabIg?|}Bd%xJjhqqSP-*?(7!$*bLRTg%dF&$oVf9(c>E)`x-*6C z%;SX3W22|$@yMSauRP*gzwNkovv(W$Gixbg+1(a%WsswFFCNbD!`9QvVJN`*og~QO z6ni{k!kpX&ehaKG|Eu~3Yk$LqXTh-Vk^k{c!u!8S*1|wUhKp|!ae5&KFz~N^6wuPQ z5FDh0%hn(P5W?tX1x0xNX$>x@J7L3h^2)F-mc5%NxLG1N>}guw?=BXM!SiC=uDc`B z3%vQi>U+r7e>zwjFedh(I5l*ldK~qZYz;)m_@Vmq?wUGl>lhWF(*oIj@pw?;wok3# zxZQh|6Z?aytyUZF7bA@K=+d}}*pSAkX@dKMyZiXR@G6t;>P!mGJT z6yc$Zo!6cWmeg!m>JxF{nrvcOf7SRd%jXh_bM<9TQ^XN)ykTw+bVe5KVp6Ec?{m|N zdFC}EbiFDb9b&AW{4n1houfydbB7!oh7mm zoNnwK$IZHCpeE-VY3j9m`u_es;jG>EFCwRaZeLVlI0FBGkzog&^zNsk_`q?B2=kg7 zSIb3Fz+`~^#WnJIl>S;N9P=6x znu@n?#cd1FJ)szUsiheh1v z)Y*=r(5mPE5lp6UU0_rw;~6(JT$?Iad=ySJq}#2gyt|bhGO{Q$-iLl0lZbp%KRUpj znMdn+7<>Nf*qj`TAi~6Ej2ku^YBc`IeiTmU!xN4SmY+ycc2MobepoXJOQfLkg}fa0 z3cTsJA}R|852P)IhOSTSqS~9SZkNffiVCwt#eVk+Oc!vTpLzF*xUBz{@)EV6AgC9= z^!m-MPDmF7$l>5e1VF|>ZcwRV{BbakF&@?yo@y?RPOh9@_I8mP?;OBE-Uijrccf~b z5#1!ws1^P+(z$EemecNa^WzW)ujSyBUguq5=%ls z%$Xxs!Tjj;V<1suURcwA>8`lakJ(kanx>Q#D}c@Phcy~HGjVz1gXt7zREqx0dk&e` zn2YSII1<|j^8L!}Lf%VLMZR~!BT!=fytl>S+b}MN<(LdbVx9@r>qwIQ${E*|Hqygk z)8;Rklsr}WeAa0lwWlcsm(L!%w5J3of{j^^0mB z#s$n5xQXV|UaK8=ee;IP&D1^_-DvTq)0lM^mRY<#ZO*%nDm;~=)H>nU>o`5EQkSB8 z^cPuOPNsPtbIk{vPN57Rv#rhc@WoW~#)oV1PzI@nes14)zGULm!7XpOKtl7+YIhgHVa?*yY=fRjW;qzSsWZJNZRY@DLVVTP`tkS0uOJp z_LehU`k;gEuYzueD%&8vXmU044#{9y&A&nKhR{F&-`E+I32uV6FHBpMbSC!1C0kWe z@$tyTVkmfNta3N1Zubi!+U`=12M;uiQkim9(^o;p8}-&&>Z#m=-kEq7ik>&(`v(^EUB z>=f9#c+@`dS`)<@l+4VKxGrJniBPAl#^HH>&yb`4O|Ed=`w1@M1K$btGnMb$*w`;k zg8VJMzT-1qJnj>1xTZbi9(d>5mrUQZ^wb14tz7;z(`3^&h2-7w)Zy_rjhniMmYLJg z9bldaHy^WLI96S>_dxx~-wTdFvbFS0#leL~Z?stcQY$}@?{?r#cQ1q$0^oe69G6KZ zKrW_n$MFiq&+&*oWKZLuBan}-`nv1L`=CS3ZG&|m_(tDak@gZY^!nSpr>ClCyKGt% z^^`?y@qkd4_MO$u*9gI^qhV?hkDUZX>>ptze$B*-zH55ttt>HxH1(aG@{h>H#H%EE zY9-XU(<#OzwF0e}lT<;3(#yc-2eX}35o-M_bZz*QTzp!ho7EF2wA0>NXp9`1Oqeet z8{*F=a>Jq`&L%(ZPpdVCs=h`MBqWuwr*go2Tx>s|-Dmm(ADgY`+0z(0WL1Bu>$nD6 z`;(Os73ky}236)9&sXMd#w?1-E-7wQZE_|HFRJ2Au>x+`tmp4OAY)Mj0YO1XakW)#qkqx1f#)EEBY;DOLj@~%S~%fX@0jI5)pR0-+6+R}A^y<%K?oJOb!b-b zJdB|k`;vAa)>vE~)zEK)5T=Ar5Hk2K^f;_D5-9#CgbZpk1V(gV#AQ|BLz9LeoRD2; z#}GsUo}DvJjguJqdIW+Kmn4e=X5*hD0ID(!da(zfF|ePv&=J^=Hk5b-{2_$ih5dYl zronz5L1#xGlJE_EadUknP?3)iR(O&bSW0oKGe}V683+zV!PEmaXRx323JU>_=${lW ze#>@Yk`O*<`3Qu7tH%Sn6$iF%5nx9CEvHQZxoGcP?X2%xxN=?m@IXz6A%t;lyEstx zAqYAG1q~z)`;0hla~B=j{}FtmPe(tm@X$h_{bLYC1R1&u5hy?Sg20!A34QSif`uS; z9TrOmo%{r0MUbS21xTQ@;}9~+iWs?6Td*1r!-AE@pNBrfrP$yigba}niwY5%^$9|R zfWUMS4dI8X4?#$wDquPY@XVK@0bqcVW0#f!hA03&BK4nuaKtPSsQ(y*8%jI|-qg-^ zd6Uu@gftHQ`_BiNWQWBP$8mp0hq8@>jSU4@un4;x7qL(^FaY%d%NqfO>oTSk48W8D zL5TbE#`CY}P}@lL_!ZrKiCXp`HhI=A|HXZVo~Z%`^wy-YL(5 zWm_h68Iv{(;fJrjeHkbMo#;XD4uKiExT{|HGFp8OlzA_58F)1ZAt%4f^_~mlZ|`C44n6fwn;)qzl*FP_c0c zA^ev9WxP8WK!kajhDMD;h~P<$FQZ$)XbPB*TeVl-neV+LTblT%y2+=}M96^B#V_I>7yO!Z@kcO$t4i0 zKl7)6vMYFZ#1aU&p7k?od=4fH^XgZaDE5M3^YE$J4 zXx0h@AF8$rp@E*kGSpKF(jj_5NTBX3pkbGe!LIAUSA2pVuRtgS(SIiQx2wwE`6!#Y ztd{>+H^6fPI=c!XfX=Ld<)$?UH36}ppvOkCKeDf}3hi43qaUn7=;2eoLnBuqjKEb- zj=xi}Is7Y?3lfBj<`V9AKCim%`;8!S@)yFz@`gVU08pCtFV}XzAv#X~g1DHM`2*qt z;i{Ln-v~D6e<56qKwlyNzn|l(2e01{y72H<9fe*DV_eO|RVP=!5#|y8LbxC?R|8;u zk3U}KKfZnbaqaUPq7~&YhzmzQS2JCEcCw+cz_H3&Z`(#J+A!5D9894<6_a( zRfwxDEq+7LWB&mG{Per}pPF^mW5REYWZXY6enR|Fs=o{MD(C-ih%9^<1n_V7um4%B zSLx_~W7HDM3#`sU&xVjSX zH$<-H-w^+)qOi4Cz@Lk;eq;R5`5WVE)dfn^!u?u<@pBgWH^i2~Ul5lIGXC{801)Hq zO!RMzK9j#NE~lmcg#kibopbvQF=75U#2=ROM|*R10r+%*V2<*$Jp@N)|`==S@FaDj&o pfGJS^8b3gRgTwiK9sFnL4iCj%hmc}9!a2e{q=AFO_Xc6${tuwbI(Yy9 delta 11588 zcmZ{Kby!tR_x9O`Zlt>#rKKBbL_rWm>F!WE4$__CMmiMfhC{ak(%sU6q?Dxa9mMN> zp5Jp_-}&S0z3#bZX6?1to>{YIaw;)v#?WXUt0Ey2K~N#+5D0`Ga#VfkC<}!^tjQn{ zLI^q(l<|NPmh)mlVZF{XJY+#9X+2`@RsDuCGr7uW3G&>9`g{qi0MP~7*w=Uk0)a*! zGjdH`+-G};!ac-9n}hAn&heELrM}^}Xub4%!9blr z3|y2MKLwr21fkK{DCD%~_a{+wDHx@Ui+Y*I9<0kk;f$}ctYOBsPwtg5tvOUcyaj18 zRx}-v<|5Tr-k6UL^00E6S8(IiG%%kr8@;J`w9{!`3>~iLbwsMwVf1ME@MBMh&G7tv zpi+;eawK(^jlRTeuVq8b9LGFW(+ACr84RzdLtDNqvoPuL$nCC~P2ZW`TuYSc`x@WT z@^|ju{n)1YrbZMdBqX&xRw=`qF-pLpQDV*6(_ntzYoyOc_ROB}!cd?xZ6QqX7w3eX znrwngBO0%r)v{w_;No48w%JwWy?DaLN9vC0sf%*X{t>IlU=Ie%$`SgHz3>D9xI7p3 zhF;yKfIp0mde1~H>OdDG--PIug?FUk!=*<={)#Im$X`%ls+I=7xq~W2>KW=R98CnV z{rBokBsP@187a&8W&?%=m#Ky(E~?d>)Qf1Jq*|_Y5wUKc@_r7J@>O$!#v!24RRkn( zhJZAD)#CgUS;wy3S!0NrgJoP)nxwvDYVK7`J*1SpZi*p1OFiE5^EV(e$Xxt9PRizP zc8r24q5st9jsK(;0zYr z(|LSc6g4k}QrVKwhDBT%i!6YIIkOqk|L8O}MspQC?0J|~hf?sjQ0d9T!3^`AsS3N}JFN7u3r` zxVuhRewxX&eSQ(VETE#Ts5r)H)rad}lk9HfUd7Qv;gIi5=T#T)@V3w5S=2pnu4)&Y z%X(%9o9TBwTG7xkNg1L()-B8DZRy4T(0W8JC@zmXCBFD+d{0gxDe=Qh;G$T~BKKy8 z+t@GTT&xjP%{Cf+`{(oxQBFm&(oEdiPWtFN7MN-;x3aUe-|M{HjGl>GD2C2>R78tgBk^sB~%FGa9_;H zB9m+j8wA>06=it6+X-p8l^We4uQQDy@+6sKk6ezC=;S{`!XNp0OGO>Gv_h0Lc>M^l z9uuH;ko$ZvhJ0j|4j*t-qRl6hCd7J7#oR&f^C8=z)fSKDhVIbe@{hTI6zbbM6qnaY=jQ?eOb+00~ezfwi#)=b!_K zfrKf{D^Q6CxB^4pK=I+s+yEm0-@J<`fsb<{{xRkAdwdK42!sO@&dm;R1F&J04j!W5 zJ(Pv4)o&knYU~rt8txd8`fqsqO{G_V7Q|3a-QB@Sd0W#LKuQmurKEa$vtsBuw9K-I z`U_SQMKUEMJ)m=bK9+5|YIp4pXNoI-Nz@nzB@=l=Kij|4e~v<7KhN-F{Of~~aGpr5 zi2^T`hx#(T{SP?scY9?v-@SkdjWKJBUoSEb2}JW3T-@(Af6PBa9J!&l^lKr5=<-vI zIMpTvm^ zGVf=)r*G)qSxPk);E(u|OVKtt^5l3)ZY<(C9D;3<05M#O9w3Cm@!4))4K`e#5x{_= z%teL#*sak8mZ7i#Y_TNrp%iKq=Fy=s_?n2(D%enQ$?g1#wQdJiczxdVZK0WxI3&Gr zxt&Us9b1M(0o}bE^czbEV(DiT3msuQAYA`J3@5UUoh!9zM>b2?%$-tvJil_VP5o6x z-gNn5)*LqbbzxJw=0dFpS7R|qnE=4^V2|x%frv>$@4zs#@jnVird}_VGSC{APWCr> zcd+L13AeK0Jihx#OuqGD9C8#h68VAY^qV{W&9FSa#uAm8lJU_Eqt9!-U4v5IXQ%6o zZ;9vC9Lj%;xj2leQ<>1R7-1WC^)usB`LUfy#CmnRBnU?myk*}xiuTeG8#(3KIhyzS zdR{V8s@=s;vsOu8eb?T8Lxz^xevK~9q$2zT3&o)3zL)%YWzm0@ zSUW9i-v^wkb2Cnsu6A8c$Bgo(mV4f&b@1~xW0_L$F1)9nf#HK(_hz^M{kcf zZtn1nqDM7n4-$6HnsLw+u{2cdm}(pxjbMzc!C70vj9s5=&Q5#mD^?woOZ!iP?PdcC zB27fb;F7Vwq%Liw_4Wzt%uTO;7I1h50 zjSApg#rk3;TS=XjSUF~%-u3Y^iB znxErZBf{2oTQTW~Npb1W^C<%hK*YAv@e=z2?@eT%r5 zPE9;(_Rn#%y85E{R}X7`EA`ZLD!wP|!hi5?9oS~XW~-3E52V3ml-*9cgyEUG$^Y_x z`mOtfI>YY7nSAh0zsMA+n^>n`pfDtTNIaB>xF+BW+4Qf(-q-S6`fsx9_4?NiLt1=K zFPHWtrov}%TIfR>N)&X(n)jyJ9DNq$2qF~3(IQP!{F97jp$pV#!tpa!baf@vymcwA z$>;ZMQbcuNwpkz7_#cH|A>E77+;mU=sL!xv%)Ixh!l#^j#zOhfxI}=VgjpDOOpDQF zI;2F-bgP4Qa|H(cu^!6AWCeN{xMv4&!+P!K1c~NJH>A)vlP4kw6cx4&kF24>H5y{` z{1gL`hD|EYEd03Grn6>3^Ip^Pa6tF9&_>Lvs;9DY`h=^sSQ+5(Ae>>a30$93-Td6E ztxci&MSgh9E4R`l1-0Hmh=S+ zAO18F5!GaGjdERAy3|B1|7&CYDr0Gzy?_a47KlRWRjI1;ylhn&@4;&`3Qrn?_E3{u zxs5Yr5ngNEHtEK*CO*Ly43qjZn2q4Y1sLC-#M629eKfxR$aFZ}`HNPmzVF~{!mlKo z$c{B$q42Qw?Q*rk>!C-ZrN^3XMK-+_a^P-BZlmVC?Wpn@{x|K_p1RhN#UJ9_0?u3o zGHB=dgfc$C`)W{;CR!p3@MIQj{UK!XE0n}4G1WgvIb10E~2(+#~msNJgG|%(k^`~YZ-MOG}-QdMK`J#lgwW?!M`nwhCY&2CYH3k{{s$3woP zCfbd{&Q^>m~G^6Z8HR zebTr2q!8O0bG)`rHxql`#FR(ZA!lV;opKy3DXMjO=c|Y5RtFzz_6%ccEw?)*D^@}? zTle{i#G*}1Kw%RxuXEUHigZQTtI)uAqx3uVul6)J4v4rgMRf_5dDO%yMd%+yIBjI^ zcjGP&DL?V|k*(-%BHN`VgswDtx2Hml$9oM$gz%FZvmY~CUc$;e->&>-?4uwTx6dwM5aPFz9b zJAlS0n@tDiI{}oi^~HiBA}#7|aQu5ku7$+(6+d%|F#Q`*0(vS!HV(-zY}n#uGz}PG z6-@iy2S=tIk4BcV>k}P(q9vRYF_br$I|DLzI^~4-jfsL=r8mzWyUvxbBm5}wjv24f zeRsD7#1OthyWn$m8)9I$$aj=%>6fOlVIm39$g?@?^1K{Oh|P2&Ib}PPh+MH0h;Gud z`sDKS;ZEz~@2XM3J#vQ>*=uD{SMCgEZ6PpD3{z=iWr=4)pyK%H9a#2qNX@E)rB~G$ z17ITUToj_q+-JY(8XoR*>hdk2%$5XsjygsfUh520A;DH#%Tke$rqRS?l!XM2wSRFe z^~6k$pTbtn5eB=`>_#&4+RxRY^7s&rg=BpZEeAPf>;V)6{X(VvezScTk|}9i5^r2K z_eV^G9`7C7PBZHzy1MnW+*-s(d+nGXjYTbG&*^LRSUsxw{cNw0tIGRN4p1J$X}L+ z8`Pk{(gnD6beWuam7ViKD46>OURz`v(_YaCUy}YA$l)w7;1UbY9R--6!>il?TU0nK z3D}0hpMC<&0I(+zm?w#ikt%MU31tR>pg0yi>WlP8Og4y|%LYR4OfAcqMJ#a%c!O$wj8{6b|#_ZF;E>7%I?hRE)!A9*pLuryT2?=nxQ#jF<6w%DbFs1pBvq(sA|;k zqTbc;r|XQ>rck!s=F4khA^&0-NlyK|na*m7$%=gbp)ng%%3_8qr8PXeVac`r!$cAc zTU4eH&peIx?N9cf^5(j(eQ~dD!xYR9>`|X=kRcFByxZW<@d3b(gm$XLKhKCW4KGjx z9sroi-eV5h2-~v~|KY&+x!mn+`;vMP6Ej)Y9?Chczh|!ETooBPny$h_h=oj=IE2wj zyr4R9Sxp=lx;kS*+tx+pd2dJ`%_mM=Sy?67iHh}oP5Dx9Xm;(T#{S)i zrpeemeaZ|L`)o(ghhCCK<9V6U16_#}p=@K#`S4L?t|^=QuG;FcE42yX#MKfi7EMx2dua!{BT)_Eg357FADws^ge=!XlX_i^FSHrWpsEXZdhGt7ywy zD1A;(dt0YnsiK_H% zqhK^S{#P$b)r_2rFMd2T4OxGs@uN@|XUp4~b9mz1Eqm**eoQvgR^H!WtO#4~HSf$J zf5asSD>}`uUR+Clv5{U+AS)Cazy^>lL+FS)=`xKVJTAWjHM`^jzcq7K-w}wd8M)?V z&GMCgdCB}rc2jt0VKz16)dy`}C)7fx`>jX4Qm&!%S2q8YI%BP~h)RpNMm z#V^9G7GU!1|J5FJMZIkO1pv1l>3?OGPw6+-uj%bucfSGkmyY8~b#|_9gvt4RhSe0g z>sz6red|u+iEG0XeH@XW=VJOe4cER6s<0agRmWX#bAIr5F1^Emffa@uP- z)O|ZbB0d(jp6{Amh4fNwCjwIY8p$8BR{VuO(>v;=@r+ucHa`ByVxLqi5au8y)$`FV zwaReKyYGpojkll%Z-%BpA4^}9)0dY%{qHTC{E%h*sUZPLP+2IttN{w%lI{0=m{2XK zu(5OMlEmL*rmEXH> zPm@=P$YIM=RJ7~trS8@57j<>s_l2Y9o^&z$#`p1H0}tcTGa-brbZf$BU2LxOIO8cB zzo>=4Z1^0vDhm^7&Q^0g%{Aquq0fu7`JHl29+c*~B0=!J7-eVfiIy#18&Sa??V`dI zTKS3xDsPNJ|t%mTXTkTcFdT&x| z*JZfPe7{d>_ay21B9nir>jOHO3|jrOHT3|sCPmjO-BUv9mil+g7&aNjk;-GHDyvgk z)iX&xqk4qY7pG|J!%{c749vlb%#d((a|! z^QrFA@nJ`;pe_P2)sSw1X&$Tu@1dyD337wTE@dJwd4c}rMk|>DVH`?wn1u4zdPUAj z8P3AmcRZd)Yq7~5>^ielq-d;YU7x=#l_JTxm6#t0QrY$%D_;EQ?(R_g_RPCzYt)@! zLOvbFC3!!hQuidUH-IBrn=|A0v&4(FEfu`Ew5F0s(+_^4er;tJSzEa+-}&ds^vQk4 zggW{YoD%a3=ZIHKZRmPZ3J0_5Nizf##=b?qbIa-Z7T!GEX)x?H^@yjDCtp{aa_)F7 z(^q77`H6X+-iXom*hAW(DwP`4J%5PE7#=!0%oGcMl)iO83ca|5<*owEgEYGfY+ZaLF=FUYFSn_RdQa!~M*#6H)h za-nbZ8H{~A1UDxh`%~6IU=PvdQEpoGv~ObfY8cV9=GFLYt)v|ZY@$55WL~KHZWRB^ zflqR^dP=pVBUe9`5ARCyu{epw;2b?5UW18RFJ$4wn#@4>Qy`PZBy_SoDk1^6m9z#L z;qt_>BW;uDSbTsHXUfNl)pKFeM&ftUQ~s8EdgMkl4>5o2hTJpd=ABRf_!yVJqHJdP zd%`NCRd+!?klS!DHk_lde@Z%CE}1AO_qHAH!Yn=KwVx%15}RVdo^IZE7cG?WtYsK; z0ZLf3A+;7;Ne)LIZsJ`H`tOfF?dq1*ubVv!8gCoHDuZHBcgPtLKSk?(SB8#}E3}Tf!VKG*j8q3LKD@Rd{4?SzuR)Ml<$RXjm zI%$d6r^^}zHBUxK^g@Mqe$UrCPxD1#yp=vNC{&N><;r}zkR+GLc!;FGpT@f5da1EK zeekIL_1u}`Rvg}u(SwK92b`>z%(P$B@HxC-^T4&GWd>7aIxoB@l44mM_Kox54 zx20KL7^YbpjJ9ugqXFlYkYsY#NgI=!374c`#30=08@J1kO^R^w;l7~spWmFQhPrG5vH~qwNnSc< z!Fu@SwWdZnB?rg(1E2R7a|a@?-l$U3qH|@~@#0Y#65@G95)5|4oY$<@lWyf4wds4y zX}h#VWE2*x7i@kxTJt&gjHoo9fw6LXW%oqX_EIgOFVb5gr5K}=?bG24m*qRMfmss1 z8uzVd;y2p^?${deEF^WF|2|26FQ~4Vrv1FLLfjT=Sx1C#EMth30HFJ1^tQ{-ka#Y% z%+LlsoMU=U#iTgO@hwF#xxJ8qZ?nj0RJd>Ouy$I3g@H1-M+p0Y&^!NlBbepp;qX=& z<~X^Fd=y?>%EnsFsl@N~nAc9OQ|!@F8lQP(_4s)n8uD!btH!8hW@4=s$Zl%f_(acR zN^6~-6c;QnQSZs`<KDrwGvGX^J1`bI8eDF;XUL-$!Sod1D}1OF*kJ{A;}C1Pp(y|l{$>dnM@{I%!h|DBr@Tl!z>SW@E+1RE%LmM7YJI=Ln-nHK4-D-Cfs~%rZ|zu2HttQroBRaD*Dk*??7sNa8GrB z2eUBHiA1FtZPhIWR_I`3&}i*`K}|;f?Cyh}6f&PUGd4;~6n!zgcg|v@x_5q%ZK|Q{ zD|{*Lu|M!muaEL1emL3uEUTZlT}Yr-BKZSj)IzPJJHC;sWL5gpqxx~Q$FTfZiU*|95^Y?3;zPa; zI=v_s*%7HWn_c7(MLqrL`}ReSf?!p<&aTeTW}bRa zm>MQhN;O-V#nBciJXK@*?jt+4`fIZO0S<%OOdGrBk9yXu2d2}LV0~Q$$|?1X^{kO5 z%h*D-df6{X0Z#sn(St6lD=cx!?%b+`q4hkEW$}LJU+SvAhw5{i?3!Xt9HUb!Z6SJt{h}X9W&vu5=0kFvUdG!?@{Gh$KU(^f+JNmV* zva`iS0-+f@m|-f3Y|x#wNpgSrOGYoc*9JDUZ%AjE?2ynutc^&nd(#Z6`5u{WuHKOy z8yHX)U1kCbU*_B0XVuw4NsD93uKHM%79=t)&7}Al40!30_0mtFN zRARWNV=B#59$msE>+xPc$usLT6Dxaxv)1!HA@ZaSmv~XbE#mQq73Dp0t^+*-IJeyU zs^9ptyE}Lfw{=H^t3?wO9HP6T1IUvzVpZRcLugF z>;m#=2K%#Vcdu?U>=?REnjPkdQxcT$S1wQv0ERw8J)OUWidszPg72hJE zJvEMFZ+v}bi{c!fpWQBB6Nh=w_u4|b_Pg+Gwq@yPispg|Q1z&1tC_r_ws5aIbMzZTBk$~xJ9NuiI$MYzMzI|pPWCi0HzhHn z)~T4{I;F_l1o#MX9XqWb8pX)pH)oyTU>DYuS;k^d-8T zq`xaIs^n;JKX@$8{|CErtuCbELx5vX+A2jy@>5FUrxQ65ij8xJIqim+r&}ly77ahY2g~E+_@}^V z?Tx3S8i?PtHgxK8vZp&Yhqzkc?L6s`-%st3tOKcMtEJ7fn3)^(wjVI0CH9gZ)4Gi{ zADUI3YLmG9*a}p)1ghT~1~gODix!TGEzRti;?%`IVO@woS$9rfQdcPc)(+QucG5NV z)Y{%fYEj*kz{&y(?G2Bv-{*PuVh3HA4d$7@{longseJ=F`?Le0bx%v@-eU5~rGVCBf`*I$8EB6Xz6GfIw*fd2YlV%P9o3_k;3)90+}&U(avb()Wc5Ko>4gb;4D z#Kx!pKaCyyzA0w}DSQ#?62lNR_OEVhs2~KYKL;HUGxsXO^#8Xa8U)k`gwlZLK~Q3< zo6Y=W1Z@}Nzcc~lTbgn(g7(iY^?zwN=(n^a1ntkZD_9;3C4n;G-oon$`0suq5CSEJ zo)F&Pw4e||_><)aABQ05tz@@w2m%HbLZK8$t<(URl?YIRk6{4HA3p-k{Q-QOf7yWk zFC*3;!59jKav*(Y{0otVLAjBJSpG_ep$LL?7{X47U0n*KM)tqBML2@Bd+)DQ6^`gT zH3VTuTE1ItCU3MMi9l3|5dKS2k3c|(^f^BEKZ>}CfsbOKk~jHu3ZyylKTNtmPE2)^ zQs+mUyi^hVuibj2Kxuy{Kh-~}_5U)&ly0=(r}`&J{9i`?!y5(-h)5gXnuzM3WbuEw zPc(12I5%(opR~t+Y3n+-w3j!uo6H9vVhCBG`7dqnL&>4GX8$U)2ta%V&gQpBSpZZX>TdC`V#+`$ z z@>jx+Mo5OPefcX5IYol z)cXq1F#L#PJ;eGwA%{{mh_Ty?Wv`R8}|6#ymPBPjn1yU-vI g{C~<3cUAoW==~l_j;jgLgbX1LM?W4$#Lkfa2jG>o-T(jq diff --git a/doc/SystemSpecification.tex b/doc/SystemSpecification.tex index 29ac9783..d60c5390 100644 --- a/doc/SystemSpecification.tex +++ b/doc/SystemSpecification.tex @@ -876,5 +876,28 @@ \subsection{Results} \label{fig:fittedLines} \end{figure} +\section{Vehicle Controllers} \label{sec:vehicle_controllers} +\subsection{Compensatory Model} \label{sec:compensatory_model} +The model is based on the combination of various existing models, such as the pure pursuit approach (for the feedforward path) \cite{NovelPP} \cite{MultGoalPP}, the two-point visual control driver model \cite{TwoPoint}, +and the compensatory driver model \cite{ContrTheoMod}. The idea is, that there are underlying patterns and the driver acts as a closed loop controller. However, it has been shown that feedforward guess of the target +road wheel angle (or equal quantity) highly improves the performance. The widely used PID feedback control method, however, often has the bottlenack of being too sensitive on kinematic parameters, especially longitudinal +velocity. As the connection between the vehicle yawrate and the vehicle curvature is speed dependent, it makes it difficult to directly calculate the target road wheel angle. Furthermore, nonlinearity is increased by +the geometrical relations between the road wheel angle and the vehicle curvature. Therefore, the problem is divided into three sub-processes: +\begin{itemize} + \item the tracking controller calculates the lateral acceleration target, which is still linearly connected to the pose error, then + \item the target lateral acceleration is mapped to the road wheel angle (vehicle curvature), the mapping contains the velocity dependency and geometrical non-linear transformation, then + \item the road wheel angle (vehicle curvature) is mapped to steering wheel angle (as the actuator control interface provides only steering wheel level communication). +\end{itemize} +The second and third steps are only open-loop mapping of one quantity to another, and the mapping function purely relies on prior, physical assumptions, such as the Ackermann steering equations. +The block diagram of the entire chain is shown in Figure \ref{fig:compensatory_arch}. Please be noted, that the current implementation contains the highly simplified acceleration-to-road-wheel-angle and the road-wheel-angle to +steering-wheel-angle control maps. + +\begin{figure}[h] + %\captionsetup{justification=raggedleft} + \center{\includegraphics[width=1.0\textwidth]{compensatory_arch.png}} + \caption{The block diagram of the compensatory driver model.} + \label{fig:compensatory_arch} +\end{figure} + \bibliography{refs} \end{document} diff --git a/doc/figures/compensatory_arch.png b/doc/figures/compensatory_arch.png new file mode 100644 index 0000000000000000000000000000000000000000..d33a3b80317164143bd5b8c9816ba1ae54548b1c GIT binary patch literal 206564 zcmc$`dtB0I|3B^y_qO|P)m-afo;F#vW#-J3Jb?G^nbd9O%&92~n@&v;NzDTw*nMv+ zONCi^KCoq`rpOEtPe{8nF%_5xKvA)Yih@drprF9-ZEc_W+~2<6e}6n4K9any>wR6X z!}E2#-q*f73)}v;{eLqvGuwXpl=nF^vk&NIW`7aC^A_+wKd&puz(230oP+(ttdVE6 z0DO5f_H)0_&CHs}+cv-X3-JA~7f*$zn3)}Wu=VrWC*OvRo0*xaPkVpYX7tPQ;>jO7=$sM!+korQ2md`v#+1NJRJR_thjA99h7bHx!qfKCNE&U|NlQv zvo`UEUbT%UrflwElO{`QV!p51%-Y=bszI4wj(6W@#?6Z73RNdwHNf_M^R?)Ni=hUN z*PzFqSB$t!t}P4gxl(|_S%zs{yWV`okS9N^#1z6ULtU|;{_Ng2UNPeG&QW?v^x5Ip zU-`G}?ML9b*Q3xee|^QDAG}u<`l@N4EzZXjnv7YdZLga2_6YZgRO!(4uUWS7+SsL} zGk5BpZoKk%Z}(cBBPIOPf-gGm5P7rTB|q&`$SYPf+Zh5bw3_T)L7LX4TnL^}J5v8b zOW&5v{rBg|Yb#f7n466LN3O}lNug(Ln+jopVEQX5_q$O_>9zc4&lD>1X5Z-d_iaMJ zcdf<-j@hz%1(m?$#P1tCjy(@F#2ANrM;1$Cjd?(-@A}1bn>nMqqoEr8i ze8m{EonX3ZrndKxtfMF9l>@x&Fz#5PPvOsrF*>EG`-Xkr+pk#X$+sqze>fxmTb@T` zoO6F>_$Jn4_Kh!;3=k<4rLK`Dqg+v#;8s=RYM4PLVx>d6p?{O(nAfJ^2tf zcJ*q&+3^!8-KQ%3plNsCeZ|u*Q}V%ITTTA`m}~r|$SdiRw5J?)Ytks8=SN?_o?MlG zpySO^)ZxP`Hg2!dl_!S;+xM;YSd@j%jYfUz{8&2ys9=@lS3Vo+q$=I3_PKeh^EGMy zC?JLyXD-X~b75y>)qs_*Ex?UmjT`HI{}p>&|Gr%ZOi>KveW(CX$LZc&37E535DW5s z#o#B5NYLYUH>qUQ9utH8nDQgIAUCtV*Q>H@?BX%mSdP$$z`iu?>8C7P$+nNae-F9M zOj4cRxc49LeAKnajNO=?xC{98^3+~S-xkqo{`Qa5cZ+>xSA&JX0YTW8;l~tWH1B%v zAMdCHW=|q;G90kjH0rgd3Y^Rp`1SR5G=PDF+Yc7abOO?PseA603Xq$U|6XI``5LpY zULztl@mmWX&oMmzW#I1&{(sN%0}!WKq+(D1Yu8N5!%$0q#D7gUe)Rv?ct*=;^D(=A z%g{=ldzU+3{IanA)a%uadCd$nCw}`Wk*6`s%tP5e_2Hq-TK7CqUK1^_jcSSs24G{u zb~_V*XS&MYufMGOPXsGFRfZ33FFRgbdLzS2hBNExVeHHR$z09Cw>@Fba6gRtqCb06 z4?%(YzwCE^xcg;_Kd5KePRqOiQnp z^|g$bB+D!V3^sf1sY@flOeqWB`9RdFeGM}+@z!P3{{kk@V#~{BTbsDNmeTn46IA%d zWpHxh8xI&SFJ)#ku>J4Pi2Pu~P4vdrq7N+Hn6EvZMg7V)O|6qZ2*TUEJi*vqgfV;l zNm=-YnS|eFbD5U3^oFFjZTn?M#J0$kK12t+InN;q)W5m!wA|9xiicw|+dgDX9gxN_{ePf?+xX*^w_U4vqFpo;M&6IsJ z`OdblbS!z`)YTUK>~pDo#tJ5KTXKhwS8RP*=zp?3W4l=|t;@{b9yxt=A^nl?%5fI= z2)w=e$$nN>;-Dp{I7k-ordekR3W;oRRQUa3E-e1LW}EDK82i~Np38EEn(-mjzkg}J zA=9Bo@@+Te4%r3)6Z0nHLaIb$W(YN-IRYy{DD_gMduz%)NJ*S1KZjJb{ zjoQZS{QI)(>J-kd5!^|$2W4%~MfgD(?Jsz7P*%VC7JoXU%M>~E>kDfT`0y{V3YfXs)0jqrDT3hmeinS=jjGD_pQEXP&kpk(JUTUDzoZBD=|d-O zdi9grd)Bt&t3)mTO9?Z6*o;!|@%0L(d7Y&|TqAuAzh{1Lo9g9nT~&=WL&-g_Kcn!5 zW0E>%`EAANuW5SSLnOsNIU?+({lkI%d->KcR30HleWmc&1qqpX$DIOR}pDq^Gav$e-U+4Yc_HrNa{WS#qxE&b&a;w4Z07m6Rr=%%}gXW9y~etG`1 zV=Z3_upc}FS+L3G&96rSUHiDH7oMYTXMT#M8HTlIg#Vk*rd+0XPOXG24|uNiYFgci z(VZ_u>9W_4S$DcLQmN$NO?sRU@kxSn|J0Y9Ub1Mc>KV7`G~`Akw|G2p`(Mi)C{cFC zY4!JES6>z;1>hl!-Rs2Pr8G2od1kBMjmWTMAKvcBXW6Q2>8;lyoQTKI?j z0*`F*V@>@n?_Qjg-d;Ur>Xxc9Ng(zYbQf6O=9iJ5@N&kK-;l)YKBCy|GU010J zPaHIT;t@IXcE4`jyba;7`I#Oo-*jQ+l>-aSxy|{w%FVp8B!m2qseZgLWm{X|LKd7pn_N zhJ=|tb=VStDdQ1?O%0((=(>X9tU*!r*kE3q=s5AUY@NA@w4GW=vCX-0aXHd^~93h$#wuXcj1}Qg=_h<(B5~jRohA@1BM17oxY;#J75!V^7OGV1TiTGQ zl(T_Z_9IXeU)Rl6PifNsj-m)=?~_Ik(?XOEAv2Gs#&LelN!%vat1no3nWTTXl3h>C zoU~Wu+P(%OjPLwW%68U}S3rIw_WC!;jhxD~?@tgvjhRthEB4#@9KY!7R_(0I%zQho zF$=`a*I>|UYZRvz<9(}Od`O(q?8i>1M|O>ZL4=i)Y|oI}mAcMdSyKm!#sSl}_*m36 z`rCaW`rE+H_I!yYnBG88_qeW%%da%2^9MKe7hZe71aRs-icF9;%lA^Nm+0)xP`I(& zVMq{FbYwPw5tUpKBXAAY=?0Srs$bSEH91DVw8} z&x#^vIFDE@Fsr&@8(&TKK12R$n2otJ`d%EZbZ000Ie4ZcHX_kQmW;|`oAHD6|GAbbOGIiA=oq)dH5OxL>Y@?iHTLgy z#`rJ#H}}VFokSP**@_NnJc3?Y&q$m}VQxlzerMq^$4WQgB%|-H+B(1mH6F#A75zG7 z^^z^!vr4>0C~yXs&(8)$IVc&nRa0>@FqJdmR@T=QQHrZ$WBJX$jR5eK^^xnx7r-YU z7G}O-07Bl+YAE&G3agM&I??L%E~k#=dKAB2m^WA%7QAU~&Oh1ai_Ywj=)G)Egq26c z!9xUA8hO>%)99UA9xDOc=JzMOhS^*8)1&>z=QhS&Gt2V9SLsd@j1{~M!LTOolvY}kXbX{!n0U@Uj3(b=(VV3Q$7{k{Yr+sa`>`0zCOUx0&gN(SFq->9@TjdIKQzaVaPa}h3 zMw$Z-Ju~GK2QZo6>^OFB@~0Az4gU2MJ$OXb7MZ&emV~x07md33ZBE+N#N`hs*2RJN zbd9|2tFz6RnO1Oi(tb3CwsYzfFLUkT`G;*%|Vhy5f`Nu6fX=XI4h!vls zZV4Y;+DNj+m%d7D>Kvb`u-41P?p?j*c%SaN_r=^?bFHdtLOJkK8CCzC60g81cA zVduS?IJ?!_g=9Fq(=YR_{pOT12ZGJ$fK|uGYtfDdaf)-YTY&7aoV_}6!+vFk+3ZBh z&Uz`}+a)F^!NYY@#d-kF0mI)ZC?b9$>1W^Lc-yE(C%vG2O>Oj??P=ydf#SO{SL^4x zYxKc5XOCrD3hnG@9*GAf_VQp%OaE&qT#Af_5gxC}>K8o&Uzj?#s#}8fYGU8cD*z35iQa2c*Im^&xI>YdKQZ#~63X((93$Qha zjmEzjeIYw#Cz4r@QPr7LI2;!Gg_Haqc4He3Jy*Qh7HP2Zg5J#Kkcm6sUb_}c925ZR zLa;mb#l9pczY#AIMC4?Ancs+Q6ZwLs(PxG4^%D)97qvDLOAZzxvP9f3?0gi06|PhL zU3T)>rwG95c)B)yx4F8^GFBP~Zem!1MdEi*I52vy>^o)5SyN>_rwG1tqlNN~$3V8;3wO_pP6Zp47gu%uMM-WX}9y7Df9`b-qs7h(k zK2OsNg{K^*b>{=edZWYPSz2L_c~%>=Ygp($QSJ^S^6AHAtC}fAUVq?-XkIkiwce*I zO@B;VSYInxQB*&&e3W`=VLv|jDP^VfE`nmGzphT3aG5N{^5#Y>FW#gcbOq54jj zEJ?=5d~A_3Wfu^UvJde8_09|WeEko@=ZW0~UJsxt^lR0ZbZ@Vi5B3~ng1wB#S;YNR zjP)>NX<%V(?zJtVSowm%EoH*#yS-^uiXp!QhsyRQZ(8Fo2j=i)j{Y41&ivUup8eKQ z$J^iHDIQZbX?~VYx9`F`9;cAY)4S(OkJn(U+9kG2Yn}*r%CuuTYhcQ!^q&u+a2|JsOQi&B_zVQSpDofGpl>(=08P{us3dfO@-J7>@ z)~zf1f9#J_#S9j)T=}a>R^uJP!yy}S{EeHQiSPwQ>ev3*A7#JooeMx?-sH^icdKKY zmsHMBROd9k|Cu7G$Qjb~m$HZ#>pHQp9Q#LPA_^O8dat#m&Tz^oB3`Z>e=k34k$sTq z9O-YGTQw*C!nb)w6IR(-X5v2;)p1F)d5`ddGBD^#QOPhrgd^iQ^+orzH&L&_gh{Ce zD}WRh5j0XQN}L_gWJIf6SwxG7dNu>O`uIM}@IJ8`6K~1)-04sUhz7GzQsb$D^f}%$ z>^B%(SZ*=I2oPrU4vkVpI^Df%M7N^x>qtggxrM;kb85t@La6xV?zJcEac3l|)CyDR zWolnZt=OPH8rO(BHTvai$Fb$w8P#9f$adNRSvjY-ja88Ysz~~V>^!&R_!y1;)kzf^ zsp!|bMQm(p8~96MMssIMdSjcNKM`gm4XnSwng=^{urc!x%;t|-os#KAu2Z}P)lZ|W z>GvwGtV=&jU%M)FBZG8L(a)%(c}tz0Up6F6yiF8y^I5L{adfVs&`A7>s1bYorR^c2 z3Ud%@wRCR4MOuJ0-JgHkurf7k{Oypbnpcnw7H@RvvcnPEjKU%O2fTod)NglHFc-K^ zWp6}$f%FQrzL|ZfR+-PvAjZcd7a5oQ^3D(WscS+(dvEFZU5FWOpO4fByanGRWX-7P)`J~HM}`SQVidb0=1hH!Ck&(pNZ zr~Ly9vU+KXXrI94Nx~Q_Ro1(ob=M8W9YyUl5OsR@2+EO-f3io^AswfU|7`2rvq_a4 z4C|ToWFXnC*Un-{W6cZu_4*QdvA5^vlL>LCM$fwC*nUD&`f!~@;RsW1vTx1hh^`+< ztrYH4G5Fub<7uV-ZMl0eB9uB`kzi>rl6UF#6o{8-l}DZUeZJG+(nfVSada(qV=-}+ z{&*9ATO!NUsGm3kNiSJH7XQC-kQ8iBy9->m~a87Nl$6JE8@SPL?aOaR_lmH$-q~uPRK3l{BEr=Jyq$Mu>SX z3!>GzV(#~iKhr36Tbe(kZy?wdfTMBJD`zyRbeZSmO0D7M#!)*IpVj2gAJRKeIPzEz zkRfC^^Yco42)AjX#zE33nyV6x?Xv}hz!PwXWXWeOf2OoO{8RSB4V{TTz{!bs$2P1! zgYJZ`;Hv;|%yc@4%_a5ebZ1}02xdF_ytL>fhU6|dWb?gFW3k)xUV-a~?P6@K@d+RY zKE%vGzJ#`CJ6YgAo&?YOG#Yrl?L>ErYACChN@-3GvhwE2TtnvJ9k zsnzmhw9P^lB-t2JsQ#Gc+QCEA@T6lYF=s8mX=r^xo6Liw`V_7D*Y)zIB3Bze1u{3f zVKK8Co1Eu*NIOt>c!*N4_l0~sC2xK=mAxLI6|9i?@a`zUQBvnbo=LV8_IzTS-t3=( zFei3%pIZ)1%xd<3(}?8c9z}>4CN~&xvz1LT<)J2<-RRm`K}MhZ33-4b?W!0c4UE#P z#c*%#@h^5{5#2fvgMf2E*%PAmrR@l*pPdXisE7>QD^0Et(~x7{_KH_f=qqrA`-aO+ zHHpZl1#0V}S`OH56r@BF@{ohekb3|WgrfeyF2}aJ0{C75w(qUjsGqj zxvV?$Syl^nHum}^$@372w@v+0e0w%H>nUDDPF0gd&yLSfUQccmqG0~e<=mu!*@}Wg zQ-MHAfD;cWu-ZX!sp4B~R zsXd7|Mc#a1!62&EN^t5A`8TWElG7kD8u_KWfDtw4S5SH1W!DQD)C8DBim7e^El4!#9R`^~k=%H}iL|-IYb)D9)TH-=>%tVvjn>>V-i3^0Q&xm9yK@ z_bc7o{|PA=N5Q*=J8w{GMMwyo&+pTn+>D%3t^J7`)~u5Ik7`?W$K(MRQcgC9B)Kzz zit<;sGS1TrL}6uNUPto2xI-l{3a4u8IUmhz;tR#D$=@yKH~S`6(sc=%SZ_}@>`py) z34eGJ@2qW&h|AZIWD|Rg{qj!u>pN^m8E#Djz z2`kiT-k43^2k3q*jlmGkE;{`!gvqRVhDkXZ(Qr>R%C9vY(t4*rVDDJzao=@$mU$<{ zcrN_+dyEVWNuzHrppbKpkyo>Z#R3%ElgZ2tmLa;Roe+YMK5`}8XXKFA-XtGW(iy;X zvt0uzX=er);Cr+>x?mI3d6axD1+mO$s1u-CUjuX)hM(PpcSg{-&g#QGzt6Wd&klMp zyHjEZ)b;(@tJK``bbI>j6rOk*n&>KA;TFm#SF&ZKc&y0%y9NQwKuiw^xmeC zMugYQdAgv;9Hw_>IvFcYcC|GOCKt*l?kH7`w1B zp}Nk0PiL)B%Sz4zUUtp>ASrxb5N#BJejk%9>77jU1 zdKPQM`BgSv(!QkZD7@}lU(QUn3~z^4u3I^4wzJxE=bAHjG=6wZSO*j3f>2Y=-VnGEmCECwt?`U-a=rZA_;}8tx>S!2|CNo$)K0~Op?|G1 zguRoe{u_Jif7r>h`#bKTeq-FXixE-2aV1x)vM;G7^0i0n48Kh` zbj>q9Wk%I)TH(hdWW!SP>wX~}~Z$oY7hHrw9a89GcF_qa+qx^}XA zOpd)!&mP+&V+=ykoX%9^(K^DVlN%|kIVQ#y4UmA_5o4NcE%;m{w&_Mwl?v~y_X z1dUYOZEIB}&a6xPQgnA&<}CNbg#wQojWyLv8pSy`bKN>an!MU~K4tcVHv*+ejJFov z7Gj!_b|hi?w-P~%H<5LTm0YOrIz*x_U<=)$A>_e9Mym3yu98%wAAS|`Xi%Hmr^7J7 zww9`pcnB|?BEr6x#U%2{FwfJ}@e;!OEBJl~R@+8MG7H2b(kQb2QxuWD+)&EH!pbKl zm0>Y&W})IDu*@)Wbt(emcjEqBLo(D?!ADGWH#x`a^EHZ7le}}|tzRJ;19Ju$88lnC z1xr?VJA~%a#$z<*htT}Y;j<&|$iY}YD|SJbu%;&%--^J58;5#3`(otf>WaJ!?&^sC z=*c_e(RlwLwcB_?7UnUQ+jGu#jkI)9F?FasB%Xy!p27&)NW%$7W~V$__QtNEXKt#! z+?BZGKg7W)CkatXL)rP+(@4>`C=|XEoLRVh{aCz>N{J9xC)-W8S-2R^WF5~xC~H~` zlMC?mo%t=o6;$)FLXzd6FF1wQ8%?XOPtA30(Z{lgC6Adt_EC4(^{2{)xg%|l&PgzX zDCcpxjNrgCX6}*8mhrOlyr_dO;QI1zR-Ws!{u?Z9k?u{u<;a9VrMKbDC z6_r6?82oQ2cB@3n(0GFJpVss$T7PBnp(@%B^~f*Wl-VA0pF24Jo4p%FW7`ykU8TBw zyCoCL3G&hmKUx;Bc^7oUY0=C|Oy8Kj$RUzyi#I@Ti>|896Fv3SkUgg50+(T12f`+J zCH#is$0$EYnuCc&*dyO4VkG~A){uWGoCZFcRmUr!s)rif(_vBdHmu{mO&T#jUTiP*g5E)1b@gqKcUIJ@&Gx=_MT61|n+4eum$1A%&pm4CZt` z%J%5%B%lQI>Lq}jrT4DE=rvEYq{wYFpBKNBf*8GWj_%n7#k zQgg{Kw~bHIm1N>tw(Z|U_xbDJ;1dHAeK#MhFWz4c=F}T5;Oe-sy|WSdUQ=H__i1$K zRUmI6^WyKaAaP1>y%F=hV0>w!c0uR+O1aC9KYM z)l2NZW$@tfwkARQ3DHN>7my*o2G4P1dY|U{x?=4J1DZ9vD4GpuJ8B+VubXn(8NZcX zY3bUmPpX?GH$v7L;VJEm)Fh#zYOvX5QY>~Ua>|M5YlYJcxHHSw<9=s)@qn!e%ak zQX=n0u%bi*GZg};WgLt~fej~9C9Rv)da*maA_oiVIrJ*y3sDDxtkNX=FE{ zvmn+JDdY9(77sIy1|{;tI_jxd;mjtpXVp>PQiy$Y{tpWeQrlDBZkh8fls!stb7<)? zE+6w5rwk9=MFa4pb>~E6TDfdH@wuA^YlZ_+idf6!*8B_ZXJsg zmF-E7=6!6cQrC03>Ip*ekG39gp2uyieeN@5pPxJfP7VxHUU`_`tU1_f;Wl|jkFbOZ z^gPKgqM^KrpNjkAoX$xqwUdw?EO(!TNi$2_f?dmyc5c4+#P`O+x((qi@aVaFPaI(Tv2R0N@rOu>3h)=vd{rLf!& znrAJ@+efgi2ieA!8BY-cR>g6FHGTmvSh*%SjP>el~*?dVE_g(lDS;YWZ!K8zn($T zhk{=q_tOt`oUU}!{MvlXuGFZ!b~hh^JuM!ao3MYVU%9y5?OydUHJe}9-+u313GI2R zB5*?N7nekbvtCR7I3l}Qw=T&`N5v?_t3!G6YHQZ-j?DCr{f>enSLYs#xf>syuv*|q zGA;e!fZE0_Rb^9;;n5T4$hOuwkmw}ZGs7)eSqZ!UXrQ!nff~3rb5l^Z3kKHKqvds) zNxIRN>W_v2yx#QDw+pk<&#vic&ZOigwv`s129S`mZ87;W^_3FIpJsQLoJ_Yc!O zHi~m_MH5dB^hPs!Y2-!uF?l(uIA5{XNu2I?*3wDuUaLXK*#|V5y-h)DVqx}J@)tBd zOw0mDpcKIyIKusE8?PZ-R+{&~{H&AokNnhSSuc%S!k>7Nf4H2Zam8o1_UGrhBu`4G zQq?yQP}a%{xm>LVc@ZUj%EOF-Js|~z5VvP#JWrT%uEQ$nyRaOI+QBFBL4BN0qFqD0 zjX7L9@pZAFxeC0*NQUVTjzDc3VzqB^OQMQKJne*57T8 z+YHr-+E@pR*sJcmcuKjZv`#mBjHK<~P4Fy@wa#ICa%ONd?n){gJsxVjjj1Z9uY}!r zuBx1MA5-H=8*;w-TyOM1ubTSkT#2sOqAD7|0ap_~-pzOE{EcCs?(?~$Wk>6=-VJVI z;St#`C$Z8cqPs9yY2KCxB7|*xd&fE-1CYXlm<4&BICx?qk7dKW=r7eY&yI|L0-BzW zv8a;Y-QyhXD1byRUF~Q21x~MTuFvnJ;5D{>cyHQv^N_mPi9sJp%`=^q{3f)sA!l2T z$o){}s`H*+xHl#(z*9dUB3csvqhKWYI2wW{Q}D3y(D6N4{)`lW5b0 z@s!eRb9$=fV86578uuJKw}o*JYdu&m3dkBf6vXo|LhR-Firq<<8dq0xvpJx~`J!Iu z+gi?GOT%LgX%xN|%9wb^7!2qzr*(qWBkAbjYFC3Gt|AA~!u3@3Zf(OOa;|2eRU_Ph zMe?l{N*3tiD`W0f3#i6tG1Z7JjdatmX-BM4<12d5jbH~uiURfO@L^luXd>Y>5; z0xZlzQ#^(}FH@bGigrVHpVFbrV}^qm%jPKAdKH?Bi|UAugElZ&8bN-0V;$kXFpFy; zO+RiZiPCKYQs-v;_b8e<(Odz=`K9>yJNe!BU8dVw>K+x?nZmReN_;g_V!)y5ZS$G& zxEEsba2=Ru82XZxM{?HgZ8_8PlN0HW{Nh;2F__A2tjv}~qoTSbXc(gjIGQpdDSIO} zF#&K~P8@p+HY6FW!LP26&nq4-o}yeN1ISAn6pNvDLQGRyUUrs9Dpd}qu9r&m>$SBQ zZi>B+aMfjM&?Rw8JHb$xMvt>6ky6kcbIiic23{RRr=8od&?q!(!MR-r?^h>Jt01~O zd7dFu+Fo5~`Ri0zSX2a+>DrN;7eTg&kOsR@vRyQz!OYG%XbLy80EAK@#DlKM1yc5#1@(#m+1LI9ij2em@6T#RJ` zQMyq6@v7WX!Kb+RfT}eVQ*%24HTyMM%L`%9208 zD2@Wr)b7lvM5{bGfVmUo;sV7!^DKUE9LT5Vu(;_^grL7h8<5sa4W%iW;xEYf#>51EX=JbhP_@>1pW30dRHIiF*1J$CW--JE@sR#A03W5A+$ zfvIo1duf=dzJDNkGQdXp)pO6+LUkRecFZm|)pW()f|S8L4i4ps@hMLR^767=cEI`| zTl#0cdjXGrY|ba2_!CgS>Mt2AQo%{3cQq zZ=WnoxW%lyyc(9eYcAzu+P$K5$J-d~{)G+a4OSi6W9Uj~+r(DYWdAZL$qj`T_SZ0p zR8DT=NA;!t-QrTFjpeLRqm{IWFEwnXs;HV!SGDAh&Bk7mc5I*t@;@jVA_DPE)glz0 z%DaH|Y2YsC_wTDPxpBqVyYaIOQ9N{~;J%{m=YpFG&vR4u`izhH2boEV(P~#p_1u)5 z%@jyBXqn?K0X53U9ULgxEJM?QqQPeo4R+GiX%8r>O!klN-Hk^-o8+MC9R=F4&=$w_UCIK`4kI15Q zqV}c4YeP2oGauHE; zfWB#ZnAs23V#M|$`N^Ln0~5_{+``BJk+ex40d?B$S7 zpw6aL0D6}f(BM_n2VAo#W%dLqguNc314gKCbG4{4BcTP7e^BIXw82RkG(6~9AGOn?8)*^X3#P0hp@v=1K?3o_u6|?9$Er6y=!?JP?o3 z<85FY^UqkC3+(CT~xhR+{&5Xewo^tU-mwo1%8`1 zF?ya1_ekR|o_Ox*%nu)6NL1g&sJ_oa0GE0NEHMYUnqlE%Wqy(NhsnQ{Xd$x7t@8;c*3F zQ0N)V9aaE(raJ6z3RdD0;8Q{l$QZU%6D&&Lhjof13}}Bm79}kt=j?NkW;<^*%rVjy zZ~TFw6I3wUE|OU329swZuQNo+L9*1{e36zrV;ip@gf1}B9hT0S21e39CGW?p7c0`I zo5Ge)*$SG<>V|>*Z1?n$LS)mPR`E5&?<4ND)wB2p~arLK{|)b!p*-26! zb(}e-JW`bYEM;5^9zPkL6d1-*IZTtv4t+t(!wWLw$J&VWrFz0~_Z=)~=-~}o&+ona ztWM)$lwg;ouo4Cl1ipX8S$14hD@_sX6O_#qCf0TYvOZT{Q*iW%Z=0uLhDTJ_)`L>R z*KpJ2lT|I!+_n2|>}+P;QpaunGIVNWV;p zGth&{Vaoh1ofGMg)X!1{4z_!p!g_2%RzsDBzEh@{Kd`hlu;M#baRtg3hh2-j+bKas zIcQs={cT*hy$ULcvxqug6OmIwoUcY+uQgq$P`Je@M;jg+urrx^Q~OgRax7S@zD~nT zRB~m=D)uJO7+vPhjo&ViMAT zcq#p3BP#+L61|Q~^uMoIB$uS$63wJZB3zYQEww=X%KRx{@#J|Jb9~}ImM6QJ1^iwv zsS3B$n;c5lN~}(#L`ji(e|nzW_;%`X2C*tC>5hLZ49Mp6)E26~XNVme)F^9MqE$nj zkKUd3JBT=IILi+z3pGYk!UwOE%6d2TE~z`LS>G_VW5@}!@_x*(Q*!F>%lnEvM5D1S zO(9Ca6A5P`5LGB8eWGcPQez5s^K-yZvsRMK@pHr3_4*?=e9p-M-k;7$XF$cnph}7} zjbAQ1=S_sk^uY$olk3n%tk#ZqvPu{2qO|A1+DNb&oK{@QpRHu-OBXIGQ+*?e+oP*0!g8t&8^UzSBu=qq-p<#I!s>k&SY-^?lYdBS@TJKGI z5#2xdUjM};Qs0!=sJ1T4o$+&Dmiz=_x=iPl-Mh#FnrAaeX%7)3`^10NgS(a-V)=fV zELWQVbsyMPYh%e+n|n|K)xGc@{rsGdy&Z4xk#X~(zuTl{Htw$q>j@MN`;UH`=-Y_w zE)?ITrm7ZI{^>n_Rhapk;w#RG6b(y7;};xYRKWP#+-TYC6DEPX_p`{2&N+c)*RH?fDjU z0Kr<()t?MB*#vAveS35SYH`|mTp8rxJiYw9BgQNXvzlr_sUv4X!@a5`LtT4Aoo~iM zm#I@P%#qmxs(dF7WQN=v^(l6(Y26U zN#2v2PvaE5VQgxucA&kpON4#6zg;V85NEMR4~66@c4MIdOYGu6JR}-A>)!kXqY++= zCHpo!l$Qd2`*`5;{QeG`T~6(!ff&(kAWy0CHF(`W3XS(K!2_YSE2#xD$2yHUOSNVn z9MTL4H~EWngxASjZP1A!QFsl|cVRi()^(ge?o=f&?+SyEJ-I+IeM4rGy2yj>o!unQ zL5}goPR@i&K~qQTmQIKr;mM)T3S9R3w#pp4Na&LJ0xphr6l8>!W^toj2>@;#3uY0o z6$c^7aI6(taibd7%qi+ysLtt%Go*0Nk3g^8XRgX2=Yj+KbBoa^V3L6b^l1SGCSMe7 zoWL&O%YO6TqM_E!G_RxS z4;9(|{`Mc<49Y;WHemy+p-`X- zcQ1r9rcLPr@|T!f<6vhDQ1Ww|@|Y1Virr+6GhHX@$+TYQ8KUQg=PiC}?1=6jwovU! z#}sWwW1n-ZkJqTb56-` zAZZg-^1Mv9n8d>aTjmB2n48?^=Eia3k~bAO<2?OGbetOy;n*|fzj`Yby&JV0PNN$8 zIi%)~NN#GvLuCIFc~n}o@v&SYhPq#ckxc^PW7<-_UIw-D3lw_dugJq6dHM#%aG6wnytP+fHg$+2j-N&!e(SX zUWXcWtKCv(N`%alImETvQm6+V-D__w(bF^P*P-@vy56Kd?5SEBPl<|x zK&Siu$Y%&@fU2=3mX;gFt_Hd%{#2|@rfbxuujb0bnubqdiUQH1|FWz;)4+n;n6lUL z4)RVM3OSpW$U1r(nM~=Pa=yJ2hNJ=2pSUd_fyUckRJbPIPb=(5%`6y3Q{i~Uuh{`E z25}hkF$Wetw$~X)XbKWa7#WU}r>1@wTRX_QALcD)B&SeT_0x^edJc2n!dAL7bp{87 zM3RGSXbYmoIhm5z`4;aS(l@=3HFF)>6+dyC-NI|b&m>{>o*nlvcso-^UmsA&-0C{3 z=k3IHiAHgRS>0X}B01GUS8P?KKF(j-;~Xz8X}T8&66){wE%=Dx&bO3G7ZW-4VwzaHR%2QEwenzEXBp<~7O zVYTHB*ho7`&QQGzSgYF&taxIT^cPuAPY36@iycDI%3BL#7S_Yrr#ilxdY(Qkhxqt{ zpF%>r0%(tR2@6q{Gbg=7GWOHT1LD!hCBr|r+5)LKH02so>sMi^N+>LVYME7v+r)%PmX_0fOB6M`3J6XMAbx+gbI1l^UOEW3KKm4MJ{1sZD=lY|_OH z(QZQK$;#NcRFv!&Pn%ew<{mZ;Hsuqc{3Q0YJ(#oQ%?ZmF9!onuQ0@9C%PRLEs z%&|%=*W^V%o5#*Gq}ipSV9IekCZRLM3KwmC+9O^$s;t96x=zmQjsqok0SyF(X;s?9 zxsniW9MGyFTXd3Bhr^mvCw4K~1@0zI9v)>Fi`4e?A_e0oE*@XT?M$i3Z)@6(sQ}~k z2ZwUyv!-UZV8z~Fr>-*sG2xMDMhJp^GNBGoB}UJVt@>4G;lw?7VSo0hT!cV+4>V)G zqLpXYesODWzG9b2Lf=E?#Fq|gM^=0`xXDua;nK@xV+6~TUxXWuJ&r}s zO6FbdN|EqQxRbo^SY(%W=%jZW!-SJfS~>W6Z{kmTB8PdTAV)Ie*cWK!yi1j6&RNis zt38S42X7S3cqV&8Zs%r)bJo*o{s5W6X&4j%UK+~E4D)8iS0-iBx*Wnvvsr}ouUOjG z`MW3#rJ<8Br(OhJB%mKluSXepv(%|)eUML)a+w;lamLzbL|M`K{HkK>na#h0v)t&r zF%$c$jThaF)=4sQQ7rKn>wv7w+d;ULYqI$~|L#glX^giKG}}{DtQpNn@G-uB31j1% zEP-tt5z!uHBakFvbx})^aegap!9F$a%LIV)xbL9+m%EBT>1B-$i8B0hNHXd_cozYWon8v_7~dGv>&G_s_hFZ~(s-c%YaNb4)t~Qw zgp2!ldbC}O#^%mfFI8irXQQT@EP(S*s?KxmfvQUn8+H=mW*S^|@yi)YOI!dt5}NOe zhK>km;Fi?zqLEAHRWV{wWIb6ar+)@Foq(<=AbWv~r`AIz&*PMhw29}Y%~@@mMQUaU z#RDj$hRk3K5m`+4$^}3*qo;%@Ig$i#gyn$i2~*RH*s(y_$f*Hdj(z_;OW0yJ)FAk@ zCyKgR-Apg+VO84SKB^fVH2&3XvT_w}M=M{;EpKeWj|^I~coQYOHVh(%Wm^ufMsu-DguuIE6DqkSI z`0cxmr|{8~L`{?@#i4)^%md;qC`?M4ipamgGu9*)+eQxyYYo;GlWl+ofXu5PDlkS^{$&RE1)tU#D~ zVNicRee=wCs}Imq$UKjSG_ZO^3EU0#2dOz}le+fy+knTXJ`->?tR_EYF1LPe%$hL1 z;@;sOBha4g463;45;;M$AyeI(Pb3rD+jAKrSk6QdOA6CtspaLS+7rY(%MLLJMbcuJ zBtV-$C~8*at;Bfi@Iygx!g)2al*}?_bA)r485Yx)DYwp7E3MhgMdX*``(NwyB@))4 z>4}zsyv*1Fb?$1ut8v`81PDq5R_Yj6|k|W%g?>Wibd*0l7@q$UX*sjbSl@7RQvwLYF!JaM6!titI(d!e12y0>F zT?7iZghZu7(-vCGMW>oQV>Uiqo4V24A?jK8i1haYN{y&Oxh*+1UpbVrS>c)JU`CuA z=c8HLyq+M@6MNxtfgsvjUl_vk>TAF0?#5u;Py=UE?IEc%&KOFvX7KH#_De~y0moJ!!Ue92*1VncOFXZ@3 z)916bgU?=xv3{ks=net#!E2l8nylqN>XE}Md(U?Lf9$u^=D>h=5E9B;49slp#fwFbNf8hD3&hAtcZi2{NTj2_z(; zKtPBgG9&>)!m|^=`s@GR&;NPxJnw$zg&g6Wz4uysO?&UPz9(wbVQx<;#FaK-<_Kv_ z4YPv4$JkrdrQd{qybi7$x`7U&AA0Bq%8ylJ!nnxGkLa3`-&Gc^Dgf}u`HlL-!f_*C zShHr$>YYNJ1CXoKnX{1BhJQotpa@vfCi>>XZPDyb6$r}+XKqWZ#+Pu)YU%SP#X5q< z7ss$e{qOL8>GFf;y>pc|K>}zcf5Xs_-S5(8V1nRkq><)F(_2E#rei-03FKxU*M?Ex zUXGb2DFpoFO321ToVE4ihLR z==t)jaYx@g$v_b zcn6Gletj%}0}ciwQ=|6$MXwr};HJ`R&o77J^Vvoa-iyD=4YUUYytr_3w)hb1`4 zC!e(h?@B(id3G>YA5^RVUFPI9Nr%xPw~aeI2h}pS_=&yj{IL?5W8%{ipBjfnlrQwV zPI~eIoq*W1@rJ~4n2^To&Pk(5eMIx6q#|aB!Hy>X8|A`A%?y|7FiGH&iK}o8$Dw)W zeH{*eHh)?A+2s$SN|*D$FL+&W^jTpf4>F?7n}jr*0Gt&ISJviRdsym#d_;flP^bn> zc4lFwBHf`nBE~vmT$$*$dalXmsr6ENisfnU?a-4RO#926!RklJvSM#7?Br4pC%p=4 z6WVY%$amkGt!&06Xnr-8kh>^;1pRTsD8sEeRWcEn%-gvaQpKy^9EXm|-3(y?(3_c$ zvs}qxN#Rxym(aC}E?Qo&F0`t|!y0qYfg339L>ozi|K-{@U|K`>n|70j))>Mo}^I{K7t=%oP2?rzY-jna!~_Cu|+$k3I`5Ike;HwPEg`4WWUjw0e{R!IidMDUN8BFzUVHQ3_q_KJ0x!iZFCL+_aCvQH^GcZU> z+QbhM+y0E6T>2!raigMd%JDc~pt4(kmu~_p941mjO zEP*FmX|4=dc7H2`vS~wOO}Y$xZQw%vq$FMb=Qe3~*qSm%jRS(wnO-|)H_@jRxQ=4?`b2(KW6dCC$ll0Ejdc;%G#2{-#Qk^D&bq$NwV4_G zeGT|$@qREM8^tb3?}C4LzaStg2K4@VZivje16k^pHt)Tk@X{8{U* z5W=7At;17^YotAEeZ$60V{oKz#=Q2>!`Ze&Q5EIx7lSyRg;*2OzEBK8kpkTm%eMW| z-Oty!gBOFnpAoUfzt@|)*?^*6K#}(*HAImzS!M>gwF4lOT=WBjRf)FthV76B^6LEh zT4Po&Wj225-O|?j5Dl&FoC?Sa!)WAp^L|Fw*vy3(186#(P>wJ3bYdvESC%|QDqu!W z)g9B}dsP@QN`+c^ubgr5pNZ-`(Wp=wLX<$CuSCl~l})C^tc@uuz8Vnj1cX&<^WTNF z!OOT~H&X(+K~Pr?H@l1{z0|ceO#$g;<70TR(;!MSJ4A|M zv5fOrBG*pTp&vk?!D1rCQ1^Mgp3t~d|8Q5|LddZeyXtuW~J&N$c$55+w z0D3jp`^>-`QlM2L%yh%`(A*z%;MxLo1Sq4DAop+J^TCxY*CjRkR%|49>;NDee;XvK znn!Yc@6#6fW(co5Qnc&qc<2@gzn8N6J@9t`7s~7?TxFO$Gg2`!KRh z_G%)oo(hbxMztuhD!EwE!`{8xB}(Uhc)XX{APCKL$E;8!l5;jcoC+?%q}*BBM- zKSs0iN73yTl5zC3_L~}v+L~EDY4Wr-rcm<#z&;1)bc&6sTYreW4gt{N{Tm4+% z{(|&3ZYjE#^iN`p&Cl{1{(Zl(Bkkw5B)}9DKjYSjn3kRfUzgzR(T|3^t0zM{WccN^ z^SHQ8z)%l0Y^#|n_=g&-k2V92uNQ!=URFh4THMZFAQ4U~ixrb$@&yEP01q`-`B4(i zO`m<`@IHh0^u#2oX6QyLbn1XVYbZP@fCiIb?hj)%{FVlkYka%j%yaOxMZOb+iiXHL zG4yE5&aLC!&G^b@x2ulFPS$4}i)#HrQIYD{R@e0VEk=@`?&(Ot7u913pTA?K5LC zYA<8*sYWBhQ=P4F-s^p$dvoadqaf#Xl2PpaaA3}A?5FKb2W4s+epJ)22O)?IK(Nfo z2Fg$m#U3VeRs)&Bw;Nw%qwgP{PI|xjsx1`gnm9q|3xn3({mp`_us%iX<41VDh#dss zIPJIn0GF^k)y5td)jK%_rfxoRhhISSL=|c-#C{G*Cu8)}a9WD)r&>CdS6IW58nDsD zBiIU&WADUQ!s=mOeiNf3Eb#V)H5pkv4$Ephpr&dEpo&m?YFY5b>Sg6z?D*Dqmlg}+ zLzX*q^v(=XmyAEM!=C(tlZ#A|Kl?{B-ZEOHg1i@QOOL$__K(%oq$zs$(%l*)cFGiF zGBg@3$2N<|b#{ z;>^ETN3r;yv3DNo;KuONkLRbgE_0f0EYxL~x6X?Om)%#i{HuD*J169~ohF$)sd!jP z!t4t|9ssq`>i|2iFWF}`W{2;(*{8pG&`*?bE4c&S$XF@<1@m35_o3YC0i8`X@zEbM z1{$98XNNCkQg!*pb4#Dqi`^hGFLtR^a8gnJh;M*HCJ@UF&;jr>jpt*HF7qj`p>r{a zO}8EaQLGTM1dKo3ZT?g!M`K@W+K7>&7a-V!f42jK<&$Mi=zDc?3WbNPn2y{=74Kuq zAok!;Q@jmDAD`4q8?R!~kZp>=WLT+pP*}V-43x_SI(on|5KGn`2>WFAU0#@;C~0!~ zRC$uo+AJA;3yn6DANu1EzUQ40|Ivi`h-5eU_p#@#>7-(tpX)9MJ0@i4ymMw*dgspW zSy>Kko1I+78pi;n)z2K+oxSn{Ij@XZ2~86(m!(0|ZdRiuUfHzQ+9U5zXQSsDH)G%` zYlGpitg)NBEB&ZS^1K7W9_$4#{u6N>0;#*Gv{cNHBE{BmIXvXgOiW)Ir{BVm7I~9F zRFKQGs>9tukqPk?*cSCh^ZgQ;CgUriD{R?8s`WJKyAmT78%7T(;jb^nGRQAFu0sE9 zy3|p;8{+t&DG)B7eV%y^&j{0i*#y*mBev5-W8eD&!QwTBQhCbXe;9@vKxpIJvRqNQ zzxO>iM~K<;Wz&cmB9r6z2W;NP2~CtpC95v|W_!ToNOOK`z+9kA*k1E~CqKEI#b1cV zBJBPm#WN;ZJGYF#WaUZQdL8WSIo0-fpOy!IH#I07cJ^GVs}S!CRgjYzl7!p&;d}jM z7i_GqigHP`MAKw#P7Q6}I?!(%K3?-nV&k?Nf4HXr67^u^_wT9j>`63 z-f_nBmU=k&&zzxmM(o+G#@I@gCt10lZd}>ztu-BJ(QOKU0o6QrbWJ(T-^OdX$2?H*Q|&(G2@A}Igb>r zo~a1NG%7!crja0v;mA|9g79DQEW75$h?zl(C$?i!QL)1e_Ba#-#oHyE-6g|td9I`I@>}fyT(Wc8h*-iPitMfc`ISsNb0ZFwUuB9U=t&a>Qjwt z`WcSYfb+^rYOS%EE80_SXoDO*MlC=Uo?$V9{4lg_F&(Z#Nz4b!1G1a-J5=$;THj70 z%0HT-H~MC+_uZ9g$8azq##0XA>>>FuKr4oO8QWh=VK|wgzBL(wY+!ql z?sm!36cpr~(Ggu3fHeUZ)ReJr0jt znH{qmIXWFZ^>X5KY<-50fvmj>?IRlcp=2VYW;M5vYy@NrETBQ^CiSLqhZ$*=*7)7! z8mg4OYr(YjUK9tlT88p||FsaaH0&%Cq232TQ&da@CbCR|+c3Xt_5}jbHsUYNx9ZqT zXf{oExkiWG8+>}>c79UZ;baf?tMSAg7H<2fD~!+c2W*sCXNN@f@kh#}+y_h}Geu5J zX`0wMC**>q>F9mS)7_Csv>x}8!dF=RRG_sgntFt_t=G#_)DOq!qhh1&(0Pe&!7aS{ z$^uq*yeo+pnWXRt)aYqZ{zs*8(iyf-#F`|4<{hHevcrr^Zb>@YO{cq#d)jBnHy z4)CJa-N*WbSbEZCCk<>c?hU^h@DGx2Umj%daIc1@8gL(y3)3_t_vpHyOul|m7P!v@ zm*%)@NiZ2&J|&S|8lSW6H??y$2&I9Y5d)XWA+Ly-uPaWEb98NZIax>b<_JqI{Gm%a zHN|xJ6A%cm)-EiI6Ju)oPr%$&Q!+%BPW+nHPo`GHLSR5!j)ib5Sg#vfVX*w#_ysgG z=ZU9GkGOkjRyv#$ii!>r>|)562hBWIDEP=^QYdN(cjhVOYogVx?2;yn?JQw8q(xd< zr(%nvUriOcF)GZ1UH6YwkR`3UUQav!(2wkQ8=}(n$jc3Q--D<;jHIpy^CG|kCYO?r zCp4nHKg5Ch>TEroRe&M~EL0OJxQz8ALwIfX)U>43lQ9=YjbDJVYNBY7qQt%DK`lb7 zHv$#Z;m>4~eM_{!cJbIyqMr?FdNu`{;Hl6}8|LnDFcMwL0R5=Y_28F;N`z!9Bu-Cd z;MT7=dIwawvW(MV1>a4$3B6~)eYv~x_Aa+>i{uh$wgGoL6m=O^EFt=wL`WDZ9iXH& zxlF*?TjIEIdbfXCyJx!*f<8gMLJ}jiN{#0e>3H@YkoQ_BUA>e+og=rqmU++o1W*RX zPr4Kff|91vrHrWKwhJ#2RbNoN}L%{W;43vndO!!wNDi`^|!M3 zhz3olC(YcZ3o|Q?Np*P&@6$)?I}}471aZ%hBaGb> zB2Ie<@df1CF%(1al9WH7r=&PfvT3^!p*&b92PFyY?lfk9ywno5G_9til`v4xYK_-FFh)m(xt^g!ALB1v#g##k&nrds1)BY(+3*B|YPu}=hXi`) zLU3@0$X`Pg(6f+S7Rr~jm!?fO-WX4RMVt#9O^=94NWqlET0J;4uGDdWb=+?oYkEk- z2iNTM6N%^sRAocy4hN!vh7-PQp|$jRx$#_7DYSOS^&fy^@$pymfeb{G4z>vvk#xB) znLt7bOL}VTgNCbW?jlw_dhMZk%=z|k*kynVL^NXc4vaCE4f@CQYzJ<`d`zMnZF|R0 z*!B)sCl6YP?IzD4v&o%>Q(88?*e8XWB3xmijtD=To9~YrgFZ0D59CRP+-xMhiu-P2 zc&SD61NEfzRI}K=M~M;CX^%b>t9v(s)%=IOg_{hugWKRKYrlWeAd?qz)e!xZM#XTa zvyAsLlp(G&`5O6j{?MMT-YDE)R;IB57DlTb*`~u-c+s^l0DlGM1lS z*z%tKh_h?nyP(1>tR*}Ok;JrTd5JPTh_l9_4H*k)R=d5hB&7ya66`Net2NmIKp2wx zL;Q#F{bS_zmy)I8%wWe{+{=o~toCWiP}_ljlFEC`DvNYvPfO^yh3MibTX}xTl-+Vc z^6xi2P7{$}gShuhVhyP^8QYvuv!u+V)KAR}0xZ_$tX zk5(wU52u5M7Iu*hCXb_b-FV6UWq0LMZKxZQr}+{EE$^x^8n^TvKLJ~4C&Zo#yTiW( zBeWR{yXpaqQ)WtN6}vFL0^nrC^ywpj)b^jy?Y`C8m^<(mLtPS=;Kic*kj0O(T&?Yq zT4oKl!h)o0ZpfAA%f<`SW>tijkDw0>`)}(>$_1e2%ahdTWY*=(Mh!F5Wy>*FKqa|z zx|Q_;$bgFwue=}bU}=6>x-gb=QnJ`%U9RHfP@j=WS9v!1xf>O&h!!l3Z4034fyl=w zhtpjihSV}fc}y21MfEn66yDqG!8mD#+gIPYyV{3wB8L;o?xEc~F}i3HDLZ@W(gg1| z0yP$9ON%T9ld!&?-;hXkKv}3`qg{W#+#lL}wsZIvOW(q)WCb;R)3qLBVEc+XYuGX6 zw-B5rd<5s1y3xmQ#>Ot?Bm?(O#ecq%EMa^Fmw^pZ^YEz#) zbD2qb`G~LC6hCylQzcP?rZm~BS^McIQ1keNI)-(QWi7O)KhCxHl}~NACq63cP%Eg* zYMBs&XA|CwGXgOE)dxKMB)xW5>^l6V>e*r(lSCN*3U#&oMGB8!d+%RO^(rBh_~ z75dB1BN_SMPF`yHL{)d;1WIw)I$eQHuSE26XtIXA(rb9tjS%*J99)K&B=aPbZQ zl4A?KcE`*BsD^N|2N8_y3O|^fIPl(BeZ@p2GGFy;u8!NG00XN0dpY;xWyT zLeDH+z#Iptnm6O#cFFKd^Y^aJ?HNS|5TE2F`3LFya zvjJu)9REkokwJWK#{Tb+nz#iAQ2rQxA&Bz` zk?YoUL~aD~6b(&)Q$z$!CyB1k8JG+aJ|?i`rj@Fc_Y!yY ze~JoeSuHB%B`gxja)ySPIiEVP;OJ*bUtp)}<>ZQLDRSKdN5hZ}CVsiOpxjRD&BCa2 z&RU&~05+sNPb_??AsCc&`jJYCpcggJY?L5sh4e;MvMal%J!%o! zRLLKpbTGI=LrM-oHhjyms7fwTLC)82w+u-0F|pp7fW&b~MxTc@{;CoW zYKgF2vjG*JG*|oT{H}GT_zj<_Jv2uQ_q^ZJ;Qnax0vq*;Ictv+5R#^Nv$;WhZ5Q5! zAx&`)t5ZXT$}yF6xh03}X{L>>AnUJ1yvO{?t5Gabrd=#8vNIllsCqblj_}|?jS!;*>5RA*S@m8%Yr_YX&Ib9irt<;XPMz zQtzuBN!Loz#NnQZ?i%s=|6pB+7ai*{+SG}O8jb2$7VG=0rV32B7Vj$4NRwcR2tL_`JTn z!c?O6%ce#EnIHqFr!p?x1@Rgr0!&ga(G>ljeaNfECQ~Ib*cNRP=oTeNCWjTq0{pb$ zcScwWc6~+dmQ$fxW}#LHU*>0#a2uRw7^no&XQq-8Q?3R4G;3MNk{&<^xZFK|o>K*T zX7ZKWZ`<1IX)@rORadi!z2}h`Z=}t^>j_@j=HQVJbz)|{$m@(cHoeO!SEmcgL63P{ z?gN!fL8PJ`PoTC2(&T{@OSC_08Ju#Wr(_?JiBQNo(fq93PPbA9sNgit}eZMJ>-~EVusxTs)nR&x8R<>?*dYNpT3n3OY7BWul zx#WQ`gP~%rOABELN075l&3kMgmhZyst-LB~D!>qIJyWk%Ot!@oOEe#!HgjmXi9Kno z=oPNU51shEC)BPZ`{?9b0z|M`b5C8J4dXLv$L#>BL~Vv%x&;`GMJMy>YOe+GL4ch6 zupY|IvqpHRU>Uh zg2;$m#iO^)bSX>3+y6^s5H5Y7Oq@myvh0P1E1*?|`={vD*(TbbP7lF~ME;DN*`R<1 z&&O4$m2;Un&Xb>k_~s8yz5xK&GG{I)N#PqI&bT-1)jnZ{RQZ=F+QSGU(bk=~2fln@ z67VVKq${$^B+G8sl(bOG$CA+pkYan6U%wUPRQ1ChFaKW|1uZ`Ns(y(es4f_YcHCzi zK=JJmg5tTrRdNgp+VR}m7}_&nDwz&Do8wA^lb4@r>m0vK|B%jj%C}IW*|l~CdZXK^ zv)Lk{Ny@4lT-vT9k~@KvMLq8;lg=#}u~PhB0dlK(8NnotFtn6j0dSK{eml3UW){iO zmgz|f@*}cJ-I=@-FdfOV&uz~eYU3UB$VElUIj=M0Hs^4CFRX2jIYV{S&0;e6bTkL{A0^fFs0PBf3 zR&Xe%;nQO*St5X}Ut3OuB{Ho51g=Dpm2YzI3Y`3&5??n zgnL5ndeUIT4yOtvd9F-gmp$+kwf^==aarr=wg3vR-!x7Gd?ig451EPB%QHsI+_hlH zqa(4Vnq}iMT~VuR%So3P9iH4*N%GvW&MlU{zL)Psvi0!iWogHI_kgW|3eGF{OeLBtz z224Wk@PL zuQsS@EJ>d;JLc8R%wt6qltDezW3W1{Bz9lVE_xEv+kqGhumcYkd6e3B6Q8HCks2ne zJ#)4bSBZ`BQ86Xig#}vsIG##a+O(tyn=Y{Kx(VrW@!9cOrmP<8 zyBuybRv%>QA?hPZ1!KCl?L(YBPoO-+{PD6Wl<0n=ZELlecZ~8ILgZiPLjTD}xEkf| z5Bc3?_zPy9b<@>g2jj5$A#FeIGw1oKvorV%P^AY@VP$hPT}Gfd8=_`@WeM#lD zdc;gaJE8(qeM(-Sf?(h5!O`baK&0bLKkDTmUW_lON=wEqo2HnqKCUQ0j8+~gDw1|w zGP~-qr}B!eNmgN!cXCSQ`)H1AV}YaMbYDJ;0yv$p_Yu)QpH=OCF`)o)vkX4&LCi%= zWoG);Bwr=I+JAhDLHFm8X|u!3-ej6@KrUe*q|m`muG`;`RQSG$2hnJ(G9#?xT#n;a zq4s|d`WJ#f%BnBX7Ya=F>-k8*u3>uRB+toim?Z;!QNNqkl?4T?pX$ zCH{W7pS-cF73qN6TThsjv~{9JyCr_A{TB?f;b-|Fucz1mO<2pAMuoK>F(JUi&&z?h zs+-q1TmN5oc@2g4rP4Pm4%vn$;eR*2ty;U!dUFlwGD`Y zFjz&HJ6;-(aOu+b8qXw8F7HcgPc&@_19)g@*bWOkUN1Swzsxg}n%1s!k8(^BL`0Sj z)0iL&p*?0gYNEzZX5ViyncGJ)6?nU0s1c--8ukKdyQcr;Yo8nU+SN?@^{?b%n(~-d z|2?LD$pzOpfQy-B<;S=B{Kn4oKT9FH7^S_C_C`UL zm^5Bg)A=9{hrRXLbFks_5$m;QtR9oOCEDu4)tmte&#wOj$NY$nF$El5&rA)39P}uj z0=QJYg26tP9xAqGH~6^lsq(Ih{S_Vva6ZJdhxWM`hX)-u-;>#6-7WF7-z6|g`pSsg zTiJC}q3h-e9%>g-$pOa-aC9^scYlG3qI;7%i~X!kl~$#!)*iFVeP>s`hgU$GGvQXX z0|;)X3HTc2jBU9GOX_Kp<+fVT77a=$N>7Ui3rxWGMNpHcF7b|m{g6U90_iEP(85=c z^zFKl1`hq-l_XJb=L>s=$pruf&lA)1l&N4%gZwBv^_lSByzlze77F>X23m@sf0jX9fR zB63c=Z%#(_Te@-Wo>!XSNbx65_dk)XxMi1+V{I=++I1$TO@{0AYTX&qEm!2K*|%`ugFnXem?AsXM1Cz#7)GkONC#x>O@dNTvfA8%k5{ z8CQ~3#RnBsW7Pc33Wtytka(92t9B>-L$R$zyxbQ6@P=!ptynz3BDrVf2JnbR#qrFaB8_u6qv^~&8cw#v?5JZoe2X*# zF@UbYi0V@2LNR)k1BZ>Q!=kIUv`lA~Au(KA!Px(!ZTtMaUosT|h2XoholY2Y?BC!!4QsWw(( zf-T189mJpTo=45O%w@};Gvr}!C0YDUp?+1cC&KNJ?unXSoKqN|c^jTSa(c0K$0w|D zvTU?n**2LH4{aBr!z?zX4R+4C2Ht$9dEYeYplZ>%TrYY#nZ?s@Oqd-vYW#Cv>AngN z2F2~K)Y)Kv3&OU_0-!ZH;eB2m4Bxbs22_}sHJ-&qhYTPr@p9(;xf!}TW2M8d^2s)c zUoq>!dti%II7!aWMWTqW4O>&2Uf*TN=Mjafyij#k;};$Bwe(fUNQ5Y%{lM_y-~$#E zJ}f8r`|%xfh=aimE1A3<-DZTS$F+_8VSfEi*xG5$^Sg&2*-t#}b-~`hW_OUCHGjeL zPmjdI*e6{ixU$iv$=B`8IqcurWi^+S;Kw_&J9?iT?`hXmJdrn?CI6*0BX;f)ty{4% zB}=hiB@hYGkU`>FFR<<)v`yH&x|c{a$Sqnj>HBZW_rXjGQa1sc`-HoFsY%Izzt;9^ za>h6{(&nS}==-2~PNl_o?{9R-;lugmCTu>Zf9_^ejU_H80rQoJvc8Ev9)2+a z&cFFioO}Rr{@rFGy01Qnu^|8#k;{!uv|!ygX-lp=aE_$DY7y`&6C>JG8ZN6{8hCDx zzngY2X1rpqi#D-@m3~F}l=Pez)|M3=OTd=c3L|-1_`L(B+2sQ)F99Uhp}D2JZK)=LeAUyqHxZ>ikz0 zKLz?v*(S#(3_F4ZJJk`&M~F-}mXQa3()Yzm#629xdGjNLA zSa*1I;^g9k9!*-)k>!KISCXs)6d(7@4`2dgA8c0TDyh;*2;n4Bd z4d0E^a^tA(4oLZwhYe`or8`JeZLT&lq4-)XkB_eSZz{9)W#X8}UB@Apq>^`+NsJF{yU}X zx$UaTEAd|?vm1Hlf43*=8TUh=2$4sB^BH<@HgQ6A{QP&RQ-85Mj#!=X8Ke>S=Ck)3 zdHH|etX})-G~CbF9ulPkiig%dHNR0}5cfCTS^GRVt=l&Z^4fa+BkvN(wLAX*(WD#&)p9XrAalJe%k`h25Dg9v%UKq+ z+raHcg4Ex%^G8s{X0%n6Dt!r5t}WUE2h6K?0Jm>aEB^5!z>wF0|KGgaB)}?m zt;%z661lr)7vBIifX;B*PM0yK1FsBu5@8yeFyK7bF3Y>XW3S!j zR0O$!+b`PX??urXQUt5Y!&On%+8y*WEn^#xL$E6Mw01F=re)x6F9q5~Hp^f7yy(ZwJU~CGe-}tGSxg^*Ok+1?wdS z%dy0dVZSIh|X+=}XV`Nj>n_<*}vZTKV zbbdo1R(_a`Fd4JMuv5K~pyQ>lasDU^Wcxw$`0Q~;-uD2#L=rq_m zjdSAJHH#Pdt7p(%wu67DP&Cxn; zwE7-+NG1GHH1*g50&ixl2IDrKg;=J&O|#bq%>+QRSAM(HJjvl$R>Kn?%o-dL80U!7 z+w^SSpvU;RZJJ23PXp@`o!?R5y-pGYqRf7~eb0^db5fFyowhPGt$oA%#no!r;pS?e z=-9y}x84iS-g7S=+7GMRvaSDE)%ypu>V9wg<;M@t{qf_4f4MoG_;Js+vZQx?{SSWE zf0-HQ_WhIA!XKYHA35?O?%niXZ+9&?OHNdme3bCL#{L)YRYY)RZsv8i{j=|b<5ecJ z6H3ojhLCR|zQOxU+_l=($v8Z!DN$xj=AdU@WI@HKfbi|>h4_$X!9K752`22x0lVgg z{>@itl^vhf2j1W}za@{Y*EfV*=)8ph=-%5N@@{#D1?8dGXNBUpJ;Jr!Zh1@78#+&! z-Em!4sdCu9I&gda2wmfu_T?>wE5nA-nV)XH&h)a5{; zMmMy5DETsNHd5oxwN`{T`^|hk!@u3tmm6LEbRzD?i{3k~6LZo3>iBjGvm6eV^=nsp z%iA1y0)DCHz-g;=!MDdpZsY{F)%ZMXZ%hBm7&Nwa9Xg)=+1g!m!=ry60k?NU4{Q>C zOH1%>N{znWes25yp~HCGuV1`*W4F%+adF}Lo1MTL+XbiIVLpl3L&qHUe%)^Au|0U` zBO+@voLq%Ot+fp%?#0_vIRbQ2J(cDU#iN7b@js@fL*-r@?Eu4U4{^*4qUm-@w9g#7v!Av-TD)q5dpJI&oL!aTbPAvMQpV+ZMK(mwj{Z20mSE)3FhtD5Y{bl~>oi`j9OY&%sta_?_ z>qPqnt+p!dFW%Uwk%Q`YFGzdsjbi&FD2hVE)w&L98=5ztSTi~hbM|4CY*pi-#Oi` zpanO`TCP9ZJU^XvUNu9fJoo*)u3opS+GSRA^|Nm@s`=<%6_kwOA7Bun6fVtu#}`BG z9Zpi;s-GG`3jcB&H&`a&%2$6m?qTe)q=RAru5p4(RfD~*?epb^Q3#L!Rlh^Vjnr2C zL3N!vs^VSqKcZ)!@3HZvaIIlGPni9S(OTnVClm7r1s2e(uC2Xtbl)TSBp16n54!P} zX{tusJiPtf`dkox*96vsBDPdF3I4ftNyWXm_d|?-7RcwmOx2sW2{O&n32x+FaFJ3$ zJ2&z4;7rxi%_sh9<+OI^3FRA6x^-f$jY@8CuEA!9sc33lBF0*dz1aFmKT^)+%u-JoAEU<*?qIQep1QM0A=fLWB!IQ(|BJ)Y5+p{07T z$Yo0b_@R~tno2oXvFjC+K+;l;RT`IF4;a^Qa`A?-N5+Iu-ur0vIgknihRy1VKGGMg zfI-g6@gpkFmj(tBgM4*~CZvf~jjOKa7yDF`-#r{biEYqMtm^iy_6MwRcjTaL!yW-mTY_~%T?9lEqOcXyLB_`bMLET9kPa&FE<<{r1@XDYyqWVrP@%E zbdJ9LOMjK|J*B6fwpxxT(s{FEcMh1ymbI9nE>^$>i&T~C8mVfmv|sY1|10fy-CvXO z)$ze`xbRZ2b$~$OQFuZv8TY{ZbV|%GCW|*Nx=cJ-o#_a!<+w};3~}7f-C%@q92de4 zz*iN`;J<4ZpEz~jA*CwfsvMOmy=sQOb- z*R|Ti*Xdkq;aQ#I^xU!`a%L{su<2H6B(HI|`0PILw=ILBh$ck!P)rzJES{@HZux$R z1I1#)8nKsa1bPiIv3Tqs1;b|s@jBCUoQ4Z(KX4q zQlXHbcg?-(dZps@HC$*c*wIo24{IYhHoe2c`i}zlbTmxuCiOQ(0_2w)48Xx*;KtLXdisQ;)>OWzyXtJyo8H*@Vz8PIy{H65FibKSDWNvl<9*Nr>3 z`z)DSwT%S1xQ}a@Bb-xaSw_lcxJ8r}G>-eR%AQ=Owwr)as7d`c$~Lb4d6+8BfVe*? zqC8CamVQVTCf2!eMAEE=nl0(kM^xHGg*N`VL*^+dbs;5JxGnAR;PncODcRqvtz@R!3*EC&oo4 zc8M_iOzjxAQPtjcCjCzfp?AD3k1`afytCeSuzfdC%)+iLENoyGDoCSu_dEEx63z7OjHgup~NyJ*mD-UC`#c2=E!G^fX=`@FTY<6um-u%Vk z&2B0|cYjiQ`{>~x-|8FA*xYr7CYIC0yj_l#J?0Ss6JgeqVKdaFE+nQn*$_)bi~H5a z@_hBd_j#gbGDwjE>&^DPZ;k$fR)rc?|x?nn-PWnLvBFnTv(d&+intDBI!D;*O@34zZ$n z=Ss8Q9p}@$Q=iu?U_E%M(?xbM&$}Diygn-pX=y3;p(=c$Z`tt_RYE@%#CGFt>>n6|rr@Gaq zz{xK9&(vgK(u){9=1iLek*cDtW z|2KigQ7`Za&b2nmY0zPZ#CrKcv@8MWA(7t+!gvTI*@Bc?K?=zpz@CPlIg?!btfw8>;h=8_bHa667LHvxw9T5T$|y#V797TL`dy z*;RqNKKN{Bgeo$syXXUl#C1H{TD@=pf~XW-Vszp_hPnNMPsPy;G)4sCTk`%!-Fsx~?M&X=k&}x)!Z;JP+e@o`(&;00;IwZ%>$Cay8dw-XLOz?lcsv6Ow-J)OvALr9jCEf%hKEzoZNC;1IbVU zdz{H^(KHozvc@g9+`|QJGB*^;1#-noBta!XBtZ0gp?Tlm`|F?nDCORJ&OPUIKId~T z=hv)!?~9&-c-vY073;J98v*%SJmO>b2ELVY5IB7d$jtz|$$ZvV2cMk4OXqlzDWb@G z)ql#b>Pt&-OWo*+SC;IXb(rz(KvVP$vJX^w_o!6UvTqyR_Xe)weE=+qV7Mfv^{(VUc3sp9Kq>Al}v1+5T#)w+uKZ z4?%4vwonQvXWR*EW8Oot|NBYeyD-2lAbyOL!>vRZLqS=27XVl`9I~aK#2^0OlSYTn zv~+c5vZOi~e*)aOL~imi9mq^whIGRo##-MnQTDjgqO-Ts-eyLDLcrSc3pQR*q^+}? zW~$=j2#8VEE_upGs2JXP7nwDwD5)SQLq^kWt`k}6-=rk;%UU)Ai|<~rgG9kOCv}WZ z`=41Et>nbXb$p5qY z;}J8lBZ*FcrQ31^<`^u$LcW1`aD~!S#W2?NMr;CAmvTIC*QLmb;`lS)+~oT6$XjEC zn42HkHp?oLrj3BV+JDW0Rmn#3iCli5kAmQFyACJQvv^()ZbNX49pxB9 zww<#13^`K6*WA>}dVkYkLS#SI?YR4iV5{`w*3m?dZnhj>bpFcOQ0C-&NJ>)TmHQ0l zdL&&N^9)Py58)DLA3i+95MNB$DBlECKqI$cP%L)-tDt;Z@sjS_(zVFN_{|xBH}cy zQDOL2`)QpjK}^e9sn7L)J`iwPNm7;K{Or=m=kf(7=x1=5o#-;&V2YAXQm?Yz8R~CG zD7BOyA!=^8V5OI8!Y8TnkMk|*-NMqin~s{le?55LIQ}B%l~GN&SpLb{%kBgQIyq@8 zu-$rISH~xLHhpk~8MZZKvx+;@d+5;c^H8uV1!d{bG!dj;?!a#SCQci1@bL;*8LlPINXhay8ugY*gi1 zyqu-=!?EieA)QBr2?+#0&XWw_h%xGkdUGcb6MiW|wiXvaTu_|E)=?-RL_U^>$lcGi z)l4Jyg_Nt-PnK3kh6vZx0&ZayA9_7+a1I5)ZuPG3gAg~btOpGlFY=i;`=n3MxH<~i z-%$J8o%max&@`rQym35{Vz$4uf=6iGAWMQ2ko`pl^03xRb>}4-jg@rCc|`PIon7vA z$FI+2-#+Lsx$Y$k>msYYdv3fA6RBsehfUdE9e-R}F&elR+|o)P@zi%SrnCO(_8Mw0 zv@?*O>(wy1y%y%ptJK5B8;z^-Lyuy?ODOd|oNfBpH)y!=fAyM(PK5(#Zdh7JZoND6aTQ!PO1VIw1E^IK)};2sW1CB zhT562*vJ+>kFzfQI%otw3F3F26>A=~yL+05fXf4(qM=8-XiR_fdZo-l(@nIk8`BPRXG(c%2porR=9g6Wod_u5G@>ONcE z^nz5MQ9C0h!^GeBWp_1Tl|8dG52{avU11(HX;?5&`Hxmyy&9p^*R~4eqy`KL9Ohqugq2CV^Y}b-D zqNW*PEIgOr=#yPCx!q45uwBDZZ0h4ys~F!UWX%ENvtz9>y!DDHlQ*qg{|EWN;L2vB zOp%0W_C;tKouI`=6Z?|2M8H=KN_S_fBCdC&2 zUGv4+lo%?T{Y*-+6aArM^}-*gQWRlFw4>y*Ooi6haY@KUgx?;!eln*uaiyDpZ-)!W(C)iyhW6>;;mnYWE7+>KK zpe_$(z)R?lefY^~{#((Fvw26hKYDQX&q+0q&N zrOS?Hno%b_W~Y*EG&~C;uY+x%?`a3GbZ&1ALF;+*`r5PjpYd#w7x%2eHr^*8+ZjT3v>E-a}?TRagX0L92;GYGbo zlsLhRNt*SoKq`KfC<_+(iu>K>umflLybbBb`o?6Y?8OpOt8{Ymo9D2D_E1EPDivDk zi#@o7_U?o%rf8e(@-`jZ(M^{sgh!54UTH6ESp_H28E)89)+sFGy^Ac??yYqx3HaRk z07I6l+#6uWma2a>4|>v9xkRu_(HKB-kV>7o8O-Als+Y~z8T~090y^@3*IkngWYw#k zq06|XXHM{rtWu^K?GZb(R7a2Tlg6_pB7G(mozqgllC8yRzc8IP4j&K_Oq~g>`n2Xk z`EBVu9qU7g|1|*AozA1^s`FU8-t4^d_g;?aF}9hdtV}_i9Jg7x2?vd(5o>*%5agw* z2ugyN%BfN%bu7<#gKtceW~I(L+X|g|vN2m}Fpuyswv}OiiDaQDoGPiS)Pi8I z#H%TNt1;_T)gDbbV^)&)JT+4%p}-K!I8F7L3chjp!w?}y;EG6k;2sPj^vlDn_uF5> zlBlPfm&}-MxB*O+g#0B7xl}oNr${na>*(7}j-&SsJcH}}2qARxc6A1p0U_OAQW>Ql zxHcq-?Wi*KpO`p6YaWn) zUF^(Ln<;(bmK?n+?CrvbKlMzm)c(Vp>86R7ZoOw4n_lKDSAmLCH|TnOtU7l&Q9fACHMUS8veO=Pj>L}rwecAFOYh-kS?Z~ELxtK z;@QCs!6zrwuX_KFe~duSy|nuWsKCQxqSV~ONdG3)@L#+UF(UMHCsBOU%7^>4A( zO)RW(vK2QV2AWuDc5JtU*-h=@uI1a8pvnB)l|-E^)iA?Zqq`BmJ&%w0^2 zH{NyHc248IHPM70oiv9K^=u)n84z_sus6Z)hU{3B0a&mXaFqFbnQB`-CSG3=pGiHp zW^>h}sm?)|=qG%rCzkPjb2i2$#f~0X?kPj7l6vhS0(yga#&(vbZyE$TLNoscF%YXRw*q5Ful0?8QR0GBQ zht_C>x(78jcj7X$^Juhu(-#_4>f^ay%vhe8tb~~%($neFoc?krsifTh2*o2K?2nW@Ig+*f^~Nm(Q8RG@w=ir@3Us;6V(*AoRo4LzCehazN^-LTQ6d3GOJvN|D0>c zBjh>4ShsuJsjdiCVCsrStTQ#8qlt^C0Nbn_0o110`bQRE&dsLd-Wd9(iF9@POL3gi zX=x!(T$rR%9j4D&>__Fl#OO(;zL^+!Ih*t9U~umU_gIp3w9#-edG5wJvNke=U+43Y ze`AW@NU|qI0K%+OVnO>Z-wEF1MZFEKeCicu47~fTbPh$*73}mhhUDiJb^HmbB;4M} zaxQ#!_mpjLU}ulNv~}cYQ?=>fqj}_*u5#S!=8vR?*n(=QydIl*Y7OF=V#n^n*SOI5 zJHt$7tK){u<{X5?izTvX;ADvij zYo?d4qcbzc*N{E^)cY`z5IR-k%b7OYSi_}J&H%FQD^}S&67%9s`ozxoFX=4u;eNmS zC~LQO&pRAtBpt~Bux;Y6bTso0JyuS1N7ZU``ACA~kKU0}K3CZ8>@S@N*$Y>0_oG@4 zD`htC3~VfWeIPKh9?!|UHRleBl$U#S)<5X1C;2YlbDPC>C-Du4d;`(?8gWA~sAQ;@ zH&`N+#I?q|o7sTqtNc&&ogxXmZFaKMFiRy8(g?$pql&Ca_@NU3YeNu^7y zY^hivt_R=Qjg2_W@R%d<;-!y5J~g&@_tvoHJp+|yoD`c2y!=LM?mx=EWRV}T4_zQa zHFnm~MsDkI=RfkYVr4t|TIULbQUddz`jUIefpP%$@<+#;<&Jk9E{+^O?L*teQu>b` z%DU2pLE_!Xu)oUOg1SCtpEH5`r8=Tsbrk~XUH2xmb$q={{(8UT7Sk^iEB+V}o8lIs zqF_5JWY|pB!gKID$L=RMA`<#fu%xZ9z$>Z0+0=&9y>Y#Zo*>>`4v(4iE~FS`c=*cIB7t z6D!%l2-ta>?7(%=mL!S3uc5F}CFKETLGyB*LvzjH;-$&;md)7k-`nwriZ|=qNfqEC z%x0n(ZeV)iO3!xj{*-gfhZ@cL%+8;3KJ8D@=U5-WjES&Iq}1+7t%g5hecGF7n;;2I zw9kA1-pL>B#FCl~34Kqd9e*w&cJ4|<%Rk#Dq1egvgbYApx0T~y(A~_gO#{;hq}mtY z(Yv3LgRcDjY*pwI@VT*&9^60=%|%fdoW0H1c6k$!;+kTsbV;AMu`7;hOpKe1sjh{0 z{4CfRn^G0w6{=0zEbafpY5zwp9SEUhty?Lokl&e@hE>*~>K7W8u|3#Bg~xj-UMhFA z>K|Z^^u_+t&Cfr>m02@mTOM(%Y(=KwYt1f>Yt0S_!$3X%EK~$(ck>j$2S5+;H5r%~a!xXp$=zuV^{RPo+5jSpiZ9505#q zVyy=`VhbA9?8DIOJ1s`B>n!nqEeU15^jd7b?K9KtfOnjpgZS&Yd&l49Ry%l&j~#Mb zpL%XZXun7*Nc*a={Kq$b8MK>y2hQBtSCV7-D6mXt$cw9d`CT<>!h>PK+MkVb#jiFt zPR)G!%?1Lg<9$vSLAh&hcKF`xB6BXG@R$s}UJ3Nc8(%X5W${Iv{dg(Oz0j;3wa_yUNl2yp1(;;qQ!**{qb%>Kk)Fg1t|z|=QK2oejRP(5ds0-9+8cu% z;&qcZZs?HBSH}p81y(#o4KJSY4suCBUsx^JL1TY_X10EhvC!*zA2Ya@L9D@cbx^p@ zHE8e0pP#wvFc@)ru^jZ;_$=D^nhfA5KLbYW!e*n={0T#L6$SI!pN2lYn-CAvf>4t` z{ph#IQChs^4i2w;NnlLdk>SnxB@rXb8*lEpgsQsM z&pf_WmC*;yV1Y`jXfF0#MZ?i%Lq;CL_+w)%4sc{+{h`GUzEr*^EGEx$(E!_CgAL5( zua{@p&<>cQ~5fD z+!6RROf((?IwR=*U$V?dc)eA5l@S9Fn>W;Rte0}-M2W{atWSW0;uQKD@96S{56%@v zl9ygZlkiC^-0V6+*|he{Gl1vrbn34?(CN*`RHd7%a^+``!q zPkP$|u-`xUxOX7+66D=3^KqbUvm-zoRLTaDO?}o8RieE{lLV)%kr3SABPAVR zBQrZ$@3;BEgkr8_9SNCP1KI(4by#UwjdrH0w~@uDA6^(w^Qh3VPr*d&g>RzyILKQ$ zz{9tdJN~VOLY*VO+gHc?t_K#8&VsTH!#GC|7B?Krf8-%axJ7 z{1!(05--N3n>@dYV{sqXgq~6_*hXX1jKz}}GWEqu-JJN;92t&U?DiJ)G5@3sOG7V< z2tuI7N+{0ocLaaQ)k*dS%HlWeHWtg{Z}rsjp31N)@d=bzRsrzmjSskV z1u8NHM{6+rf4GC&F2W%TMP>Gu{Mh+(l+l=_j7!Zd=*CqCPeanrRgywzLcA<9?5U|1{@< z5LiTq|9&pV-t7M~;Wtf5XZ}Zc;m+@0gn6m6-pW4vbNa?&bl&AJ{(f;=-*BVK*?}Cc z?;1V+Qc+>#%A&=6R&wCMv1aWXo>ja&n%u4Z&VVXPe|ctjBuNWpBh}U(5bTyd8hx+2 z{n@%V9C>}rlci@j;n5sP^bR_QAb$MN01j-y^2JCUgG2u81>m~5?Z)qfi-a~NLEzZ3 zRtU={{^QBn0ibPn`F|~12fB9_i;YVJI{UR=(k$O@p>@CMu_}R}>IBbz0N-!1E{W|* zXZ(u;x9rX)j}fw*SH$U@6HT);>#Sy)6V_(VYFoJW5Z#2sx(7fsq;o5{$lx!zvfkz+ zZqYdi*wMy4Kx6xnt)j0Z%6rauiq=nwTPEL*P>u(;*3pjzPFIOM%O@;Phx(RYrZv}e z_&skc^kB%19CVdhE*2*Un#$77-e`d)Jyhc z?2&{UBFT!o*EZ>&McO$;HlX-gokoC4CyuP>#A3<$tv+zlCbmIDRx<6KJnugMy)I(4 zYH=mNc)2x%43RBQ0FPw2kXErn<{LgKf9|zc^L8VmbROGrLJwm#>ch|-Mwo&pz9|-S z$D1NANaorDh{oj+G2HQYBPWdCF`UUqovV`?M+Cld;^TW?!f*2w(v~$GLPT1g6m|PvuE#z)Mt%&g zhit8Heg06sHuL^{(mLO|#G#{MvIz?<8HMIXf)12vEzoL6kclMRRr6TTla2V(z>;r z5PB~bL;oW0I7a3CA0OZ-eMcD3QZ@)8Es>=IJ?ejCQ_ghv4i8RM$L{Gfm6636(q&Z2 z?(gd&>}Iz|_!oMY#`i!-0Y^LMa2QIdNH##zAFbXYMd`$T5x>Rt?-a0$W zw$&iZd)3pXrd$Ygk}!Oc{WPsYa0ixetH@kH%q{JwcV;*bxy0BKWn)CyGm#;pCVmNC z*CqZU$&X_u#1(rp8}Ci7+68h0we})H@2)fk-iy^nQA4jY|Cmf6(}J$Ile}k}gg&A% zkz|YgitsJZfr-4BHnDTwYd=_G_H&T9zv*V_dP}qvrJo$rNW346C(?B%9%tiWOh%UX z3DfTE`R*peY0zqPaHf5F|H_Cf*=t{+%6f33(}~~mb57g@VCx~B5BSOXSZKs3)Z?Lx zqis(j0@W98wesct`&B6RV8nCpjgc0D=W14qExiGhS4XCSLg^FeS^HAsTG!|>Z^eYd zkv_Rr!sZ|=qB-s}&(0u_2uv*P*|p4E;x)&=SRFmob6VfNmn}*fc&4WQJ|+Urz?3ay zgzga@LqR_ixT$zTAk4zGx}ru0=*=tNx-@-eHkKF7WfTOXcJKd4}$k$gf zKJ{dIleE$uTwHh$yrFR}sexa&7|O^{{T|hB*Pog;fpS2=8W#?uZ9?S(6Fb>4F=ArN ztgJQvJuTj42P{eM%<@>a9<7m${2d^Wv^)k*0+P~pHd&{knUWED$Zl33wVS&#j{ZEk zmd#aiuGu{sGPjU7Sy=Z#7<}XUnAE{z+G+KXiSSa$>mh*r*cb=RQlnslxZZ5uKz5zo z07)+60=l~QpjRW83U-$J2>h~~ODtxGRO<%>X@Y)lPAtKj3AO?;{}p$O^Y*p7xTwki z>Ru(*tpYEVK)XhvRAHa&IO}A)9nvcWn@~N1Dl70OV2Lf-P@rPTFO6JC7jZe(!+%l~ zqe}bx5}mR@drKP9z5|F3pt30!l&wiwU~G65hpUTH`-6d8K<8zdFqAoU(rS|t{;@QR z*{0cbZDjbNerSj^o2=pQ(2gF{UG(+zh3XZxW!c_0$>MM)>0}<@;LsLz-iUzBL=Yb! zgmQ)NG7Of4T6svVcd<3b5a+JdXJG(`i;CHGX~hr1-P&wR;AH18r#fcql)9 zw#}5#GVR}SRK9JafX|6u;s8fn=b?3*S>0+~sM_?MB4`(Dl|j+OGoS^TxN?N8YXt8R z&NiStkXc&D^rQpZ-;r(tuIp1^`~FYL)d;F$pygRu^8^u)f|vR}rP|^)Zs|b-##p7c z?$SeVFaqR*?H(NOua7WYasJi%S}od_DS>)+qq3u}B>LrXH$+@njmNBr6L^Sn*k}+oH1Je{(x>g&@rCoL-iJC?l3_KX)Fdb2@ zJ*)wYd{w1h%k0~Z3lRb5g>AF(|98XtY>U7r;w>S7ULZidMfUw59Et{WOsx?(tb)gn7fhg(~@_ z-Sr3Z>NNi>&J+ebHr$C?uH)V_QFF;~b*Zo}?RCKU8fnd?!|t zPZ!>6b4ZIX`1CfqQ5So(gnX?JUPHi!A)vK9fq9Ux{R(=$O)qJLaxBRk;h_pn-tTU_ z0|^uz36v|)u%@dJNtcYB_L67abWz#_UKA~6uu_k^wSJVDuwG|`sFzP@irDwG=XGcU`4Iq>V zYTt_qk{?&LXC5@X~Q6q?rD#Hr-TCGM!zN&<;^6v|M z=`Dn)+IKY~X1u$^tw{19rinGeK8CuJpErGg+I(iJXG968SAOxg@4E5*3&*fT_03x} z%9-4WlG(a6gRJXr*y*6&rW^gol19Q)Ita&Nq(zRt%u1B}s0>}0*WZG3VfyBw{8O@mL6_P{1f|7JdD5F z=cS_2?w2kfjKb{cFT$)X_waOLMwC6yJf%YEi+hcuaA5FAJsiv-m*_9Gu7 zP1dsaTy4yFI{8FHNwULYo}EU$HM+g=)D|0fYRX9bja`j?JxH2-VX{(R7`qLW3#H4)fe!43{>GIZ)&InLxgtOINIw>YMbU<) zvir@)(>ibKV8g6=D821am8vCo03&{@eT$x*|GBr#2~6*S{2fLx@7uERu%n~t z{x(-|GRoo26Fp1Q?a~&QBapNKiA<3EeL#HW6X>#u0FY=4Y%~f4(bEY>Fx@!~9%+;k8 zWkoRFOB68$I70Cf(L~U{_=gE!^0URNl^pJQr_tu?0Bh@aUBCad9Qdxj4?E!q29*dE zC;hbhHW{~l;e)3sJ620u&U^MC(l%lUw1vNg-%fTK6{Jy9AIKpp`Piib@>-Z;hNwj=Yl(s{?kVhz&89V_b8xi`p*8h|F zch~zSl64aUQg$D!)1F0@Sr2Yqd`@Gijh(raGxw;4-0PGQ5|?w6dh#ks9aEs$IxW8e zZVMAFBL{v4ye&9_J^wo)nWvgCM$q|sTj!-{p13|=^{Fbo87=+{^FE-+7w-YI{Vz}n zbu_2gv@kYoeY7z)Tje)`83#gxPHem3M)guhD*nZ4h1smqwCOG8TUGnWPq*I{>-@KX z@|JACgQD-jX+q<79T=bdXEJ-C@DXodD~IL5wFJ zQ**Jhr*^3cM|);$+-}R|-3aIv>BzkZX$(3uhaQ}FfI=X@CF zL+88jvtZuM|HHmq2X~(?SE^U}r^1Za-a=(>H);(9cd7?e`Eh}JDCe}Eb%kCjp=d6- zIi%@)EC`Kill=D1xsQVE7lZi5G@4?gtQWB7A~w9CJB&vU*vALoahJ#e%#37KbtCm5 zx4qMIl>M)sLVRUuD(b(>o^XWQ-@l=WhXcz|uOac5L${Qb-_TNO7@5e?1>Ve0BQH|Q zRq6*=dRSoNQMIv4avRfc;tYiGcjDD`9Z?H>-^9<1*n-p!dpVR%^T3177*GDAoFWTX@LqJ4Fwz{buV_WVvd&!&v)b zc%<}h-qRSs#}zwreBo0oYum4_r-(3@4JWJ*=RrP4>#R&n6)Hqi@og9f2>noGMRy^sf@VTzvyf9i zsZ+3xU8Ff9j!DtV!shjt`0)XP;9Cf&$|k%jx~qFe7w zB5Xmtd%8#hT{xDts|`_?!zyMzLjMJ;9|^`yTq5D*N3dh&J~)DHDd$H3wvTEA)O6id@dfXK^ky(bOlAL}0#X07|@;Dd;BsQhkwzRFR zHh0LLMc!-5&$HG9!4i%XPL6D(jue!tJ?PIoV_(4JwbNp}~wk=ivY_J~mjr zoG~xCEsrtgXJk(#8Rn|0m7`j0!N)ch8HFS*l?xH~CD!bGcCA;w+Yj!pp?k_|f%&zD zcKv7?X?D#jgBCI}QA|Fm=QUBAy`S?yw6}OOhHT$lQQc7!-z(6x9Mr8MCo|?wG);+* zYFKX8$&gys)HF_Z5XPH@u{-1!|GMM_jJN1SbTHq41u?P-9D{s-%iqWMQeyWcEvTMk zn-D0LmX{X(zT0t%b^!PB004zv(@yWZR&=&s`gi(*C3yxF3 zi)Yu6493$VEm<$t_J9!ouPjTw=H-OzvPYa;m4<=E-1^9@=Vqri2ABPAgdlzrW-+q9 zKDaQIMv?@S^9JC;7Hd&3SPn#2C+^a}fG&hh&)R8i!qE8*yqS0$c@I^9!G*S5fZ5^+Qy*Nf~Dk2I+?RyadHH(zc2$iprsGrUS1j-CqD;I3+iB3gUq zvRQ5WNgdE~TY~+Fr$P&oTe#pvJeRF^1@Nz(qae9E9#cuh97L=JBIuSWEkyhxLdsZ@ z$?v=!>lt;)rrL}2PB9v39RRot*O-AXo5VZ!vVy0D)iKz$i|?@g%XhH@ID57IFSA~W zI5#UloE$Bd1RciW&dHu2sauJIPT0Dxm>{BcjRiq&ir=e}UM6*0nEO?6Q0ex)LgVA9 z_9nAH>%ygLSnZjgWGDNt3o#St+6uWa3MU^HHSd{Nu=yeALEL>$UC=Z)^Q~#tuR^BT zDVr==9oQ=5gGtx_`C4?uR=LB`n3gyq_h+-zu2=)X^`ZaW zUS_PQl_@)Kc3Na$mOtLH;AU&S%VPCae>NHS2sN*?AsJcJkiOu0XL0h5uVU<{y3_UH zsl}3jWS)clzyUD+)7}LbQOF)jPpkiTFI+KRjU$*3)~P>AH!oJuG4IpCHvtG%oEeFB z;r+=dl6bOO(9(H4+j5Ua=gu26%%tk}WW2FS!f)jr1O9iN8@Np)6N~O=V2F6C7}aq~ zXxdGdV}@UbX`p4d6^sfhyc}G1)WeejK={FwPSRwP^yOh${5%0SuQ!}=s=!C1+H3N~ zHts!negBfTG}YQsWaavm=h?HxXFZQi#IG}^woe^khV}m@{;l6~d3yWu<)8|3`b7No zqjNsS0)xY&W}!<0&j`2ppY3g|$ybR+%LO6jT;JzJu#_jRw!Jp{s+Ye5K=yz)$2+9( z>>o0ut*}58R*+gC(Vz<-xHRjpQ^S+-JS)6f)aHKd6aSCq-}%WnukLOB8nc_v#+7$4 z=;7dZ`Mp4J(jE5=WR~p!X@mm=Eh2_;UmJ+hts)OFR$Jv?D#h^o4uHv~#hcKJn#q=} zNN+_?)AH#LVrA;?2)?Kgzbo8R~?&KJE=ehP5hD z&)Xclih#J=DzEzxUov6%Il^<_<|#QZ30Y7KR3~VFv50l~m|?r4IKweyx7ifU4KH+K zpA1$D>Vqqy%k3re531ZxckxYdS(PKRcmBJx$sXeGW7L@>LT(e2HtAo=9nN zKSd*CF>fUB)TvX|CJ;z8j%*(qJpcYwJ6Nb&aQ&FIn@T!Hq4{#DiFM&-&*R7+G|5HU zw@Px#>J4dV#o&Yp-SZ>UL+9w^Y&(F7f0r`1TkW$A0O$e&ad4y73x9a&O*oPrSZ%AK z?|q@r@sFmW#QSqdRMieJcw?uMQ(3A}rw*jYFK-H;1WUi`#Po`;jom?z*Q{{!wCGv1 z<fP}AVlF( z$%ht&rg^9JM(VMY9eX#fHBYp!mb}*u>==UU%NM9sbKL#pZuWj@# zqYCB$tx_#OW1|3c!1vPdy^_o0PNrQMArRPkazux*yn}u=w3QmzQgYkKi;He^t)Se! zd)M0^%oA9T6*tyLhduQLgp^H zADI=$j*MNTpbft%cV;f2dsGmfI))k1J!*&>&Xta&BKrD1`C5sTpzS#G5dkh9+@5wRUyLT@G4DDNj@sf6Munx}Kgr^n8XMeI?|Afbji1gZ__EhQ1 z)K-xVQ(!arD)`zS%3#oNEDt4t7PD}?rd+BG^Pc)Ty#3uAgPIlyDIZ4M+5iT*_Uuu2UBjA?~&Zq1kOH15|@u>2= zV)^R*e8utC)H}yV8CTVUEZ`{h?pvRCxlz-J!`VuQP^2Q+WyE7Iq({o}6~TJ~mT}4} zP^2$8K3=;bbeXx?_2hCD4-R3MPM5SYHjuN@rRsUqAO(AU43)DL@-hG?g+OB4NcN$n zAz@E}(k~%&<+P7y&v_ACaMV^X4F-r)txdlSBv?;egvy(So#COIFXRl@Mds=Y8|#Hn z7)7^@^qM76??L<2?UTE%O5Iv*-d?+mz*-$e2oY51EZu~un}d6ZwO2RFW^em&g@oq^ zUqMiISw_un7dAFwORBAe(d<3VF%IhG(%;TytxevZxU#fq5CF2MLNMm^DUynSvtzM9}K(z)NtZOWysE%H?XSRrA5i};FPN0?T8jLTdk3mE4hrexoIn=n0i*FP~(xP z{p-j3I>Vz%-&TJJ+RIY?i=#TmQPL4eS?ym%=}?bMOgCO&jpE$Q3cR0@w7?Io3b_;n zQt+GZ+F#WI#Pw5nyzpWzoK@m!c3zHdJCS^gH$Qe-fJFIWJGjo;nbOjABYtDEvv;K7 zSTLsr^_-RM93d!T4KQ{}v#QA2V_O3`H2*%{!6+-v?WYiPMx>PcUso;0f#wnHhwey$k`@p}@<9U8}QD9tfohcC}`G*XOXFthIS@+ops92@M> zjdMF#W!6L4!zuaxMy;Y(k-_x^Oq&K;Gzz75K29qa)M=k?y@~TRgGaE-X1$} z1H82m8Lnjr-YD6a{d0%!*Ok0$SpLOE!mVM&yiw(wY}Luzlq-lNcS{r^rhKAf_7{wN zn^`qAr#ZA1UM|C%^J<%@oU+-&j2l>4!>w|OKrv(fTCqovOo;5awC~LwS<`Rt%I{ES zGh2Van20x=m&z(tQ?yM7vzhFn68jdj$N`Br!RqSI5ZG-d9Fp)8yp$5x(s1)B=M?E6 z2<%Z0arOjgbjWVw#g_O}1S>EU)(7TGkTySF)C2Q0*(!%vcOdd&xmj1ct`h=N+;*YJU@?aGEyu^0j#O5 z6y!pAI1U9edr9>9M9t}@&lLKT4E@8-B?kQHE3~3nB;l#rTaT@>T1S{07?B-_)PZz< zf8*mUApRl=#Ko;vSC*Myt$aKF+GYrr<=@^!u?6))d`jC07^k*=F%_W$o&}JPQng5V zD4%KkV|D}>=hbdCP;W#&O9c2S;dr^u^Gz(Jsz&ShES-DYxGhF`rh`T;pZ?2yzguU` zNyI#>Qn%o{k!bej&Ox)x@fd(L61Yy(Q2D}9mx{@*bTbtQqnwsBkPYodx${LgM+2q(B9Gtq^sQk;SYFoec86(pr%ug!D)*GBUW%sC zt@)kz-t~xi>7LpFru{ukVYIaS-1Sl0eS~9kzfP$xi{K>he?h!WJFsA@Aj`}h_rcZL zb7uvPXz_6$ze{p3LNCL8uC$Iu4=DeJs+cf4h1+Aaj&+hh$x?LuQ6OQ1axqPpzquIv zcqiI`{k90tif{Gfx z@GTjWk~Tp%%Vs%+m$6PHe={Hk^5&dcTknm2o2YjL%!}UGnYW&pcHG>@x5rMyj_xM} z40Klh|Cj%)X+yI^j`>SM&e^bJMI7AHQAXWLU-(veM(Q+C3nD$B%ObI06!uuv zy!u7wjF6tW^jVzch+7eC!c7}OEnt#`cTvSci%;pdY^IIbS)Z6yNd2T)%&dShW+Ie_ zHi+A2vly{XYs003;OPtE$PZcap(MX5KKw=i^9RYqW!oQ5tbC}hWd+Nh(7LX6O+%~- zUUV2bJGEVN@9KY^$yPN$teUaRL}|*?zSf-zomBwH&IVj$WJG{AKKHHaHEyVfiBEi? zvv8ES`LGwgW~j-D91)B$?$F+-rex0RC5^jr?rYUov&4;@WX8vKyYO-rxq?uWMR-=T zP}?7`Fnm;H?4vigR1(B2xc1TO*K@kDXz9b<8OI5S715Konu)4QGY{Uy_Oj=TN7DB? zx(&rp8w*R&DKE2~Y~?$R`V&sF*EsiriXUb%(6@^f3A&;Uq2=*-ZIAox+d<{iIdgxR zsRI)_PKKS})u`0A5toEaoO9S+(?{PF$d_1?zo;wRx+e!|6Ie;N%Qr#5uMY%2qOj^n zDdoi9fH6IZA%&3@Hp0ZN(->^8kmTJ{gf7dln9D`9KWJQAFKQa$n>LK^5T3zeS#z#) znaYY-VSgl>6*3FgmUy2g*HG(sN?EvFLvEz7Z?~w~kob5ihPrY&$AsN!2S2Ns+yb=_ zTKLE}HZ!pH9A-PFPrPL$j`O+p#NJ*009QiebK}nZ_*w57ByNu?1eU`jgBhaOZnb`J52G5WlLAXObcdD`V&ge#;COW{bbL;{ zWFO(!Ud>X&zA$6dM&`CrcMt0%(Wfl^=Y~ZZbEn4qvwnL(UsIB2YyW?-3OCYsPNri< zvDPbalJz+~V68|0Ypt7^aGn*>yML6ihl3&~HBh0Vf{MdzoOE1XN<+NMbpVHO>%rPH z7;*fEEcy5^aLM%>vsa8Pnr^Aenp01be<(beVsQaiTL&_Dk5xE8Qy9>-H(_mk8Wld<(7L?f;6Pk@;9k z{wTU3L&>;jWFlRax-XX67@ekjITm6&qzjq2tXOa z9*ATv_OU~y)Vyxe2Un6Vn{eOh>?JJKih?Hc+hFotMeQd)vxk3h=TF0k(?48N0F+&g zu(vhyf5%0*F<<}An!Dq#^SdUi2fx;1D<2TMX7eaeG%jU=2d3IMCGWS0_sb1F(~^n$ z-U1TUx3;>w#`}Op)5hv%SM&Xh)knco!FE};C4G$fxzF|G++P~>9W@s%M+)28uz@0j z;j^CoaV9nXv*L#F9NWaAJ1Z!exVytqx48mLK;?;V?YJ+ zmhVlujMx!o5V-1-6lO89>M0``9j0-w3cgR6m~BqgX9*82Enb8B17U*lF{Jwvqe$lB zcr@A)V(x~MM$o+3wW!^PS#6PAj~uMPh>fLyw}QYQ5%wlwqtV`?FB?ccXB1EWRG!8~ zRd_$(wVLc%PuV1p!lsRNn~x5~?ldCIx88V?5k8f1*-;Zu5M7x5DxXju0?lj1n<6m; z{7;E)bASoi5Z7!7JJy$d#6|ssO%bv3L%JtvJEia&vUnCA=HvCjlojfQWem{wAWA9R z5DYd2ZAQ~GC3puTtO&oqhGTq7a}Pi!_jh28LKYJ4gG}DYD4k|e z&Ezhyp!i3hDu<=-VfbeIrH*vo(szn?csh4=)t(tMqxR^Fh3BwoP2O*LR#|=MQz<45 z7t_AR5Dz*ND8e0RohjQB(%c$x?gkeKrGK%x6PY<#8NdB*S`jy_u;kkr;=~pY?UIrHH77^d4toAH=3EF@Ob`r+Noi!%nblS z*|s{*hAJhQvIOqPsUOZ*t^fhX@j>!KPKTL|tHA z3+wIKRptMH?|VK2TAZTWqb~(B6z~&=c0BvkQG8J>G(g(u(ge5(@W$IG0K0vJPcpHj zoVn$)PYI^R(mUX2e{rR1%qpU)SxvmmzgM`M>V~yh%nn7By4E}kY%d7axB$LZT!W!+ zUtmY}DqV+VVOWa)-!sH-`A^~@WSdE%N7gHiq!sLlChLOw=GmRXEF>YC>AS>mZz|$P ze+w|XvuGh_IH(G-R!HA_6tT*3uO01^c5X?7t*w7Ln}C3_+MV+|+K;^x2_;TWBGloM z@QXW=Et9G@c}!)sq_k;ge4YGFH;Fu(Mn7|nc?_$$U0&kOm~(Hgf#MOqHU{fx*);j{ zw=#majj+%)yKs?d zwY1J=&RsQ&)LdHo9G``GB$*7C4V-J@q3>7(`IOO$&Pu4QJm+SAW^A-W-0h$GceKT8 zaE%eNKpKxA>hF$Y?$`zLMy@&4vORLqNpgfuj25rJqVnXSE#DKXwzWLfuFh4QUevRX zWq$qt(e?I$Oz-{wxK3BOuIq?y&Z*>PM;(<4QAn7pvq~pPC^C1|NLozOXqeUI94hz1 z$XzNVX1QH+v(>3gCKR?9n_`yDIJRbOv-!S8=ej=kzt@ zL|95Exbt#P4{ z{w#84$Epk)4CPybge~VsodM`A!f9-a=ne}dY$fnP1g8m&09@|x*GgG)f)_vg;qEcM zI7N9tAAW@#XJJ_V%vo|*QFZJPfEBtG06#X3OI3-nEGpo>I_ac+kmq={WIMr}#NtOt z72pOd$Gz+k;gMzrmZBawsa9{IM0|titg25t>>KSzLm0I!U)+u z=)nCVNt=$06h?DCNxE6%pSXIpsNw=e%cp$aW0J{5 zd3&~ftrb&blFS`(8Wdhb%bAWSMco<3kS|8`ixk^(jEL zZ4BvZvpC{A+4&)Ey`*tj$|9d2_s@5G3yhA^!u7a6ssjs zm@<@~_~>}Aboy2qVAXO*>KwzKegHUf7-@C$8l=$;To>hz;ZhbUk3dR3EM8eyl)NAh z_#-rb7BoBrSk1Ivk-`$%bE^ciz0|{$&TyP9(RPK#8Kav`yjZtw&aOWO{BR-0+0<7@G+8_xyT#!z7@t93h!55-gr>A9NhcvRgc zUPvd#5WB=jDjXkXS6VIyCr{Cw=84n%AR+&t?pwQ_EIyhyi{syml7EdU*+hSX^HY%B z1L>3gvYX6DXsfZXtXEf=ZB!ztHD}KXze8&3MPu)Iiu|c!Ymj1c4<8sURB!X+6E4-b2pWR z^!UpLc)is+SFly3zUoq>OGRft#7j@B=zAJYh2|EC4X>2Unt+h``u0afmK?jx3l@;Y znccmS<(94>9qXD}mB~hTVK!}k%(-+}=PA&PdyB_wh zJ7Mqt<*f+!NCax+mDM+QX7mtnLxlF(i^lUSHS31*{EsY$SCQB*n`a76XZ&KYinBIE z5%p|4_Hubp)RJpAp3`;zR@PU$e%^}B4=wq|m#pQg3^QgqPCfSwVb<+mbb^!gl5 zx8LN~!`HRnHh0c8UeW$_sAWyJ{ar>To z^c~SyJYj@jN^AeVCQTDex#n7awaq|j06cgOXq}ML3iDh*{>aVm_LERn&`r`)ICV|+@ZG{SGXMYRi4(%e3lpY z@e-qSu)J%fuW>^WB^@FB4iLGJQTYqqM}h@We}*Wik{5D{k}9E5uDmHz`0NaXK6q5R*LU;j;e zrvfEBuzYmM)}`1M`pl6yi}8Qxr#L@|WD25|RM@jMSX}GCq4m81>QoD96cGMV04OYY z2(|Dt><4Kkk{sLlIq_@)m*B#qUe&!65N``vk2{sDcL(#ZW=B>VCnwbx--SAQvTY;g z@Fy^cMoO3^XsY95;g|7R~+A#sIxcnpSJd z`Fmf%_&Xz(jj4Z0yvSTFI`odm3%|4+-HaqT-Wm%Z`JR4$uHaQ@)KsY#V56v^cVcq? zMKu0tSN&|@i0hyr@$Zn}zNb?0kmD}dk$>np%Z!C50^QL;N0ROw+)9)_{W&m0M!$7X z@&zXdX>}_%s_cBvfa5Db79*QoY|0Ecw*osZN&((yq$Ayzu4DwjabFb{PcLfnW3?xZ zJFR&Giwug?@w#$kt~sM4xqGMr1d&VP89G}hs=RCuEZ>ARNm%KFR;J= zuw1A}5B2-!^QJjAJ=|>N_M?s)o*HY$GC&`?8gyIh4cOBaK7uaahu#kKpJ&#jy>fbl z(C%)zh>d)F@LehEC&f?PWPkoWr)ylyHtb%jlZ?=)v(@gk0f9kqw(M*u8sF5l_rwgn zyx|MK5fvy^zszPE3N4CmFND(H{UT6v%(+)Rtrfr60B9XFjq3l=H+ z0D7cd=g<7ocb$pp%#dEGZ+h%#A*>eF6H7Sle3x}x=k)3KvCbFvK1_JWnsW>Wya(lr zU1ET$%=K>=u_MmH+j>NQ4jFpOTqf@EFcW>v?SX`NdgUA3vunDz68dG4!8F5Dcn7no z=a_0$cTm@d`+XaCtf1C1WYO{=i+4dF4Xs4B9xwsrPFA&{mwnF`K>Y`e24w;k2CJZe zAt6e@L_}Ao%TwQ;{S0&BXbR0JrfCJt9yuSKV zLJKYES&#`3!1GAG9`i>_zK(XJBimD}HjN97@G?IA=N>h`XVZ4QK;PBG8s}u-`e36U z#z*iKd+5{^2SMb-u-7K8$kBBw+%!A5Qa^Wd-=+MPMcp-9FjW@<-r&}LgbAo~qj0^_ zw=V_iTmIFtY=8n`$EDF$#vellT?xuN>r>Mjd9-VjEncpm=FAP3t!#6Z*#|@ipq)jo zIVobWHfdy$&HKM*BCJl7t7wZdzB)D&^)(6gH3)P;qRu*KdCK{H9 z3ZrMETa(ohrh38h0IoD(u`NzCDBG>^1vk&UkpJJ;cK6C%M;#3!;n-7jkS7OOHGBAF z97E-a)`chjQy06MEMgmh3z}7b=&_!$V9gP4>V$MZ>l3?Wf(p9g0m$!Je0syt>wk@8DAZ1rzkn>f zh$CHpy&D}g+RMkQ`TRqOlC-c^)_LNRMNWgQ^sVTY;#ZfBx~m4#(86}GxTM=FWWs*X!QeV6Fl%yNJ}Qb(-O_fPHrbI5Uz?8qCNd+)WGrgz$m4_}rl zVY2?D$3o*jTE5?LDmss`35uT+SdLN?K{gF}5BcW>!iXheLqAAe6JB0ru8UY*A0K4= z_w8cSAh9W>)OdmfXtEWjC>FE(?wjt`i{;ahM`w!Wz_>sBB6mu#RIVGn+j=B zB~YpAx~?7Zf9zOD)MIMSaqpW%UQ%RuxDpdvXNe>{$%xP zrZAh^Bg|zbGNCU#X$9n_nGW$`BaG8JT1@0a^}pwFzrsUYYv)p=lNLnk=0ZSBrS(iF zy&)YGg-VIqi5j@Xu%Ix`9V(xI@jOdJoMf9jg^&v>8;w$Wm!uP1P~T;67}yRjkqtPF z12if69hk+0r8G{cY*^FcOB0b*&4iX;8CDDm=c|S{wFYKSUruH~p3hxzUGdB|L3wt= zN_hQmVx8l`Rebm3DtrD@3d_w(LY|(HqQHjSYVlA;PPs0_oj3Va49$az4{iYH?87mJ4q-aiZ zbIPUmZ>Q)c2p`Jl_QnPryf}Q2RUg=#hpXBn^$Wn~DH{{)GUP?>?K6|OQtzOdIHPkp zJ6dzn-WJ`C1x8Op;EsJ@b+)^`S5ea&JMm#ENbaM~b?ItakBR2}wJWnk-)QB`9R5+z z@0y_<`{3czc|wfc5xAz~3n2~oQ{x5H!t9;@$Hk=laCNjT;rRl5_5K6pBeX25m0Hi? z1H!9+yK%J#<2Ss;FsxgBg6gv`8EmPwBhKGXXaxCmAmYC}63M}i90P(sx8$&1EGVulG7!> zX?UPqaVXPt+;Q_-I9pq*qs~0Q8~dyzcEU*6#8ie^l^s zWkUz}j`Pkn2l*1LwcS-TGQ2xdtk+3m1%@h~iY9xzqzk@&FRr>2skA zvb~_??Ezj3o6PyHdy?Nev1Y*kzn7ubc<6&CYjy zssd(XR+X|y3ca%6FueYalpyQqsjRIW7#&8XvpTlG@xoctX}{*qGAi57ZGgq%6QP%G z$D%36nn`O+5zfk;rNUJFY@tgVbih-}#H0prs^FzTkD5-v@+xh@1M|MdB#?UYp}PgW zKM$`3;0YchTwl;9{_;kW5i4jxS2T)j8;29z1ejfF;|qdo*eyNW9O+L4$U!&804DPD zwUENNOAbEY)%ZJ3Y)U*>lo%v=i z-SA+?xh+B)!cV9j$3Y*bKe?P3WdiH9;Y<2Wy=2Mg0Och2vanCZ20v!YWbC`>o770F zr3H7#S6q5ac6WN4Z<`mUOLQUjTE7x16;(Z_uz^IW>2QHCO~;p0E?9$sGzv=nO8C@h zrs#5RN;8v(?y5K3b$8#zp@&xrBDmHQ*2(qmqcdfq-Th6&KVljci0*oBUd!7oq$j>t zFI-md=oZ`=TFh@ksV3V7xJnbDyO11mr<^tF?I2rqmU4XzrF?;}Ezv+yZ!|enB5INW z4V_xfpKTZClHw=wr(v&E47iG)&fG7v6$?NwOZkn!Y!{Kz;3@8;XW)EeFrM zDaa@2gQjR%>jQNe^It(OE2`ciKII`SOE=N8%*E>9I)4k%k*9wAK_EKz+f{*3rTp}tA#TlX>$6IXD-%6&D%%xZmp(#s=P@$J>DBo7MfKKhT zQX5FRgy-5g0y34Vi-jh4@c{@R4_g(R5{uP)i_ncqZ~+wmqy@4Cghb$_EKXv1GIY|d zFv)%j2VNb3nJ*9zP4Ju^HBG|=G&fA#Hr95_IBuw+Kx(Px?0_y_r!_?kd|VhP{g^o$ zms4OJ;985A!PqhSwL-TWi+2Z&ZT@gx1W=%y&)=}MXZg{oKPLJ@eO9N)SK`O?CdMCW zV*wUk+;`s^2Vk{R-!AbZd(9t|f9^WCDLSqzR2!KIE^?}u^X7m0m$t2WYM$>iN}4}U@L8;N z!#!8QKaib^Kl960LY}s@74KYet|)3WuX*(mfikUDX60Hjjbut74=@(0Oe@e%E)=GW zww{|c3bQC+DSrv>)o;V86aEVeqz%c?hS*V| zpCz1~f%~{{LZu^|N{R@&>{{FETcUelANGFk^{*&V0^s-f-vaG$3;+TpEb{R7kR7AF zn-V^5g6_ZH{oHZX?fYewyY;PoJ`c1aQOq(`ZPcC9;S^@ok!p=Ss^27&B{(g9mG$tfjEhsI_M$d5`m-KI;=5 zYKHCx2yA<^mSEwV`PYFGraP`%`MPb&4fTYb;0)v~4}w}hJ`wbwCjx$UgC=s^6xsv) zf|Ch4{YK6URYx7*n@SkaQA1@^c}X4R2cp6HW@ZA)t|8M%#)IR98Cf#|6w}ws2s|-BRlODXHU0%!wSn z{!~BQ4v=0a1Am|;#i~EYIvM&BUhD84o+svvNH0oTY$jW+j%Z|S#m(9q;@i=KxFX*h za&PZNtk^N>3HwK1g~a*jD6_Na2`dez-$D(+#`gFLG=9kwr){E*jwDau&!27=Y*iwVIKG0!rj2HzpUVvU%ZbQPljn2oF%CMzAdOIaQ zXA zY#Z(uO;m?yO2>W7>8Ob!YWpOWRNqElt-aO%q_^qCmI(}6B%ItrgJB9C{k2(UDDC41 zPI9QtwO8wlT4>`9V;rI{q1?05&9!Xw<+{UN^T#V$eeQ=n%4DxU{RU2ija6m#NyV8dC+rzjL|e$HOkchOI**n)|o zCSBR23#fnvin@W8LZP3eS?6)%YG1S4D~y@b0H{3dv=mo8x9X8^7WQa}D)FweQkP+M z<>HspguVGEbOQB%O=RrXV9BQ|es9wBTt<52Z3YRuVEW!ss}AHA2~DQ)-AW_99(B_F zqjpP=Rs^OxZ{mGQSRjx5lu2;*+%}8t_46kJt+JkD4uBK_^(g#7sp4}h%~&2~ z_DvVh|1RKu_AcnGODB>_pz}5rcR~!KYCH)>4MAS+aVJ{on;p3R(VhFtyVrWjUL>Eq zORyO>#Jjs~#9Mlx%mo&b+lTR^&2`+Y3tjaC5`BjZs`$L%;DL)+H04tNK+Q)9cZVh7 z9}tP$5YOg6AW8rr|H3w!J{L%M!VKi?u>@VDW1LRzq` zJLzVw(=XH7u~Q>W5jUQovM)~+YMg(IU!fW_3KZmHePfA_?$~NT8?>3~>GN|+tk_W@ zcq^T-J@TpjSShnH8U5I;+zH2nKZq}(KH9_03>m5%FsK^D8Q&Ho*xVfghUBwrHL=N5 zISuC}fN2>^enmpHOqIu^wI_GY-<}e*bliix3=wwr1Ij$;sesUh(QJm{E|zESc%Rzc z!tUo}!9QXA0FIuN&w(>NQB!m%Q5tcptbf8*CVjKnb9XT(|ub^3tb=#iwNZFiyv z`zNR1(xbZO?h%L+kdSQ{2T6R#W47U951tR0eX9`MMtS@C15L5*sWoTfE1Armk&+MU z##b>8gzA0XL(Dy>1*Poz?&n0u(X|%LyrjXY&oJ*vuV*-TjlX z5@D7V<8-qGJKRED;GDvMnv9KXux$RY?x3Hg-_MpWsj+^TW<}K(d`WX~Q0s9gQ|UEO zs?THcsi+cjOe>>)0Fx(6daT^(Nv53vJQyLLH%Pjw_-ANbyIE63s*BR%yXOZqNfj=q zWi&YfCIr+GN?j=`Hn_$NGZFTQi(v~7j?d=#PoARW#TwT^8kP@smmutNNO31)!0s)T zB?}|Qz;ueY6ZGHjfSI2`5jkY1FGdVr(j(F+R+Wl(SEc`e$SdFMkg?>{c#)Bvj(_y= zstD&h(WMXDQcb&eGmTUX`z|)4jD2=2Z;gI%`Om9k4``S6hp@_#0Q^c!CoRk7WcwGlA6r>(AloOMpFm2rRu9ImSZsQu$GjQGl-bc8lMn`mfVG zMaFZ{8xdU>!C-)h-pr5#E?9lnd>=J5)z{}^Gf(tKdBn<(pHlUKHR2V$N=yx6FOy1~ zO#;-NDog$7#Wdx};r z`K4uS?Zt)7edrSxGCPk6+hMn{qutS<<@mLGUUTj>l8O!v935XjLG>$enSi61ow&VU z9^ff;U281Bf%`v*ukrs5nF~3(OJ977Yl10G7BF~Q%>lqR016rzSqLi8ni%EHTR8n_ z*6>Vib*{IHVl+34n>X(_!C=oO#f>R7Gea#XDtyX(`g2 z2{GWxj9qA*x!cma6(_oPp(}KQAVh#<_d&;DXnd~L-X2PXtDjOAM|&qlg$Ga1iVT$y zjFED9@5P`CpVh}LHt07jz}QBg+UusGE~(2&0v>d~8#Wx69lKY3VGnSW5o+(%8jWd{ z*f;hZ9jdD`pEEMMkU&`|Ye}h->=a;|@@yv1%C6~s*RTR;n*W1XeM^iz$}5ncH$3@# z{gq8)-KpR?ztYMCq7NrTrb?SFFb4RV@BOzdRi~B$}CLIyr9y zRgF?mItpzn=3m&zG#D*{<ODq}S#3m#o;9djGjVV(mi| z)-OCY>^MA$X#_8QVS?!TqiR6NyT^L_HL$j-7;Df!d@)2if2q?JbXX|++TiSRE6H~i zRkWCO9Sn9WP9T~ptA|a9E-olDW8+5b+$>n3-RN9d@)a(9hLluC^9?ahPAIMSj|mQf zFjYoU7lBwg8Dy!X%70^qvX|KNnn@XwQ1m7HdjG}DDS`S<4ipefO`aO65@2-#)LvhP znyQt%m(^~#$YG6qw42szic=mM8jxS~prRD9P@H75XJ}{0R>XX<0K2D-JGi6Q*)ylN zN$T5NVWwiUNKH(>GdLfCH0m;h)vr;xCGJ8=KErd#OH3_x@wRmDb`DHA>_lOnXqK6n~iQKqN*QR=9iBoM-G)iF*J zez$qdVrYW!n3-l?v!P;!AMHY+hWpq?J8T3q^q#gU;`pt0Zd0u=_8TTNlAG|^gi->P z+S=EnT8r5Bk8mFDwRZ0X$>kbtng=U&*~v>v(1j5&$Jq@dK3UXxUOgBU!U&Z%CM%xJ zB$o+zAXXpbCJ+Az@9z$u=5IbZ7|N=h*{xc&m$UR}w7e1?x^^6hR>TH1mUDJ|X72zx z^Zl@%@skpIzUmWYK$Kyd+k5S^wF{+w4^9O~5}kn&te6=G923KpjaGh7IPg&xLK%}9 zTcDUcLzwkbn=!1TjeQ3olGFj|;Vz+9ns14JZEy{O-P&lMm-X_CIe#Y#k8oIBGm>-2 z`}l?Dnv@)LVtslYz}$~EmkPflbZVTL!Ci?*I17}20+?%oV~iA--f?lw<9PBN4O-5Emf(O@lljzGOFZZ=(ZIvq2OEo`B}1ag^^;ihl~ZyUm` zAfX!sAo9%VvH_ zo-e;_MY0~H$|qa4;iP(_LG~AigkdNo1e6BCSXAg`;%-w!lVHn*?){jd&OT{%BS|V} zVUA8dwqpqA^A(ky5`Ak@tSaCFNC-UKscM~wx!f%tV64;cZ?-1cR1;7lk&~VD;NSRL zQM;2PUf%S()~#_nfgIyIHEzgD3k+L**CO)vQUpb`K0EQYw7Rc}kIIWKZ==Rl8zPG@ z;LQPFHr?$Q%Jdq+!+{kZriwGrmjL)xyU{@$ zk^__Z{Ze8fxcnw$D=s`mmYmniJ3imEt(tFjv4Fpy*WfTI>4BH3)*>pxnrz;)IG6ki znnS8$8)A)N%<3v}{8k)e-E4-LvnC<4Z31)oS47?pve^#7XJPVtZCIYlc9600JXGGg zR=B1prOoZEGFqpWW0hEw^Xk5)cIe+>#YBP>fwV4QZ2c0*3Lf&bv(Ones%fkK2hdd7 z*y%btwIQz6u(0Tt0-xaY?>Pv;ZoBQ$Tmv}258VW2$E?}yF`J17zZN+ooSp}V|BCC?;2z=fH|G67OLs~{hpgOY zvD}((Th9S4QA#g$%)8Htdpj-JTH+YyF? z)?k!+s=Ns_QLf{LG?s?$pWkP^3z(9qN4+1!Lw(TnW*&M@wi(<2oaEjx7Yy?o>6rg^ zCO<6ucTDA)tU4M6{7D&&;)N$kt|iZ71h^)vkZlx8L3Gow@f30~-_|_rIG0>euyt}@ zd5Kkjq{%5+VX@vk8@hJ!Xt-!f!gj9UlcQTW}_aBZwDQ?+25vPS*%eG|!{8?Jz}i@v?`gHIv4-?P-8+h>rb=vqVE$GyIO(RdeVfNY6R z{8vyRNQjS(@Wy%T&sHlOeS)hbb{;4vT72NH_c0~rrJ;9H?FnZlrnbTIVlFvEQS5v4 znnb8Qrt(C6S247Ri1O zAC5~EgHRt*f@y_IUEoSX$|&YRd|MC;u;(U?SSC+|Rm}J`DK6ZKy+>6a9N;IvXMrQ~ z8xRg=3y&a;dPJ$%UOC9L@4+Tyjg;U7VyjZ`bej;YAS~%(`n&~kFk9-D6xLTAhLeOnzzNY;KSmkU|u7AWa=QTvTXLI1?+_34QH<cNe6*ZMGVgB;FdC*Q#Q=y$9$vLQkhv|U)+iTgZz!#zJ;G^!R zt-p}THaH}07dfUAda^yJ(bB^wXOsoW!YQ%JJg4=uJlQxmdD5zpHkr+CM#(RGRa7-8 z&VfTRkz`m)uO+W%*uCqHs#2--GGfe9m#PcMuBRH=BqZ zw?17hjipS2eBMcJUaVivAfHwlL5MQSDiiO=v3Ve;Z+sU9=OzEGq8{o-AXn9`F)AG4 zXO#)U) z`b-5$1Wv88yRxYWkr#TBVh(dF*p4*E|E&1)6nNm{Cc>~BeX;(L0;{~ovV30AEk=d`U8|~(EWXg%c zG&tt>GR%)K!JgxQH#Ma#o;W35NH*M;r#Lmol-f~*Sl?H+6>O@}*w7Rl5${KvV1m#L7`Ze((AR#Zqgqu(s&O zCu$#B9ucPJ=wZv&X8h zs~Nb%&uv@Uu0ycw=k3awiApWFfo<;n?cY!0EM zc{Q6#(Ym97Om-br#DQy4r#>1+2iJjrBu`*!e@no|*_~+@8Nhww`IRT^4hPKovk9@j zgyD!aDyJ$uX=~IyMO;2FWU3I_yIaHVe&rH`Z=Gd^JH@j4A~8Hj(%3O+OcSbI!;C$z ziA^;|thro^Ty0qR`s&eX86EHXsoh&3iY_QQ4_DFWE*K3|7Nszo2Pm7)QcRZ$Ha~%< zQ2VCb5Yb-YTD_*UZQ{Wv4 z2^7WCX*x@wpj)8Y4RPop)2>jM@)-avAU}WcQaZSADDYDm%_>21ptm+))Lrql?-6EoGh=Yt`jw?e%n_!@h!MuO?ZN6kLc>O z7!z~TRWnUv>@qQIFCZ3@WPtW!+Na&rPldBIY%EcG^YKsZWp?PC!h)pW%f(ICY1Fyk zuHP3NaXtQat0rtG@p>Xn{0OL3zS?LrpFmxHu%8@Zd`K=9h&8quOG5O*a^-ZqA7A-N zYNhh9bgx3B)~6~5q%XHDr%YlU&;|nA#^w#u`QYy6odf-PLmPR3yU0usa%ra8_OGl5`nx?q6){vw#hd^c zWFKp9q%W-938IYK7d`9`{dO-Q$^sVd`laD-G003JmFFB%8qhl84vLltzkfzLbR{f) z81EkTm-^pbDD?Sbzm)R(v6{PJ9*n6rs2d*o3GBD_g{hGyOB~C=KmOkT;8KzaX`bk- z{+hA)m0sRF;;wU9UK`Uc+%~)EnUNHxbJdIfL3*zmH;L;0=?W%r}zh-a2^1Xg#L9eeRbvOfFHD6F+I#n*tO!EA-I|S4CO-9 zt=JC3DF4>?GW!!=3QMN5@F%Sl``3S6#xZai)oB()EbYnv6lHYy*FP?~=$so;VP`dc z17t9xWIl1Wq)Ew$y32%ZxEgf~i+}9Tr@m_I`B-*)_U_IuS()yFUr$L;HgY0TEG|p6NO9HM? z@Ug3fzaw(TlfPQN%%K8?UT?t< znn?9uYr(b&)7e0X!Gze7-k6)nrN)EHL;#fs_-#4^z(qq#u-k{Fgc%x^W4yqxpC{q>u`2w79?evKRi2`~TrZGX*LzE2zSvI4AqwgwItzZn54EzMIt81` z@bs}L752>XScsNbeY8<>bC^{?bx)mm0WQsH&KR1s^w{y`jWFOJN}j5cG9mJOlPU5- zwj67$vjL-vDyqn3zC+A`+hK5a>CRGRNDx~#Xb?6Sz+&HvAzg_{Y)_Exl5#dUM{ z26v=y@@2PHls!CT8?etU@d4Y_>AWlYY&zvia8P@bqZ`-plgdA#%W-QILx_4bSbLoq zNOgQmoq_{rQzPymkkHnMJ8Y1?i9REtU+w5atby*7;s2ra)YIw!Os8}2cAhp>$|=); zthJt9BV0?B-VHd;KCT|Oh+MOrsc8a~GvK~HQueA4S(^u}hX>lDXXrmmUmBX1cV{O5 z`;W|ny+_*jzyQY>nBVCI%`*peKuAl9p=2z;G17-cfc%ltB5@Ro%dgm5o+g(=gMQGj z4xIezARtDi=0kfCmy#Txeh@Ug=hR=JH$ytQgu!p%gWO(rCLjMfE(k>u+ty$CUe_(C zYoI^b+X%ybwE#I~y$c!m62B{JU1)@Cq^eI=!mqrPJU81x2UrZdf0ujdmlNTS_(+KA-zXIhFB=H;-7=_ufcC? ze|d04SVqfczKkP^5fCvWF(uXQghL}fY5vHs15U5XpeZ^;?a2Z7Ce{;mLah1)RvRcx;3$n}DY)39GyqjU$$jPHZyYvs10&mv@F5Dbm7jA~z&!@W2D2rfh z!G-STZRPxC!QnnA%nchv#=|A`@nEc$Qc*idErQ_! z!PHk0h8b5=wbZ@_{ zFuud-0oFbDN2tKLgzDlsxGI(_7C#+{`DXcJlhZAewx=8AR}7YFJzq7q5+nilmf9F2 zochZft0y$7bqV5nIrru^l-iL3{H0)7sgiC2oX&y7n|nZWULu}5!7HriPpHwO!L{03 z@*Yca#BPD*D*1{f0k)!bfB^SOKem|Z4ZLmx%JxF!U8elWNUe84O9@PWm|2DM*fH#I zI0tD?r$Y6&R+vie0kR0R+LT)39+kJ*VGPa! z!kXqptZx#q_nWtp;+SrznhcfJkIc&=7-i8pa=kEQmXK=~@a0#teu4?(N9hsDdrndQ zVqdQlx!p2^0(g#->p^R98AE?kun+oZh7KV4AM(B%DY2s4nqGCZ;$Q8txh&oNziuVI z!8Oe1jj;83(-QecQ`fmHJA6rZiY4`{)o6Ta+KN4`&X6sg^*eey8X+|ygP#s1DH+js z?TxR1=Utv_OGtJ&&X&A|OIMm6$;r_0DW7xevbv)C)Pm=Dy2$Sio^D^6eLXx#FdO~1 z1EkrbP`&oa=#tj9x2e$H3w{P9mjXoY5-AS9m}LINcUfSXCg5)kO=I(~<$s`YRh;bv zp=*z6Pvs0~H29B33a6hf?JI9IcRXyp7@{*N|&ZMW^@|nJ>HPiB`m?L z1cpz}8XM0SxMzbS4YCN6k8RTIv$-?3hOD=Wc3S?QVP?Q~nNembo#I+)2* z9S(rhV9vl3PfnhwJ6v3utzG5#<RXZBmSW30{^IWa{L80?T4{>-l2iX&G)-y2GB?G5cK_;?}3A5 zeg9AYL@k1X6}UqumqlCd=+^qHA6HvzQ;!~KwR#@U1WtmmC1-wO;hsgL+qZJgUQo_S z83yEBnt2txXXAl7ApOlHfIB0N1;bx7MS~mt*CQjgt$K!&JNT~lE_|Ys8g_r**ZT{q zT{qjHIikrv5z35)y0?%JoGzLJ+H*5jwM>Ze|2hpf`q{+@!uyi!(wXmA9p6sl7jPPn zBcSd}UEvu{pt%TC{K{UK?U(?=MKr*&$n~<`@Y5?If>iBA2k-L?S`GI(X-0Mbc=N+a zrto#&imj68*+fzJ&_+V{d2j})ZE9b=70*@!0@eSw90))TISU0Ak>TIuuu~%k0OSso z$yygjoac`vdKl+|3o`PT{MD4SUC%|xHBUC)W+Aj1U@L20$6+(~t@Qolr8wrv-vpwW zzMFeqmc7^`i8HNBgLVKxoRuEjyhP#f|0jsYu3_$PW(EIS5RX34Tks=u-TQhSH>aY> zY^Sd=LGTcO5>d{wmSnL-){8p5f_a{MBM)JHaj)&Ojl|i18t(ghq_MxX-mal7*Q`VD z06)O22EY6g{_3k+dEqWn#Hi4@te;q=-?@Gm&MjDUj*HoVb|X*z?sV|8@vZmz zKd<@pJZT1DC%V6{b5rB}{l`9Uc)Aa{w>ft8ZHRv3X5IB`uV~wc-v9Uee{Xp4_g(qh zexCZ5tW1fUsdWC=mi6C#dUfdM2Z zcvjrr)}iRNcvBaw&Tt(|{Q)$Co!p)B3srsH@+w|RoKH$_@#~oV;puNyQu&6DBf}EG#v!Qs`_Qc30$Z)f;98s(E6QTk z*cE@J*4UW8=B-DBT9WG2t*+=j1+;{J6lGli_3W?^k4_e3_9M)M(OIhQ$1CuczW3nl zbe5hs*L*Nz?jtUJz19J17B%Y51zH^m`HtJ1$;Lu z_}ho8`3Febw8mmJA0CVAOzp}@T0QAjuDr0E@>o*$krL_Z+0A~Z_X*pxea>Dy=9RmQ6q z3sTu*`fXAm3BGHP;yoTKcTXROQTcIH{-S0Xz0|h0cvUuJF*iv5BdOuQhX1)*D(CAT z?SmmW{5DqH5p@SL2CVV_u=n0!P2Ow#aJ0j=)>0fOB5(w?4#ok>UL6WrK&m*vFsv*g z1cVqyLK1p91c9VzOJpBGWC%e<5&|T#4uXbJ5E4lsQC5H$A|nY90`E6Lt>?7wujlvA zdtL8!_4zB1JkN7K_xRl7d*9y&Likyl)UYPS7$I>i+v}gBglc=>NzP1JTzc0P+2T9u zFEn()hLLZ#WYz?3?Ajs?cP@JpPSYA@CiixF?GU>E!fm#Jxc4}Ak*5daKQh;nQ(t^y zwm|maeG*_^>uCZ~@7v(js$*U)fJE=5EY}%#?C?yN+`5m7opZ;{UA_BH;wV<4QYr$& zV|6ZriHWjbYSskeT7GFP%5AAx91U6?#VKZThl40JpPw3A!Mg-DtHqjlLkkxKcKm!r zB4|(Q`dPO4*6;s#Abu|~-((JK9+Zqy9<^Y1kq?BXNA_M?8u4BZsrk%vGdaTs(0Xx| zR>d;Vg)as?fG!*%BA2POsb3cKJ^+safyC?;DpplMBWYWrX_2WI?6vwz^tM}TjGrzS z-wDEW9^CnvyyEnY+K&Eozs`eFS_~U?bu;n6g1}u*jSVhO$5A3$R@Fj=UyUfg_II$p|JCo5UHyIXQK!lM}E6)Db-xTadO zGcz;m{UBpf6`jdt#4pBUmqj>+&gF_}hje2fP+zdCZV};B(`RB0tuMOD`ooJ3MvX)(w zASv2QP4W43Be$KO6}p?APm-U@u0HeIaSM+WQJ-U1b()khJ2!I{`+ZT<4b0krtK&fQ zXJclp*#5KTHFS{92I9A0usOH zpD+frcjcM*9-s_@{zZygH7Skd@UPIi@@3iUUaKX4V~w#3a%3%>YiYZq;9T}&a8Wxv zpx7gMU18ZT>!#_dJAjE}I%zHdM&!GKY6b=YrsDpsb7=v*KdFZiw)m4dZh>87VnrOE z?RgjPW&z6E4Ksl&GFJ5rHgZ02vaS<%RouDMW3K99Di;3i2D+ zuhg8LngS2*dMy1O*eibNurhbzOYF=ixS6Y=V;eDnygS`{)qBdF5{Q}0jeYFh_Y}vN zFV-_(3`)cqYFD@{d&x2RvzRL2PJpAk(=F>nP!B7qj|IbT{G%-=$US7IBcpBL!n>FK zjsm@TY6sK~dOu+(X?xOd0={=pkIRwhtnp1iirzD_M}zd1mZgiPAJ3MWV=6Emb31Vp z=BiTf?1wG56@~&0u+eB08__DRAvG0UmW;6&sbj3{;^wI}&ovPP-dX@T+cksvY1IR- z66UE?^uGCbdw-z&!S1G#nBh}nKh^`j;k{7WuRG1gt25Qj_B{q9>eh{e*3DUu=Ru{JSX0JT1>w=f0oVi&!Tve*}kp zMG;*?5gk?pHn28?*wqQh-e5QEF6}-ecydUz8uQBv=+{b9Q>zHlwt8sNPXeg&`^Hf4 zIP#HiYEDMRUSq1LEAh%RKv?1!RW;C~D;|z^+co@XnsHgVC%)`)YS1-+qX>_qdo9nr z6jHYIQo|ZwV@8Uu2tQx* zR_22zsLm4}8*j~|k*}G9y{a+zJ*0YfVQY2!hVZL3ILkm|?1`>*?%05y=(5z*s85Z<5Zr90X1 z=L~ekN$@B%|CpoMi(knIu{mEB1RnR^F|@dm!ogmiGG#h?6Yl&(;VZeyg-5hbV}5yGel`<)7B~X~vJEkMg^E>h@(5LeXq@ z+_cgkw=26Q*uNw|XsQh8A;I=r{J42#%Ji{E%m7l!YY-oyFPtYUZ8pJCm}+eaIyh4p zRPTx!&WzGU%$-!)RmMA7Y2t`MBgUq#$8F!qHF$I64|vlJkZ^{`9AE@4{^TlWE&D>9 z!YsN)rTRP6h;=7ol)fw`l+0K^xT(CU_KqcTWGf6iF8c;3L5ee5afk=Wn8d_R7fv>D zu%B=I!WnO*xo^N#f$(cIJJ!tazR@!Oz?E39Z!^LzZP$e}P9u|_drYOz#|& zyx9uIumZue2#YhB7B2eU;D(z(mATM_!5;-PvgzC%qVlHBZ81wETR9m+7_a`M{?pSw z@M5NYH)U{aUeQY-vk&nYWvxHu=&k%5Z&r*6z~xm~DCQ_hmC|`tYLlu&Qh2PnKsUvB zLXGOuyR#Q(p31Vie~h%&)69zN9m5Y^5KyRWccBlvH{-HPy;qF?^?)!l?qqfN zgzs~5nlSUcqC4L~WPg)}83>EeJ3}K07^#v;$x4<4E~=m=$3So5FP-8`&*z2rMTftu zfeFyIpICUx;6CAn4~WL{VH+{PM?d#sge9dCiNvBuL;uults}R7d}*ngDWkeL*_>>t zQ$zb#0NS^4l^5JX=DyU1x(@tWFror#>M`W9Pr=_qM5^%q;bSwXks!K@`o&rxWELFO zOL0$AJmx0v+!X!mtFXq+1;&A~Xnn)aGK%ubiwt9nl*b&+wTo^gIg+2WXQj6eoNX=qX_|}LL+uTsI<>ReY;&-mpYVK;6{amAnU#=y{Ijr~AmR=I5%-;If=iaX zjB!lj_qIPPmTFwh9%3j9*oiulVJFgNLHH8uo0D-jHry$>Zy!FfzUTr>*0gn133tJk z!+5YRz`t)uzdbnC*Y)qlE>(GFhc1CYxAW<~28D@C-@34CHRPQyHs$-)bQ@2p7Dk^V zMzA~8>X(lRa|;ocC`^(1h~P(|Zd2ae_5>;U^8go44%@4mNkT+?gbL2EK}a|x-9 z>>5`5E-aDuivX3~3nvu0kI2mV(MBvMgFWK40|O zfZc{1r90dVdI>Ws;?m-7$)-rJV)z`;x!djwywPt!n!;EyUw*)x*CXO6H3bYAMySA$ zQ#@^@VBAN>#?d>6+CY2>UN^Wib^gVd*tTNq`H+z>_sQ;UH8y}OzOVa-UyW&bse=+UR5!)FO)=pvNWTQF-%l@fmQGF!UYE^Rn$=rf_55H4pVaKn;fIx!gwh>+oY9Js8785Tm z1~A15Dg|++p{9r-Gj^RZCa1J-odE@mn80N*QpddvfSw6k*(QH$8_acXQ>322SD<7r z+wGnrMAvnhi5Kf>oqKT4R^17mtvJksIDJuwaAStNPwfeuwbb|$FzOus2&IaRmL>Y` z|1I_)EFGVJq##d?bFnvzEvTGM=qjQFw%~m!@p@v>Puzh6eH0kKD*|-0hNp&RPkqaG zG4|j|^sF5|S$NWO4GJ&Hsz|C(FkzhTGiWJA7FYw{l;a~x2;oy2`p>aZoT*#>*b(r4 zYdhci4U)Q&$dxR2SJ%6oV3{tNpQF+L*JBP#zqXmWNH*Iaap za4GAqfqQ-F*AM-AY4*d@wOhmY14k=q3Dv|Yp#E^bk<9m%{=zBe%G;`^zJxJ76dP&< zrAV#|v6t4L>p&8;z`eSvr*K?BGn~$a@ehuHjwXA-xg3huhyhB8JQ9Gd@N#l-sG(lF zMYAEVR9A=_6|=@s&ZmC2H{N`-<0axc<^QSv(g&+5qV3|Ub_RibY`IJwVLacx^4!{0 z2_k!$2X^T+cJwsJ7CqI5Cz)L5nBBl`U3b7>EUrk2HdnL|S6Y(A^<6FqI&RCXc9N?0 zld=5<%!l~_9GM@<3ej&K^fK0$@)T4{h@xS1ef|Xx$uvv=Z>UK2hP3ADuz^XQ3;^IeE%$=m0Fq%gnW|;~TbrpG60`f(`c?6wC+6 z_4r>CgRbs_68e4z^;BtNEXc<+bu%g|Q>JD95E;H);sF7n@zd?H?~DbUp`7r+9@Nbq;gq9Aj;v5t~Rfl^%gLFShX_ zKU6vFCk9PYtsSzP3aGt!bVxh&ceSYy*$LspAj$%jl&7c|*>v$r!Mo-=Y^0GZVwdXfKS}G8dqMnzsu) zX-;O|*g)7MwU9H~bOU zV;EIC$SbhJ3VQ_-&u3Y7hX+Jg$G6iN+|JKo(e3tA-SG3u%Qnunp3S6EPuZq(0n>>l z)Xy(O2F?VHpWK9wrpBYqh5*d2h$!gg4K(LVVfbC7?$~O)q>?LM!rVw0 zltxH5)xjxDdEq};XOxVSE8j#e!G#j3F_%<-8QF)N>zQ;GctoAvGAuRCo0#bEKA^W6Zjlu|ug&#}AV2WM=Q^ZI_9G3e5(G6R9KG9U%`e#8K|tpuLxN8p{uSXDSEcR<|z9eu*&fiZ18T)NeH?k?pP9gq;%~A=*X{L zxNy+SYUbIMj=-=tbeqH8J*~{^=rdm)GRJy18yXQYvaTRaN}BlYg28FMsTz!-rQo{^ z#WpJmqiyb>p=9eLON8{aTi&9<`H)G>Z@v`Uo1a?$XoHZ}9*yAY0)A-+U+d8eaxARC z@?FrF280v2i`Sl6TSl^4))!AyA25LOar^{17=h0rc&EuY7KaR-rxOIf=unaX!?}g!R2@c$6*3ehZ_hIV* z(y<2Y$};dwDuc|oJQvB&=GgY_S%hv6ALPs@eHGx{9930@soKLMb@Od~_%w<%K2Nlm znK32evCcP>QOW~7{2#NDDrN^@Tyb*;4_+Dz2h*6dm2ox>AZRY-^J-DLIIAbkROI6E=0pt#5(nASWxLVMK3u zUfY$Xr5<_TLMjIBEqgLiZO-~Rn>R8{XWWeHpDK;L(KKM?{DxE9C=4B*TU}ETnFa={ zSi}*O)ymV2PZ4V4Me>yG6po*hLjRo_>SnVyZGSSb>nbZ&CG*}V)B&jsOpGG>Y^FPi5$uco%}~yF8?(6sb=q?E&%GB=P=`M@W`0NpASQL>f%12(>aEek4aa zos4m|5d1t$=p8MFFT1q%LibQVF-TvL8^rKOXR>JazCDzH-0uX9!wCo;JjaJxeOc($ z(b3cRC7cU&ei)nCP%Lf9HA;qSUBd?Mcs1fkL4BztGLuwdpjX?u z6tL7>a8=;^tnC^PUX(X1*kLLw3f2!Gbqx4^0k3aZIzz=CJ*e~yaG~tR8Lr@wRFpD4 z+NpvBBYDN>Tl-9+vgHYFDr!TN88 zmdrX*P?9B=EjabvoD#QHN9iigyox9wb|0^<{UxPyeQ{$~{A0$5WZil`3a z{mHtl0el6#Jor)jLl<}E?NiD^-jsmiHaUY3*YN8<URETVfq01K|)~QJbiz(TvLfg)2EV5Ihnm z!;WMrkj88|CHzS9QjhA?cqZ<~pfzcb)RsC>WUS&^c5uw z>TeYw!E@IO&`y(!dciT$Z!8gt4ak0bI?b<%JCU|fE}3j}mm(`G;>jzf!yl>LBTeHT zGbXFev0KxUVnp9uG@)9`TG}iWtyX<|sKM3oO8)YgXXf=vgkhSndW(u1j~sw12K}2I zmaD~y?@HpsASrLft}cgD6EkI8vxl;<<=)+QMCvG5+^hAkUag1`sk_UGy7AG=M%lU# zOk5w?C#fvPb}y?yy;iUJIhENzb*T+3b*$XtUIHmDr0{bFcr&juLWtgxgtH(P)sM0- zz?i!@W_f;#$NlwBheSKm+Q*e7`Z7AWlE2-LC#W2ZDZ$Kf^m2NlyT*5XPmz{VByq;s zi|dimZetV*Eey@wafw?MPJ+h-nP=YO{>Z98#4NAjIL^=-=(skM06vt!s7Y^6!}3Cj zt-W~Mh`=n0X4rIUkd#%+!8q38>N?uwz02;rYF(e^4r7!uG_r7JI?Mij7?o^>6Azb2 z94*TX96k60d92cD1+Tq=?G1pDV;|5=@}CN1wOUp1x2!o^P@nI?jSddL-tf8=h>Hnr zs1e9;kH+IF%v^hJUY_nl=b*f|>C%Nql7jktL?L3;Z#*=W%q{~F>WM0IP8Pyn`B2FG z!C`CG$H9+qpguUnEJ5@?LWa7H6?YE%=f%_7&(JX^SRd=^q7R7T9=%EdAs^j;9le~w zSh>yw`M)%%Ky*z%7E+>0X+0Sj{q=pzl53;x_MZ@OVLRD}2Mh-XLRVDBfkiRr)0y+i z*TKv35xuE0>>3kBm38<8JMbGe@finuq$QvP|x3$&9#Y@I`Zbo6UVo`ZQ&72|ovAwKU*Q6+EWVP`xeDIp6(8Nqb?3oa%7B zgK~Eva+I0Yiv5J9m2!4R1#pz!^cuf<39!IixUiChI5Nm6wV^GIs|K@!!#kG!9>+u~ z@pF_?{d?sOQ*8q-H3-D2bizCGFQEo9475O`kWUW&0LuH`n*W#-d_w>92uG=`?v-4A z>A0xVJaIU>#u`;)X|$+EXKkYkVZ=0(iH?q3czdj@7i(MsUdDIAXV%KW&?C+{rxYI4 zoE*tN=r+>Cc}{S@#p-IiCT6fRT(+Je*JQa&UK8g{_y2CL` z8%7an0|S|W>uH?K8EWjr@(u7_>u_oV$(oZ%cJ^6FrZR z4*3b_m?C@DUeOXkOs_i0_lEO1!By~0&tfMB@^C3Ke6m>pf_aQAF@p8UOB7q2Ev8Vy zEji7KN;c^jpOizbo|Kz*oNj)8IL|-qgmb*x6hds{Nd^~_-S2|>^vPm6)OIqPI$Xk= z$$zh#6o8$u^H7V&lywxK?fqOy1d*+3*&S2MlwL0&eE3pKwSnu0MW_vU*x2#rLdxJc z=23a|aH?knF)gFri+(!taWgknNQU1$*i5Oh>2_I+crYW0=dhs2b_Bb#BDf0SQyt(! zh8uafjU|}#B$qSVkHG7ZD{%Xdc)?LOyaL?w&Ns6}?oUuvE+y(EqI`dP3U_^cSMMR* zL@`@6$^foHfam(LvXsw`VOhH+%Y>y{9w`Kk<003$4hbcf_P7Nyllg4@bWO>jd|!xe zQfdrHy_pMjhFH;Vp>pv6xJpWRH-k9yo8rXLDwXAFFUD4yo66)tTlij{!qK>!l^@^V zww(;u57K8>R}XRuo4Pp3M@y%Q4&O>}sv-mI0+Cg&c{bVxWu5ee zb-q#%6m%;yC%Y9$XA6!4o+s+1pQe|kRUPBwJNe{Ex!1!a-N8=(=tu_2P1JN!!99^j zky;0zIW8IwoE&hPoKKbY+6OilP3}0P)R>K68?iU`kXuHycL3g7bgu;xg~&!k(1oc* z!@TV?O+~KM$mWXC<7m184d)BHxZ}FMa-fcypO1ZG&Lm%}dbEnM)5l1VAp=V-Z z&~Cjp9<#u`DsK~=%N0E1;Yv7#7q_DqX)c-lnroF?N=s#-CE1piV?4#-)m4#{tGUgM z_<F+%KK;Ei54BR;0XY7J>I$z7eN85v@+fLPPs{{N;!O9|W<)E> z$$XxVg8M>we=8j`cm|bxKiB1)%cO-*eHfn7F14QZW4Rz(oZJP4b zb3<5($5ndq6+QV?+I%hv*C8hz6O9Fmk96Z4snb$_(RhBDgL}!W@O5oLvQ3{mF7F+U zTkfoSZ6h_0tr1)aO1OC<;1VC1Ay`+{hu>+56!r>iO)^J02rFW@l86%4|D3fT=($;D z8-(DP6-DOJXi&!>Ym3%y3}U?`(Oq#b+s3)yJ#5mxw^DiGqN>)PAHALq@)$*OEJlGmTrVDJUNIInzCEvQG-wQz%Gi}!He0m$- zRBZ$ft=2_86>#I~QkHwvM9CB}&`tgzdx0M2B5o{eoo`DTL}dWub~;*sp4GZ7$m%LB zQRwvv^X3!uV|4Q2E@iVKxgy zT2=)fVzPr(ocXbudvJcW0s?IiKOEV1j*iSP39jJ(lqNLK$<50pE6i$_dK-BrnX#mz zED5YnNh!tN9NUv!lt-wTj*h6eL5Lem{e|Ne+bIo45UgMQaWF*^Ss`+7igzsXih-`N zyWVnbtm8B3zwC+wmdm$xh1Z9zfGCza447ZtpFn*PZXQASwk_xt_cP^%R(0}wdWKHL z<)v%!YOY6}5WbcE!q+E=7ipysgkW`yt!5rHHFcJD1vaqVIKJBf^0du!eVePDEpAc> z*1^vu!c!pPq%zScOh%=$EG&ZY(gYl>PZRRFrihRKh(B2h!|Q_YJgaZXbzK!zehJ=y z^@U9X$K9r?CtYswuQ6jf$Pa10%`4fh-992rrI$o`YBKgy%Q4f*d2Xj9waL^+yscpN zgfbJZ+f7L`@oO%$W>eg_KE!5j?X)Lvp$!C3{hg%}jJrRA8|WRpaGu-AA0HoE%*_=A-W)r(-`*9(D@bc`4`{Q1kz1DUSRM zejoi4U8P-7L_XhVj?YZS7lVX&F{o35u;G&}6+X!=geM%avzCiGXLf zcR)K&4o=Z*7MjV$1WH#0ExIq(lic5Hggki;ow&%-6Ua2i>j_esHE+_Xg6wdD}?BhpgkFGo-KF_zKYY5^56+mD%i%8vL;| z$xyATh6PG>?i7QWZa$nrE?{@pHn>sC%(jADmV7bF>8gXFHiQ#v_Cs(R`a!iKsoP8n zqYga2YZXzGqzjqwrYCsifA`j>e32)>FCT| zcWt7jLv_d})YFrYl*}3D+cpE<$z$J4AhfSzvyCkKNEmZOH0_iGH!-^v#N^g)JWlA% z?7U6<-}rLi-8QKxn2h$=N_eo-No8VKCh9{^T?tig%Z+9)1zHs$qv#8slDHgeHxW{7 z!TFCYNgb5);=xx_u5MH2&=N(UtS~IPzmON-(K7f&LGw0r^yA+6IUaaP9kf*_jyXb# zsqhMjj_%)QZ+KEdrM6#rBBxFF(rBa8$3$TjQcy~D8fytX2X$+J83Tasy}}1EtilXi7~t6HM>d-!(spsA z9vO!8QFU9R3vfxZ=#k}lFX9s4Bd#Dv2r72!F7^ura^zP_N>cQ(UeK$lHcFdEieGsb zT>Vnd-5(e2i;PXrGSVh@^n_dULXAr%Z9Frp@t@Rvdh--E`$o7#bR0!da}JH-Gsox? z1Iuj#@(05u!7<7V&&+TQ`$~pCAmsiL8Lib`Y08zyF!oT@&=iqGb_N~?YlcR04QGjb z7whbK4F6__j_gTJo_MZYb(PN(Gu1wPNj4JSRe?aTLGGV$Lu!pMn2fb_umxdrsy{b( zAqdtXcN%(ri~B`&E;vmPnln&k$vVT0e|okgzzpEp=_SIw&T zj0Bf-iy2wf z;%j*|)+!FXa56!|r`jlfd^Fn7x&}J-4sgA5uqu^X_jnh~(roCpX5{y4&FkRa(#Fh#d8Mjr!$I4>)K{7k2ozyk zk8fOi37fl+w(3hFxCn0;rOb>^@#9@8QI|_*KVEZIUvxY%T7prL@rlg$oL5<9v)CFT zaB`mcqUXSyJbU3Fri~^$-IX@q7+jad#J&GwAHc1%dGarxAPhN-Tc(Fhw}AN!5aE<0 zyH;&bTrEOx!>rT}n)?Kei?mjaFS;cENk*53}(hbl8YD`p)nZH;Gjnc_?ZMu^{&VfR|rbx7sgHmZpQx`BM5;!<-5hy%}l!weAcn$^uzg$!=UN| zf^nC`0@*;Ei@~!4#0KR*W)jTSxRk1U!MIpo^j1T>-xz>!hSw<@OS_UlBKbYk94L4t(0 zTJe#G0^_V`Ss9lNQqmYaCATTrEDt#RNLJ4tUSH^!F;0@19I&1Awr)y)9n+^EJ&VD^ zZ1LMZ+q>-dsLj83nh+MU!U1~}c+RyBM#of%IbCULe6gXjTd$p42qbO6^diAJqD?L| zBf%TRfA5Y%XX%TUNf@y$TS-5ERY7!b4*I@uu_X<1huUW=M#b!>+MZK)TgroO#?`#)duE@~q-)u;c`Oe)|~1 zoCE5fuF8+o6vkzYDy~kt@8TChl7#*J-l}}JJOTPf3A;4@If5-~fVzf98ZB8iixzLVZbBDhd_tMmB3?L#$ zHoHmRuS5^x8WfR;G{(7p0sX76Nl@C+?@nmOAlM>1gHk-~{%ZCy5=fpZ+Qz<8s`9bw z36B(=+f_1qlAqb$QQp0f3QrH^x_p9S6UyOZW04p2Zf*?D7cHkp8zr3o(h{~Bg`QG>vAW{P?6XAX4Qy0Znwg&xBWPRLBW zFea9uBzznUN;JI;6x(Dl!KB)FBmXB=yR-bTB%i?Rxw(b!rw9*=W*+T`og;@t7r@;X zD|rjo*yGCu+eH8zD`@Ren4_K@hoT-2%u}Og+m?4c9B{Zf7BOc>lhsZ~q4*zYRB_zR5vX9@jiD+?kk9aGx*r;9)*qP!SKN~4 zfb!Spw%h}e6~My5p(hg@7{(6GYE1`*w0P&NOi8|*$2c)gVO9{8MgC^2x*HO!E5(?> zAN@s#nTR+%kHKFS^;&f7&JH-v$`TV+==o7O-eC_B@0jp!8p9e}Cg7}glO$XL?u0CG z|3-|gl^Z?WYw3dumS&?oNhIByo~>R5x5-tdn%*3 zxk4?-i!>CX?~!nD#%(fpXuodIInb;Ee8&^5n)<@iz#}g`)-bYX_nk6zu_;1Ec3*0l z`}}!8WcnE}8UuKF$4!C`)h+MDX3Pmrzgu`(ncN9co4_4Os0Dk;#AnHN6G3*o>p_1Z zU)*605!(^(){Z#Cq>N9crw8-m;$<}LH7VZrH~2`u$YK)mDxr;sVt>gnx4{0407&ut z64$TmfM{47yKn^;ccj^nF}(4qk9yrYtwpCHL+q*+XI0;_#QLqienQq_PWHTRVxVN! z{w=lUK&V@ONEz~PlHuC)Bz393RWlNPE#tug-%Ua0d#th3rh4}5lYgr)%p4^CQM)=A!s_y)9so(%#P4<-(OT~;@q zsgFCU@|dR@R)YVqdR&UEAXUTuA6(FrBdyuNEzn%}>_KIM@WT_~u5O#_zYmTm>e5wb z7wJqxPlx2k0rG|z?`;oX) zMQ=#&!wA=(<8Ik5O!-9}>IN!#R@&0JwsFI1t_WU++r7NO>8E;@Oe$l$@L&Fbk@dAryo zg%31J!`@Z7{WMg+(PK!RJCgs@v~m5dJ~V~MNpP2EWOQt9W1<0FWT8>p z0rzF^Ei=tq;6n-8@0bYP23M2E)dAgWeT?_#_fq##iqC^Q=l1Eq@HGS3Z;0>R!qt(* zMv$dzh`Hb_I=-r~N8sQ7LY;Rl5A=D-OM;r0&i~0v&G6vsbDpAJ2{|Ap;A| zf!g{VUB@?~V+-_H1Gr`40l+q=zhs*oqbBf*a5wfx=|}hIed55kQ#M7ILt?LPw)N<` zdHNM84K-eBKDz!DA20aBwb>cxvR_OfjNXEHSD3Df@Qw_eUHI*55vDSC_x;x(xLTGw zJT~8|ddGwhlt?9d7ve-+H`btix01^_wEZ$Qr0aLfN1>Q*zAwei7z=Hj9-P+e$w zmfn^Ao`&^ze7^o&>HlBOJXIvT?00u-(N=BEDJfguTggp->Gfgplk`8}Io5TY$UrhlR)ZyOwT}`pEdsb(K|HIs!>i6D!V$eK2d*a!H z`N1oJe2Q=IQZuG1EJXk0TtCTb{Xw@$IXPI@n(FMqlexQ+Yiyvc@5YoSe5meC`=9P` zi*oziQgfM3&~wwRhqk$2{z-YRau4bq>MQs1l+k=e^Ms+c=EAndv2a2DVZ3Qnfm?N%Kv#CGm4KpQ8 zJQgn_l>*PB2rF$#x%-gG2=Nh#ymJDsJiPLPGa0M*zv@wv8w}rn=7PlsUv@?iGeeXW zMw#TjqXTu-@%|o%jLSG#pdSktv0#!<`}Ah7T;DG@=*f4e0XGeYAcg;WZSCioc31xd zunW6$gKg5S!m=-$a)t=ThxGZQ#vbDG2m9PPwUoV~XZU7BJ=3rJl!OfY2EkX(VaBT$ z{%bSqI^SV|hFh?+?qyY<`Qo};fPfcZbsD`q?Hszm7E*EFg*Zu@s?=@9=Ei|J9l%H$E z!1&KOPpFk;_={{_u=A>dz1aLlT=5|1L(P!(@9qYuLfkI;+HBZ*cQsKl86Hys?R9c3 zcaDJ=uioJhbk|n=r4GFpsm-2G(1H6y&(CN-Fo8X51AU+PthLv^fdS@8ehlw35dW_z z^>a8^Cn*ERHOc@Fr>5yVkzi6?hKGgde{&H%X|p%%VHTN%QqPbA+WuO<{SMVWkT>d^ z_B5V&d*;{!6Y+d79lpzJr(Wdx zbglbI0+QvZA?wAbf5r5fsL1XIrFXN?W?{OM^81U!30dQ!+%K}9fth6=c4wMJOvF0E z34-i@^*fL1D}FF0e((v&^wR~M2PVMDuIA))wOP~rVNqnXq9b2`k5-solC9372 zT3iqo>~Y6z0#d-vl~nMx{j4bdTb~Cwcj{9$&v@tYU-?2n6H9#jSsVF>J%%USE!X?G zO+|Fb8-gP@VN5!{?EJM2Ak{5a;{S|P{k=mO)3ZM}Mcpu^JUQ@NSvhDV|fG+3i z!9qcP=(*-d<@{g?<(=qKXOe#NDwRHOgsFe(u^-h>Y=LG7OZQTq=n$*eqPklDCI56Q z&M5J+>yKyJ>-4*RZc45yBf{XIa3A(5b(^`<7t(nU)`8=%J!q26v47Sk3~)leZ98+m z&Z}nrT)-Zl`NS4nzE#r(pEQe19sF~$el6wSqvMHZwNNbe_5dJa{L47wk=2>~@A|E` zk!MeA3CiF9)b4b7Y^86Q&g1+#itoq?N>wn)3l_o89X~Fut?;Cs{G44$^)#d z{O;OF5Mbd*ef%yX$dj6Ry=dhF^1Pn8`kOn)$kIz;DaxD!=k0U%o_{}ziw<19@9)tQ zM1D)BKAENw_tSEo;!CSLDiC%EW@F5b-M8ee;Z8U+)z<=DrmvknM0sMpU)YeeMe~36 zUbOe-#C$`>t`APQU4OLbpCR0L_I>Kp=t`ULeq&GQC=>8%*XFl&Gf9C}2 zR>iFO-J2Y$rCb|jzf21?UqT>Suk*w^E>))LCsb;l@a5MKCy-OU{H(l9{^RNDA#=@f zhtEILX1NKcTxH42a}wWs*Fcum1Bh@I#SKT7UEXRQ7?aRCqTUxr#W8OL%{wGsehK!MvVD~iL7W71wM1inef_2SL&Ejf^bHR-|B?LP zzYZR3{wZ|NvVl73e0^L{kFl)&<-{rZ*u^3Go9d%>-rBN#eex)%Q3I{y?XYOEw33M2if57mjuP4)315^#P;>CG`~m*c;!VQ zXN9kSwR&>=p;wnl`TJ&oC4aN=Zv_FX5`Wv7ra|cy!2FFMe*^K~*!Z{eRO7+l*!XvJ z1%dn>H@=FSSAFE)apV6*-1v*t=K2iDMo|1frvy(r3s(y$5WBbjXj#WWBEDk{zCw|_ zRZ}a0JpJ%bZUl0F#M^c^1+xLGd3%c0tLo;<2u2NB>bqz^y@u*acv&jw{Opf1+zjsG z{(mOQ9tKWRZ|`cS)s>)GZHA=OziQcd<9=(NCi*L%Iynhf`#&I^>TS#3I5aAgG8`-U zZuUj;I?ayM5W53^WWh!Vo<-K`yf>?_*(n?HwCYbd0I@Upo1nir1Qw_N)}j9otV}*~ z$$Ww4F=Us4Ghdk8jpv(Rrm<;h3(0#drrsOyDYWH*0;BG$mA98h|NJs2-d%7aVJ;XH zN?XX37w7US)aymF3j-k*zqQwIu5Yh(g-&}F`Y3li{HybWQL`7>`L!v+6UQETnudY# zqilA5|A3Rrz1l6o8DPNPg&JU-hAkl+mY~0?Das02p|d!9S_>XdBcSx8b&x-W$k&j? zW#2{98xD=%wCtOTDxMG0(S6?GVd}EYH5|n*^6LyWTub!*khb_rW~4z%2&5=FcJf6<{ggsCPshogA1l6;~ACNX()Ye@8d^Hko9Q zhjyXFRh4uV*zMuL*>k+EEhYZ5{t{Vj*ikeqvLR@HCGCVKqQmCJA-erLfAKuji7n;) z3>0J_B)gRN?I98Zr#yU z!Jehjx7J6ce-&K|3dtvSwv~z`YATBWm0y0&Mxqd4_3|&M6t6`l$GQaLMZKd71BL0} zq4^G^>IWuY!ngXN1XI=5Ld%tQ^>g{pN(4)5{=y(Yw@(rp>9VDM;HHklfR6<`-XB_I z&fQ%9oE(r_+Faj4cPP5-7hTUimyPs?$}ZdCdB-7f zHDLKTIc!_-)L&pECJ**O?;$?ygAd)5fjgVWXL&|R-Hg*O%&~^z!N}t;n?CW-JGI$epzS^f>{wBgn;=swkWIDKWHzTSrhur20jg8@G<=Kw;8n|n?*ybAnkdgWSAr`{qRlhS? zH<(-et)yv42s)Y1oblFqcZYgvytaKJ)6tTP8#gUl!DF%}GM%lcT|>3;{j})@_93^1 z;aqVuK3Fn?P*OVk=?!3C)lA%x7#x0_oR^o^+j%Uk!#{wJJz67evz|rk(39SR%&+t- z71z)Lvc>oZZ)cv^`9aou7N?;9+Iw=}SGVKZepKvEJy>e-@%w3)e9J8!vEBIF{z+DS z>3O60`{EtT|Fk%p@^p-PknEfo9T)7x9xnJ{Qk}3-88{e9vB@KSRuN; z>BzMf&mJKyF}ltm3`K?a>I<#8T8wW)UM=`&aNNHi?T0tg zZ~mft@#FkRc9UbfD?^kt1( z9)c~Ql0blqwi76FJdA9&Bi?`aR{pgM2Wx^5aI(UElTfyCtsDBJAo^ndPOe_}Eyr7Y zLPm-0kK~1j+FjDJR5D`(&W-9XyDl%K!bu2tA)!*0W>-wrBF<3=+w>D+mfbmL5DiPY zXB7Q1*OM_oC7$Z3pZ<+w;4)y(3*b@}+DC4q((V}96GKksUnf<+$B}L9g{PHE zHepCG_HzFL0`-A5ebH!0whf(LDxtK^_MMAZIpxl-sX!J5toX>r{vXEPJg&(z>mSBx zr`GB7)S`7OTV;`2wgC#r7Fx?9MWjF#NkUK%K|+WSA&`(@N2h{75Ks^hQbh&CBt=L< zfCQ~T*i!@&Odzpr!Gt8TB!Ps$d!ua!XP(aQz5giGkKXsW&hkCyI@dYp0uG1&R7h$( zb1DqA#qVUOb}sN+-j2CE^I<`<@yVQc+d&bxCYnH8)Y|_L%oscJyjfSnXJ^46>1#Yq zh!hG2daq^2wS_!>v3pQ;C5`&TK!ye20)b*d>(10Ju(t+u*6 z;47E~oIpTS^*%NbDOsX|3_r3j_PmoHoZ850PE^ra?y9Ou)Kv|CtnwgVp^T+~BipS; zaJ%bc+Kg=4?uMb;Z)ny3FOGnm{CUvB4_f;N+fQZCTZ_Rz$&dV_c{FjVsb74lp-}Ws zzPe#)=1dMa)nI3D;3PyTrnR6-HU8Jc*8qZ&RWg~&u3G|&y~AE`=)>%Ch;kP*n| zNWWgYmm@|=(`&l#Hmvp{^3&4ajw9b_%z3Lqz{M^$shEC&zfjNg(ta|hm`Tr#6}+1g zoN9hM5;WjPGdZrspO|PV^R|xyK23^D(b`B{FPstiWG?KT6p`{%=1|JKM6@@eYELY= z+9{SEp^gBUFliChi+2a(yT@2(D}ZmmfcXE3qVnpt)xt{K|MyXI@xy9+%F%CmQ_Y;C zpeAL8=nKo%V+X*ql`Nyqgjj$VV54ReX)fR?=!>s)zv_qGnW-UvdjW z;T}X2>nMrptCtH=h^4|W$^G;D;>-QmV+L%i5vPyr>6usp@Lj2AgS=YWZ=|P}@eTk4 zn=JAoqyRvQN;XvicCzP{HS2bDccqbE%lXDONg3uL@pvXh5u3GUR7(eLHm8rs=zCrB zx#?g@5HL}L<>uyR7H?qBy-#qD+CT)^^xE8@!BeY|l;6Hh9IA8qhyBclfOswbM7$Bz z2dco|oZlrNn4h|2vw(?z(i~<{(<_;0xokUS!;@+&QU19uB{@Vm6EbtRI6@i<=o$4< z3W3`h%m&eQ;V2XB1u|3?FuuOR6l!C0H1Kl2TM?o%AxQ9uoL@`~m3q_(k%Q$xPss9n zfKF{%z8>8apvog3E=q}iR)6c3^_o#I{Ut&$6tGOS#B|rsXudPke6;@w7pGJiNMSdA zw3QmgLIiQThw)4%f;$}D;$m6fUjt5+8HUkCrX|w;a}`=DYgksI3Kfz&cB8b7wYXaC zi&;GXfy#0sYgSsSB)#nCJzFCYiWM(M_B}bYxE1LBD*O|;CJ&WMse1$eF=EwXS-eCe z<{bHQ_qL{{5+N&U+-k?La@g6_H@}L@hP6#l!HVL`KiJ$pbzGXeSEk@5r)YyyfIDNl z6&ys-$O-^a%rm(V?y>8U{4lB=6L8;|0VcFrYKk{<4OUAo$+AJEG-iy{*+n7p7CunU z0Fz1n6e!UZLMT0MTd(QM-F904K5d zYl8l?gkc8jjhUIkfFD)_sQO~Z@!p8oV-@B1*3>ihYUV)n?2U8N7=f4(DGA6zpei6* zA$+~YQ824qxgjabJ_#v*KDZD_sm!7(zl=lzbuIsm%IsQ|IlXMC5Z7;kzkjGliq1j;{LR{C=DI3#}Zb3tw_0Cmq5E-EpBaWhKLS zrRLevj0I1mxh|3-1pJ4H5!RBaWL6m+Siu=nJmBTulc^uzBr;Ag)3tUHd!Mh)ve7B} z=ehH0%}4V+NnR01pi%w5k=k8LJ3t5T*hZe&Q8=9{rk(5lxp+s+$h#2%$qV%i=k)vy zV#y^?`3-nW$w$b8v?U7@qM3c+mq=3E;MqhpLJKQr;@NN}Fp zKp|C##=S4mv&xw6F^|ex0+pWcJB=BrK?Wl6roKuQyNi{p7IQ~t!KYwIp!Vs%k?H?{ zW3qSS1^;;d6I5~T;@UdeDhQ}-xrsQVN?L~IP)JHiH|pl4}d_5;Y_a-cTn&*8@jfS)5#PIoL?_~mD;EqmPx zYZ3xH5iM1SWL7H@{3=H|bIu%AkY-D`4YZu3>5gDg-Re6eGd64u>uKoNFsp5 z_W6?>C6azrD~;BFOE~7&qHm_0N(SzDl`=&+v+UrM3}CiVjPK-;Osq1`+aO56^wf{e znny+iG4{MXh{SPsy# z^j}1hefN5L<)k>$%V+mC0J2*9VNUf^uqx%SOfs6*)|v^{Ydy>=W*EOZwo=9efcno7 zh$PJ5bQE|O|N7wWO{Xof?SrhvPtr}OdTBSBb~mB|p;j-97Mv(RrOto#cvDdCz&HUSwJyA(# z+tMq9tasAx-TLKO%0JLuyjGyq>ec@O@!e+Mljs8kfN91&me>tWoWYozY7^2UX?khY z;#SwS55nqzI|u%o$~fvY2l;Crg&x+0VPFGJf%+cqZ&3fk0m6GQwdtQo;c=bM0=0N{ zM&R=oMscp~n${d);+2#@tdZpyX0S4D8TlI)7e#>$h<1tq?Z-{v7UvF}E%d*=&}!=4 zViA6B`rTsJ%ImM@UruVhQ!>3@tqgqgNqK%aTOx*Q9kxEc!B6RM`e)rR(5Uo(OJsqW z>`-fET6pS-RY#fJqCR0haHjAiEiL2`Q3yh_(kaberpp=#^YiP@c1ploQB1(J< zwP11plYM_+b}?M}xCXXBMV=5(5VlS6SNt4$Ibl4=yTsa(y-gj(<|8Qe9-Fj0Hx8vq zL_&D$JuZ5~8@}j7q|)W}rJlck5E1izp0N4FCX)XEg_zU6d*b z9R;JwZ33(9dO^T-nm`O0p9vY)&_g!A>|)7sBfz^mb8(T_X~m|O85M>PR3HI9W-xVs z+gN8}c7b*r=DK;Ev!WxLcM5tiNhlz_EH|!Z%nBVFd!Qk=8820=i_aFs+4cAeoa!U+ z6g7SX2-wc);7V^MJjIE$ov~VpnekpZ5lOO=AQe8^`9&)qEuxh)-oTHn(;m?UlerAu zpleM`ytfewh@@(y(Z_7)u`q$5b^p^NnNj61BY6D*Mb%(>EkQ2TC&`zQK@^=MpBW;@ zzF}#Q^|(Ss+q#LRWF2DTqQpO*7dwcRfJzQK@zg>UdUy8NfCLrLMe_-KvAdw?nNmm* zT!uL`jg>Hxe66#S8Ny|B4%9ElX4~u?`6!EP@30nT-dq=*ck&ZBFvAiyt{* z>26qHd@$3z$7eWMAC7RQjuo%W^-n+ZXqN`)BscbDyE5^)0|6)4&pSu!G7-7Qha;rf z#0H^t+N>_oxr2KDc3qJBUZ_%`(+LH>ZsN*+efBG9p@ZHua`cDPwL592RP zZoHfnAn?9?4*`yx=^Tx+{VIa&zBVo(hoRx9(mX-r)Lp=QHg30O7zrIM@@O&5LRo zJy6K@8BR6hJI^Z^myrwt0|So4D5kR(jwjMb9IIWfpkkr~T=AGMfflG>8pd|(A`Rda zPB6Z^ScX;ROZuPJ)QL}#@(!r$I>3-X8y-Y_yyEFSyh`Kz%(rHm+xfA=FY?Zs5N}*t zRjY$p(PJ{jc&>v!0tBf*2tM1BbRj`8EOj~06xOGm?Hdnz=MTV${Yr-X@ejS(_yu{q zD11$I5Nz5N#?HSV=f4%UYw(yt>7HYL&QAl~`4jaFq6*V3;KN>vVgwwjTryDEkG@YK%blAxqh_(hDI?Hv>;rD^%Oq759Z`rZk zrlm0+ua*SWSyzY?ZS#w}=Bo}$o`%J;p$6#P+w6ghH4Gp-o?eD&A<{T-RK6jkC}G%* z))NDuK4}ygCeN`ikzmTWqvY%mk-bmpr=hhYQ z*$YSeE7NO%snTZBycC32;yCLim6}2zpU@iU^D>gGPt|Q`PrGM|B4r>z zf?)yh?+{8+eGQDG!%PW5zGk@gWmEVfR?2d6~Aw}hP}a< za*y>kuTSu=#wbMLfv;#(j+1L&T-43`yfxunL#KTlE^GMm-yywMU?HXV=9fA%j~~7^ zHd9>hyS@OWDAB#N{YVr0W@8Mh?En%xVwiBwO42`V>O1rI;bgPLn*xKE(UeTH_|idp zC+tj&ROLw}WLYRi6^an8!E1L1m~|yn4H8Qtw)#@`!|%v3xE_0qNVyH8{=vpq+~5)x z3oYWQo*prvNDR~;YiV-DV9M&}vb|We7x~-&Yhl&q4SoLB<-$}nH{fc0HHTD5%C^SH z6oEg7>}*bu^$sqamS$ACuGz%5pud5Br+ykI!feYahPrOW^0)=c;9h1_26HX1CdQXN zoKR6h5^!p@_EG0xqI!|&p33EQ5aF?diB$?yZ&3#3!+G;fmEIAuHcGr0KxbD>p!|mC z*TU^gZB81lAJ8@2h|UQ9VmylE8|j;08+82tqB$t&?DK%A=S#G}tYjsNsw!8hUfm+BKaWmVXl}cJpZ{Ogu%qX(a#U*T$hVa+3JTWp`Suc7{ zjjq+@>5+NvyZxeiJ<};3>K)oMOU+*Byv#BT!iaew(n4)BA?M*{&q>vZY~H?w`RD&> znt=OdSY*cx)rki%{zK%s#ZrHP>Hy(`f+ow7aWJS(mvz%%sB}^^(FHXM7Q5oflO&u$ z;Dceol>qXsOH71OxCwP^*28)5m>j*@!X1=~0M-KV!cDIgY@FxuaB^y!%Y28h zJ?S>UR{z95*m}qz3_F};OAXUHmwk88GU#0WRFCVZ;I+*m{Er>iy7SKd4i*scJwhx( z>&i?mQBAw6v@OGHzIr^VQ4aG^@^)cezBX=yuN$Pw_kjH0BDJquy6nHuRCx&4l)UvU ze+Go&>E;`ZRlm*H*nzKQ>=4gbLS~K)&f@_g36ViXhFLT~1#4OS6RRE*U7DI{l{pnG zjom~bouW3EN~kU0aW)g^I?$w+kMw#@Ne3#WYsJaL`!I+fr8}$}m(!$8F`1b{^^6l5 z%>GZo1N#9Fvkm&z|3zQCL#0i(a_JXjoOGvJ%bxg#?Iga-=ft|{Z(q?xYZ_B>cl86Jm3WDtp_v!Yz-<)+aJ{;yvM@r&hek)2$y%GvXcgm@@Xzf z(4t=2XwfgR0U3 zOy&6TD;DWCBH2lSRetSTy;1<(uMQ}Von5(VUK|KFV^=5(?^iq*pIC<;E{18bMfBk_ z9*~`}w{E;j3|IlEJ&tgRlHQ`OsWoE;f~;l}zoO5TDp6T8uDulX%Unb`(-j(TSvSp{ zN#e9B#@W=q*_&maiy`#8ftcmfEKOSjnGP_h9ETZqb*`l~B;0aD@)G zG_c4-VF(t3yi}W)5nH(u@}M-5c|u7>Fic35b>x7-W8<-d_*SllkB5bbKkv!y!HtHH zvmXW9nyUB1kc&4X^Y>PWJaN6c+B>X!c=@2_q%@B>sYG`#Uel&rXg!_Sr;ixJ3c8ep z;X#c99fzf;6j^R^%dW}vXH9Pj5y;n=F|A6ct%^=MJ3aZTy~5{kPMC^e@#y9dJk$K3 zUr=C~z8CUFFMX6xgr<_V1IAJ376}n>aEjXO;2Bz7e4B4k?c6!V2*8+%92jGeHIfWp zY)a8yV~e7^Z5*GS;KI=e7zV{q8U{;G!W+my4pfz^7=I1v5lKkh21rpFrx zp?p2Rcnh|UQL>#~7gYL69m6fTbc`|zY6~;#VTH&cOLaan6gJb}sP~Ad>gaF_6}od8 z6*(zF{10_t73GbLjDcuRXrBpKynI7APSTCb)l?C<>M@wC*J^~3#hSuXd1ez-QoPYT z$_SZbGbtabA8zC4Hv_k=vWSyipqKqms(UBTy|o1eSk~I@UKkF$ci>P~Qv<_%cWhjW zodso`=^+82k%}9a`aO8e6G@p?LT%>piUJ4W40jA?&QA6$@;64Dlyf{WLcm5VSWr~z^u zf3D3Y4_6B<7UVcE(;wh^1_hu586?4kVuvt6^dmx}bD-j}G+%y%fDV~*MNU$RRRM%b zk4lC{dQ(jM0It110AFow^yRAp1XH8#YU* zK{!QsPgauP|38oJmi+z97X@st1E4th_ohCZhvn|q3`GS*6*ePs81wxIq9E%L3Zd%B zPn$OUBG|Sh+={0eHW)gByWwKAiVGpTdC09T!|p zmQk0HiFB7p{n*~<@Iq~avyiX8r`w&5Q$VSQz1=He~ja7&+JgAl=xN@u16 zT$^}o_=Yrl`9g|E&|aWQ?5!umy4zY&RT4K5M}$`dU}S7Kc4Dw?cR0SjdK)srWpooM1{hunSlRKyl!C66I%qMh4@Ai^gtA; z;y!JUJ%8r4m*p%qPBLLd6K?effYAO+CNr(b!6adU^sIrJ zp9XIOyju#)uV-53H*=p>Pagw|Ff#Abd&$_&NHGRs9ULnJ@pBz)1_}k?27X3gw}Xii zRRAX1xS-ejVSms#3-F-i;&6EMF;eV>T=a4F&i}B$>@≻GO3hPX@dSrnVbHcA}Q} zB7SP9G<&o>1DJ81l}6(3i|!L7zRbMduSD8p77I_7+;Q3N36UU_HaEiK8^RLr=J(gl z{FsfvDwpnzw0w7fPjqKtrlYhL5DiZPmWpl(n<;}cKUzx20!jt^5kmzx8obgh3u$`* zC3j>2DU4i&5rABB`BtyIrakAjJk+*N;`}|uo1W%xM@ZECM4Gg?>Kbya1qI}>Q zcgK#Y0T1hh0@gqnb-1(OkxlaYVPrWq^=BcD)|g-1bG%*_ViJFgDxXwZb)u=TOvUFr zPOimW1ul%4z@36AnpQ4A*gM6OHZgpa8IOG*=Eo&(QEKcl;}2xH*98J@4OHEAtHT+N ztI;N0h)g&bMjv;uV?f*aYac?`jpz@POS7CH^zGQ5g!_f`OHquUcQbU;xR9LcVO5(5fs6E?_q@& zE7sm~Kxi3oXpn3O{G4A+wf_RbHdfJ`KIa(?l1or`bX3qVTn4V_FHTOerFQ|FWgtUf zFRQo&7@|KS8lk;k?1~K>!8wLxCKUC0TX#oC3Noqk!Fg`dLux~c_9r^>I0ActIey$Y z;Dfgy1#szsuPb_%FT*1P&#Y7tStlabpM3ndHKVn0`GQlr0Q`*FDmzk2>)#D2`laHA zA@c4Ra0A;2sABNgu`l-4)AGx0rWaE6fx;d$|E+YwIfdbrgML7~0bJmcLTtkX<_))@ ztpn~1U{<|z33P&)1o9|F`>mFajvS_$fx?Y?tMh^R_HR9)vW*HXLv)+U=N~;|^s=8E zc0dN0TUQUSoQ$7;*J+-At9Tai#bAUW5q`Ld#a;_@`-3Li}q>`DzB;L;n&hHv{J|TV~OLSVU~P+ z4^@^Gbb`I`a`N9W1Xrw+vllB(F04Y{&6bEsV#PG;t z-=$aMpH%m-hlU7s)FkTVG*^ZIT*~0_65dc&*?tKt;8&?Ad(5_J_$;`-lCak%Ol%HR zC#iNt^WC>Hj<%P%?SW`_&HoKRaaRIfETcbM^w>JD;Gd|d8f=CWX@t{=*IM=ehn}-5 z?b;8Uz@Pz$M+bPJS(sMR(|9J)Y}?cWKz8vHO?3pQ#%Xgrhma0x8MGwG1?Ur@XD@*hL#-7K1 zMH>}FlLI`~ShY#}2aor!+>D?9*l7iP>=dtXc%(fsAchae0t^b%25VibX^tU@NJwmr zuD|{ZKg2qndmr69H<(FE=XFU-6 zdWF$7s!Rk60HFal7F?iDd`OrcV!s)i@-Mxg3+VH)3x>5iSIhDX5DkOLDaTB?s&HEM-0xtJ z6K7VEmwpxRJ?v_*Z*d<62=T9LJ>2}L1Jvj{1RMYq17iLy#5ib9201PuET2iSCW4Ir zMbqowmg6>R+E8OkzPjolICDbuIBDe&a^Bo&3&cDbo-LUvYzBzCeBP{k5<@$18!n^X zl)^`(+A=00@2Z<$f`2hjbvoxW_oznbxGiw$B7h9iv%j&d-UnheFA}a@<@t4D?#J0_ zb_{Ats+cSvQY_+Vigr*XF(m(iSnl|>GwIgAVf|arMVHsrV3TA(mPAV->aqLOK0JF=bv^u%)3%7fFZWFQ4X65QpaM6Cfyx?G<2uz2wfHebEc2C$ zLddEZg!W;vfxlbRZy2>#KZQ+;rR13{EOWRLM7^`T`Gl{ywjZ8DO#y&&1Ifu|QFmqT zb(7g|u?6@aq4#Tza))W-9ePcUZZRy$uiG6ITEy^qXb~m7;Ti?s(agu&1)pv`A+43= znv?4gdDouCOlu(_f6lw0p6+MI?qRQKIF z5tLJ4et~*44@Q(Yo5_aXP1lcokit zgiIg=&I|zpm$>XW@8=91uAL7G&zT*1*5oHeY8&WwU~6h9J)*o0P&7V$cJTz2P>`yy z&9DB?e8d}zoadwIYmY;RqouX%uw$Lh@j<1Pj58Ml{N+D~9A?6vd&-8*Q*6M6EXTeP z6MY#E)XoW*nXv#|E**N)s@#n8{2A60qNSnRI<(AWtcKMsqoT&Bd3(P`R!q5m^8BpLo$+6=NZT?Y z7G-aW%v6CgN<8jw>^3vo%VA>c{9iI^PPQRzwB>JRBfi#6z5I=uV<7Gz<5so|WmyW5 zk6Wgq>;C%X&<>Ds;NkQWp0_O?d6ZpVc!;UAo~iCAno9Ca$^ic9YSc<**);NhJifoY zx!&L7b$z=bxwM1y+BRz7riUIw9_e+qaVc^-(9nqbc`ElKr5JQq(r?TBU zFE&m)SG!om3*Hb{rDfp}n6f2ub^H!4_Rf2);A202p1!%d#XhvuyPw(p+w_jQu zp0xVQkCl5=2b>bNea1O*^<+`F@0@?!zL+~+*j}&kp`GDBwEnO$viy~Y>l4v&QFKk_ zP!{NM-E>N9|E8GnRlyrf8KMR`1f-EL89sWAXY!pUlt(^iTz}U=*qd$1`R3|qp|$Fc z@?33XeV{S#88BD1f4&I#0PVfk{IQm4KhO`uU%9;&IGHUXzNi#ZXEuG}#mBOo`JmO1 z4DHXa+2bCeU3iM#@I|i|@oAq$o$5Xy5$#Sb=&d2X?oiS z0EB%1;(;B8a{u@hY4suZf|%V(H9z9&Ucc*;d*F*JJ-AfM6rc`AFE@*G7o*-`V{ZLU z)0HD%tddbEUHN;^gQB|jq)oEcGpX{tKHt7o$uH5p)}@#HFq74c*vL`EjcrFPTs-d^ zM-uE$9W(dHy?l*1RcsSHHPZc26_ZPW5y5RY_be_VP~Y*sc~|donK1S{r^;m)hl@d> z99~#&_7|c-P^)99)uyk_agG0$K2h?kV9&ok=79q~X1gPhw$(E7#)U_uoRd~NAc?#g zyRC0Z2!1-Q%lI6WnN>sann#||BhHMAr_uE7N%@7m{hMB$aar|PxYMMoD{=`5oPDQO z!y^MOr(I$Fojh(p%hD}h^)A}sXILU8|Mj=m`sl`P<5>k>Etrm26TRFz@m$@A`9DB) zGZ70q|J6y=W(HS79S5<1ni-`EB|+T$YNURmqt^f(4>n0DGPj#mP6q|ygYDZB8A6|@IucRFMyx79N27wJ7iC?E%94G znNQjPfj+MweJGATfB9#Hglsy)I>q4#1>uUP8XM!DuS z2^`usXu{98SDF`@$vWVSiqQ{ehN+u7lISDG68FVlueEeV%3m+11Rja|%<<<-rRtEK z?zfWcZb}7|z>_6CV_hadzvyIs=sPJ(LyAA?C~S7lU+do-ZNTn(nkRFg?nf84jfnvE&)M=oK+@69>$8kb+^KP~A9L}m z{xNwm!xejsH-)F^y(tRvox=Xp3h%Y`6mc~@zI|VO1&~42xGr(qqK8#n5PLwNDc=Tv zxM!1yK!>r9qhwzZg0BDZA(loju6?J%33MFySe1(_l6pvQ_tc2z+<1niQxTn24&;&)4(JC$6@+Z~E5bv$Fj;mLThbw$b0# z#L|2edwHv)qDoG5oYD;NdCFgfR>s3)?k<#@Lrx5)mEf-z(Mdr08+Ta5;b?OIauLOx z$Y6>c`DVINzOZs_e%$=aO?-P{)_CPW<#LC5wPS6AL^MM+a>c>S;|$s)Rsj@NaQHk$ z+P8~91nlfL?GVh~m0Z4orW@wtq;$M$wZ`77mq1seMlBeuK~A9><^r5?sc4DY17R*< zI@u<5({nzz{g}u6_t~4iwAIl}o=VZ*e$Ti4X{PHPVoj;LnHF0#eh zR@uJEX>1dH6Cp2D{7buoGU7}#YhUYq1R1CNY9Om+48CM+Eb9n0`HZAJn_pu#bN-Am zs$B)CnE!ER7DN$PlfEBKy*uzpEGUj&XY$6tPfo(NyjYXO4##Hfj`XTCy3w2P($ALH zL%XS+I|PGhGY<9elCe>V)>XuF>{NtDYuLlm=FO<`;spO4{h*AG_Wz3**_tWaNbVHh zCV5%~5azgZyU@otvfa39dn^#_ecrYp- z8hb;Kml?K#k~kq+7|qEL{VG%sd<1<#&a(@Wa!$zW7851zN>r zSxh2U?4Vx-v;W~5dr*7JlMD|)%;0Tm7oDmTdD5M{F0GKYi6<{o`CtEUtml~|%aspw zuLFu?AfVv-v`T+%Ue$|j=X(YTRp3$DfDtqCt&>lh$JY4FWB9!n&S--! zsP>qQ#p|{ zzq>k$Nx*g=)?wT)$#R&bmp4D^d z#PdqUOFip4q9rlCazN?3v}QcW&tKoAww&-=#i&@O6|UvxMBy5)>Ds{Hl5y#HmV8svXdi*qNWtZ|A3_%IW_7vF3IH@7sUU$zT5c)dfBx&*h01g5j;1Zqs^bQ>+ZDM&p=As9lW z(r!d9e#X;MjW{?k>mshxc5kk2e6gGVbi1EPMpKn0X6^kqC@mb%*XX@0Rl5eH%%ox! z>`VWY=>T}mVr<=k!UYJNQnYEGrcm72aD?Kxwzbg?P6Vno<4bK&g}r%=DYP;C8;JU} zUGcu6X&t{~k-c+7q%eai!~aUzshzt)w0B*9q8(mbD&XAbc|&Zt0|z0rh(f6=IBXYc z1h~jqXr;NX{z``OPC%U%xrV_$K$vWnxS(Ut7*XS+UiEo{9L4lA-b>yd$oi%t=bk+ml;?4w9H>7jefrbANWg|REDb2n z7um=e0?+jVQ4A}hFWUV|XPX}$`H!G$ywne*TE}*L5AkKI#E{7AbO*7&M}~2R2v3vJ zg#@TT0(!AH-1hzQMk~>aM04rqf}&^N+2U`N0T)fqX; zwLH19bWdB$*stn+haeF={jtb#B*lX*Qm*cqBt22b!+#|4EJ@j#=Q1NgThK>ZFOEQe z#c=uZ3X<)YXW6U$`^1gR@=bPr@wDs%MNq~m^UQ+RA&n6kH~-Tq+0&8j!y}*s2Io08 z=sOcr4^tkMOB|ayB9ean6l)^yOR<)Ts`mDwJtU7cx8822;@K_uZ8))C`8@1R`Rv!lkP%QWO=LVX zHY8frn;z6YIKep*kuE5>vL+qNyY2}aW|C2h zqY@%^J?nSkn~sgKJ3SS}Sq}QK*=~Y*<8_d!oQ=Xcf!EuDwH5a|tnlbx8NLI%!br7o zR+Q=Y)Rc)z^Q-toH<0Y8C7PW{IsZH=2+!T2u6sF&Zf_+roP>rBb* zXBI1``)v?28nwI}>gNq~>MAmZb&pN})dDWG(fhKxYvP}n+$r^gW)=nq`8@N7u{A5f zmWwUtWtXJw%mikba0gR6X_G9#X2xz?S@ZI1K1Q=En9{sj?^k3KW`%vk`ak88F7}-=0!BbZpw5rBf-{W z&->Ki<2g0U!hacZ_J-xCcqeph0Dg@!fK!(>BaOdLhw$Jc$AVtgtGL(a-_O1a0! zzpE}%b4K82j=|a#v!R~r!WdYkIe9&uV8+KC&AF*=wgb0D5r=7*sPdCUO5A!plMxdU z(c(9SdvzB(?%|~``jN1*O}q&d^gvMTdBD9VQzEDGfvsc9Qz}J$O41^C#NbME%(kCr zE!=*#`fZ9g{xJyI;FCaCvtD5XagH6rbBHCyNFfqx7;h|<2#Op4qCrXLJ z1g@TDio$3$ZLxDJ5f;N3Up(;;Uv1fidX+c1{%(D7w8%U6p|ox|+IAwIii0oX7u;N< z*V~=$bm%J^ZdWN0$McCc17(*QyuIXUgsb>zS6I1N=qj6=Z+#?pm-HW$N?MIvxhT(| zX5X14+|&Axqt!kwP9 z^wlq#PbZ*;GIU}rk|>^0#fc7+u)UvvC1F8GZGj52{b%~RK?e zVK}D-tx7+}B8;sVIz6KcJ^S}borl*lE_rHSly_+A#6RqY@P36x1ardSng~g=W@$e6 zfp%zqQ`yL40o88BYra>v60rI@W>v4#{R%QO=I7$Q+uO_r3fUPK9;OQ?_O}B~ zF$zbGamo~pFdVK$|1d_c!RF5fNO@%*Kajxg*j~jAam}057Zk~{4=bu`$1P-y+Lj2c zc=goECL(2;(#meT)Vglo$slIj8auZ>Jc(Xv@(NIlQt=84N`WKSZ(JPPrHo+wpr&C} zw<`B5N-S?x#WS)TLFGu>mS>@VCr;Vir*atVOp}e{gT*@A_j5j{z>JSDr>heHMCv>_qU-lY?duCr0q(SKJ6vTS%XuxhpmmgJG~j|Q>+;fOHN&u_6`)_CP?HQ*LJ)P zKi#2P$vX`Fpdfq!8{=KsQfK^S-*%Aj*W2u7d}Ufbrr0Cs&0g&V7^~=41I08aZb-96 zt4cmrylfjff!2B!cztSOh331Ef^5iK_e9dTwnn@RBtld$#|O;>@*y>ku@AAh3x)Z? z<4TaL-!y!pa$!V>TYI^1(`>*kaV0T55I2<4R_SND38`O@_$A}S}Vl}9Ht$0wf`fBt;LdVKWY;)v03CmiQ-a_-wC@EEiy`WlIxA zxTX;N`B$^L?wZqZlN7zuQbU@X`n+x_e-&8wPexTrX@jejX(HjI!ABu-7r4$&5D< zj^ta2Fow4npr{YUDkU`GxSFGHrfp@h?vI4`jwI2uWR#C(h<%)0QN{}y9URE?f>iV#q)UGyi;&-G4UDpyo z(1ZEvS>14p_#x=s^bXx=#aD7m&`-L*0mFZQ7y>7tQiSC`?YK}T`l@UJF28pu02Zqc zm=@J(A8n$q?l~K!v6`~c8etEpyzspPK#Zx zFOH(vU#&4Zc8=g0{E+K}_R8qHup-q%F$0(+D1um%o(olGNy?;aVkBp^?Qnz_cE-FU zfAo=U{PTh)V41%fbaqiC^`6yzfkqhgtWiTsKl5u4 z!BmnyYe2Z7>C)Ei0YE49+`@` zHcL%`7@k;JGPR&zC5=+Buw|{b;5k>&{yKQPzhPL4HVAf!86D4IY&w$BJ2qrohMD-< zOd0Td&@i&~9bkK!I3%wE8>XN7iK|Q;B+~36Q;4II{B_J|a!V`h_2PSh#Ru7qTaF+m zV};f7{4ihuk0{7D)3PfDsJEf1RueypNj9QZ(vUOl*p=n*I)%ZovbAFt+)v`?%3 zpLDXRswQPF0-chVk%NKyw8PJP!-C-Ksp7>&%kxJ!Nfbz#^=gT0_jHvSi`Sbm0PEtl z==Ad|3Ct@4W)qe1y_YTlm4y*OGh2G2G4S^Q+chBLWT@udaCLwZwD3}$k9I*vt^+b9 z!R?0~s-*P;0^`9pAR?5b;AU&(k@=Zobs1H|`fA*+YEtwlRrRm|St7QkJV!srjuAP>~P)dp(A$l9{_!WqP<~tGOu}KGvoisP3rI1 z9gvc)S74z$xfAFrWZ74m%hwl1C&W%p`v;EfgH?~SBX?1*^NzO{E;H|uJ8Zh|Br~!+ z?`)@5u4=!NMcO43c@ph=^_?_ATX8s~It9y}b`>PwV)k%xYo9ZtS0ixG-7Kk!pb*Zz z*tsG%;Lt&8f{2EflB9RjJ8o4TR4WdOYuv>8X1w-FDBEa8{CVua{>zvI4yn3THE|Q$ z(~SCe5v`%IFJAr+pnm|t?Jk`o@!FtP_C@y^cG*UYXWqOywo^6r?#b3LSeVUxK;Ci$ zh5RIo)bvfack2?iX>DKVQI3q3GrgTB$qQJg2ZMYAMsgwe@e z?5EYU{ij>s!{*(pUYuWVob3O1VJvvf-!9cy;5S-04JPBMIwa=rd&uAAJH7dXgUNUD zvIeoU(3uanT}u0*+1SsF`=ZkPb1K1;yQ6vPvdg?;ce?ifqw7z=lFq)zah$eknwn`W zvox2-^=Fze*c~Kx6gfi9`SkP-gD16_ndRjJX{GdUv#D?8@18eB7AR{|BI+M%o|9nRkp?fDMTk~ZS#2;{z4V=y(sPd z2LxR^rL;XG#Ern9^vs948zJ4a82o6gRiA;h@3zM8p-c|2u#Jf z`vZr%?NO9WYkrKRNl4jsVeGzXeSh-P`nUp`i{hKxueS?FCdx%*ue01BpfLUfWY%O(bj$b zbi~Qu;uC)hXvV-*;p}MePPfy`XN=&@HLy;E4({zXMkC@YdUMv~P+st|4#P+~>6=GX zGTiZQp7r#8c05*mH@wt*P>O);>>>Az{@IV4Q^$mE+CuxxVIo@LAvz8`2y?Bblfe zdP_KW^eWiKHFFfnY|Vkdu|*Cq@O7ZjDPBr-Qe~%$^sW-9Lq5&9%+cfqVGM?y2&Kxj z&_1aWX~AUnuw5voALlz9icj3jm9oBXHsIKhAC*6uDjR)VGT*}XVtF<1 zfOG#XjGA|fM>k7gt|@ClSo+P-9%I7^pw2=&hoOTff0kOj>7YmY54|dhuhZ7Mawl`) zh27lnJXCi`+EhVi=hy?;7bsHy#PSvtPyTdXe*stBPdmKTOFX_X#Uyk6-_#^O6!`+# z`@OXpsaf^GTzN{EmEuwVPKXe2w`zv4_Gm~-H}JB@HBl7M3(L<4mjT_!u(2-h%^}8# zQ&5#RNX4ScS4;7%=)ZF^nGwP8Q72>icH5$ERyY}mzdwyOLRiE;sVApSN$tiMNpGJ@ z_-?4ffy6vgTG)+d%hY-Md8J!{PXjc>6ZIvTc@vI9PA)9;iT(!()i&=qHmY@?Yv+t4 zNWz+?d%dEduWm8rxxV1}1{Vd|dcec$^U5PN)~LvVo5bwqu|C-s(hGqwGs1_iWq>Id z=!AwEMEp`WZn7_}gL;+gZq?QE{w919&?sRE2{Ev%DEY(zY9HeWR|TJaRzuFNAI=&b zx_D^_+P0K%A)9VF)=>TYjN4b;xx^>Vv-tN+vWixSaDYPX;_DAHcqZ^8K-^B-0>V2I zR>G$Fn#`W=xR!N~IbMFBGvuPWKx}uzwU3*4$fdaf97BfMALswne4-2ydn2?TcuaT| z_E7j#_;>B^Y)5(35HBDYW@rc3_xrCI3jz)KsJ3ZduLI&!OlH<$BsQS9Z0z0Aci9`K z&autmF-Py}1a5;iyJ3=PNN9a%7&ZHPn0GZTWBny~9-3FGT->GZJxtmM6S~&~U27 z#u@#mB4^LBMzUSz_Ke|=cZz>0{SR8Qi8N&Mpp5s5N_jB2Y{uwHvwuhrEybJ+Mp7#; zhxUW55!^AcXUDHlN=4N;KDCSp9jJ<`3;+ufg4jHCJ4)X+fZZR4I~m-lCDXfhj@ZR> zekC;uu3K=t;6m(0XLDg50{*%qIK6Ge&wHAoY8j=dQ{$JqADyOaD!7qW`(I~SIQev zL2eb^y^TjEhKgvKF{caMnQQT;3~utzi`*QwiD^7oxT zIR4Fpu8jc_uVkQN{D|WTX_{4baZ^XNO&unDJ;?DX_}h&j-_z7+<}}9snWuM6#rM^`J~G_>@Gqfx22<-GnVethq=;%nmNUT0Hc8VKry=y=Nx00jG&W>jv{6g ztl=(;F13i_r6IfiKSUR@`S0KGjvOT=CzzqQPZq+tfDarud?vEQh?=2Ln3D=(mIL+k z*tJr5Z>GrcHQ9Rpnp;1oy0*LQ9(x-Ln(8*Am+ivp9gT|$qyfbpo}i}IZ|w0lAS-u9j`aY4B}1Z>pOC|W3a zK;@oC*D)t|Ve+@icxOT@)11R{&POHpEH<7d6_pB~O4v#?H2~V&cA-1O64qy5*`I@r zbbNiK97gGSc3CnBINVU>qiv2a!$Tt)`DO|e@-h`DBNe<99?w#{ES@FiJfZn3MoFXJ z(CNMX3Fm#A(}$#hUmi%UaiCz6onaW&`SBzDlOHI|L2A8s+fo^qu82pT?U=8*I$Ix` z%Kn3;D#!OS^ah9sNlY(}0j0zegES`^Jw)xu=SK(yF`9+MmEK7O`vXQ(n)JBAbARgwreFGiElp=@glDV zp+S4|z#2E0R~|C|TBIeuJ56;cyVsO6Fxi#HPfieLL4|h46SDpDj*f%!*U{%%YEWId z6(KRW0#U8GG>3sM33GHNPyqK8qwR9cfDS5kRLGnK><2MFcc_TOTXd|15R+szc>Q5E zW}FcRgJi!oihb`#HCot}Pz?WY0)liqtq7s<-I$|4CJ%b3>(3z|`3_Xi3FB82i=HX+ z(z}dq_u(TNu3yLeE04|xjo(Xzb&IbD*-HudzG5Vl4msBAC*nQrui%^jWL@69s@`}- z=LWL1bUA^-^4G5_7#GEt3OkgF>>yT~e2+r*0PaeEvx=QSyr;MU+?IKw@FJB88OGit}NuO;*^ z?g;Bz3K+yALM9uED`NS%7DVZ!<~SFQtkyn#L|SUMa=vZ^Uk1`4kpVz$tH5S9O43at zhAi>-PS~+AsZ|`F!T6FYK8=Q`!u#YQ8meE)x=n>Qli1C;SlYa=3TD$_cjNznpga~Y*7c%-*gJ8H^;-`mjX-q~R} zVLC|>V{@M1u4jfRA51=^N3amhZ52NVU0&VoMq0b<&(!@e8e*F@6m#0TJd?3)mP+_g-EHHzo=_ z%-nC`RhFnjP2b+B&omF8KR(vbcyS9_W0D$=G9s3z)skoGNyE~rpy(8Ac5Nh(itiHF z7yl{@48$cxG1xGLixJY3BOO>Ooqfj102}DO92kXo&3!1tsn?@}-KWwzjQn!|ch>La z0bV^kkH9#kmbtrb#^!&8aSOyyq8c{&acWvk;+(0rG0WqiYPAM4AshS)pHC&cXvJ83|ySy`$?UQJ^M0m%IGhj(IW8@{6C{_Urx}GF&i4Tq0 z2$H|rI>{&kMBE@seB$}uwXqJFj|+zRhIuwzNHRg35eyns0q{aVlsS8hRwKekG%o;_O#W^q2S-akCm-|01aL&CvN~x}n!zne%AMbWb?8_29WBi)sd5uzqz+5o`BIm6&kC!r3 z_`^;^0I;OeL8oIPShE&PV$QRacIf!}OrG6-#UM>6c@?&NfE60-0_|P{REFe`X3vy| zA#gPa468RIKI93h&X|NP4@p>zl+B2${C39C- z5J)UR0jK1-)Yvow`lmzbqgmSz_dH4si=cPD|i=+80n5NPRY12I>r7Xa7hbh zHt_aL5g!VM4#$#Xyt|gbgF;tLRVvwvyv|qxW}&?GwS@J)x(*$awFz-8vY4Idde7}w z#+~XG9g9_B?x1jCW-;k)SO@JXTVj{od+@D z4AeqGndNW{5YzwP0X!^kmXc>cYd}F_Vvc~CCkV~W2b;>RIc#|oT>6fwp3YTm0)c}Y z%JX)BVl&uKvA$z`s8OP`AokaUkSwTa&_Do;*Dtjs7f~vF2Z^xx`5i3Z*~D4BeBiU< zO>1{O;HY->2aH(PuLSkiX|+MzfS!F?$V05eKneJ9mlaYj#tFeP9`HbjPGq z_*ou1@D(#~ZvLJeMH15RLWE}xfBDHtlLcTM z-*gBvoo$qhv;jm+wP-Nwo!+J){{~K!?S8yN_~rOb=Vqjv11EtnnxO9m+i;~}qsTtm z4dGIjD$ew$UVw9c5ZxUeI{~5IR~d}HwItUWgDc}neAjLh)?cOFwwT_A`pJi7 z@bNbFU+H%J1Mh7Es8{>)Qs?8hw6gj8*nefrSJ3sjDV<3DShO3fky=YGW6jYGJ^zb& z;4XJc^`h>MA!tOQN-k7}`lK0s9+(8dCl!^3rK)~koVEaAYZt#&X05pnoo~Q*z zn6ps;o5MbRxa_)-iRI^^xJ&64nj{Mi z(Qjf@~MQ&-#p^V&=y&V5A>B9Ar z?vUdIV|Dq99T6Av^#bb!%7q(DMtH^iE@@xSZ6M0td0f&$Hw$ z*cF&}FID)dCoJ%6?fE^=LexA9O|6B-zz=(m7j(RS_K_RN@lD2^e#K`^2DDi|>G2U+ z-M22RKDN#%lkv6`3jH!JlNW!j;v6+qhhOZl)w*VK1>D~9W7fO}kHvlQ@S2wMOy>X) zcU<+s4s1hZjfbCQA_D4~+%%?;Gi4lU8+NV_6&5zQIiET4KafwhqQDVeRC zTjdqJWy3LiR)qHmA&B*rg^~oJkQRE<9f1J9N8qznx~54tp0ix_ zQaao;T+QB~*z0z69LT{i7(^BShKanTdMcbUSKr;U?4zyK80g+CvYt^{XOu&kV$X{u zKHyM&8x(m}q-B$J^~Qa!LqHc6<>n&g%CZd;0x4Ml0RlOvgOG_ELbO2AzrD8IW8*Ni z88CGHNbn%7&3@B}#<+d-UiZNK>|=(kH`)fVdvN)bRlWmkVM*ULFgU8>$SP_8v2~fe zOv8tuTfPc-q0+OkZEL)B3*Wwl>;|lYm8qut!vQz5B4h1HM6~3pu=MMbJ~2n{Gf(;k z7<3~*^?r3E+V$YI&#B5`6LJ;ANjFsGR@(AxJZF>(Y*9viX1f6#73C-Gg}amA%OmvbyMZveN^wLMv8(c*&X&;k}SxYB;2Np*5+{WLn_cB`*Ttgyi|rI=INBfUIj z&6>TiihV&qs*Rw|rheV@)tbE(YHpFzuLx+fbabUIW*j6j4+LhLn^%?LjF^&MQD5=O zMjd@-0upGeU*mx==-bnO7=g%wOkbG;K(C>Iq{hoh1O-s5751@75RbZdVJ7y#E%tOt z;(|ORb}|k~qX7T17>Tw963qTPnkdzG4!DkOY#LswwD7ohLF478runJ4g#bwRR=Sx? zQoaKANpeD=YRFhL8mT}$#G{3rt>0Ije*ck=jmXa57= zP>5=#&W5?}xDBnRPp})AH4UmH?C3Y%d%dX=e<G;Th|CtH+-6RH*O`8ms9{8zA7L&&U>@{S+K><9)V=i8s_E#aK$24& zzfuN#glQVPR(TDReyrgQNz?!9{lM1e0P4p{|KJ3loJ5K@&9YC@sX+fV%tI0*Is&@{yU-R`U3R)RUP0kpNLbjjUMO$Nm2kMjb$j|>KgwdAK z9kficrrN3W{{N^3(g{OA#)$27n{CbZK~h{wwK1olX<78D=F`OJ;Q%vM@lCq5lrBkLpmp z&5L!{eoe>sno#d^!kS7y5U@vL*&H+9YM%YhRRS1$MWN>=JNoCbe2B>nFk zfMn4cd`W2dd~4Hb!npRrp3)HYsGphzaJ};E$73xT18STD0W~kzklGofDD&vmaq=H? zkW&}^ij<+gJ%-OFTckP0>A}F0kn_hAgNiv+r6>7o4XG5zdu@#WJu008S+z8F3-Di# z0xHQE64aNxtkGWXw-`BTjJ~Zh2M6aCP{Q8&eB|jod2Fd3p0FXV0sG}NV>92Bic>Oac(8-L9G zr@Iuj2OKLK*v!wTC_X2@S!JM1M+2z;v6l>Kf!Mm^i=VdgAuZ%18(dHOsLj*NeD{23 zdCeSH0boke7+ZiN{%l^=zv`$cxs8)=6OG^fTCDGh+zUrD@7;UhEmS>uc9 zTlX6yPfyYp_ax(?&CwX}h5x{EGQ9mBjb^Y45|B};nRog(n{G|o9V^ z8wbMSsXF5M^ne#Y>bUuLMpi4u34l^Qz#*Fj-+6b^G-6c{$%rk0jz1R*3Y9KJ;agA7 z3#3_qwp`GDJPRBK4c-?X16CBxy0KZBJweD&#!0epB8*kgxt~69=Hqh)R9ZPyLHuwdrN1 z(z5VYRIlVNVDm@v-Snid)8}a*4QS=S{(C6n0UpC67Kcntfm5nCA%O^yrlSAp(gn=7GEMJ^E9<9&8e@_O*OPMpC~KwWt!)Sf@9l1I zc-n4i5`S_pe5x<~!bI)FA_y7qqCrPy_dkv9R^S2z_Vjh&IIZj>#fk+v+|n5Jh4QAD zRNUf!QWbHgT^UQ2gygp~6);-)V2DBKrE69tqMaX&k=6SGfdJCPJzJJ&Td(oA(M(uq z{(D$Jr z_Eg$EVxN-c2WkxU?vL%qo%XTP1*#G5uCTv4k|D2=-<4)?lE!fV$F2?%WZKIDZ711< zR6=+X1pURx)^No!>+T;!`V7u1uIIH18nDzret9M(@%+1wN?|n|E1X4Z_B7d)0eVgc z5R`kZtd)PL#mIHT^ycx=v9jh%jP4#)SJT2Xl$-iDg&&IJ3ebVOIcl~G56g2V+#5QlYfP4*=zk2#eMp~P0x)f zp16%kz@>4Brg&`CO;^X&R_4d4l>ydkUI!d90ZB%QxdJK4*nCGR;9vt~P|R)*g+=Ar z4~!KD9Kc7Wg|fAz6tl##(YL#iqtrw#j`5^!o>z#u^xg%}|EK2-Ff~AgF})?j~! zz?1m)?mqi6Mq_RiF$|TE7jTgKAqcK(^8x&eK@MGua6gtJ=Q4-!>Nwp`V5M92mer6mW0ufs0p% z&@Kv!boS}!XJBs^9sN~m^q={$l#G-UXTG_GS$yKBuCa)jd8WUt)^3dd;>VoaKWqgl zm`84j8ldX72lL{VM|Z=@8)!#7@74D$1Z+dm#HK_HwVrJ}vip;~dh(C%@A2!K(3)TT z)OLPjj{$GpPCs>}#Vv76OfwLW|J#a*&n4b(k65si3iBliq@gQOIdRsDhoB8t6_2#w zqur_woCwnw217tzZf~h2&Nq(du8w#8xCP?t^v_Rzv3{tZt(i85EDkgZ%$FO<3k)NI z-;1(FY*MaOS!*a{!?RGg!tTl^ybSH@QTeSIrzkBMk0UC?BxHoox4O~C%i)M2hBtt! z2OM~F25O@(aFzZS1%N+7sb*T~+MhqC*qpku;NYFM{kJ|P+k4Fv^xn4~xj-A-SYCwU zN1Dw%$%+^HeMUw{s_D57vH0YR{zWDo+dr9jp>Agvx4X-NQw%?U2-0xc<*TyQIkz8| zYdG(9qB`T-&qol(X_uRQ3E0X|aLaN;QpPuBtx}SJox9d?ulc1EM>}1Apd74ZIE;oE z#2~rC$3G(#5hh}LSqL{$`VfinLfi#jO|04h5A$AD-=z$#X~d_r9&PN~ZR^(1=gr!! zmg_Av0~P@npXoKCk|6P4j6BcPw-t1%{tU@)EQVY>pmm8?!*s|#98<#70g_jN9xgF% zJ@SwqY7o@7m#o4+=I2^U>k>@hYrv;n6wWsPtL>&~0mhG%Hceu6Cwob`5kl^qxdTDR zRQ|dATHDFu!rkS5?I!f3?M*rE2k+hs1vQ!5kM!?4x$Sv>NUBK~qMaL{pQh3uC4PLS z^C4lsR31kypSaRa|7daki&QIWZBq+jO{5TpSB~;`wOfrgLU13hY6>l4jy}^Pe9&%U zOh(I-j$_4!mY$|=IdD<?MkKp2Nq5F867jRm4LVDH?_ zGNAX>zehuW*Z11X8=mKFG_O*d6e`KyY4?5}2VMl!xyEqi=H@pA4uB%_h^E`6T?&Yny!sYytB7Ty}d}u zDr!q?ic$L(Djj^*KYEvU-RFi;k@Z!qN%>G@AGxo;uDv2Wp9ii!vuU%#vI_E z8n74%HnxSDj!#m$bbOzO7Kh!~dbn`duEx=rGv7Yjc%u`0>~@{=m3FHIpa$(~um8#- zfT}sPCo%U{VEhkWb>?TMzH;ehKUHCoP+sp7;`tCmk*~Lv^N_H2{@k|BVr#+88tA z&+lh+M{eRL?m#qmjYyp{ncgy&!nXE?7&Wm_`Lbwb_BGb=#y>%?DSjQpS}$BkjXL2R z_q!|1Q?lE$f5`l4qCw+#233#o*p;G!|FeKH-ultsX^)SCY_e* zYTl6bNfi7#5tuFk8I8dR%6mpj*h3v;mCW31K-B?oGc!g_C{hxA*Tnw75jy;VjjD58 z?*8aN$5z&sH;gw7%9rGvBQ=pjJ3DZjTvr8Gw<`8R5yM<<*Uz0(# zX^^!k|Cc2oZB1w1b(`!%;>n-xe-b>bFfjeX8l%TR`?L?lSOuSyZ#Mf>2KXx-0H{vi zlj1sX-hy;z8e0J!|hr??yt(2*ZPf&OhT$wN*j|2A@M;oG_Uj6E2opIQ_9^+~$1AU<@v zb9c-3?Kk==ypFb>wtqA_*i@UO5MF1fOt{`($(8AcDDz2#kudrRT>E_yG2r>x}OS#W2 zS)q;_hJw9|72Y$?O@@}Q_r8yR${NlqM|h6ex;qvsbv{L-fQtr+uv>wN$1}7bOR}#t zY70DH+xjQqxY@Ok?KWU<*Ww#b8q}$bfDqmN!hS!V zTGJ|iRcK>QSnn-sQI`B2jB?6d}TI(F1j5MR!^seh7a&Thl{^pLqteoEVqzZi0kjo5^xix4VdSE$fQNYbIS zxX+&7B`>}6#m~*QTM;BInAtO~z?Upg0M}9^O)2(Mr(29{r!@y!%Y#(#Ge82MTMu1d zta%)XJWF}Av=w7*uo<;v7+iN6%*o^+TtXsppcL`Y!~^k*I@;)&Phj!97xp6-(}22> zMUapWP;Z&dsh;$hab>$UL8(1m(tYA45Nw&=1g|FL9-L13^(RWXj)d^ml3GxE1U}PV z0H^mm2vfqar9-@Ph!+MQow5JgS`!C;GHL~Zquu}l$1F4qi-4o$`pZq)gl6sO_K5tt z6V0@9J_pcayq~H`LqfZ4ztd_1o-hAI%nqugr_Sg>YH!X)e_io7vQFs8H>U4+_fQb{ z$z?WuT;?4NFJVEH3zsq=>h=fiKjX)>m+62hSFY2DOoBvw0rW&bNP&o+lj#lt>(%G%>V9e0(a)S9u(R{X8J+2eZwu{}A>2 zgZ^Cf<-qF>h^4yJe{l%#2Vm|WEwS5n{4am}k~VOo$k=6p52-5J;xJbQP?3lSXN?2b zfWA!?npBIy_;wkABp~LjC0(*E;UxrV+Hfz!-Nc4wg0f3Lp$tv;sKBT%uK`6GP`VY> zzY7PGmTMIKsZZQk-+5JX1m_}Lv;u|O!RJ1y`zRUTz^v203NkZ)+*xryw-P$xn{#{X zjnjuZ_^$53c3O>?B!Wu}KG;SzlvZ!&}F(uRhz5 zIb}PZlrXJN7H3xZsKspTm&swfSKWLqj{ z2=!EI?fKEH|6_G2^Wj#bQ0=EFw=;sR)9<@s0tA*%eT$D zURKM!nmqg2YF*m0b&C;IPgr((4U7Jeh3P@cdghl1(#GZfi)mFz3eH$kvhx*Ay6~&z zxGM4D|8w1NrC7xkD7Q$@X*0@xOFybjOQDWBf&XyPsZxhF9(VK9C8*6tOzQIELXAdG zR1-zbjeV1jiZjBmdxQ(8A`D6IV*k1@YC@swBl@1?A| zvY05a1KMakysT51LRk1wa<+5EC_XX%_d}ZYOeK`L9(!p42_Ef)m!{hKRa}g~daj{`*^vzLyp?`P6tT>2&V5ar~E6#Ox$uK4l_Kk*_ z$$8$I)`rqJyrrOI~Op&6~W7@8hCaiD-1pKrug}(L^3G8eUAH z+&-+x*bo)rIw*9sr)ot#@QSnUR?|p($hf=q*qiKv_Sqq}=sI$?ut((39gVoBk_AvH z0oUx-kxpu?WZ=((tiLerBU5Edr~Z1#vl*q-XQFfM2RAC)au?ukfnZU9iMI1-+NGZx zC`a*3B_F=S0DB{i-qv@mAtKd;_ZnV*r*WK}h$Tvp4+l!aw^l|H$Sh+pzoE6m*2QG*gtxSY%EXTK$v86?8vw|Ti*Ab zOBty8jaeO8FTm7sYsGzgng0Y_r*N<`<_d2#i*U)vjBE#MgDG5}#@|%%s%910ac(Yr zT(Q;Wd;*XH1Q>azzOH_P@z5Y_YspsPDsPvHIe6%6_R|!sOX)f0ql2RZk+(5l?A%eME)C5mXC^GGyns(@!Ik^Uc2LO)bgLM}=ka?Qi0P#l zJVUwr;&ZH>c%2X3ly4XDs=(W@?NVa2d~```Urxc$H}h+Pe*k!U zdfT$vs~4Fr>+%9U4#}07Xq$BKKTKxlzYXvpG_+(i<9f+;PQnD`(&c_T zsr@QQKvP z>!p2my%0K4GtG0Nb4nrW$n7S}LzLMNiz~X5@HWw^cUqvx?PZzChQv7E$*xfJ_THYZ z-(fYvjV4!O&Tn})d;)k zmbKBNhnH>kI~LTC#oOZ>;zH*2kMFzo%I*w+xpT{CJy}NOE?<1Z8Iv!zQFMwD<^HA- z6II#aIUEV+DZ9^Un9IwpWzP2t59N399x{QZlOhz#z+NCLK%H~)X$&!N8BA$LReIAN zn3LNS6Rn_yH}?*$*72BnrA0)$3S`*XzPrUhGVBzEglj!Db!KuqKfP z!RCWyopgC<9ye(h<_K94GMj?G%Y2WV!l{NL4jd9x*m;DF$3cacfX2~f67T9RJgO|g z4nCL-P2HhI?9#gnWnsOenSnEh16Zenn5`81+;*5jDV1;|uatA9h?{I(4yK^^Z-TXKQxQ7j{38tCu;5Y(RSU%xaRXlytij;JAC;Ro%M^m zL-NVLB>)@@l3&_Wnc``AqJOi0x8?v;RaVB3&tgWArLa9~NojzIV4Z*K#4_4BaC*!z zBKn@vc_RI^a98wMwJAxuBnMLyYvvcV=Jl2sdYDn3Al#>~Cw_EcF^EWs4(m(-XD$Xc z^M)#YQ_{qu3kyRT;e0AtOz+ph9d(7&hUmFL!=gfdI!y0$C)7jueR5k#_*BB_st7Ir%;3E-ON{sD5vCsh4J0!bre7Wjcp|V|{VHF^0H2yV+vgWVVMW zdq6a`Gt6C;(i3Mlsg4PmuSm&a3}3YLMSZm}#0xsKGZ0=91`DFq>?#T=4GB9;bSnU( zNWg|Y!^nM9hOy#_oS!3PatMd1Ng(|arj<`hOIq?V3HQDrnf>M3i1<^*#_cqYtiawhUY04GwPr8 zc!Q&nT^W>|+r~rKSs!meh0HCO_w3ayX&&hkCcM-TK%x9bcxR@`%>=!j?Md?Qeh(+% z*lt`Rv54#f`x*A+q1pB1(~r`b7tIxCH|M5+iMqJ2>?#%LuJ9qsi~U-*=M8KIBWaB@ zReu&ZowE~BMiG=fT*-%}D`V=KR%w|0W=|s>sA)kWzQr6!30YV0e)bDY7^_|(-%Aq3 z)b}6@Dm=tzq6l-f60v8PV!pc`ItLC+jX^)|CY0hDJ+Svgeqyc zkFFbp%9yZQq@~W)w=NpTM@4$iPJ1ST8BO7?L7{O zIgxhFB|sP+S#T5DhQ3A-WiWt>0B&6I5m6YE<=`#4}dOtpk3*(WWqJ#-NlxMUaV$&MYs zix#r%f1`*z^eOPet6NSrc~^dO_vqpJ-{K4WhT`mMPf|q=BiDwfU%EuIE@lweUcFU+ z$msR!n^N{2Jq5=Ls?^gC_|u zXD;;!kI)dur{~nP{dxj7RG54isC7n znjHu{meR+)vfPuq_|_AtD;D+yurDxLnH;P~V{2N&?`m-Chj<{ag#jz5c#07|>BdAs zU=uyaXHV$dI?1V=Kg9AeJ$dUZTuC%7yTh%3p+CN-Y)qjuuU9bpM?_u0YzWt5EWl$) z!i2gJG4P?+tT@rULhcDGAoV5a(s0c@`*?iK+)X=JZ4Km=>I7SwwZy;27!LFzA8XFw z9Z*duF_;1Bc7)xF_Y38zjj-y%+|jmTgxHU|d$o;qondvN;Oj51@3d>NBB(#qk@3JK zS}Yt`dv&=mv)Cc@vYHsO_Q(DLohsMBAD$_4`evJFp9-7&N3tw{D@Fd!?TK$KeJWvx z`$NuFxqHXkKFBh*r{RKNzBcvSD+0>KBT8FtMF1BEdqo9t#;(rSf@{#lkcvXcymGeF zVoR+DtUz&h7j1Kall!#~jFk8AHpV=wN_tvzjQElZ5+8~MIFGOPizkX`01@5%bW z*ezyX!>h7u%7eKE6elXvOc8Tf8hM2R>#HEf7%uAOW_d}Gedv-aii2}l$p<9yZO-!d z+;cddoyz_U%W<#~LnX{#E1L=qV6;vtZ9NbURXb@*r+J=>_9o@&PT5&dcF%coR@HXC zXI&3zu3^b}Aojk>nbk8JOcsS00=)15wHon5r)<4O%0FJO;}YY;&bN{k+dx&7yZl=V zw9Q2B7BIdGocw@B60=yZLv1wp{~$at@j0#d#GKLH-C9Iqt5i%s&L4~{RDO?WgvOc8 z2`oKF6>`PCw#xXs07gzAF!#v=xG!kp6z9n1^Ab$mgIvXe(Y%;Je47o8!rbpT%bx3h z+ZXO*f*ML-RzL^KbANs|2%fW-i2V?C4$`N@Mmm%h+?+OeQ@&-0`#ty=Vt4f88YU|n z%Kjl#+QWF*<(tP!alX>r<9emfmME{JBB~)(3wbzlF(=n)Yft3kkf^<}IEoh3$?l4H zdqpkOQ_Oxi{PNjMtq2Jjq+$TCk1G5?;N&h(p^_&GMKo5%ULDt~8l~pa&vK2%ab5-{ zf~47VoI_QqBz8g?FA~*7i)wxq0B`iC`8ET!&w_WZQsGTq+Ewc%5l?rq`;fCxIwZ@im#xQ8A!a=7Say{#&C zY4Ctx@`WQ)`Req6?oL?WWNrjEOJKXSWy=3*4&uth*OSjNOIHT3`DYO(aW&UFS6!&+-qPzgvzkL-dQsl5911F z?Eq=g`2deu%p#wjbqEMFK-xf;1_P;CBsS&dRZAOGE))F(KRkfw@`45n6^k zW86H2(U*rykz_Y7SZ}mR_e4c%^!-wRKT&Es*v)Z0l%`5-d_~S!5eym59?hp4uJo!q zQ#iAXz9>{w-C(R)D6IR$E((0C|KBWWmHc|2$IGf@&bQi6-d&8{cV&Ud1W@=uRum!# zod>WO|5KZ%(*FnHZrjmodtOv6DdP+)rY(n(R}7wb+j|N7zK!_}EFZ`}Y%$Tt%FTi! z2#4?V2`pt;1mT?IX`d5d<~vE9hV8gD!tqnrx^RVE84qZMq-6@eRCRwbx4Zd$0F>Od zE9%J3|BtXY4{P#F+lOsCPT$eCmWm?EGKFykWiTSLg=s6$7AxWcvLzLSP{LA(tRciM zR>VMx79=cTG%B(rDaIshNo-|N2uZ1guqFzU03k#ONyz@)p`DiYo%j1af3zHj$&>pz zpXR>a#}42J z=`rr2rj}IknG1fNXvAk{ z>^&!w9c0^r^aTnPwL}c}frL@h|IsZ|9*IQUlZV67&H&jPqJPaUhqzbvkaMY+@TE)! zoJ&;~Z)?^0uHDV9eXj;=*t|GD>GAJv{q}ZS8Vr&#zQ68g$0wu? z%eM}MPg5dmPNn!V0;~Ju z?57gN3YJN*7_L4*hQ^mh^?x+dp%#O$Xgl(-J3c4bhJ-HpByEEz; zdr0cSv$Re8=X&^wHSKH1t#g(87rJggiY>2&n*Tw>V>#Hw5bHO3S-mR=*sIUBs#w#` zTWNNzY~CCu_qZzi&i`P2Ud{tekUDU+_-OThho>s1!!A?Z9rv+@s!NG^uaxKKhx{s= z2nj7I^Eh38j0fS{q7%l3y!hO60W8zpunUr$R9iUU(6n&M`zfM(KLVl~QgsTwm;yWE z6K(PVWECsR*|^=xS*0Z?v(&hWr)&53ly(%V%g*Eys>g$Cq%4UQvcI~AL%B?F`Bm~hs_Z8^)&$1J>om$UZOSv z1!<3sSNuHZ(J)gb#9>i>jj}f^R){(1?vy}5TZFyJnfbzRkWJIh38VW_@*VEI3i2P_ z;)tzxL%;n75w`Kr-VagD8?Q!~ez@@%)3EAw?Z3Y#q8sg&94+16TxY`doz+HUGaMa* z{eyl1^bD4g5dH4PvGZK(;487aN8C*E^(Pl%wjt;%y##I3uj0wg?k0{fFud@FDc-7R z3iQS5Pcv&z%2Cr=FZ5xV_oR$nvKB`_|NjF=eMF%t#!*Qg^y1F<7d`$!;%$=WRy;W+ zR1P^)Xmo%21ed;WlaKX~68Jb)<}%X0W-Lk|>k=CCFbn7~X@SJGzu~_KrSs9MjxfWR zu(^$Q;#WHpD`^X&IJnh3L7&m{B#m&C2ftNnOUfT_JMbTQ1pmKS6@RXhnnWgh*|K;J9IdmV|?RXdfP=#tV5yP>fVo@4X^c5|n69${~3YdUW z^4?Yb z+OJSX_*D&n&>U&{b(0SrwsO(Rv{!OVxDV=iO&U=cKjAlvqmS5DLxM`8>QOBj4w;xJ zH1vAiem|^VAo_GIymhE7Pzf90FNh-MgPsTGGLo$ zf0x4~J=xGifefmHa>XZm3M*O{N*jBE8*>#&;*oq6GO%eziaaEZ60To^;O8{gp$-mm*!o;*;S6?urw$rmIOF!p=a+I6RE3)&qEZThDmgWGC7MVZI z%?~5<>KQd7J?s#$!zsMn0Q>9&jG#BNkx+mTM(dj>2>#qiQ;J5yu6zXXs_l<=)F&1T zk_(cm2u80zY0Da~jg4`lV1Cz7YfPw+!4%V|1V2B#ElK9!XWp)>bPj8(o)CJ+(S$A1 zaq5xasJRv^gz{_;7!?D;sJRsv^o=k|=-9$^LT1g)wI+Iz$3vc9wa-~F4BRP)bfx2u!002)XVOgqNc$t zw2+m3t{PbG|7gd7ybr{6z~rD|>e1AZ-gtY|FZhijkg!$L9mfADOkYMDk+KmUmk}Az zsy=8|zJH?>A=^&x=dK`z&}lU7vENLN9C2&thhTy01S@*8SYIfsf6j-L-6gN zlWi*&jy1s)<=Q&~Y>h!)k32HkSfLn^ap#1?Pn8^C!NZAn7KTvQ=eC6_CgybEJ@AqC z2N}hqsc8#{-yNSVsea*6^6(|-Ny~m#1b6mkA`dVqf6n@pcNwhjKDV9LI$rwmkWK5q zE2gpF6jjlA!)Wlj==!a4w8H=Ox#*w)DMwhK&^%<-mf05I4J}DOoJ7CrUk3#5Qs}ws zg#bghaBJULW%b@&r^Xz&;Zj`N#VGBnb8a`#V`vScXScT~5BNwLyVYJe6*3ZW|g=qjh!(L*-#Ql?vvr zp_E`RIOt9D5jE(AknWF< zzy2LenrRH|YC5b%!7|$o>mm;8SQKgsHHDd3lcP}6mf~dSO+YB?E%AMCtcwS4>$ShJ zDtJR@UDk)_><~p%plM`lkmb$8fnd6%=sTPfB-gzrBBgUVf?mTZ@znlC{b@mgi!shG z%4h>^|Pl>ktHVDBYerYpbs0PLciZ181 zB+Ywwhf)@Pb$|L{aq$OMtu#USIY&ZpXAGu8O4LrBb__{#8#6}Uet(EqR~P}o{5g`j z|F8aI?>eu1$k>1qoT!$(+TP{rk1;)Y&%IBabA|0@Wgfb*uH|x$f3K!8XvOPofBwOQ z4Z)NL0pTF9ftOP~g zag80FjFPoJDRgHHeLJP-Z^zRo6HU$@W^^l%(gwauoXl4+o*DykCEH!}Ls?c)x(am4 z(@bG;B{$44a{+FlwTZ8D%;wKpsfaqWa3SMN)0)bNB&xLz*)k~EUwlca{x0& z;*QbNAI3D1>6h7?qEb*?vi5W)H&kEHk0T>{wv8l6bhHE^EZ%|l0N;{fsxNVD zz9U(@mvXiS?TFpw?=m;soQ-J0rLQ{he5B``Ke||CQ35bex{<(&B8VHi2ySji`nc zgqjR&xQIdVM1{)bQAcq%LLJ4Y#_Yj}IEnvBji+uQVxo?smN%Exv9ubRZD`lo5e|Nb zINUuf?RsfkCx@h+@6WxE@cx5(3`h$eGJ{QgNZs3VlONAd#Ft1=-APd7SR=?iIhtqQ zAXAu%59~RzI89+|!e9?|sE1$J6IWuZY8`0PjXLMC)kAi-Fwvgzdfjk2bm+sBr_Pkp zP)A3yYAYmn?*7Cvhxhr)ffdBEuc~z#HgwpQ@N|VK%?43ZEv6$%<6Aq z%GxgEX9=M0h6^i-*mnX&+EEl?65W{5TP=oz6rf)h8q1ch0CMITtUAyB;U-JY>4UA6 z_5NQut2f-gO=hDn9m^ZTc^}_;yq+)IR_usZWubK)8i`$Ab2-7#G=~~(4}_;ll0#A) zo9n2aw|HsaQK4qikzQ?*KIza6vdQBHBzHcJO1zZEB2*BbhH(s@#cGeSK}B2%Iwgp5 z1OjQD$1o(Pl)i0Q0?m0Ow}F8lhV=GxBg4rrlp-WFPW6ULCyvbnoJqOK{XQt>!5j0}(=WWm-^MC;($V8$ z&?)VqW%`0#PkL zCzhZ=3Eo>=NMgy8z<+7N;vt$xATM(l_0LF042FEMoftsWmKDZ&R6hvkF7?#1^|Lo( z%f$r_(<^|NfpIf+2Co~B+Pb&zBH|PlzLfo{!3p@O=%Pty*55xm>bup7kHC!vaIM3< z_Puqg=SUv3D=rGr(nB#J;H?TqtIgA(Rs2DafhnjYHFd_iXlM{x~WWB zjA2J>NxD;#XsXpYO8;FPWd>yzfb(&t_|5r8J{4txs6G;(@xVj9$1|$6`pMML_~fE# zd?07hkSK~m#-um~Dr+L7MP>Qy?n?glnBBLiaq+BkbWD*n$e7ewjqh$1gu#+Jw`=Uk zcPP(iwEyh=j0>x3?_j%wK}Wdj z>GJ0Q`dcRUi?qLNI|X{PCCl&otb5q=LTW_SbEe2!GuC#CKl>__dkv8h>>hk6>GhrIkKM^Y=s@9XF~`DGo5iZ%@zVh6 z*gDb282^*Q75D}dpklRa+d41S-3UNhH$8W5 z>>{MT8Nl7TAKco{Z2;x4=$QAni_B{QeNNT~rkoo%F532WCBHxVb${~~A4AUk+UYCn zIDg+L1dkg8(h(EeHw?Ls?n}^4g@}z80I`B&c*jqQT>`6&G)7Enc0nt3D4Qd9e_P}A zTbCX2U}VMb*Qa|nLiYA{2A#QzkJ%F1@y$mdM&cNwm0CXgC|^@|V_nWB>jy8Ki(>P0 zDaMl5R$qyi7M<`{aJ;*K9sR`W3ZH~X? zk~!xB4^nM;1>7fM56HTU(s#NxO=YhOc-t}D`VS)#)?IwJ%T@b$A@uRV4}PfoXd@`; z2fKx$>=rqoq_4Sa%Ksv$tZT)|0DBE-krPbl_xp+*rWIAT8{U28AxcNSapI??#ZE=4 zdM(lFVhk{zr4zJ@J3o3{4+M|8%2@I>&9+zefFLH1Xl8(w;wKR}ac$0pMbz1MgU?!C zF)rX{gK2~pb~NgD=q!Id`vP!Jf-?EDdmVY?-0z}u{_X-@DOczEq}T~+=>x3=S~%tk7gH<-dGvKJ9W0yTkJrPeKl^9vBu9$RKC6;BVmQ z+}Qb5xzt4|%Yu9Oe}7S5Q}2K4WFz~vMA)stn&4`t$=*$zAcB}?Z-Atj29&eF8b$3Z zV_QU<5o;lQ_8Nec-5XmJo!nS4t@y`4bHa@iz3A)a z{r@y&|INhw14fQt$Ckf5Bl=fYSHaDSX+Foi*{w8}zp`UhAc0Z`0-2MRWYuS=@^JV{ z<7CeMo9!YCvSAH!FQ0*IGIgnY?*YasZiY2S_Me~6InPnO!%@DYN?TlkI$ZX3w0elr zt8Nr(zBYLM;8ogV$lU>llyj<%Af*DQa;pu0fw_q{Lyn}K9$fpN7heZ2D!v9t%I|WSNH6QXz6q6-E3Qo_os5Mi1N$3keWzzGP-|rp$)b zl_{_Q>Kp}7JPx01eOmPXz8K#y^I?3;&-eChS9~zvpJ;XtM66#KUP5&3>DXNj>HW;N zdy}d*0G}mN7Z7xSu5_Iw^C3(vyv+FA; zdnor+wjcdP5h89xxSm*VFc`(?A2X92oL2&j9e$J8;CfD)oE#_9kZ9CqLt2Lw!tA3M z8dnJfM=+E_B}p(q{4FKg%};bM)a!$DK@9 zEPFBtBt>8DN&4YCroq=q`t1+0qH4bN;|BEd8@2Fh*;m5N(j@xX9cj`L(dMuteHU0C zPH>S4r-xGm1;jOPbls*^ zjg+=Mav*JZtnFMqBe%RtS0H&EfM?3Yb2OH{W(9c2zD1FrOZWTZXKHI-=H364cdWF! zEr|b8dxlabEL8+;IP6!FUwqVe0x{}S9Ur(9-PDl~7$8r$IysFU>pwy=7aT^*PwNAH zAL);Z5tOo8`uR?cBD5y1a}HU@Q9G?&l0zlX7=pPsKQJbcK#s`2`Uy~aU;GZuoOmKF z;?tRWf1BJmf|76xnTZ!Ib##0a`7az;%4-|eK`l$kU)FrRg?G@I_4xU`_8!IwEJXlC znDnVeuZrdds+PMAf0s&-bxBo{CI)RPv#gDZMKMIb9biNSLmK}MX>$gru#KT= zae%Yo*jnqo3ey?UKQG)CpTBV7tAQl_CMjYy+4PY?-^Wo`c{o~`Usy~E36L{$tW{|W zrt8t6jlStv1Qg#O_s@9lEnUp?Ga^Wvnij^uqAI3cX?0*x5iEE$&6#c-F*Bl8ivu5; z3AzEX%VZ{8*r&>K@6)Wb2G_tl=VWze-zzU6YlS^0aaCnK`l(c~Lxk4TJl8{;K!1dp zyo%6Gi)hb@MQIVyi7J|P>eG$;K}`C%UhW_3-mr3vQrq=E3)1oL@hIqwEhh;-@dZ=R ze!E_NziK_cx#?%z#bH%ly_LdQOjdn!chk9Bp!+4)qCl;I`P6)SDOo4xE{^<|oPJ%D zy$kk%IsXM+z)#d6AS8a8lNeq5{HT6Zde4ZoCC9tzs%0qmm%{SE0zGeSG`^5o1i>gX)ZOSwb?E*XB!~GiJyClDn>X#0wMZp=t9_J zIR>pra_=jINDaifabUIb*+Rig0>7txz~kU=kbyrASbQfB)aDRQ?mf}Jzw`Vsb>h

xd__z{ahF9e4A?y4@|CN92e#d|bhut(!G zno^Itl4V8G7E8)ekMGIjaDbFqHfN`&&-pqrmfGTx^MLg--!ec^_btwWli~HYV7i31 zza;x^$UUVv@>C~`7>K!VOl;ESkM=4O=T{0q8QhpxtBXEbhC$axL@6D~9C-TOhGBNaTK0k3whnH63&)TC#zol7;|L*yw|wh>q3-aA5Ad7R7R zM<0X&Zt8%k2bu8?bqfauNuWmPu`eKN8yY&?SJe&y5yFVLLa6#m_vYt_I7MWmux0-4 z-C96~gu)!=77-RVeHH7*!Ps3<>p#kSgN94c{s#NGqY`HpSs24mv|n9Q6eRP%y=nkM@^H7(3xR zNUFQuYUB)(5Q^gbtT&sHpikA{sELi_&sc$qtQ5FhT#>6>RHq#j7byb?^rJ^e$4lG zN@_o$xy{5=gY<*KtS5-QHelU^@RVAw?W&31r$jp>bs}*bJ%i4=&6wzmOR*6Sp91W_ zQHXyKs)?`Y-%D(qvg>zwF&r*Gljeik%AY|_{5&QnL*mC+2J(yBymJbj(Jp!V02T9q zLz}t-ipujKy-)sZX9z1s-M^^MYtXHTypioB4|S{KwA&!7q~b{&i#Onr_m;YwDtF3A zB|%;E7cLc$$EQjOhuyWwqrO5C13H9kJ_$={Iw| zBr|`#O{$ujQ=&bc?TfD`jD6w*qMaa%$L|1a!9%hR@dhMGUr6}!A9Ul#1J@f>ll!Ul zSe}&?KE;-f*D9vlnb=Ld{E{>OXpF*ibS0gBa^NIoV*>L{R zPMoe_Enc64aP7zNAkXFHsyC=@Uo@5YwB^=|UL0CS;@ z)N;N6lEpb?JSj8HqULso{z^PO-{e!guI6&+G7uguqFmp0D(7`)iqB~ zY9}b)mM^62qBawAI%=7Pgv{G8?$SI~NRB%?=%rC52MB6+Og|&dXbA&iAEy#n2!f&< z7*uhXcFV0@vLotbYgS62FLQ}K+EbaUcnozBuJw101XyC{v~{CDr&$*%sPA~%r%W6> zP4!CJjPF7Pc^>FedhtZ#s196JT1LaKzJH1R;tfk?;uq|eIql(4_&sBSZioR{AF^<# zV3*ZmrB3PvsYMN{A-O)NVzdv6m!v0T@*hxJ2~UFg)5)AIjZ$|&H8~$Y9>qHbjIp?Y zOs0KKWfk=#Rgq=l1{fmEg{K1CJNFWs+<@bF;*I`r`%J@!(;Hwn%u=7{YGDQh#4pM!Avc_XPRPgfl1;`yTM%|I9V zsqu%WsjYdaI1iuW97+FMAo1ez+eX~4lWugu$~3R;3aa%OWDID?O+-UJa0e7fI1iYK~I?zyX`_1rzUvZ*Xx z*MGtjc>Sxci@iRiQwhSvPeC}HI#$=W|+@2BqoEpQ61M9z6tJ;_e-zs`gRTbQPZ zpSaSKbR)M7p{7F}QQn)w+b4ayI|8XaIwKK?iNeA_7tR5|KJZ~v)L^qzG@hDciI#dnlQ=dq~rE5Lq&xO=cWX_JdjapTcmXbX^(wemC z7Tn&2&1+u5ou9t~rKjK^BsHNwuCq4}O>t@yk7v4E z(WcazYv`zYjt@CaCDzH5_X^iJ+-PGmnL`J%!3T<_k49oCZA}^I-ga|W(N<(mb;0E zRvuZ#u;D?X_1RWq+Em%(Zqkpt(Mj!5(ApM33^c9cv_I)e#qTm!5S9Q9Z;&H~{Ag5_ zHVQh{_VbAHtj3GIpzk=iKt?1?N75%m4qQf5CfIgPlpESBSiLGix*0FbYD6D8*>kmZ zqJh7dlsV7R4rPTeD7K(a^b}I{+gzx3Mrcn3P+BhTY(!dZ)X`rhD>L<`X4a||_T;&( z(J&4Px@kl61wKNpM%3zi&>M};y>k@O+v3qh3Lq+3t0&&Haaggj29I1L1z$e zw!E>Y{bcQ!$dqh5ovg+!7sQlc5@2h*v2}HpeV8(_{4~CuaHQ>(`48=7bUDFx#q6S4f@Ys1ULa}x2mAX zd}_4{9qETJ?E?%aY{h;df{BS+TR zQNwyfK7feTu;7LyON z1YYXHD%yAMB#pckX1j3>LeJi@_y#mj&GL?)7?VRg=(^0*&>pX%me1te;_#~b-%e9a z-Dw)6aW#MHunJS&b5a?9lMb;y2!k9WIeBOXg@($!<{JdQFW7M%HK4zROe{Mw#&1F= zz-7v`+`l#olxN2l03j`VuZp{*gW6A9}}rdI>GNd=8nau3lCx%%&jtszfX!|Lf|Kx6>_R|u{W?J%YjW0YuV5~d$God*so37@Qy zC8(zUmp#YopOc1YRyvZVebuZ9R9_2%e{2DT6H;sO{1OaxRgx-L-Shc*?S&)JcOQQy zK#kY>zk?#9w)LkAU=+}8fMN+puJp)SXj;%cxZJ9k)e>V6a@w^X79*y1Y)^Qj*0)^* z;Vq~>Y43c$2*C3Zn0TL zW79&!XHlvGv{d8#;=&8tq6jsnz=36^d}#J-heMG+$_yO)d%tTKJo=w$Mplg+W z6!(lX?tM@*Bu)j%Sk4fn-0zJzGfb~^hTF! zPo6pd6VZL~TG3h6KhynCMF4O2}xw-H|}CarTR8Zjb|u_KZ^iU5(_lc!B#`vX1e=MweR?=BM4HzDZA&RiJUS zo4cqUveMTC!49iQo&u+9~QQ!v}jOh@yfAi~&1jEy}6X)=tb{D(NY@O3(j; z&3a-cCL7X^_W=(8KD6?S<89%GY)LA;Q%HJs7k%bQ@(-X>M^R4&$1umbLs}aFh=MEj{V$qJvNvTK&@pkr2K!1OOO^I>fe7Rq zySWAPvr{!77)fJhF!T|ACzb6t>Y#OnIrB|Hy`Kp;GI$1sjn0d$I=0Z7NewhQ^X8D8 zotm|>S_dj|@abZx;yu>83*|fTU~o=HE>ai>ioE94as~MJ=y=AIQl+OTo4}?6FXWAE0MYNVK6bhgrF1$lV){ZdOIMyl?Dig1K=hvTgL@ z8MFgNJ(|Tbb6bx^2?SyZA`Z*Nq&l>DgbK z&D}nIIMxjxrJR_fWfTt#TWNZ`dcDrZXp;1Y=7duoyzU|2F!g>XVlatzqBbN7vCF}~ z7hd^f3Wk#i`lI8rsA0Uxh$!LXd#!$X1uqf}g=hH#M+9YFZ-w`}6CL|gvN)8pLNfI_ z%WE(bN1-u!WIMcW9CUTHc1;;uN!7USQ5kd8wADoj`0CY1^#BPE=?-N}kBTvfgfC`) z#>HHKX(k&~L$bgE{^)2G`3QO2Mpzu{eo$_`(@~e?R~5LS$!4 zZgDj_T>1{5+H|J`-gBg#*pkIh>m=A+=Dz2M$|?a-q}>y*bAH;S@=9M7=ch>E|FC6#gC2^EM&?L zn8#AP&m?4^FD!%!kmJ`l-n_7JZ}SYiC#tlSY;;~I6?&V{{LcjZ%zX7hXG(2rF_y}W z7b|I2%3c;bJ|r-sB%HEijYNJ5GJ=2~aALW9?#*!9MWZb#9cB!?i|uh-L7Q#90$z%7 z)l2yf4B3i)7g~3vc6YeVgXdFyG>ERr%|TXr>AFsOX`L@cS73TZS0lwiCdoi78Nw_|07_Sb%9#k7Xylbx>ra{ujl?*^NzF69zvQ3Y-w#r50OLRba# z<)cgYzm0cE(CUAa%+DM59NFw2Y)w2Du-`RvBj8>@OIF$sVGsL`ito{1#u}2n8%_Bg z@zu^MZ!5(BY5I^q{K-pBc*PBD$oR?VwHhXpl1w@28fasMSNL9nZ0i z-|yOZLszqwua<+dz?4g~w$Wm+Q~oQ$H$d*{Dx3(8_3E)uYY<0o5?sH$J@ZE6B=?0B zX%+e~@eIz&$Xj0j41<2~w-9iu+mwaOl(Ug^E70TC!%)1*cby~L;3?J^#8`AQ z7}p=54fMB(n+Fkjm#gE>x<#*#k5>1sBwtD)`H|BT)*j!oZeh|-%v~0#cH||b{?%dP zFW>zzc7KzNo@svFynxNO$hUdvA0R+F0EFQpbMWeE-q&9St?PIl?f)pO=zzkg87f5Q zP{Ggat=n*xVk`gPYq4w%Vi&Um-1|_B)Hfu%G?(_GA;9)qEPjgC~Nfhm-@#W zSQu*4m3!W|9f-fl#yN++JUCX;J*Dbjm}m&!|97w11(Z&}SzuzFH=JFq1nf`H*0G@= zU9ic*ApO%tgl(mxH?3DYMC?Cq3!43ns+?zU9(|?!f7q21?GX{rc1`(hZEKAR?OR35 z@#?GP90Taa2jyG%|9wwlY`Jiz%T=@CbT?{bfjRj__|{9|w`M+$7PHOK3s1;N1RD&5f7Ln=4L7%i17!j46#2fbM=WmZtaQR`WkN7+Ify+~PeS69U#b7f5$9 z&R4O%ya7CxX72Y2{~KOjQ$N4|ZQA@by5SC1>A%DedZiDpo8X)T4_x|xFYm@BnM3P} z2wmD`c48Do1isRjym|dU6`xTH9i zx*Z(j9m{Ai2CYc&o_!v=iHepy(+gF|Z!7dxcOofF7QDz-khYSWE*+p|1Y7mJ0lGd3*C|pjc1aIW zaPB=Ie4fSu?2)2y(-PGvxpCOCsb2m7e9}LGW}#IsMZ$|T7)N?VJX9@%v)lW(1h_)x z_5Aqb`vP24=tENZhGJlE%bH@r0Rz+RmR{~L(^qVQ-SG3vrm@eTDz&_Ao|F!%E z!X#2ScCdzp!(#NpA~O0lie#J($FI<42?g0JGltZ);`O-|K)TG6HMoO7X=|SCbt<=2 z8>I(#pQD{{<~*~>P~9-@H-BXgvZfmDh>b3A2aBX%++@k^(gp9k*oNCg&rbDtJa;Y< z9xs4ZrOTuY#R#$k`%)bnB6A3emU~cM2}h-h>w@$n)+m|M_?Y99f1$v0t%7MeyY<$o zCdGD@GpV*#FOin68)=Uk4K@@?MqXO?Q2h^eps_7A(t%9 zyHfBP7(2}2m9Bf#FJOZ|%i^N^8W&Y~%kF>n6+pRVlq=@4Rz!XqDCbKZx^i>=s!}aKMnEOl z7ak(;lq$|AP4ns1_>ot;5!6@Gp0r|W9ps2penD0R@Pgz&Aq)~Sm0C?)6&-~fwq)%=ZF!ugI5>_5O5P?JBu7{<>p>Aigl z$LM!?=43D+wb6Hyf7crh9>S)V==oD<_!m_jNk zr=M0t4;mnHgYu2E{QT9iw4Z~qv`cc1VW-L0vd>m56)DPhSh!>8=j$nF;34?PZ}&;D zo%+|KmXbR;>!`C<*uw%XAm9)GNsMp0{%m8;DDGICZrDMHP0OgIyrqXy6+h6XQ<;VF zNq~3`9G+hVcVFnCon{{N*0T-KjclSr^WV!fn<(F!dn|U33bcpl+W&eeowY|tpvYjG zP9G+XQyYI|Q)TFvZ+KP1Xcpz=`-+7FH2D4n2o~bf@~W_bS_ek2O&h;*88nw$h+w0D zO1@t^u{L$`?EQ$_3$`1UCZbqZR*0V96p3l}#CEl@gZ;Xr`;Ca(yQjWC%g6g;G*8_u z4FYzUH4m_XUN{VdV*}+OeNHwzu;FB``B|8X6MqzJkB-A#uDQW~di^K1zBo1b@~}$6 z7q%@z)J-<0quX&)bc{^zPlXk+WC2?c zkJxaM)Lg2}YbcDjxP2FQTYBP$?p+)XTjp1kY@l>1S&w6U8MnaT-k)}kF6RcAb6kmi zeC|U01Bv(LEndRHq_kq%oNwc{cE0~;_Y`ezm=1SDCvd&PiUnSGsvnibg^{$~n#C2I zh+5Rzb%fPVMzI5G`LJcxG8?bys%>ui^PNYcgkZ+NoUB1O!=H#%R7Tyx^q&G9X>kG75&EV^YK*YfD(+|}$|Vrh zw-_d|)>Vf|4gw+;A@?*%)fMN()a5*AKVwhr+2cs^K-iIey89S{JvW$==CP{mz!=cl z-7%16B2x_~hplwa7`l{vSP-j8FKuvCuy*~`(zq;YlY(c4iy4rGs^&4EHP zKbwxpw~xb1Z1^d~11ZH`+q1K{hkV4ObmZ8!-2oghPEeqQ-I07R`8#NK8<1|p3)Ctt zG_1JthO_0r6G)xn{A;Kyrl`5$@P^u+0Gwn*SXMiIr;-`^HBmv{ zHvNp;U6QFX3=a1RW+KlW5+znQ@X`-0Byw%(;-P#QAjYA{@{Eo)&&9Jb!59Nsm1{qX zII#3i=~Ob=Bi8NmUQL3FCuW|U<+4;sdMq@|w1ze{rBjV_-YB?wRN&suva^e6*YsCs zGNYZRw=+iZ6!+fr{s4R;yyps-K@b!Nf0xRk^Psh&1G=<+udxL`jw<>nKLj6oJV`&G zya|U$BjhojV`=@ELn0gjnffFv3Q37eW2N%imPS45NQ+Cx-EnSisx~XqqRxT$;x7Lj za^egOG05PfGP#8V9YIrp^V9PLp#&nvaKBTy)82Gjet zQ+pXC<1tceYJEy9mm5?YoG(VTGTo>*`O**h*#-W+@!%ZF-6-hx#x}%TL2=T!#Z0dI zEvP6igyKG#D8d+43W6C|7B%PF{oJX^HqF@+Cxq7N4=CT~6`xQx*YS79y1B7ZcqxbK z28P4?kap9zCC;%f3Jh<+%^63e&Y`SEpr$u54l(xTndIeWU39~MZBftt5V&xFj=)h` zcaAO4|2DEvq`l)ptx0jp;0H}cj-;k>35Rbod?JJHDRIM9$j90Rx(u-=Hl+Ut(P$u; z(v#km1l3jR3^a4%f~tAOM%=?O9veIyJ}dLx-p>Cl5ax{f=fTP#gU_fCpc5j|%;1*k zDbu&${TJCnsv905$20w?hn(Mj;iuWkqn@?FlZPFKD{WOYqrP+k*t7iRg z7PG$WYUd;gkv^gtYP9(ozKpB2MJ%9Net zX6BMFYS*MbQRqn3j`YRN2}dIzC5!Ztc*%*LiKjiqGf2QE8>;+qUI*_>CZ4Lrc80-z zBrwn^KlX~6w#)gV6+i3<;x-=*2Bx}K2H9)&Z1NI2d%-$~@=gL2k^ck)KH~fCWlf=N!#D%fsiM7n3%%K6*N#Y3W@VlrB z({|LhtO?MzKkWet6fQ{5rE#I6(rt|lv5)77dXN9PgqWK!Y{EEHOn|zCEm?&DdZAB} zxTnA6q?qmkr^s@&MMiu zb9N)%dnOA?RF;H_h;CSz}Fhw9m?0aE5 zn|;sceE)(kKkTu`BYE?_Uf1h--CfVu^EFf5$|SX`ZnkN9?g`}^7ki&A53lA~uiVv= zl(@N4D>dgsA})i97lEwCM0|@UzZ&U#X{B!FHwyfbi0FlGxFEoZde`S_!$3TQD-KGAM7FL4q<=a=zw;_WJfZ=m0JV}CPvr*pJ5k_LA<2n4@xHOK1*Rgw6v zgJ#kN)ty`+Am)1{>_5m3k8EQQAJkxMkda0#n{r4)&0UV_+fKr=*r!T^-LuKIW_&-t z*a(1|eFjXInU_FJm0p%2I*#HfU4dhtuS0O+<&XBbBt5-FE$IeWhCfg_FW8~Yh-GYD${yCjO_$Q%UStKh@)mQ;h+sH}ufh*~_zHt4wa7mbFBTWmXUXy>xMO3eljLjXVc|!J%hq~Y<>6$KuanZ#h9-BTwMcB zG!Kjfy_bV!k{v8>xuTU*nASS$$U|UeFAAg1p=2~e1XWlJ$!=}ZuOG5WZmQ9QRE#u@ z19U1mDxZo!*~4|sOG~jwUCmf@t#I%Z0Dx5v;FC1wv9o~_$g+h|zagZv|FMOaZf&5LVwL8u-FelqWcE()tLAttfrM`5`9IjWu;tyseyYxYBp(&qwYP&R#F9t zBD{?`VqR{mRmczD_YJkuE)`_$1;{NZb3``!lO#>sV@!#c@6nlh=gVdHGMnl|Fo-SS z7CFWpZ;O}KP0kkWnoi`!sKjdgZkdA>s$s3JXI3hNP`);pF~jPLF9vLmP*R@Uu_RQi z&JPiDrN$0fjS!t)a{mZs?4gf}g%ZT)?5sQAJ4Xf7yoP3aGo)9{La|00DMSJVW2+pV zQ5RbU)Bds@oSPwNL!ZjGrOK7Xzf^XTT13@%_$6a&j~}WZ0M+eZKVLin{UmKRKTq`$ zuTnkpFnxn7U6AiA7{;cRt9Xd-t1^$y!JXv=bK?=tzu?V)XT>^@v4ty-7eP?eH-0L2 zpzQm;hUZCey8+W1Uiue&GjE(Y5D`x9uo89;J?}L~C>e$z|MhV#Q{= z8iKJ-&=!Ymb)a+bbB?ETVR~rGis|1XYmXjT;y%Bg6d;m|Vxsa-3PbMun*<}KI_I8Z z`AX6)@|qYZ-_Xw_tt_Np)}2*{4UD1M=k%Z~h6tw{lu~b?k^a=wb zjf9@ykQU#0cp#W}rJXaN<3H}Ztsbsx`u`=V=xI1CqXIHg7sn1rcbWhLaaPMEE$)tz zgHpl087=I74vIc>Q#b3nq6xDfsz}9CEo5p|g zLP!SyIZ#yLeF2&^&QKAWsZIm!ovb!15hcv+ct;H9|$9t^mLc?J{>cX^5;-zEKHH1JhqqhgY&Z4*CA zKx8!4@S9tZQ>51Zo_!(`z#qzENZhM(>`7^1#j)sRZji`=5F(#BY`=F<9pi-mmu{x~V|hEyR-gDCsts0xzoxr9rqWlr<5>Tkkz!5qV#R^BjI z!{*l>jte=%LS#g5!asgv`K_Cyw6G!NhP5#+|aOX-5sR{?MJFtt2?E z-b#zmYg3*K2nDAXtPUX1!_QleI-&@`m(Vccr5MAC!W;-i_H>ViV`BpT++HyyAr#+9 zq72uNat5d{rY#{(3{%T36M{kua%x-c$b!!rDwHN9%lCIxk>Iy;&B+d2Yyci7bk8Et z^5fZf^z)A5p;F+geDJqkSeRm*2M3O(c zVGB$SF}!Ps+FLNwCd5Q@b8BRc>4ha3MlET0`VcrL zQZit%BLNn>L`@UR)Wl>#)z(tg2Y4WnE%$j(T}t_5TCv-s9aO%(X5cXhjd%nz%fTDl zQ~}P4oiH(Wlz;;^sm7T|9y)HSA#bic?T^X}+9|U5%vcsE`IZtS)tvl1`Qpp710K-~ zqj`GBd2ebub&XQF6BJ*0&Co=4iR2i$Dx=f7aGd-quu(S#vklm)H2S7lKV=wmR0HXT;c<`u_YxL{Y za0sj2aqKzT2^U+82?&=DfC~b>dFo>_nq37aDtx(eg&}`?(0i(jEp6W@gdc-eTA92- zb%uuqk{-|)R3Vlst9o6=Slup7vxA9J3U)2h8?QkR&zgsN+Uv(Npem5^DfjL}*pk7o zJ(Ah?O4TRg$d38)2yL%_{1oX%|6aNEA_V0W_HPA}p_A@63E=?OhwqOJA`g~ULoTcO zZ%1fXI0+=F1*a*#`bt~WG%B$Dufdz6omRPlC+?B9TFx&wj0%;`?LB)@D>Ic zw2+yR(UFMRB!@mxBfS$Fdb3yH;$p;1Gj*zEBP(4TT@#yr@7VLlM(x*dI>~4&>+i8P zxV5v0cv<@ROn*lj;Lp}KjXq1ZB?Pcv8fgV$KwxI3JQO+8*Z(ng)B4SWq6J|A5}jr3 z|Bm~zGVS4L+N;RN6VC=LBz^1vlYPn-)R92=+*6O2i% z_crNjkb3l%)8r-}=FF`aQ+24Ovo$$YmB>-m)gO}f9>D^6lC6+d+25i9N3yt2N3w3& zA~I{^WyfVLVkMR*!+_#WCuGJ-X7w5FIN@PxgU|shff&Oa4*eSp`$Q_9>;4Fo0iREJ zUby8ofM;?KM1DnX3dT5IDue(e?w7SMO8f~6wWw%N>jhU=3;9Rkmz7C>SzGq6!_JNE z=g?w#9%T1nV*zp;YQmR7o!fnR^MKAR1Ggn6Glx3$xx57h81j|0iawLXAiVM7qvGU=w(oNsR7NP83B5uXL!iUAd*3!L$2wNpJW38UoJo8xn%AUX7&W7%!v zwx`~v?gpy$mYJf?W6nICjY2w5c~nf7@X2CCt9xTZfdE(@p-;<2`%QJ`9MQ?ffP} zR0;r@y@fG=PhIXb4m4Jh`khB(0hj;!5Y*xzbAg?I-9mWq8PHVL2ODz_mVtWGM&Vz( zG~^@CWKnJ%sXJ&X;nrc?A0*bAJ}xEv44ujIa@BL+oagNB^Ie0!m9GQI~J zAZ1c7#TjbAfEKJ|6tk|i>veJygK$a>&)AE*)DliV!my>{2iZsHt6@6(Bvlq4^n3$L zvU}X++tPNE#8W?3wTBhg_h|dW#G%S~&A?4d0O*$0xuS}s3}v<;mE zdxDvU20Q=)&>+e0W57U=e)XjeG3XY}hFG%4YPixg+1Bu6aI4>MYOge4C_Vla_^Y07!E2ZRp)paQQX3%L6%}c~tdC>)E<#&~AJx zyY(z>kmGL1ZVC>hI=s13WtdzY^5;WK_*qi?HEJ~|MkSlneoT!Yp8`VNUNG-uFtN8) z9ty4sbBHiQ!^0MlGQ2{o1ixV6 zOZAcZKDwqRHV7h;!|ip7?d;8L7?w*`t8LA;HZ|N1^V>a2#MKqBtm%%`iP>*0a!8+h zGRWG+v%vZcZ~s=VzMhozZYS%(zL--V#Z;cc#%pjs=%nxvEJ2J&C0ysg+0Ds3Cg}V<@va-Ty*V(N6Wx1LzPZa{>o1(kgy7FW<+7WG_jb|e3wA{nuRD!QkeaI=4GGshfn$-Um#t`%uw7DRfo`Y1Q?{geMRLaeEkC}i z^7IJnK8Dm9gk|UPKwkbww`F0e$vJ z@oWy~Tk4{pJe!ysOZ;Pd5D3uzQL95N4&K^BfId7~$OeD4Y0nbCt!dirhZ%D{ZjWkc z=HQEqUJGZn?&6DCfwQkJe9Z%|__+me%E3PSa`!18D`0%_>eoBt7Qdur4@j(le*$&* z4;Lf>UhDdXrd1DCphP2B%m4h!o!=NEB5qQ7ct=tu#J4N2gx>oRm?F>2o{uIIU zFB+r#;o{p~uXX_Hyn8&c;oyR8DFspq+Pl)x-F`4AxpHTF+6s0Po3mlf60f2oB{4CJ zU-#~HVBQbZzIXW70-jgU&J`ESujWtE(ncCTEJ#L$9D7}LMs=v9e)p~~_j(neo%1h^ z9P#P|3Db@-58cy8p*>gH|NcSFWnIU|AJ7i9|Lz6c@8^C%UNP^Sjc;0cAJiZ2$}7?i zCBNb&zyI>~3O0gGI#e7lnR=4X-(5s&xO{X)gTK#rgG+XAe#I+rVXGIvI!ICgj_1om zFOvLg3rYT!_3xnv$`ZPqfY0j43Rbx|lb^K&-~c^2-OHZ^QZrALAo|IY#F*YkFfgPe z=*qv={(t=OBhP*LA%My{3Z9<$?bbD&^w5pRh=>2M9I$tR!LBd=0I=}@^mX^WXn-6w z8#d@UPk;Y5XX4fON(^h`r$4;x{YKL7yaXj4y?XiM!NUFFK=tN>Ghdb^#!Nm+K*p@N znR3KM5BR;;7pnh3h4$kL(0lvI*HaU-R}02`MgY#M&=X+3{PEztUf<+en9OnT8j$ko zSBv1sLVMD_p2|-fE>ABx6LDY{pnSRO`X9gYkAZN{01AL%6X~MwJpF1Vr+m07v1sd> zv&pn0Vjf|Wm)C-Vzx=Z=3YK;FAFVUtm7^!ym@ z!F+||2Y4=%WBtj!scY3@!Fnis_Ik8p!$&Jj-L<{LuFY(?R*P8;dA@X zoClj+`>X8eB#(&=1X^)7dAuatkr6G3b>rqqD@33qwvTD7L}S+P}bD(KWs51b`r( zmek{%t@zHnZSZf2xclY(d|y@@Y&9qR8`*s==wk`;G*4Ac;UvLsT-d3iK*UfRHOb51 zt9@dsn=)=y3)>gsALW>}Lv9wbD7P|Kz z-Cw=UkvIkARckK3x1^%4eJrM@J&{G>=G#()pYnCzX$%U5X+r8eR#(s|pGnNQ@JFvd zfps7siI|i=(QCmuGm#fmN1SHHN(u3su&Lrv*A+PyHuXWkP&GtbeZt=^sf8p6X#qfn@vi7eI_3a-&>1wtT!JN(HoE2%lA)4}> z?|N!4LON#Wv=vtnBi9D)u$pyYfnV&aR>W>d;2qUsxxU z6FcmBS#L$X9c}5A3b@Z{5i)H>QO@>Py=b1AiqEX>Fv6(I^q&7C$)BKuXMSIYNeH&? zbngRwh5=U1uaZ$NY*IohwzZ_*7X6RzuL3zD%F)hItOF;ax?-%=D2kifoQ=~ni zJ>{xGQMa?LJmhS`jbg^p`_;9ZT{{rrvIn+g)vb|o^?fkPYM0qh`DOssr9O9NOouBmPIZr(o9VwB;COlEyVKJ^$?g zop9r^Ub4Lsl zJKQzk*m-WzR!+7ZexCff9=8$f9nz!C3wx(ATEFzhz{^I+w_H$Q3Db&KDxm@eNed2~ zjKytra-O=0Ti6&{EG%EUxSPi7eNa;Pz?>D@bE#yj<-N0S?Ed=|LA+<8(@uS~E;mBaQDz zGMzERkVhgycxE!QH|(l(56!eH8QQ;`%t)u-JA#ec+EEO^qUTPNn6|oVl~SwkSTo$x zcF>@5W??Op&wLq^xqwVMc3LWs-yeX|d~EWWBMc%!qnH`n!SHXQyq%2?$`EV}3W6b1 zq4ZB&*3@tXF$VPE&8CMs)%j>G@)4{7-(OZuNUgfW9O_Wc4j!Wqw|F>1V(8<5QOz4A z9upeCJrpvBVF3E+bB190|Q^&gOGz<&2h*na*eq?@t8S zq+MC8yWIsNxJjz?#3!)(b(yR+l-zTs(&FCjs5_mi?KKGLiKukC$y+Wrq8<>yos%IZ zx6_v!TYiXMRSB`F636tl;_^QWMDYJ;Mou!@mkU1B2TQxWUGGzfkq{7y1lYmaC+0b z7bex#qwa4+rPa0fW|v|~;Ua0n$b+R=jFj@k@Rrxl`+$dLeK(tbWXpkNC5V{O9h0~q z2uhEW&AGOBt$K>WaY;)7f+3{jHMs<)ig=W)ztt62jMWJ8hU5jC*oi1CjRE~E%YF-t zDs}*%6a+hX9^aq2n#!gSx$x6|q?w1pp;~-^iz}(CjbK0PC{7Qe14LXE8xHRK$xB1n zZf1GzIqzALJ>I{W3jkMn;C8@BqtarL63n&Mpb8Dp#QNrqhSsp+R81N`lj{~v3)q5n zxkG?=&ir&=r*%w{gmtB0Sdl@@>`ckSd4@nhn0F{w+Ez)opti|LO?HV1Iut>Vt1Vv@ znKkwSot;L4PZHdna6sJV8R9AJZHGQ@&LgupHo>K8-ZWITYHXr`JT!8QuPEM@=R7vE z*!a>sF6qvO&p=~d8|3O;IemUC-6gGpL#}@D!=)Ax^;u!-UA@A%|5(`6AGwXXKU_BF z5EKRWb#1*%zn@GHc>_Gt?_aPlg-nZ@Dbu3$Hdow4jkeNp5>k2xprtmK z%l7L@+pG#|R_gUQ*<= z_wj~M@LR1qjq6TfMT)AoA50x>W0hQMt*>?pLA{#Rp@jjOqH416Gz8mhMoD=Vty2<# zZxZG)PUt?Q@05iY(&RgL<+Hi0PTCU%02r1|jYqFtUyWc<|_O8LBg&{aFJPs0#R&g$q8 zvgNuQ6{9ceNxM?bvg$mSF%8)|Lp87I4%?>Xbf~yPz5eK~CDx|`J9(f6QE%%_!Ee#- zkwH*6UA*k5uFW&Bc3*LDMjGxGXcnHjT~!M(4ZTUWtk1F%rHJg+p*7g@UNKKq^kKHB zioda|i5xS-L~HE4Ap0#dT2J1B$xU~cD^x_h_OnMG&XVddk7 zNWkLep7ab9Wu}ux(`>iQt?DjraAR9ttdTf~O_meW_l8I6isp|!2P^}w!M*kO(mD^y zC&8Fx7Xyw_2TI?eu~D+=#i95PfLH&=qlFplAk?OJ)^1kY#{PKAd^nUlOcQRUYUA^65c$npiFaRDkM{bJ7T;cAOYpVT4Rdtvy z&mh)1sRb#wDxcX2exZ@`!ake-iD`JBAt*FyXHb4mCLGM$Wz5_lN!Rx|NQRAe&h55u zBCMW!GU1FW4`S=Ql#GW1$kk<7B(ku=7WSl5hC;vTmc$5J;im^6BrDh9Kp2cP+fy?| zzbp+8M`UV*?q)MZ*>8yS3lHouVEQK4pr`WQBD@J51_PP_0~tcPI3WJ{55Pv= zc#*|ySjb{XQ^K*E>2Lf)8!y><_SM~2{w4TnBk1ON)~FrN>yaKK)K#y328sp?VP9tG zxzb?H?gNjrTt&qW>)i2mkS0QhBRng%1V zpN0i-&5s879tDhs++4+R4AjcOd>sm@57#;*Y}QBVlQeQ8G5sm2O0^>$V#dDjkfr;L z<=oJLA~~8}V&$@ACYtS5Hah)@^*9{DHn%I|YFU)X8Z11#mXjq?TQiyX_OT|}9V=r9Uvp8sHQE~y{=j@@^#GXeT|4IG1wx1R829Q;!w+F+ zuTF2r3~w&GI_+;68$HG%H$hqmZZ&#cI{AIieoX>4M;oV+A`Cl?fa5~gBEW{GFCuiZ ze=rohtL}pbGp&b?1eNGv*gk!jbo81DT4Po{*a3ku!K_@tLw#U?}G1uCl%aaX`G<16SkWkeT!6wOWwpK$!eu4px zvZL4Zq`V4JhQ(fk89qy_Yl%3m;B=@v4O?gPsdfKtuM$BM@K?^N^Pr!y{Lj`nl>3jZ zjM`yG--(#;o>#mU=2`im&&m!vH=I2vE}z*&R}}0$;bw$=lVZ>onRXD!AuZP_utU4h z_N>0vW?gi7^BAmc*OuKtZ#ci_jFh?IWrLu>UK_k3R zf?BhYhE!LK|JZnD2zEapbSq@+H$x86snGf}s_m|hr-gI~m^_;%1RQn;#WZquADn@e z-oF^(ID%?3ly$L3VSbh(P(&d;ON?EIdjwm#?}YA!JZYUL%@=L3iu zN93_No^F83**WD52{)^i%Ut{DK1^HEaegBO=2AD1wS{mdCLgGcaURU|#U@D~7!$$d zA8={kDQe&oUecHbs6xde17VgCgk~>WjhW& z&nau~*s$k*un{|Mk{A#swxg^4NB~KXvnV)mnw$!q?c~Ygcts1w@bgEqQ8pkkBX$%9 z#ZUA6tD%?dGo@8_yR)g3)yA9Uc4V$w9}EUi$J2%<1uQO!(SV>X)> z8$fb!<6HuJQ9MAv_&KNDq<0Bg2rmJ~1dJ|PT_E(o(}}Hd7q;qRi+@13q<`&X5W{ec z)q`k7Z2-Hy(%b9DV2=X)dtYz$p12Fygr($wYC|yh`R0;zYF`UxUY`bA%{42Zk=eS8 z3Tlydc95D@a>S}Z9c>CxKvM|sn{3`8h9(iF0)S{b9X06Oty`b4X|>I6kLTux=`WHb zz|lbPAeibebWi6YnJBh?YL92dXA-fCDn|l0+Y#X z6&3yI=l%4?_&&Se?l?+U5gYLR=;U+t$u9ZI&>C)pED{N4RqZ-bM z7gIcr2?w$Hsqu~!;cH;4XHrv5nJz%!6l9hL8y4r}1-}C!+UXZJ1j(-gfBNq5YoPIU zV+OIdJ+4_-v;+TS=;1N{@PEJJm9=o{pC?bea24Lnn32xbX2NGO^t3x6Rh8xfSTmi4 ziD9%3`ITH?Fd%(qsgT0odin^Cpq<)uv`No0x>irF1kF}Dji%24d#sU^*UrwY8f$MO zGHu@iSsZkg=N_i(l1DtJze;$^&8mxSFk|#9P)axhzic*TO}tquqVUi4Fq=n45OiW$ z+M62uv6D}dDj2Ir8jF9AS{mN^ikD|J(}I!^s8=^!X+4whUe@w#q*`}Kj$xJL6~jc( zu5y7g-W8#j6wM|9v^!}8pl-7H$M{a@_Y>`4s-)(9HS3P(@q}rM+C28&g9u{*gv^R( zN1s>04VAQ;&3VB>>qni+t=cs>#l8bEne@(YXs3nFD~h7NRu20*Nw#o)k``#r`1-$O zI{}o*nb}tNWwiqUW|72S>}ByEgB`L@tFV`|ORC_80n@M2y3Aoeb#9}pBKWC6xb6Ax zEWC}e4hLf*%n*@pFGxnt6kK@OZ2omg&wCqQ%Zk{5PF!+${-5Jcrf5<#nXZuLu&Xois{CUW@3!brjYf zT_OV8DWS|X7@7e)X<%;-8g_-!mV1DGkR1&%96RL70{peAc)UQdUjDtY-?_E+d?O3r zcQaa)uSeSAG&0(g-=u*9po5AOu@=C@v^|+JlB+Zk6cLUSnn7eTaMSa!TiIJ3vb|>~ zb;E)tK~9Gncm25}NiJcwra#T!Mvu@w3RD#P;zH@a{4LrLSttdm!sTjQ3f`f1eixzh z#3FE8W#}V9LEp;)0=0o3e^^u-*!Z{V@cm15h~lSmcU2MmLvL{1wNR4rp`4XXX9PPp zo_(x2dVj7J(5BMgqfOPsU=weVd!gF|#kK0PS{mJ?{R+-az@~<2rGmaC+?KEMcnYh=iLxsGBP~FOASOLM6sueMU^ZEWvDdDq0{F|Z0*}C9a zOrKbHkZx0&wrB#z{@ORG{ZKeBDMC6JZ7@HPKHn5Q!iZ=&XjI5IN`lmuXmnZU%ZWu>Vyx} zv$Rz5`#a?W%CLBRoLKS@D{UG99VOn$*alNn4JLpcBTS>j(b>I*I5s_$>FjAg3jaw` z2a1!F;?`4I!-g1qb58ddY?`-gv<9Ev(d*Z$ByUqZds#z7B8E~PuCfBM-ZlFQFKfb zrDO%J`laOHW8ljD0Yeb9@cFYu?;b1YdpYpVKES53P_-D?xa;u}%JlEnCz~Hm@k zvx-uv$neh%JjZ3jX7t(n{ysHlqAI!uYBWL(5^1)RF5eS23urOfsHKwycc=~7+KlWI z(kfVTcDi|t5glGz=HV!lNDP^dHYiWnFnwZlZ8cd5t$WK4(l!vVeEaL_63gMsP z4kXW3cdx3@1vJ02h6N;1P1I?WYKs02_u@nRF0y5_3fbI5xYJsYg{2}jH{(Qs5H^Q2 zP&fqU6k<)RB$INW)=XzzmMc?+TdH_pljNAsxMaeEBIf0uW95D)q{p1`veA&-A2f)p z<`J#=P*k)LInw-cYT$t@r+T0v*uOuD)hRMyiFenp86|z(1(FJ&K!EeW1GPN3xdF(j z{A_dinkCYv)}S*cF{mIvD`x9Rm8Vi!-x9}prDEqB_eTBEYrq5sh9Ty}yUNEdiG^To z^C4+%#MNWy6$BdZ;#?a$WVl)B@H6D@)ia!B;*kjE?4WiH{R;cN(P|dekeHB&4O%ZA z&wPJ2%!o&v*wz-JKM$riegvZ@gOR7XOGDY}EuGQE)tPi*!IChmH^lTY83&p}rqmgo zgttuoq(BFF1>G`$S+sL}sNyi~hxDHKU3{OmCc;{sFG4269DP58^vuupI@8>Ce+Q@- zLtM~h^{{6(DHX4{<5}>J&*j>H5b0yc>mTNYe!uRYOT3g_ zzNp`Q-g0+M!rS?YhBm{ppMP!%{Xp!h7~9_d%0IDx-2shMcXwCrIY>~r@{rN7ySnlZ zv|ZTqv0?}_Un>0-oAm|zYW3O=u2lnI*4&aBu=FCjXzq-%J$Gd&kols|kCWRtfB0rz zQ{pOd+kuL8t?fLJ^pD)-q!E^ik;xawk{QOHakig5IBA9g3msg(a zb@O~t*)y?-HkJN-%X7=Z{{tqZn@|4lXM%?`{r~?2q_802U!?H`-z}w=>S{`#*>E#G z^k=T3s7`!spIRbH?vCL7vLJqkj=PGFP0neVw z%MFX!|DPpzbiwOxgmlv@?T2#w`-g9ieUrPnn0e;Y<`K%n+~8{~k>Ngtrz6wsA9JU8 zg>)NJ5jKpUuNa1;%7=~C9R&|!=iV$~tS@=3cnUHS>APs}3;qBe>gDy1dY}`7w^UId zq`6+_Rv)0y8?Qt(K5Z-&+GWBAiv6dGZIpcS!R8_wL+(@V~e-I5#iuUU<$^xpasxv=(T$!nb^$p1@V&kBCsj4wmD`n6H%+iuKU z(<7{XlH8+ah;-Av4bQ7n?h+@VJ@iORm0X?gZyg6uY#2LKn+PA`!yzGXUf!Y|@OrTU zU!egoBAO<1a?%4~EdW)*ag3NH~N3%*w+}QRI@w zSk_`q`P+i5`~OwF_VcP^Z}!(*{5h-nW6k=o=tk)~CCuuv%$@Wkt4yF3)^)#Hr|Mjv z{5iWw**Q{xus$nqwcd)IbqHKOQMkAb|f6DJ0W1?lVWW77tj~2PlssL0rZrYI-Xwa)!)Hh zy}^6uz#rs?YcFP^i9ym$KXGPK=Mra{$l^(g_NlLXv_wumUxc7LgpTf)C^U{Oc&ydH z4yJiaKhM0!`V;Nuc4YYvk|}si;=eIWQN@4c#gAgp=YhP=S;wDrs{W_&6NTs_^s227jMtZ zhEg&u$4zbHikSnM!bpP>e<4H{8_2=OU@SYj#QlOC!AjnmVc|2E0)9*RLvrM>EQ~sB zBwoK*6oeejvhO}DRHNLL+GmOyqoDDUv*98wMVFNWH(Wk%xBRthLb<$!u9JBPgpee_PprI)6~dDq0_cA#8(-RKpYSLdI+L*8QFn&UasFFe4Gkeai1#={`py;%4;!+pB#SzSnmQt+<6 z&u^+O?a+mlliJ3V7iVO40?Xp^~x+nG?Lp^p$ukuk!H?W~NH+T~$fm{O&oYjl|0{ZO3jiFPq=pxtAm zy}TAI+#B5E-TMM{*gcQ2w;vx;Nxh+&s0+Q%R)wE8IJ%sftk9&JV`%`_}YXsC+J8HvgN7SA3uOV%sY zeKjPL%GHtU-lWnZtVUq!E+hgD&|*IeP{ZW)LEpqJB@L3Ma!b zWr^l&?Xi@!{Ix-gtnl3)U`c=S=lv=7sL4UNZy$a7F_}4ol`(bU>H6d%}Q{?Z=Yqi)= zzM(!z(?3wGZXZzd;n$TZBXQcOoOnZG$V`6c-l_h9>IXGY!-1uttwLq;O+DqmCdjc1>; z1u81Vb|nt;1Q5fm#NOA9i0pw=muZZ_O6FM3jH$mg&hm-4b#PMmiK$urtdv3cP^yT0 zvW}YE{Cqh4h}f;7}E!ppAEdL{xr zdOPL|J%^W0)hCh&Mf|oznPXEE92Kb*DkGy`WKOcN!!QjD0M+D@35uoR9^ zW&Gmpd6sngvdiQBa%qV{YQ{3;SDB`E^NS`fxrZ(+pFfbfn> zpU7vAP54F{RvMrAfCDm~B5TBK>q!^O^-UBh1`;Wr{jN?NZ({yN*QxpN8)_c_KbDZ zfcm2>VqV@ArGM{vU3z!2JZH>;>=PikeJ=QISJt#F`*2UaJhd5RsIv{m&1W7JMp`z2 zj&X4vB;%x>Ft{&}k5`7|$u^Hdsw=Xm>Pnf;Pi%6UJ)*dks+bEw)eJ!feEFonNcml3 z`we}dB9Pq{8j>q3txEb$G+tf{36GbT638g!o$%l@JI<}H^AAfJIDUJXC3EX+8IA%U@$sQKGvovOoz1%rP#s6G>SUqwB*>K9edJTL)ZYQ z3))|4OPeI#vRg)*yt3K+A7SnB$aiRJT{0h%xawB zx06+tXH}3#P^9G~GOgs|bFk#1(~%?zk7P5>VumS@#RlftYm0*O(U|q#m|e@O)E}%h z_=hDP_o##|?Fb?Ozpl^{ar!&R_8z=!8|@6i)R{-;4dG|9h3?LbaFu074~)49av|6; zx7>M7RpdQ@te$(>+*Ak*c7KpLs3MY&EIEydnyxLym{4Wkd&9`^H zdDlDgYW2spLC>?Lhp&G8u?(7d`|;?F4c?q}>zOmA_OzWBo0OsF#3=*cjsYVZiQ+_I z@`@9iE;*N%J4KSG{o^`m5M zwH)Pgk0k)ZVJ9He=%kT}p}v}7D~!)Iw1i+d2TO{dpT%6W9KSBpPY429#3`sbo|$Cm z%bBqFg&gf2-KQ6>|7qAK69jF--1a7ZbYHdYh^W6j+?5n`Z_siP;n^R+t45MLc2 z%8i+ES49qS&jWo>)J2l&q&+-?P2@DGn1o(V>a_)t_V zOq_T$(9}oQ1u1xpUj%W4*ZK?(v(~$`zO@RXFfzI}QhsK9OiR|+L}4&#r7eW{hd%iy z^Qa-Y+J>Y0iBwjD!Os=gJ+j8qAxh=vb0dq#%BNf*`5oBxKs}hye8-MjB!00G5cn+e zxOuBBqkmk-=-RNb`W2qlCu&FbNExB~SHB&aOcK`{z9XUc(;$(T5`yXWhWV&=n$U*0wgBX0Cc3&M9Ue*g`*C9EO?a9^o7z>1c>086DiKvj47}{z=JW?AsG~y#C zoVPg~am{_Cc$kVo)}P?CC?2`%k61HLTBQre!-`1RY@pQ-EiB)H+s@W6E(4r>t>?*sQIG}@W?AzV@J_K;l500b|d&y20wm?k9V{Uvpg%`B=@bi`|uEkHgNp8H{#}Lv-|qO*qsa{?R)ec zQ5}Bl&+$eW(}JIlI+Y~eW0p?Lr?t4EER=L811Vd#OU8)E%hk1rBGzSGZ0p7sa-F$W zqhc`+*ypb=IsloFOO^F8As#72*0g_?J-5l)m}EU*VI*0iPS>|2((rxd7(z+{IDj5^ zz|{^AB`*%XW5e@3tl7F|$v~y86V(h=O|bH;#}TsCq0F^qEq2!x_!DoYaj-H9eO>#j z@~@NM!dx~hX<}BLbdOsYnd;8Trq@Sw>LVk*+9XdL(4DQXi*yP-ekjIJwA<2KZH43a z1H{e|L;Q@8Y1u$Mb9qdfF)==uhi55CF|Il8DuusAAVT&HattT(=N|dmWoSFTcPglx zh>=ScJVbB%M!BzoCibr|ooR_2S*#MRi!GvbS1#n7M;gri@iqLK_OGKHdx-9poQ`{O z|4)1G8kgpk?EyQ}nO;ttX|1_=O{1;0HEC)UjpAk6DD)CzO`^mbX|)j*l}4%rP|2L6 ziAhAqrkZ#G8=1xnDm91(0dY=^CMr;?KtP2wUN9&SA&5l8cVpVbm~-Cq;r+ee4qt-d zdG=m=?X}lld#(Rk`?*WCL1$%Paso4gnL+P0hhhbf^x%AO>hFu-`!L1Pz~!!0?`f{? z2wDi?&?kuUXww!Sx>vjI95o)(+~zLL@$*t48(G@p)7^$88bmlA3FVXr{w@>oB)5^| zX%`O?qoj)=&c|B@tg-V`i6M-id^_R_{Do7ksL-4l!>^-V?$YzzRLlV(UhFC^fDPrG z&4YVz%&~JJw9qK#asw+dm&9l=`4Qc4{S0a}Xte^`TPYO2sj3O_Who{M+rJX$2y7w$#;3eo;g(qJVn*mSLPs2^SI-H(2o*U_fUHM+dY-7Ek}T4d z_MM(Eg3}&N^%F%fd|8|*sN^KZh-f&Sxlq@|M}XproJoZ6?NRP-n0eBe*U5Cs>6ZC2 z<1w@1V5g%7SaUEx_dwJhT=>)uif!JUo-({2IsMn{jVq9?>1ED!?Xb75NZbGA@9hZr z_S}m;-O`?a37sJyrf2M?MO&=-8N{d+WQ_>V(*@-=+6!Ggi)dHLi$ZV!W zmiPBxF6$Bn`AZln@$I>je4f)?RL^>;ro0kh>q_sA4w9|)a7&3`DB1Aja z9>`zFa(v3@q5k%?xqcuDKbqpwh9yM}Mwdzr<2-Oe%)ghXKT`t*Imb5UjshJ9*Dpac zL@5Zp^dT@SAns8YEDwkAqr8Y-i^2^qnjJ_Ij#f?T;+msDqszcz;Av|jZW5azhjB9{ zz!cXyO67SH=N8Byez8Q)9!;C{$k2M=$1`8Kl;wMNwo~ zf4fUh%Q_duc1U14Nw{gh{;~@`-x4@w!ai`S8};;}U42K8ai}uxVmYm-3Wl$a9=R0V z&U9qYxl{#rL?kc~2^bRaM`<1?$#^AxjUMN^xEEA>t zc;<7_{WN6Dv2PS{ZacsgzEaweIKFm|h|Ghv`_S6#z0u@eCt8hJ*S1P)i(x1fSbM#! zb$;3lyCVea0qIYhNE~ahel2zVHu2|AUBq!%vSdiVR74kB>^0*sqZpeM$f05J5iOv) zmt=w2r8ZovUVR&;st}_*lV@ffF-8`PXij*bMjMDJDHBCp7&z&9ncmhCuCAA1>vK<* zeGH8JamLSOw3&D8@s|0O)KTuS(fO}%mh6k=PQ1R|;sK{QO*BwWotuNsxdh4&gDLmLm&RgUvkBHFo70$Z+_ z16Iu(6+6WvOF~|slLkWE`=cofNJihVoHHqM(qwfA#U>n#afW8px+x!MTVPY*I3x^x z4mjM*ZLk7N?AUB#PP=atLzE*W5bPmB?RpO0d3~LAHU0d%@J;Z$#_`wQ>Vq9-w|%nb zC{p)!{Bz}i{%TGY4K`GLE;l6+3@|K1aV>sii|RE!uefj8R9aV0+2`y)(rUs=?}=Yy zuuP@N{+%YPI46XD{9lUU=+hGmS4_w~*OrJisBm3iu@q)nIo~CG``XenW>h|!3rA1; z_^1w)@ms|164J4WVRPS{H!49zuA5f3h%ap4mWdk>~5oEBv;jo?D37gCB}^#V3Y0pxcY2;2?B~_{|x6<~Xm4 zU_Y6c#8Q2ZB`;R=_twN1E$;5p=#nFRp<~2tSJJm#Gule9CD93{UoLc%A`5tXq1|4K z)&ce?p0@X(s1X!==ID61H)mR=NN?dn_!GhFdAjF`W_@4k)cv69mtHia?zc}F;FjI{ z6Ix5>KS;Rs&)ac7ejH!xX-hlcsJuA*hPqjj_#bvl*=y7D`#WE`|NZ`95kAw;r-`vhA{n%I|gubZlM(2qRm z=&6}6cDF7%pzW~ibH`p*{+Rz~zQ+^7LEW8K9t%d#i1=#M0)?=}Gu?4Ul0o!17P=R~;6TwyhR4r9E%{+oqkkDu;rfdH18_1)aZ~)C95PW`%5R zKBgw=IqI9#RcOmpsVH-K*TZ1_n5AU>Q10)2tj_;L-Rbn#R)2@C&(H_|65{j|uNJqY zI2m=^gc;8$RQ||yc$x{pC6CXVCq+`Hgq1wsE0QBG6a2m)?$POaf2yr3z)c*3@O1|j z-zwK%)??@PXeqC)L)EekDIqvrR~b9{+MjH_UV7Z?0b8#xZ|L>Ab-hZQURp`@y)u5< z`_Hy+cj)eeZtrT9*C#C9pW$C9gs&gziCvE;&90X2-}A5~^&|F`=)XKj>sfSDOcS3A zy)nT*&M_BUdWJ`7Pk0o1C@Xc#!ibIF=&b+RVxxGa`!U5b(62diL%+d~`|WY9Ydgr0 zMfzpQvrb&Z-mvUqL@NiA6VcmQBMFki)QnU-W^1Y!j(W%33 z$%4F2Z(>FYL%wh59J`E>p<`VZ-_A&ICA~S5#Og1L*X<(A^`SL2;BZG<(D1f0eJ$-z zxpMDZ3T9UxTOqyXar(87@>A^Wq(J1aAN0fAS}iO+^B!D)ESWkJu-iSVVQ$n^t&r0< zr2>ybfy;C?h=fVq6?5sTU+aXobPzA<~uhF!+4)@W|M{X2*<3-tCDL>e$%P zLQF*Qg@rN?J%~c9w%-H!D>2T}x)PBt;ww73c*=JGJ)N)N9hv)hXwdAguX%_pIiY(G zKheQQ?uIWz}*S!G`mb7{Hcm8TGmDgTqh@4irZW1dO2Phh#)*o$vlJW7ktmB8AZ#{70xj-7yC(%@~$pgkZmQ{$!WON5* zcN7ZkQ{a=tITWix9^BA0Ni?H(Gi$C09V;n=`&&tV-L3W{hB|O6Z4yge!V1Qa{DVnM zwK!?zfkIF4smJZ%S?qaj-nK)r6xe1*8h0`RoQ|6ILiv&w!o{RSD^hmW{|hoP1?yOWm)+Gem^(XB)glAS`VM; zdG*(!gD>tpeFDIK)};8O?9JHG#JA`D2O_ zG*PVqV3Q*{Ih(mi!<#M-D^+e;95;Qi!nt#9AgB2a)xn7!Sm|dMIM@L0{dD#w%O1`EBGo4R7UJll?An$ zT-v4T+YN1$7)A*p6raD0l_&;}zo`m3IJcc5YmL`^s!%vCwlj~psggEtmZ*VA-f8j|_Ax3^x7d_Mvw?FF)wmsGviazX+!K@mt=_>3M7MAu& zm^&yR-gZnd`7@!R^W&ej6hwe?>G%ASkgnBu)9`IqI_f&MbZ05~dJYCZKWz5LThuj` zNC9w61a=077@HBcGkQ>tLgv^`K*e_#$#~)d0riTfsIsL@ga?<7F%kVR7s{mYwrfj? zEbcTY>jPYzTS=wIc?F~FT#A1{-2h}!!N_QVt3L0C&CjD_LR4i(JW8uIIEXHeV@3#l zp}u)}uNq%L%nY?-_Yx{TN+5oN!G*kl&kS$IwyT0d@1~In40y`eWm%;(q;)8+jhF`< z^&Hhd`#S@bgr|A+#s*$Z!``P0GBXU9X=nU_uPS@r-7zM^~Jb^%wDc$*a)ip_Ed!FayMoGd)W~1~@6kS8!UNsWyAy(i&E%&8-c@;4VXq zF*sIBlh_YqrPxdT&7;nfsqx+AH5}3B7ga-&n<Kp9fLn*#7-O z2r)0EWtgzWmfrm>DIN9y?C-ZwmEH9}t#Lzsw4xtA6l@+^@AO>yP$>bn5_Jf(!)`nZ z0M53cs%58xb!pjd%wLzTp63SkH?&2%b^dC(I^!xxNaD)^M<{JqAd{7plx(?!50IH= z>Y&z*`REmWF-4}^uTahI`Y#Z?Z$oHzm&WlfilNHmGvq4Unth=V5RV41WAh{pT?5~q7-YJmnx)gf$8cyLhC zsX*`C`4W=8a=nN1{wZ*#I;pxp_JW?`;p7Ts*DIR{{o zzUNJbrD67IN}IR)(UySZtJI0}VyrBLKi`U)A1Y+LW@Km^Z-H$+p+Fm}n*t+gWDN;v z!1ZoGHs(&3=xsWz+|a--Nj#nkM>m(yGm`8>I5=z`AFg(-J%^lN1mkv!CIXk425lD; z8nN4GO%;W^l2{WKjw(*q*r`+`Y5RoCkwd_l%&BI&>$KQ^_P5Tnw5VyeXp)HL{v7gc zIjYG^6xW!7vs@IdFHn4PhYdR&d{!B1cfA(iDZT3gKLZ62KOMPz)xX9OLWpz3e#L5w zv;~0koacI%@s{XQKTz5{%4oQ4W}Po*@@F-hJL#L3%17OB(-U$vGK#7Vp~*68o0x`@ z@RAyAo?GMuDx~_MRV+#p)b_V(chUn(YC=Hxv>hf0q5n95^&qIamt80my0V%*`r32U z30@3dtCsaUp=KcX>~O{m!eneZ61FIoh)5-uLmYA~;yi_v%CX3YED9i_Kb4#U|8Xh0rx=|I7{R z*IM6dzZTK$135B?QHA8(YM=6F?HWIJ^LMlnyy&>@6jN|j{AVH6z)EoyC56nnn1zT@ zHe5)Jqx#0D@A;aN*ZZ&W1a;6u z!d%Zjm6<13J24G`9Hj?Bh0Zg@PP6H#qf#4;A!Z7bdxM0Iji|!U#}Ef~@M3LiJkQ|DQ4J5xOq&S09gS>+kVlOq%i^Znn8rsFPU|dn zHJax%oK_!bHFG&6C$~Elhl!zb^yA;+xJ<+p3x@h>dH-k#GHXq>&3De^zYvWJsdk|) zZ^8uwg*Ge~XaUNvyR(loKBAQYK)`^b_J31m5q<@?9t}0t`L`*b-(?&>RGA9{b3E_& zqTJD0f14Jh<_W>ZMppsYG?-N3lwohvZ{<*a2FAQnB!=E17VjlIkI+!zzSRiPmk`X} zghLIe(d0ZFG({x2q$-v)us!mcgGt8XWPt}`y#Hfi095D7A=35Z;x5I4P&hE>q9K_o zkH{vyZ3`L*GD%$`EQ$xPATeGFl$hIemarxrNbqEmHr+H2V*Jyu;QGThZdYLLdaz5H z=T0tz!#&r%s(XsWVE9#~+a?lwIXKme#FU@Dsy)W?iSl*gkNu^dIvDK=O+mZD)p0{> zBRq)J1wUuZhoJ#C%%XXmr;4K%?sFrG73$07+%Jtn+&ma2eR|$)U(3Cr(7A{9aN^)( zDvSEN9&>GDu5xw5P8`v&Y{jk7#H_~p720MJO8i?Dm`SGI368r4W^%b(o^72lB+4+Z z4sGbX5{6oQo9@fUP1{sn&`o@az9oVP}k7rjVFYwg-qMdsJrt zWsLzr>#sjTe>39D?GVt~w!#y2sEuXwW&>So+=KQDlNGuW1AiR9*_d#vGXIevlQ7C8O^S z$wqv(@j;(%O;3gDBB|TjurO}}azc8Z0+GA6U)JEJi3?jeW*oR{kdNQrEA-u*g6lK& zR)GUWu8<=7(2a9VIzjvoyd{ksJd>6v+G5)LX#DEiuB%f|A97!?xdBDLb-rq+1+K{Z zO=-V;w<_qC|Kb@?6IgW-TbuqobL2JvXF4ifAWe@~u3G@KpHOexuY~MT3w(JDL6N(ZGGBXCW&hDfOIO=DLq38p ziMPhNf*3>wMJALrQ$GXP!kWPYyCdBI0H{;<&OFt&M~!m-Hys_rx*|~X#}NIh==v)s>-=~^(O#jOu+Z0 zE>FaW?#>G5+PrhMibFR+nx$nikL#t$|R4;@fYC;I&HndBqE|HGJL)?E3q0H|b( zB4lO(CAmz=b?(IWdE?Q$X{ZOqHJz||8XzZa#b(`P_m<$gn7*-UM(z{{{B~ZVK{Mw7 zkPeuy9WJ|btm@ff_d3Z|v(dXfk-0MEG>23pJuY8g&IbTUFA84w3PSxjM-DLV&I`7f!Q)l)b-5gb>t6E=z*IuA?m-B$ zm^n2>dW(Q|yOCBKnMCSP$#YgZEtP0z$Zz+=IKPhifKZi2!)}F+p&GC-;}o=p zf^#E&?>ji@(fT>I<0dhiHEqI<@)W$zDt<(>gFUXQmdw56#3VZ16Mx+H7ye>kv`BnVO$|{V6rJU;7ZHCYuP@I;%P@3ZKs?L3U?;&p|AE zn?7jT4dRso{f%W_7XW0t@;!2-+(11tRd==)IJJ-^6*NT@7dfZcVn7QQl}Gj{FlBS& zNu~jn_H6_mQW`k0O*dV@Dw3A;a)VHQx_PHB{W>WLg_yUF>gL^HsCKBeS>c8b-wlVc zKnTycm{BCnGd(*!**mN7bGFK`v}D@{00W*{`yP%6Y8?$<7PDs+NDd&p7N>Msej z5HI@$Ro(%(NYT8QXqaDljij3pRXQcV8iJC%NXyL$FX^iHE|zG;Tn^t?<jOGM&oGg47R31PWt_`G~?mL!n2-I0=1p$t1;dBj^U#d|Nm z!t+%}46>ls|0wg8w4nRv;G#Z|P63j7PHd)&P=-S|$(YnTW1@_dm$zUYFi(ZF2xZ5= z2h}b%YqInDP3_EP_FbK~sHZhH3M1&q?j2xv%IC)4?VI+2;E0&5S;(nb-cg$PJ89T? zq$Y9o&)=g^}-*^`HQjy)yMc1wrXT=GvIu>0B(xY_RnS{DD* zvtkP-hL&##Z`vio{(m52nESyh=6TYp*E&+b*EM+2dTNH1mU9pJj^W{_Y$3>XpEbnx zs|+69|h7LYsRO4w6i-3{2xyahwHs0wkMYePfy>| zZ}&)T!QLkm^YpKF-L~}0C#R1Mzuq@KJ!en<{3v<$$-tlf)y|fiynZ^L{`vog{4_uQ zZV6UD{AwX*@2L~1ApdyM z*KC!qOg)N*ZG7LRSrwJgd<^>^$4W3+sg=%0W=?$9)mg96y)Xju571UKUJ*N%trhDZfm$94)itNei)(R*=e ze>dMU&-x#Dq6?^s>xv#;nee9Q^V6vn ztHFxs(H|?PeZ{Ihf3~|`vC(b-cn=;fJymvh;A#cWQhQapU8jEj8~i50u0W5lT6<84 z!*C*?1t!>4+Zal+{~u4hMCjpwJs+wdebH1ryP$#3cCp6_2h|(LiG~n2~oO^&g zY>|yOpd$8&S{H{(wePwsj<)4^LQ>fY1wMJkM1tInxLj-!hL%PSVax=!J~TdjH=}iV zOkW6WQ(HLpDRHxv@-Q_Db|tt#So7r7zwo+_rf?D#p@ZzvMhT?c&?= zp<)=oKLcYW?1PLe$ccT0nEnaV=8TdfSg9EGe%GW-ad$=0<&8e0=%SZMv^=-t-$-b_ zmv6kSl8L^GG07HjsiiSfS`8G5fvIXdN>}}OEB_Ng_W(f;z-0IFIMD_+B{e(jivNGk ziMI*v=r3=D!^pGoyKoLL6nG03)m*x^u?dT-m2!l4=Gor{ z?a67G4dHvMLwX6kcp@=AL>E6c0PdMrP~&YroVgvEHfn@3@m~R6@C20qdvHca)GuQ% zuZ3NowHTwoVsH;&&GS~Zu*k{SYVpcx%9#_qzTxx|IS@N9xKxjnXdWJVH*M-IyR z`nW~ITu!x&MMy>8AhKJFI_k^1>Om;o;zJU9V@di~+<{vzC&`}4s!~*Wt7~XM=q!8h zJnA{mzFuw-V5RDHy+y{ISS~TaAh7W68sEMSY3uDVXybCxni`r$6%hwE658`^e9En~ z{~C7sP~qAZn|&=8-W$Y|Dkq{nI&jhG3$U-@>ZPKXT*aqY_V`cliO@blg9@%pfh^Mz zj!_b&16&XhEGaz_qiUg!O`v|^jEF@CTX(x#yWK(Rzk6z)>Omi)<|w7JtA3YAd8-U~ z28FZC;EU3X;l;vl4)E}`4ceV`*1x^H^Ym+XS!t^QplF8fEvMK%ipvV-Z^ua+B+xGL z4X3~dPQk$tMG|AC2w|-HuNGL0vKBH--}JyeR*a`d-dBSQj~JtEFaD#-&d&4ZC*dC+ z?xM9alShBRfQZg@Jv9~mZSCGu_5RFPaxIm5zkktwQ&^72IcRcw zA7@VNa{R}%Sqb_-E>AZ6V@!Da7xb=9b>_Z*+Y;Cq67kGgXpU8!isymCWZL3QJPTdT zEf3L@yvlPbosoE+x2K!%i!vy-1T{0d;Eg&Wjhi@>H5on-qjF670KvjHAXA|+~2za%wkR>2tBSR)%HFAhqPT~)gLE14)7bM7$xYW+5+vh_ZhN5ny^;$}Q6A~EAOHnz!&vfzvl6MMx3@^maE zYZoq0;T?HDRxDTC@CL-VLY!U+%YB|Pu9Be|Ozf_GEttHSE0T_``b<+IIMhGT`Xo;U zXjdpx4--K7s16%@R2S}&9y*|wOdC1VbCz?h@)+aXu@UDro;3R>k1aR|cA-TND<5Wa!@MXuYbWr>{-RI^;9*NrZReo z?vyVFFTY|8MKI1+5%E|T3jPqbS^Lgd$R&`2{-clzI{)U<6W)(auev5L@;A5>z+QP3 znV!o2wfEXR0SQMtlZ$fhalO})+i^U>?>s&7PP~BEmqUL%W^ZKR1@H0Ps9eRc;o(Kp zFA3hrgyV~j>Vj5b6T9wA?CPvr=>xq+9(YM%W{k=XNy*zMrZMBo&|Ah%aMDOMlTHMEn zsdk)$=qr0`8Ql6HUBj2ZMN$9lZ4*L5Ej5e)tRJ;Lmk-nc+9=b)P^}& zu~z?h{<-uezF~4zp<8kGw053CR7Yie^>no}K-C*i!7hqwBeVPv z)!iDuiiF&bws9Gr;rH)^<2Wm|_PULdw!7;niD4;d5Oe_?rFgU)YCh9hM9q%sE_)is zLMD>D*w(Ffb~;b1&hijbvBY16lXr_Ox<5PFYFRz?2_E{?cMwr^#Gl8l{XzQ5p5!0n zCQ1}Rbn;lv&z-UwWD0v7b9fen5?vwsG7l_;Llj(leQoe5gw`r!Dq$Gi)%ol77Jp*(Jq_xK(B7EM7M(93tLdos4Fh1Y zz{y*{Hby{``(jbGS3p51G{u|z4!Xb_n~_B)4&(`seIupg{>kgoPME9*a#nWR*(q*( z>M_{t-=1hzzU+5xqiuhp0qHyFU46tqms}Jzj4s-C{8$Q0;l#9{s(v#%4YmZ09RYXN zBdYGSfQ+(OC;QkI3AMJnJ_yrM8&r7gfN0q9^csT>i$asHmK<$tlXT`3qNo=#Oo{s2 zTTxm9YMlm4nj+D9SN-32ScQH_byywycUd{C!YOg%l;t;!C*CaqYZ{p3UX79B_-6lO z)%PG1)sXD5^tZu9c-I36Ies$sv5j5kVtgqPVScel#_skOOt4r^t zMDD7V^t$(Z-Gh9EZj)cue9X8t-h4d4mH+GCb(zfWuOG`aq)RGx+Bc@0wV<^eU8AtN z#pHncWfT%CbRWgjSrOJC(@pKtRSo~fK)0~9T%3y#z6G|5W%d9Tg)yon`bGa%mdg|lFswd-V|XNSfjLJ zr-*#@`xrsk%g>&+wyPn{OX0k}%-ylh?ZyXALjtEx@d6xM*CF5D8qo^vD_)FNiPUJJ zaE@a1Mg{+x-~~r}-gdVlK`k1Dn>6{G=gaD6vdg4JJ~YT2w*lvwBgO|JLrz`o>>TEv z2vL*>Ur9H~x_rla0JDEhJUK$I?+M%}`}%H48`h0Guh z|M!(UmchIw+5dqRnz5_$XzBA6_`)qIDP-}+wR`f)_-yj%{ks<*RQ(&Q+tYM{Ih8zC z;&d;9dA(@+NKQYAh?UPRD2vJz+%1px9R#LDe0jngr8tDy!F*T+75#8e<6Wm|p+pph z^pXrqi^yW~b_yJ$*zc;W6C==>bE-Ct(f_@f!!$!Hx|al3j}Hev7-a*LAd@Q+v*e*U zLy~kgTRX2y`h7c&_8nLxWTiQ7@-ocjS{wf4xshz{u7Iwzg?li;tb5%*#+tuOC~g$U z^_EJS5#8?jH5^;wbb~z8vKPvb{sl9gD3k|^w$^?f1)rpIgl}9R5bzmOU8OU<52JBW z7zId0jXxSbnCquX<0+P0%&#;JC$*e6^SUNk@z|Q zYrsrH;6%f{iA?0)D#YACiO`UypqDIGrNol9q!95rqxn1^xT>JNZTo0 zP}s3J?8F!%7nzvDhM)v55YD;Kfd0w{b9i!?OO@deB{xIH4&}A;X}T_NlWB}V1lw$u zH?TvlYz!UP*@eAlV`BL5>D^WB5ye$)5xqqFta)#F6=d~oO!oUYzt)+Wh(RWFPsWRI zvJQ6q(r~34MLLvZ+N_(dVIFB&E%CkS4sQuTUdW~UXFn*sD9VJu^3*Tm=bMGQ`fe=w zn`ZM3*UPt0-#gcq%eQZ#g7Z#Q%GTXD%nI$cOo_QC-eh-wEEc#uYUlPoySkQ+vxg&I zwmb0wfM@kUt02r~`5Y~^B8IE1`jSdUo*GhIcWTSqsQ>L=EptvPc0$_qTm-NXJ4Li# z!O&`GI@trH$a;RalOKvsjWfX8Q!nzQgh^uj#i5`MQ~c?xw(S3>KCc4X{7-gKGXQLG z0?u-rZurOa$JuUjMv#VA)Wj7IC@)tX055RNXZ_PL~KzshXIO+)cV@DWUKd!iZGhjeA z<>GLhNfzrsbm-R^iJ;9}Yz z+{N+ER19Z+Q1y3MZ>@)($RY3gIm2VXgI$8$1aSPcvW+%s&vWgmuLs)QxdlR2cD3#S z)$=!Go)v;Ek)GI)GFrrx&^)&M)ZoA$!GF(wclghbaIN>x)ukUR@#a3%U1{)8%|@Uz z@G*joFL3{Xq`mY=_Uu-#*-tx?OkQ%!lJCanj=Bf5{xOm}Rj}`$^*-e{O1^P_!7jKG z;4Dv~ouX$*Q7c*8jqUW{Zj!y?f1mgz)#}!uv7!%D8=ty!VXDu;>2tgLn`~p}S}|An z%MMxAqm%0c{%bFF!?Tf(2drsL3vYa8{r7A`lfC|swQiZxdhQ|SO4@!$24jG{%cHLH z829-N{r6nDDR@j|cZ^?iao&O%qj{SUhe#_%B28O-96qO$wp;+GJy68ko!I$ z_wUzLP7^oMZHIwfe9^9(3})bqsjwA?RdIwpdm~-zI^6iv$!%$~f9>g90Bhr?8O&<$ z(N!Ngzxu9-WGa2ecXDZf%>82?_iiP>Yv7mXJU3|RI`fQ%Ir?tEmB*rU#E+4=df?&M ziJj;8DiU05+Su^YpV@!%}MXKdMY+WHC}Yoxy_sfwEVeKFs!O8Y`) zb$upsY}d1G9i=D8&pL09z89d+_g&w7;08VB&F~Tu5^48rN?LU#Pmdr#JG z<)70iK}Hi*{)@hov=8gCA=nId(HGbs!XD}Lu*nIh;~yTXjf~v=kJ|66HC2W>A$(gKpk?p{e#*pKmM;b_3^6@qb!Wo?M^;a2i4Wax9&UN<#-l4qd-cLKeJf* zn~Mhe6Ko5EMFvX;omk7nIJ$^4i*fljlPQy9P$Zp zI>>ACpCG)28cIs@*5f)XR7X*A z#Kfj(>5-L8*pg!7-n{e?54IV|O4N!bA{wt z3wG(sYIzvq)z+^cxcZ^P10QC>!-cZ^#bP0Gy17(4pqh#2pqz1+RN?L5svtA)>3Ce= zOB3P0X*Y7L`*Vi*RK zpNaJr+#+n+3Gz_re2B$dDds^u5w{x68Ly71WPkEzX~@_tqz+e}(5+ zCYXe7<8sDgw&Uvndg2(6k)dhLXB$d_s|3W0tAb>}R+IJ*VzSWe3747hlRyAK} z0(d=sz2ji*w-ZW+B?$tY?Woq!ZKyg^pyHPE@ppvHYzK-H?!8Lpj!$@zZ2~dT{x~W#tE;^q!|)Qs=SaJXX}n&`i%W$@!rQ?MgAKW1j+jk{Ltl&|K78oPK-ABqUwrfe;|3Kzjv zxS?j|!&Wtl_{|IE17W{072QAU6*;|b3JreHNNMv8Q=)Xx7M_$dw}=cE3oWz6oQ}LB zjvIH}9_Ms{yUlh8F?Q|=_{aHK2u&U6yQj2tFRhj6AJrgOaHo#Hp=(O5Xjw==hv#|5 z)-t0Gi@r_qR=#CsI;obYME9VBrp?0_b%u#Bm4>rR_m0&qSE~BpZW5J~Xo!wnK+e+w zJXL#N$BtbuQcz0tQ@+K<8Y26EBFFJ52d3tE(y5@*K9-L? ze0ig^+}Sjh`p1mnQlr=(#`H#?YV@r7Oe4H^i`?R#gKddLFn)_o!(wUlnz=Ns16MwD zjam@S-D;1LJ6&W+`7tZ`i4#X!3M;fF%vy0wE^k-ubU@f4-4CHsBRj2jMM2c1c3j$3 zx~xIHPgxi9;~09>Oq0KAKC7XbMQhZ z!@ns$-9JXv>~9KU#zqOF4O5W2BKzT~cijWT1Dn|TIeYrDIh`#!c7Ph%Tu`FTGp{10pkEQ zR3J;O;Q0n+WLET3(@!qm%XqGXDSB9TWYTN$J$kLI2s-ygE6$4trtp`C1^yTNtuu`n2JH=oRWCHZsQ^BW?-;8sEO+B}ztoDo1M4Q!7QD$G25wX+7f9 zI?X~mbPSJs-Ofsl(`6bn)s=@u*!o11Xo{HwFm*XLJf=y`hY%FK$X%1^Ho1=k+Z{Y@PQ%Wqm$y)a2y z1 zVGiO%1eJurZ93ov#o2R)29)203FugQY8+Y?=PkOhT{fY68z$M{)WtE=2(gho zC-i@bj&~QTAxE9XG1b@`*IfeP#R8p}4Zpimo0H7jSuDIT{ZIZ4>0BW+lruE zhR@8FGGEnLASb5GQ18BoJ(~}+_b^-Ck-Qy?qbl>P#c;idL!~6;zPdYkPoOqm!T+Qt z1vS}Thyu_+AhjJII6H6!y9 zHrxf&bQ-xR!hTN^2ao7ora^7~B9M6-r>((Mk0iIBl{9DOA>k?VW#6pv%*@acrs!}3 z4x8)Czqt)e8D&m@p@9N+gSWZ!l4{kA7?6aVXi&WN8KDkhtUt$lf{jr>LUYeTH zw0)!xKEANupi4R~fowD|>|VWC{aM-vf9eT1@he!;{)>mmJarc;f)^Oot98p@HdD@^ z#h<3I8ZbZhC61K&3c9t~K#2+>!b!e(JyVE=H4Us;NuCo=3{?I{Y;_)0UB7$$rBEO1pm{W8tqFOZAxPBA$(!=81h1!&s9O=WVcvmxQTN0S$3Hs7Tq*VBIUS`xC$#0 zeL)J7TedO@RULimC5%*ibsL?4O?a9(5D|Qh?f5Y`5nijeEJo~WP|D#+%jGkNc?I+S zZ;w%=hvrU1w4!4VA+angxQl?Z+@;@-Z57YpJ=pIkgq73+e@5`x`XT|cOLt?i+#0kyX}L9|ziwcx)I znGc{uAAvg@n!GY@r65et_#k!-kRMU=8#onxF<)eogVifvWtxYw$a^DuC>4EUU7Cg_J%BXL|{hAz80DuLe zz`hpY;AGtl=CH^+S!IY;!2q`?;FgRUu|Huk8F}HMB7?VawtCLUXZHc<#!}zXn><)j zU|qU2$}fw)=|*eX)~$iqL(I6|xI~t;##GK5#opQ^A>g(#H1e!eM}kUD_quzY^Gcw~ zJ40g*CK6AutX+zzd}`>eS$4V)bX8`N;ZnAb|(5f9+6e_+S6d1`$ zYz{o6%iCNw=d4?Q{mdGLh2e~QXKgTztc6eN?n!qQe%hSd9|$wF-AreJwC)(BXLf!(HemQ(;~x9h$;c2yuURR<&+y>CUOCzMTMY z)7$wx<5uLPduYp*=@{}hv~Mpb|0CbQ{J$}RUp30QM#?wsWy1^IQgNewY>~1|w0bkD zuy3OR24J;-L(bn79NafZS6dseX6h6}`hlxd^L|~%$J>n=Uzr`{t`RN;u_QI~W2F$+ z6P5qpwh`-mv*4qYYf)(Kb_K8USm@cb*UjfS)%zvOtEW+m)zh4yjMU10_DF5#L)WjT zO?x&D3TTdh=QuF8>c;nHv+l{y*UAlE5N5uOy+yQ{Z#nLW?CB>>)ZlYTD@KMJuiiJE$uX-dXkdWw3Q7MMbXl7j9?obmz9d24(zR|@p9MB zH2Lxjh1cN)9dh4ccRskB9`_)WW6vXIJQD%~#O9wK-`~=gjb$NA0Frcnz6}YZgyado z9DRlHSLHil&n-9#NSG_1+|z-ZN=&~!Gyk9oMGtAw%Q~}Tl3%p#&Tkp}dUrXwXPjRO z)hFGkt Date: Fri, 17 Jan 2025 15:45:16 +0100 Subject: [PATCH 04/13] Controllers quality fix-up --- .../CMakeLists.txt | 11 ++--- .../controller_inputs.hpp | 2 +- .../ctrl_vehicle_control_lat_compensatory.hpp | 16 +++---- ...vehicle_control_lat_compensatory.launch.py | 8 ++-- .../package.xml | 1 - .../ctrl_vehicle_control_lat_compensatory.cpp | 26 +++++------ .../CMakeLists.txt | 3 +- .../controller_inputs.hpp | 4 +- .../controller_outputs.hpp | 4 +- .../ctrl_vehicle_control_lat_pure_p.hpp | 16 +++---- .../ctrl_vehicle_control_lat_pure_p.launch.py | 8 ++-- .../package.xml | 1 - .../src/ctrl_vehicle_control_lat_pure_p.cpp | 38 +++++++--------- .../controller_inputs.hpp | 11 +++-- .../controller_outputs.hpp | 4 +- .../ctrl_vehicle_control_lat_stanley.hpp | 17 +++---- .../src/ctrl_vehicle_control_lat_stanley.cpp | 45 +++++++++---------- .../behaviorPlanner.hpp | 2 +- .../src/behaviorPlanner.cpp | 2 +- 19 files changed, 101 insertions(+), 118 deletions(-) diff --git a/crp_APL/controllers/ctrl_vehicle_control_lat_compensatory/CMakeLists.txt b/crp_APL/controllers/ctrl_vehicle_control_lat_compensatory/CMakeLists.txt index 6050c55c..d806f6e8 100644 --- a/crp_APL/controllers/ctrl_vehicle_control_lat_compensatory/CMakeLists.txt +++ b/crp_APL/controllers/ctrl_vehicle_control_lat_compensatory/CMakeLists.txt @@ -13,7 +13,6 @@ find_package(std_msgs REQUIRED) find_package(autoware_control_msgs REQUIRED) find_package(autoware_planning_msgs REQUIRED) find_package(autoware_vehicle_msgs REQUIRED) -find_package(nav_msgs REQUIRED) find_package(crp_msgs REQUIRED) @@ -24,13 +23,15 @@ add_executable(ctrl_vehicle_control_lat_compensatory src/ctrl_vehicle_control_la src/compensatory_model/compensatory_model.cpp src/lib/polynomialCalculator.cpp ) -ament_target_dependencies(ctrl_vehicle_control_lat_compensatory rclcpp geometry_msgs std_msgs autoware_control_msgs autoware_planning_msgs autoware_vehicle_msgs nav_msgs crp_msgs) +ament_target_dependencies(ctrl_vehicle_control_lat_compensatory rclcpp geometry_msgs std_msgs autoware_control_msgs autoware_planning_msgs autoware_vehicle_msgs crp_msgs) install(DIRECTORY launch - DESTINATION share/${PROJECT_NAME}) + DESTINATION share/${PROJECT_NAME} +) install(TARGETS -ctrl_vehicle_control_lat_compensatory - DESTINATION lib/${PROJECT_NAME}) + ctrl_vehicle_control_lat_compensatory + DESTINATION lib/${PROJECT_NAME} +) ament_package() diff --git a/crp_APL/controllers/ctrl_vehicle_control_lat_compensatory/include/ctrl_vehicle_control/controller_inputs.hpp b/crp_APL/controllers/ctrl_vehicle_control_lat_compensatory/include/ctrl_vehicle_control/controller_inputs.hpp index 8a037524..baa00919 100644 --- a/crp_APL/controllers/ctrl_vehicle_control_lat_compensatory/include/ctrl_vehicle_control/controller_inputs.hpp +++ b/crp_APL/controllers/ctrl_vehicle_control_lat_compensatory/include/ctrl_vehicle_control/controller_inputs.hpp @@ -15,7 +15,7 @@ namespace crp std::vector path_x; std::vector path_y; std::vector path_theta; - double target_speed{0.0f}; + double targetSpeed{0.0f}; double egoPoseGlobal [3]{0.0f}; double vxEgo{0.0f}; double egoSteeringAngle{0.0f}; diff --git a/crp_APL/controllers/ctrl_vehicle_control_lat_compensatory/include/ctrl_vehicle_control_lat_compensatory/ctrl_vehicle_control_lat_compensatory.hpp b/crp_APL/controllers/ctrl_vehicle_control_lat_compensatory/include/ctrl_vehicle_control_lat_compensatory/ctrl_vehicle_control_lat_compensatory.hpp index 78be5f6b..29eeb2c3 100644 --- a/crp_APL/controllers/ctrl_vehicle_control_lat_compensatory/include/ctrl_vehicle_control_lat_compensatory/ctrl_vehicle_control_lat_compensatory.hpp +++ b/crp_APL/controllers/ctrl_vehicle_control_lat_compensatory/include/ctrl_vehicle_control_lat_compensatory/ctrl_vehicle_control_lat_compensatory.hpp @@ -1,5 +1,5 @@ -#ifndef CRP_APL_CTRL_VEHICLE_LAT_COMPENSATORY_HPP -#define CRP_APL_CTRL_VEHICLE_LAT_COMPENSATORY_HPP +#ifndef CRP_APL_CTRL_VEHICLE_LAT_COMPENSATORY_CTRLVEHILECONTROLLATCOMPENSATORY_HPP +#define CRP_APL_CTRL_VEHICLE_LAT_COMPENSATORY_CTRLVEHILECONTROLLATCOMPENSATORY_HPP #include #include @@ -25,10 +25,10 @@ namespace crp { namespace apl { - class CtrlVehicleControlLat : public rclcpp::Node + class CtrlVehicleControlLatCompensatory : public rclcpp::Node { public: - CtrlVehicleControlLat(); + CtrlVehicleControlLatCompensatory(); private: // VARIABLES @@ -43,13 +43,13 @@ namespace crp void loop(); - rclcpp::TimerBase::SharedPtr timer_; + rclcpp::TimerBase::SharedPtr m_timer_; rclcpp::Publisher::SharedPtr m_pub_cmd; - rclcpp::Subscription::SharedPtr m_traj_sub_; - rclcpp::Subscription::SharedPtr m_egoVehicle_sub_; + rclcpp::Subscription::SharedPtr m_sub_traj_; + rclcpp::Subscription::SharedPtr m_sub_egoVehicle_; autoware_control_msgs::msg::Lateral m_ctrlCmdMsg; }; } // namespace apl } -#endif // CRP_APL_CTRL_VEHICLE_LAT_COMPENSATORY_HPP \ No newline at end of file +#endif // CRP_APL_CTRL_VEHICLE_LAT_COMPENSATORY_CTRLVEHILECONTROLLATCOMPENSATORY_HPP \ No newline at end of file diff --git a/crp_APL/controllers/ctrl_vehicle_control_lat_compensatory/launch/ctrl_vehicle_control_lat_compensatory.launch.py b/crp_APL/controllers/ctrl_vehicle_control_lat_compensatory/launch/ctrl_vehicle_control_lat_compensatory.launch.py index 9c9e3598..72847d55 100644 --- a/crp_APL/controllers/ctrl_vehicle_control_lat_compensatory/launch/ctrl_vehicle_control_lat_compensatory.launch.py +++ b/crp_APL/controllers/ctrl_vehicle_control_lat_compensatory/launch/ctrl_vehicle_control_lat_compensatory.launch.py @@ -2,8 +2,6 @@ from launch_ros.actions import Node def generate_launch_description(): - ld = LaunchDescription() - ctrl_vehicle_control_lat_compensatory = Node( package="ctrl_vehicle_control_lat_compensatory", executable="ctrl_vehicle_control_lat_compensatory", @@ -23,6 +21,6 @@ def generate_launch_description(): ] ) - ld.add_action(ctrl_vehicle_control_lat_compensatory) - - return ld \ No newline at end of file + return LaunchDescription([ + ctrl_vehicle_control_lat_compensatory + ]) \ No newline at end of file diff --git a/crp_APL/controllers/ctrl_vehicle_control_lat_compensatory/package.xml b/crp_APL/controllers/ctrl_vehicle_control_lat_compensatory/package.xml index 0b2ea145..0b03a0d9 100644 --- a/crp_APL/controllers/ctrl_vehicle_control_lat_compensatory/package.xml +++ b/crp_APL/controllers/ctrl_vehicle_control_lat_compensatory/package.xml @@ -19,7 +19,6 @@ autoware_control_msgs autoware_planning_msgs autoware_vehicle_msgs - nav_msgs crp_msgs diff --git a/crp_APL/controllers/ctrl_vehicle_control_lat_compensatory/src/ctrl_vehicle_control_lat_compensatory.cpp b/crp_APL/controllers/ctrl_vehicle_control_lat_compensatory/src/ctrl_vehicle_control_lat_compensatory.cpp index 45fb28f2..2bf7876b 100644 --- a/crp_APL/controllers/ctrl_vehicle_control_lat_compensatory/src/ctrl_vehicle_control_lat_compensatory.cpp +++ b/crp_APL/controllers/ctrl_vehicle_control_lat_compensatory/src/ctrl_vehicle_control_lat_compensatory.cpp @@ -1,16 +1,13 @@ #include -using namespace std::chrono_literals; -using std::placeholders::_1; - -crp::apl::CtrlVehicleControlLat::CtrlVehicleControlLat() : Node("CtrlVehicleControlLat") +crp::apl::CtrlVehicleControlLatCompensatory::CtrlVehicleControlLatCompensatory() : Node("CtrlVehicleControlLatCompensatory") { - timer_ = this->create_wall_timer(std::chrono::milliseconds(33), std::bind(&CtrlVehicleControlLat::loop, this)); + m_timer_ = this->create_wall_timer(std::chrono::milliseconds(33), std::bind(&CtrlVehicleControlLatCompensatory::loop, this)); m_pub_cmd = this->create_publisher("/control/command/control_cmdLat", 30); - m_traj_sub_ = this->create_subscription("/plan/trajectory", 10, std::bind(&CtrlVehicleControlLat::trajCallback, this, std::placeholders::_1)); - m_egoVehicle_sub_ = this->create_subscription("/ego", 10, std::bind(&CtrlVehicleControlLat::egoVehicleCallback, this, std::placeholders::_1)); + m_sub_traj_ = this->create_subscription("/plan/trajectory", 10, std::bind(&CtrlVehicleControlLatCompensatory::trajCallback, this, std::placeholders::_1)); + m_sub_egoVehicle_ = this->create_subscription("/ego", 10, std::bind(&CtrlVehicleControlLatCompensatory::egoVehicleCallback, this, std::placeholders::_1)); this->declare_parameter("/ctrl/ffLookAheadTime", 0.68f); this->declare_parameter("/ctrl/steeringAngleLPFilter", 0.2f); @@ -28,17 +25,16 @@ crp::apl::CtrlVehicleControlLat::CtrlVehicleControlLat() : Node("CtrlVehicleCont - RCLCPP_INFO(this->get_logger(), "ctrl_vehicle_control has been started"); + RCLCPP_INFO(this->get_logger(), "CtrlVehicleControlLatCompensatory has been started"); } -void crp::apl::CtrlVehicleControlLat::trajCallback(const autoware_planning_msgs::msg::Trajectory input_msg) +void crp::apl::CtrlVehicleControlLatCompensatory::trajCallback(const autoware_planning_msgs::msg::Trajectory input_msg) { m_input.path_x.clear(); m_input.path_y.clear(); m_input.path_theta.clear(); double quaternion[4]; - // this callback maps the input trajectory to the internal interface for (long unsigned int i=0; i 0) - m_input.target_speed = input_msg.points.at(0).longitudinal_velocity_mps; + m_input.targetSpeed = input_msg.points.at(0).longitudinal_velocity_mps; else - m_input.target_speed = 0.0f; + m_input.targetSpeed = 0.0f; } -void crp::apl::CtrlVehicleControlLat::egoVehicleCallback(const crp_msgs::msg::Ego input_msg) +void crp::apl::CtrlVehicleControlLatCompensatory::egoVehicleCallback(const crp_msgs::msg::Ego input_msg) { m_input.vxEgo = input_msg.twist.twist.linear.x; m_input.egoSteeringAngle = input_msg.tire_angle_front; @@ -73,7 +69,7 @@ void crp::apl::CtrlVehicleControlLat::egoVehicleCallback(const crp_msgs::msg::Eg m_input.egoPoseGlobal[2] = theta; } -void crp::apl::CtrlVehicleControlLat::loop() +void crp::apl::CtrlVehicleControlLatCompensatory::loop() { // parameter assignments m_params.ffLookAheadTime = this->get_parameter("/ctrl/ffLookAheadTime").as_double(); @@ -103,7 +99,7 @@ void crp::apl::CtrlVehicleControlLat::loop() int main(int argc, char *argv[]) { rclcpp::init(argc, argv); - rclcpp::spin(std::make_shared()); + rclcpp::spin(std::make_shared()); rclcpp::shutdown(); return 0; } \ No newline at end of file diff --git a/crp_APL/controllers/ctrl_vehicle_control_lat_pure_p/CMakeLists.txt b/crp_APL/controllers/ctrl_vehicle_control_lat_pure_p/CMakeLists.txt index f97fe852..2a40f31e 100644 --- a/crp_APL/controllers/ctrl_vehicle_control_lat_pure_p/CMakeLists.txt +++ b/crp_APL/controllers/ctrl_vehicle_control_lat_pure_p/CMakeLists.txt @@ -13,7 +13,6 @@ find_package(std_msgs REQUIRED) find_package(autoware_control_msgs REQUIRED) find_package(autoware_planning_msgs REQUIRED) find_package(autoware_vehicle_msgs REQUIRED) -find_package(nav_msgs REQUIRED) find_package(crp_msgs REQUIRED) @@ -22,7 +21,7 @@ include_directories(include) add_executable(ctrl_vehicle_control_lat_pure_p src/ctrl_vehicle_control_lat_pure_p.cpp) -ament_target_dependencies(ctrl_vehicle_control_lat_pure_p rclcpp geometry_msgs std_msgs autoware_control_msgs autoware_planning_msgs autoware_vehicle_msgs nav_msgs crp_msgs) +ament_target_dependencies(ctrl_vehicle_control_lat_pure_p rclcpp geometry_msgs std_msgs autoware_control_msgs autoware_planning_msgs autoware_vehicle_msgs crp_msgs) install(DIRECTORY launch DESTINATION share/${PROJECT_NAME}) diff --git a/crp_APL/controllers/ctrl_vehicle_control_lat_pure_p/include/ctrl_vehicle_control_lat_pure_p/controller_inputs.hpp b/crp_APL/controllers/ctrl_vehicle_control_lat_pure_p/include/ctrl_vehicle_control_lat_pure_p/controller_inputs.hpp index 86bbc4a7..f5803f3d 100644 --- a/crp_APL/controllers/ctrl_vehicle_control_lat_pure_p/include/ctrl_vehicle_control_lat_pure_p/controller_inputs.hpp +++ b/crp_APL/controllers/ctrl_vehicle_control_lat_pure_p/include/ctrl_vehicle_control_lat_pure_p/controller_inputs.hpp @@ -15,14 +15,14 @@ namespace crp std::vector m_path_x; std::vector m_path_y; std::vector m_path_theta; - double target_speed{0.0f}; + double targetSpeed{0.0f}; double egoPoseGlobal [3]{0.0f}; double vxEgo{0.0f}; double egoSteeringAngle{0.0f}; }; struct ControlParams{ - double lookahead_time{1.0f}; + double lookaheadTime{1.0f}; double wheelbase{2.9f}; }; } diff --git a/crp_APL/controllers/ctrl_vehicle_control_lat_pure_p/include/ctrl_vehicle_control_lat_pure_p/controller_outputs.hpp b/crp_APL/controllers/ctrl_vehicle_control_lat_pure_p/include/ctrl_vehicle_control_lat_pure_p/controller_outputs.hpp index 7887a47c..4e971005 100644 --- a/crp_APL/controllers/ctrl_vehicle_control_lat_pure_p/include/ctrl_vehicle_control_lat_pure_p/controller_outputs.hpp +++ b/crp_APL/controllers/ctrl_vehicle_control_lat_pure_p/include/ctrl_vehicle_control_lat_pure_p/controller_outputs.hpp @@ -11,8 +11,8 @@ namespace crp namespace apl { struct ControlOutput{ - double m_accelerationTarget{0.0f}; - double m_steeringAngleTarget{0.0f}; + double accelerationTarget{0.0f}; + double steeringAngleTarget{0.0f}; }; } } diff --git a/crp_APL/controllers/ctrl_vehicle_control_lat_pure_p/include/ctrl_vehicle_control_lat_pure_p/ctrl_vehicle_control_lat_pure_p.hpp b/crp_APL/controllers/ctrl_vehicle_control_lat_pure_p/include/ctrl_vehicle_control_lat_pure_p/ctrl_vehicle_control_lat_pure_p.hpp index ce1d1205..65b7eb39 100644 --- a/crp_APL/controllers/ctrl_vehicle_control_lat_pure_p/include/ctrl_vehicle_control_lat_pure_p/ctrl_vehicle_control_lat_pure_p.hpp +++ b/crp_APL/controllers/ctrl_vehicle_control_lat_pure_p/include/ctrl_vehicle_control_lat_pure_p/ctrl_vehicle_control_lat_pure_p.hpp @@ -1,5 +1,5 @@ -#ifndef CRP_APL_CTRL_VEHICLE_LAT_PURE_P_HPP -#define CRP_APL_CTRL_VEHICLE_LAT_PURE_P_HPP +#ifndef CRP_APL_CTRL_VEHICLE_CONTROL_LAT_PURE_P_CTRLVEHICLECONTROLLATPUREP_HPP +#define CRP_APL_CTRL_VEHICLE_CONTROL_LAT_PURE_P_CTRLVEHICLECONTROLLATPUREP_HPP #include #include @@ -23,10 +23,10 @@ namespace crp { namespace apl { - class CtrlVehicleControlLat : public rclcpp::Node + class CtrlVehicleControlLatPureP : public rclcpp::Node { public: - CtrlVehicleControlLat(); + CtrlVehicleControlLatPureP(); private: // VARIABLES @@ -40,13 +40,13 @@ namespace crp void pure_p_control(); void loop(); - rclcpp::TimerBase::SharedPtr timer_; + rclcpp::TimerBase::SharedPtr m_timer_; rclcpp::Publisher::SharedPtr m_pub_cmd; - rclcpp::Subscription::SharedPtr m_traj_sub_; - rclcpp::Subscription::SharedPtr m_egoVehicle_sub_; + rclcpp::Subscription::SharedPtr m_sub_traj_; + rclcpp::Subscription::SharedPtr m_sub_egoVehicle_; autoware_control_msgs::msg::Lateral m_ctrlCmdMsg; }; } // namespace apl } -#endif // CRP_APL_CTRL_VEHICLE_LAT_PURE_P_HPP \ No newline at end of file +#endif // CRP_APL_CTRL_VEHICLE_CONTROL_LAT_PURE_P_CTRLVEHICLECONTROLLATPUREP_HPP \ No newline at end of file diff --git a/crp_APL/controllers/ctrl_vehicle_control_lat_pure_p/launch/ctrl_vehicle_control_lat_pure_p.launch.py b/crp_APL/controllers/ctrl_vehicle_control_lat_pure_p/launch/ctrl_vehicle_control_lat_pure_p.launch.py index e2d04bfe..53950d3a 100644 --- a/crp_APL/controllers/ctrl_vehicle_control_lat_pure_p/launch/ctrl_vehicle_control_lat_pure_p.launch.py +++ b/crp_APL/controllers/ctrl_vehicle_control_lat_pure_p/launch/ctrl_vehicle_control_lat_pure_p.launch.py @@ -2,8 +2,6 @@ from launch_ros.actions import Node def generate_launch_description(): - ld = LaunchDescription() - ctrl_vehicle_control_lat_pure_p = Node( package="ctrl_vehicle_control_lat_pure_p", executable="ctrl_vehicle_control_lat_pure_p", @@ -13,6 +11,6 @@ def generate_launch_description(): ] ) - ld.add_action(ctrl_vehicle_control_lat_pure_p) - - return ld \ No newline at end of file + return LaunchDescription([ + ctrl_vehicle_control_lat_pure_p + ]) \ No newline at end of file diff --git a/crp_APL/controllers/ctrl_vehicle_control_lat_pure_p/package.xml b/crp_APL/controllers/ctrl_vehicle_control_lat_pure_p/package.xml index ea7bcfc6..69782b61 100644 --- a/crp_APL/controllers/ctrl_vehicle_control_lat_pure_p/package.xml +++ b/crp_APL/controllers/ctrl_vehicle_control_lat_pure_p/package.xml @@ -19,7 +19,6 @@ autoware_control_msgs autoware_planning_msgs autoware_vehicle_msgs - nav_msgs crp_msgs diff --git a/crp_APL/controllers/ctrl_vehicle_control_lat_pure_p/src/ctrl_vehicle_control_lat_pure_p.cpp b/crp_APL/controllers/ctrl_vehicle_control_lat_pure_p/src/ctrl_vehicle_control_lat_pure_p.cpp index 75b47baa..3338e3e9 100644 --- a/crp_APL/controllers/ctrl_vehicle_control_lat_pure_p/src/ctrl_vehicle_control_lat_pure_p.cpp +++ b/crp_APL/controllers/ctrl_vehicle_control_lat_pure_p/src/ctrl_vehicle_control_lat_pure_p.cpp @@ -1,28 +1,25 @@ #include -using namespace std::chrono_literals; -using std::placeholders::_1; - -crp::apl::CtrlVehicleControlLat::CtrlVehicleControlLat() : Node("CtrlVehicleControlLatPurePursuit") +crp::apl::CtrlVehicleControlLatPureP::CtrlVehicleControlLatPureP() : Node("CtrlVehicleControlLatPurePursuit") { - timer_ = this->create_wall_timer(std::chrono::milliseconds(33), std::bind(&CtrlVehicleControlLat::loop, this)); + m_timer_ = this->create_wall_timer(std::chrono::milliseconds(33), std::bind(&CtrlVehicleControlLatPureP::loop, this)); m_pub_cmd = this->create_publisher("/control/command/control_cmdLat", 30); - m_traj_sub_ = this->create_subscription("/plan/trajectory", 10, std::bind(&CtrlVehicleControlLat::trajCallback, this, std::placeholders::_1)); - m_egoVehicle_sub_ = this->create_subscription("/ego", 10, std::bind(&CtrlVehicleControlLat::egoVehicleCallback, this, std::placeholders::_1)); + m_sub_traj_ = this->create_subscription("/plan/trajectory", 10, std::bind(&CtrlVehicleControlLatPureP::trajCallback, this, std::placeholders::_1)); + m_sub_egoVehicle_ = this->create_subscription("/ego", 10, std::bind(&CtrlVehicleControlLatPureP::egoVehicleCallback, this, std::placeholders::_1)); this->declare_parameter("/ctrl/lookahead_time", 1.0f); this->declare_parameter("/ctrl/wheelbase", 2.7f); + RCLCPP_INFO(this->get_logger(), "CtrlVehicleControlLatPurePursuit has been started"); } -void crp::apl::CtrlVehicleControlLat::trajCallback(const autoware_planning_msgs::msg::Trajectory input_msg) +void crp::apl::CtrlVehicleControlLatPureP::trajCallback(const autoware_planning_msgs::msg::Trajectory input_msg) { m_input.m_path_x.clear(); m_input.m_path_y.clear(); - // this callback maps the input trajectory to the internal interface for (long unsigned int i=0; i 0) - m_input.target_speed = input_msg.points.at(0).longitudinal_velocity_mps; + m_input.targetSpeed = input_msg.points.at(0).longitudinal_velocity_mps; else - m_input.target_speed = 0.0f; - + m_input.targetSpeed = 0.0f; } -void crp::apl::CtrlVehicleControlLat::egoVehicleCallback(const crp_msgs::msg::Ego input_msg) +void crp::apl::CtrlVehicleControlLatPureP::egoVehicleCallback(const crp_msgs::msg::Ego input_msg) { m_input.vxEgo = input_msg.twist.twist.linear.x; m_input.egoSteeringAngle = input_msg.tire_angle_front; @@ -46,10 +42,9 @@ void crp::apl::CtrlVehicleControlLat::egoVehicleCallback(const crp_msgs::msg::Eg m_input.egoPoseGlobal[1] = input_msg.pose.pose.position.y; } -void crp::apl::CtrlVehicleControlLat::pure_p_control() +void crp::apl::CtrlVehicleControlLatPureP::pure_p_control() { - - float distance_to_index = std::max(m_input.vxEgo * m_params.lookahead_time, 2.0); + float distance_to_index = std::max(m_input.vxEgo * m_params.lookaheadTime, 2.0); float current_distance = 0.0f; int target_index = 0; @@ -68,14 +63,13 @@ void crp::apl::CtrlVehicleControlLat::pure_p_control() float alpha = atan2(m_input.m_path_y[target_index], m_input.m_path_x[target_index]); - m_output.m_steeringAngleTarget = atan2(2.0f * m_params.wheelbase * sin(alpha) / distance_to_index, 1); - + m_output.steeringAngleTarget = atan2(2.0f * m_params.wheelbase * sin(alpha) / distance_to_index, 1); } -void crp::apl::CtrlVehicleControlLat::loop() +void crp::apl::CtrlVehicleControlLatPureP::loop() { // parameter assignments - m_params.lookahead_time = this->get_parameter("/ctrl/lookahead_time").as_double(); + m_params.lookaheadTime = this->get_parameter("/ctrl/lookahead_time").as_double(); m_params.wheelbase = this->get_parameter("/ctrl/wheelbase").as_double(); // control algorithm @@ -84,7 +78,7 @@ void crp::apl::CtrlVehicleControlLat::loop() pure_p_control(); // steering angle and steering angle gradiant m_ctrlCmdMsg.stamp = this->now(); - m_ctrlCmdMsg.steering_tire_angle = m_output.m_steeringAngleTarget; + m_ctrlCmdMsg.steering_tire_angle = m_output.steeringAngleTarget; m_ctrlCmdMsg.steering_tire_rotation_rate = 0.0f; m_pub_cmd->publish(m_ctrlCmdMsg); @@ -95,7 +89,7 @@ void crp::apl::CtrlVehicleControlLat::loop() int main(int argc, char *argv[]) { rclcpp::init(argc, argv); - rclcpp::spin(std::make_shared()); + rclcpp::spin(std::make_shared()); rclcpp::shutdown(); return 0; } \ No newline at end of file diff --git a/crp_APL/controllers/ctrl_vehicle_control_lat_stanley/include/ctrl_vehicle_control_lat_stanley/controller_inputs.hpp b/crp_APL/controllers/ctrl_vehicle_control_lat_stanley/include/ctrl_vehicle_control_lat_stanley/controller_inputs.hpp index 3f8feebb..4f8f28f2 100644 --- a/crp_APL/controllers/ctrl_vehicle_control_lat_stanley/include/ctrl_vehicle_control_lat_stanley/controller_inputs.hpp +++ b/crp_APL/controllers/ctrl_vehicle_control_lat_stanley/include/ctrl_vehicle_control_lat_stanley/controller_inputs.hpp @@ -1,7 +1,6 @@ #ifndef CONTROLLER_INPUTS_HPP_ #define CONTROLLER_INPUTS_HPP_ - #include #include #include @@ -15,14 +14,14 @@ namespace crp std::vector m_path_x; std::vector m_path_y; std::vector m_path_theta; - double m_target_speed{0.0f}; - double m_egoPoseGlobal [3]{0.0f}; - double m_vxEgo{0.0f}; - double m_egoSteeringAngle{0.0f}; + double targetSpeed{0.0f}; + double egoPoseGlobal [3]{0.0f}; + double vxEgo{0.0f}; + double egoSteeringAngle{0.0f}; }; struct ControlParams{ - double K_GAIN{0.5f}; + double k_gain{0.5f}; double wheelbase{2.9f}; }; } diff --git a/crp_APL/controllers/ctrl_vehicle_control_lat_stanley/include/ctrl_vehicle_control_lat_stanley/controller_outputs.hpp b/crp_APL/controllers/ctrl_vehicle_control_lat_stanley/include/ctrl_vehicle_control_lat_stanley/controller_outputs.hpp index 7887a47c..4e971005 100644 --- a/crp_APL/controllers/ctrl_vehicle_control_lat_stanley/include/ctrl_vehicle_control_lat_stanley/controller_outputs.hpp +++ b/crp_APL/controllers/ctrl_vehicle_control_lat_stanley/include/ctrl_vehicle_control_lat_stanley/controller_outputs.hpp @@ -11,8 +11,8 @@ namespace crp namespace apl { struct ControlOutput{ - double m_accelerationTarget{0.0f}; - double m_steeringAngleTarget{0.0f}; + double accelerationTarget{0.0f}; + double steeringAngleTarget{0.0f}; }; } } diff --git a/crp_APL/controllers/ctrl_vehicle_control_lat_stanley/include/ctrl_vehicle_control_lat_stanley/ctrl_vehicle_control_lat_stanley.hpp b/crp_APL/controllers/ctrl_vehicle_control_lat_stanley/include/ctrl_vehicle_control_lat_stanley/ctrl_vehicle_control_lat_stanley.hpp index 36e13c4c..7332c85f 100644 --- a/crp_APL/controllers/ctrl_vehicle_control_lat_stanley/include/ctrl_vehicle_control_lat_stanley/ctrl_vehicle_control_lat_stanley.hpp +++ b/crp_APL/controllers/ctrl_vehicle_control_lat_stanley/include/ctrl_vehicle_control_lat_stanley/ctrl_vehicle_control_lat_stanley.hpp @@ -1,5 +1,5 @@ -#ifndef CRP_APL_CTRL_VEHICLE_LAT_STANLEY_HPP -#define CRP_APL_CTRL_VEHICLE_LAT_STANLEY_HPP +#ifndef CRP_APL_CTRL_VEHICLE_LAT_STANLEY_CTRLVEHICLECONTROLLATSTANLEY_HPP +#define CRP_APL_CTRL_VEHICLE_LAT_STANLEY_CTRLVEHICLECONTROLLATSTANLEY_HPP #include #include @@ -19,14 +19,15 @@ #include "ctrl_vehicle_control_lat_stanley/controller_inputs.hpp" #include "ctrl_vehicle_control_lat_stanley/controller_outputs.hpp" + namespace crp { namespace apl { - class CtrlVehicleControlLat : public rclcpp::Node + class CtrlVehicleControlLatStanley : public rclcpp::Node { public: - CtrlVehicleControlLat(); + CtrlVehicleControlLatStanley(); private: // VARIABLES @@ -41,13 +42,13 @@ namespace crp void stanleyControl(); void loop(); - rclcpp::TimerBase::SharedPtr timer_; + rclcpp::TimerBase::SharedPtr m_timer_; rclcpp::Publisher::SharedPtr m_pub_cmd_; - rclcpp::Subscription::SharedPtr m_traj_sub_; - rclcpp::Subscription::SharedPtr m_egoVehicle_sub_; + rclcpp::Subscription::SharedPtr m_sub_traj_; + rclcpp::Subscription::SharedPtr m_sub_egoVehicle_; autoware_control_msgs::msg::Lateral m_ctrlCmdMsg; }; } // namespace apl } -#endif // CRP_APL_CTRL_VEHICLE_LAT_STANLEY_HPP \ No newline at end of file +#endif // CRP_APL_CTRL_VEHICLE_LAT_STANLEY_CTRLVEHICLECONTROLLATSTANLEY_HPP \ No newline at end of file diff --git a/crp_APL/controllers/ctrl_vehicle_control_lat_stanley/src/ctrl_vehicle_control_lat_stanley.cpp b/crp_APL/controllers/ctrl_vehicle_control_lat_stanley/src/ctrl_vehicle_control_lat_stanley.cpp index 564bdd16..10ee52e1 100644 --- a/crp_APL/controllers/ctrl_vehicle_control_lat_stanley/src/ctrl_vehicle_control_lat_stanley.cpp +++ b/crp_APL/controllers/ctrl_vehicle_control_lat_stanley/src/ctrl_vehicle_control_lat_stanley.cpp @@ -4,26 +4,25 @@ using namespace std::chrono_literals; using std::placeholders::_1; -crp::apl::CtrlVehicleControlLat::CtrlVehicleControlLat() : Node("CtrlVehicleControlLatStanley") +crp::apl::CtrlVehicleControlLatStanley::CtrlVehicleControlLatStanley() : Node("CtrlVehicleControlLatStanley") { - timer_ = this->create_wall_timer(std::chrono::milliseconds(33), std::bind(&CtrlVehicleControlLat::loop, this)); + m_timer_ = this->create_wall_timer(std::chrono::milliseconds(33), std::bind(&CtrlVehicleControlLatStanley::loop, this)); m_pub_cmd_ = this->create_publisher("/control/command/control_cmdLat", 30); - m_traj_sub_ = this->create_subscription("/plan/trajectory", 10, std::bind(&CtrlVehicleControlLat::trajCallback, this, std::placeholders::_1)); - m_egoVehicle_sub_ = this->create_subscription("/ego", 10, std::bind(&CtrlVehicleControlLat::egoVehicleCallback, this, std::placeholders::_1)); + m_sub_traj_ = this->create_subscription("/plan/trajectory", 10, std::bind(&CtrlVehicleControlLatStanley::trajCallback, this, std::placeholders::_1)); + m_sub_egoVehicle_ = this->create_subscription("/ego", 10, std::bind(&CtrlVehicleControlLatStanley::egoVehicleCallback, this, std::placeholders::_1)); this->declare_parameter("/ctrl/k_gain", 0.5f); this->declare_parameter("/ctrl/wheelbase", 2.7f); - RCLCPP_INFO(this->get_logger(), "ctrl_vehicle_control has been started"); + RCLCPP_INFO(this->get_logger(), "CtrlVehicleControlLatStanley has been started"); } -void crp::apl::CtrlVehicleControlLat::trajCallback(const autoware_planning_msgs::msg::Trajectory input_msg) +void crp::apl::CtrlVehicleControlLatStanley::trajCallback(const autoware_planning_msgs::msg::Trajectory input_msg) { m_input.m_path_x.clear(); m_input.m_path_y.clear(); - // this callback maps the input trajectory to the internal interface for (long unsigned int i=0; i 0) - m_input.m_target_speed = input_msg.points.at(0).longitudinal_velocity_mps; + m_input.targetSpeed = input_msg.points.at(0).longitudinal_velocity_mps; else - m_input.m_target_speed = 0.0f; + m_input.targetSpeed = 0.0f; } -void crp::apl::CtrlVehicleControlLat::egoVehicleCallback(const crp_msgs::msg::Ego input_msg) +void crp::apl::CtrlVehicleControlLatStanley::egoVehicleCallback(const crp_msgs::msg::Ego input_msg) { - m_input.m_vxEgo = input_msg.twist.twist.linear.x; - m_input.m_egoSteeringAngle = input_msg.tire_angle_front; + m_input.vxEgo = input_msg.twist.twist.linear.x; + m_input.egoSteeringAngle = input_msg.tire_angle_front; - m_input.m_egoPoseGlobal[0] = input_msg.pose.pose.position.x; - m_input.m_egoPoseGlobal[1] = input_msg.pose.pose.position.y; + m_input.egoPoseGlobal[0] = input_msg.pose.pose.position.x; + m_input.egoPoseGlobal[1] = input_msg.pose.pose.position.y; } -void crp::apl::CtrlVehicleControlLat::error_calculation(double &lateral_error, double &heading_error) +void crp::apl::CtrlVehicleControlLatStanley::error_calculation(double &lateral_error, double &heading_error) { // calculate the front axle error float front_axle_error = 0.0f; @@ -86,28 +85,28 @@ void crp::apl::CtrlVehicleControlLat::error_calculation(double &lateral_error, d } -void crp::apl::CtrlVehicleControlLat::stanleyControl() +void crp::apl::CtrlVehicleControlLatStanley::stanleyControl() { // implement the stanley control algorithm // calculate the steering angle - m_output.m_steeringAngleTarget = 0.0f; + m_output.steeringAngleTarget = 0.0f; double front_axle_error = 0.0; double theta_e = 0.0; error_calculation(front_axle_error, theta_e); - float theta_d = atan2(m_params.K_GAIN * front_axle_error, m_input.m_vxEgo); + float theta_d = atan2(m_params.k_gain * front_axle_error, m_input.vxEgo); - m_output.m_steeringAngleTarget = theta_e + theta_d; + m_output.steeringAngleTarget = theta_e + theta_d; } -void crp::apl::CtrlVehicleControlLat::loop() +void crp::apl::CtrlVehicleControlLatStanley::loop() { // parameter assignments - m_params.K_GAIN= this->get_parameter("/ctrl/k_gain").as_double(); + m_params.k_gain= this->get_parameter("/ctrl/k_gain").as_double(); m_params.wheelbase = this->get_parameter("/ctrl/wheelbase").as_double(); // control algorithm @@ -117,7 +116,7 @@ void crp::apl::CtrlVehicleControlLat::loop() // steering angle and steering angle gradiant m_ctrlCmdMsg.stamp = this->now(); - m_ctrlCmdMsg.steering_tire_angle = m_output.m_steeringAngleTarget; + m_ctrlCmdMsg.steering_tire_angle = m_output.steeringAngleTarget; m_ctrlCmdMsg.steering_tire_rotation_rate = 0.0f; m_pub_cmd_->publish(m_ctrlCmdMsg); @@ -128,7 +127,7 @@ void crp::apl::CtrlVehicleControlLat::loop() int main(int argc, char *argv[]) { rclcpp::init(argc, argv); - rclcpp::spin(std::make_shared()); + rclcpp::spin(std::make_shared()); rclcpp::shutdown(); return 0; } \ No newline at end of file diff --git a/crp_APL/plan_behavior_planning/include/plan_behavior_planning/behaviorPlanner.hpp b/crp_APL/plan_behavior_planning/include/plan_behavior_planning/behaviorPlanner.hpp index dc343ad9..b306a835 100644 --- a/crp_APL/plan_behavior_planning/include/plan_behavior_planning/behaviorPlanner.hpp +++ b/crp_APL/plan_behavior_planning/include/plan_behavior_planning/behaviorPlanner.hpp @@ -34,7 +34,7 @@ class BehaviorPlanner : public rclcpp::Node rclcpp::Publisher::SharedPtr m_pub_strategy; rclcpp::Publisher::SharedPtr m_pub_target_space; - rclcpp::TimerBase::SharedPtr timer_; + rclcpp::TimerBase::SharedPtr m_timer_; float m_maximum_speed; }; diff --git a/crp_APL/plan_behavior_planning/src/behaviorPlanner.cpp b/crp_APL/plan_behavior_planning/src/behaviorPlanner.cpp index 599e2e19..df279f97 100644 --- a/crp_APL/plan_behavior_planning/src/behaviorPlanner.cpp +++ b/crp_APL/plan_behavior_planning/src/behaviorPlanner.cpp @@ -17,7 +17,7 @@ crp::apl::BehaviorPlanner::BehaviorPlanner() : Node("behavior_planner") m_pub_strategy = this->create_publisher("plan/strategy", 10); m_pub_target_space = this->create_publisher("plan/target_space", 10); - timer_ = this->create_wall_timer(std::chrono::milliseconds(33), std::bind(&BehaviorPlanner::loop, this)); + m_timer_ = this->create_wall_timer(std::chrono::milliseconds(33), std::bind(&BehaviorPlanner::loop, this)); } From 54f2c05269f8a717e2a5582f67210a60f21e1f33 Mon Sep 17 00:00:00 2001 From: AnonymDavid Date: Mon, 20 Jan 2025 10:56:26 +0100 Subject: [PATCH 05/13] Controller qol update --- .../CMakeLists.txt | 5 +- .../ctrl_vehicle_control_lat_compensatory.hpp | 10 +-- .../package.xml | 3 - .../CMakeLists.txt | 5 +- .../ctrl_vehicle_control_lat_pure_p.hpp | 12 +--- .../package.xml | 3 - .../src/ctrl_vehicle_control_lat_pure_p.cpp | 6 +- .../CMakeLists.txt | 6 +- .../ctrl_vehicle_control_lat_stanley.hpp | 12 +--- ...ctrl_vehicle_control_lat_stanley.launch.py | 8 +-- .../package.xml | 4 -- .../src/ctrl_vehicle_control_lat_stanley.cpp | 22 +++--- .../ctrl_vehicle_control_long/CMakeLists.txt | 9 +-- .../include/ctrl_vehicle_control_long.hpp | 67 ++++++++----------- .../ctrl_vehicle_control_long.launch.py | 8 +-- .../ctrl_vehicle_control_long/package.xml | 7 +- .../src/ctrl_vehicle_control_long.cpp | 3 - crp_APL/ctrl_vehicle_control/CMakeLists.txt | 6 +- ...ehicle_control.hpp => control_handler.hpp} | 13 ++-- .../launch/ctrl_vehicle_control.launch.py | 10 ++- ...ehicle_control.cpp => control_handler.cpp} | 7 +- 21 files changed, 71 insertions(+), 155 deletions(-) rename crp_APL/ctrl_vehicle_control/include/ctrl_vehicle_control/{ctrl_vehicle_control.hpp => control_handler.hpp} (84%) rename crp_APL/ctrl_vehicle_control/src/{ctrl_vehicle_control.cpp => control_handler.cpp} (92%) diff --git a/crp_APL/controllers/ctrl_vehicle_control_lat_compensatory/CMakeLists.txt b/crp_APL/controllers/ctrl_vehicle_control_lat_compensatory/CMakeLists.txt index d806f6e8..be15ccc7 100644 --- a/crp_APL/controllers/ctrl_vehicle_control_lat_compensatory/CMakeLists.txt +++ b/crp_APL/controllers/ctrl_vehicle_control_lat_compensatory/CMakeLists.txt @@ -8,11 +8,8 @@ endif() # find dependencies find_package(ament_cmake REQUIRED) find_package(rclcpp REQUIRED) -find_package(geometry_msgs REQUIRED) -find_package(std_msgs REQUIRED) find_package(autoware_control_msgs REQUIRED) find_package(autoware_planning_msgs REQUIRED) -find_package(autoware_vehicle_msgs REQUIRED) find_package(crp_msgs REQUIRED) @@ -23,7 +20,7 @@ add_executable(ctrl_vehicle_control_lat_compensatory src/ctrl_vehicle_control_la src/compensatory_model/compensatory_model.cpp src/lib/polynomialCalculator.cpp ) -ament_target_dependencies(ctrl_vehicle_control_lat_compensatory rclcpp geometry_msgs std_msgs autoware_control_msgs autoware_planning_msgs autoware_vehicle_msgs crp_msgs) +ament_target_dependencies(ctrl_vehicle_control_lat_compensatory rclcpp autoware_control_msgs autoware_planning_msgs crp_msgs) install(DIRECTORY launch DESTINATION share/${PROJECT_NAME} diff --git a/crp_APL/controllers/ctrl_vehicle_control_lat_compensatory/include/ctrl_vehicle_control_lat_compensatory/ctrl_vehicle_control_lat_compensatory.hpp b/crp_APL/controllers/ctrl_vehicle_control_lat_compensatory/include/ctrl_vehicle_control_lat_compensatory/ctrl_vehicle_control_lat_compensatory.hpp index 29eeb2c3..b88f9054 100644 --- a/crp_APL/controllers/ctrl_vehicle_control_lat_compensatory/include/ctrl_vehicle_control_lat_compensatory/ctrl_vehicle_control_lat_compensatory.hpp +++ b/crp_APL/controllers/ctrl_vehicle_control_lat_compensatory/include/ctrl_vehicle_control_lat_compensatory/ctrl_vehicle_control_lat_compensatory.hpp @@ -1,20 +1,12 @@ #ifndef CRP_APL_CTRL_VEHICLE_LAT_COMPENSATORY_CTRLVEHILECONTROLLATCOMPENSATORY_HPP #define CRP_APL_CTRL_VEHICLE_LAT_COMPENSATORY_CTRLVEHILECONTROLLATCOMPENSATORY_HPP -#include -#include -#include -#include -#include + #include "rclcpp/rclcpp.hpp" -#include "geometry_msgs/msg/pose.hpp" -#include "std_msgs/msg/float32_multi_array.hpp" -#include "std_msgs/msg/float32.hpp" #include "crp_msgs/msg/ego.hpp" #include "autoware_control_msgs/msg/control.hpp" #include "autoware_planning_msgs/msg/trajectory.hpp" -#include "autoware_vehicle_msgs/msg/steering_report.hpp" #include "ctrl_vehicle_control/controller_inputs.hpp" #include "ctrl_vehicle_control/controller_outputs.hpp" diff --git a/crp_APL/controllers/ctrl_vehicle_control_lat_compensatory/package.xml b/crp_APL/controllers/ctrl_vehicle_control_lat_compensatory/package.xml index 0b03a0d9..724ef242 100644 --- a/crp_APL/controllers/ctrl_vehicle_control_lat_compensatory/package.xml +++ b/crp_APL/controllers/ctrl_vehicle_control_lat_compensatory/package.xml @@ -14,11 +14,8 @@ ament_lint_auto ament_lint_common rclcpp - geometry_msgs - std_msgs autoware_control_msgs autoware_planning_msgs - autoware_vehicle_msgs crp_msgs diff --git a/crp_APL/controllers/ctrl_vehicle_control_lat_pure_p/CMakeLists.txt b/crp_APL/controllers/ctrl_vehicle_control_lat_pure_p/CMakeLists.txt index 2a40f31e..81edb8cc 100644 --- a/crp_APL/controllers/ctrl_vehicle_control_lat_pure_p/CMakeLists.txt +++ b/crp_APL/controllers/ctrl_vehicle_control_lat_pure_p/CMakeLists.txt @@ -8,11 +8,8 @@ endif() # find dependencies find_package(ament_cmake REQUIRED) find_package(rclcpp REQUIRED) -find_package(geometry_msgs REQUIRED) -find_package(std_msgs REQUIRED) find_package(autoware_control_msgs REQUIRED) find_package(autoware_planning_msgs REQUIRED) -find_package(autoware_vehicle_msgs REQUIRED) find_package(crp_msgs REQUIRED) @@ -21,7 +18,7 @@ include_directories(include) add_executable(ctrl_vehicle_control_lat_pure_p src/ctrl_vehicle_control_lat_pure_p.cpp) -ament_target_dependencies(ctrl_vehicle_control_lat_pure_p rclcpp geometry_msgs std_msgs autoware_control_msgs autoware_planning_msgs autoware_vehicle_msgs crp_msgs) +ament_target_dependencies(ctrl_vehicle_control_lat_pure_p rclcpp autoware_control_msgs autoware_planning_msgs crp_msgs) install(DIRECTORY launch DESTINATION share/${PROJECT_NAME}) diff --git a/crp_APL/controllers/ctrl_vehicle_control_lat_pure_p/include/ctrl_vehicle_control_lat_pure_p/ctrl_vehicle_control_lat_pure_p.hpp b/crp_APL/controllers/ctrl_vehicle_control_lat_pure_p/include/ctrl_vehicle_control_lat_pure_p/ctrl_vehicle_control_lat_pure_p.hpp index 65b7eb39..316f877a 100644 --- a/crp_APL/controllers/ctrl_vehicle_control_lat_pure_p/include/ctrl_vehicle_control_lat_pure_p/ctrl_vehicle_control_lat_pure_p.hpp +++ b/crp_APL/controllers/ctrl_vehicle_control_lat_pure_p/include/ctrl_vehicle_control_lat_pure_p/ctrl_vehicle_control_lat_pure_p.hpp @@ -1,20 +1,12 @@ #ifndef CRP_APL_CTRL_VEHICLE_CONTROL_LAT_PURE_P_CTRLVEHICLECONTROLLATPUREP_HPP #define CRP_APL_CTRL_VEHICLE_CONTROL_LAT_PURE_P_CTRLVEHICLECONTROLLATPUREP_HPP -#include -#include -#include -#include -#include + #include "rclcpp/rclcpp.hpp" -#include "geometry_msgs/msg/pose.hpp" -#include "std_msgs/msg/float32_multi_array.hpp" -#include "std_msgs/msg/float32.hpp" -#include "crp_msgs/msg/ego.hpp" +#include "crp_msgs/msg/ego.hpp" #include "autoware_control_msgs/msg/control.hpp" #include "autoware_planning_msgs/msg/trajectory.hpp" -#include "autoware_vehicle_msgs/msg/steering_report.hpp" #include "ctrl_vehicle_control_lat_pure_p/controller_inputs.hpp" #include "ctrl_vehicle_control_lat_pure_p/controller_outputs.hpp" diff --git a/crp_APL/controllers/ctrl_vehicle_control_lat_pure_p/package.xml b/crp_APL/controllers/ctrl_vehicle_control_lat_pure_p/package.xml index 69782b61..d6580748 100644 --- a/crp_APL/controllers/ctrl_vehicle_control_lat_pure_p/package.xml +++ b/crp_APL/controllers/ctrl_vehicle_control_lat_pure_p/package.xml @@ -14,11 +14,8 @@ ament_lint_auto ament_lint_common rclcpp - geometry_msgs - std_msgs autoware_control_msgs autoware_planning_msgs - autoware_vehicle_msgs crp_msgs diff --git a/crp_APL/controllers/ctrl_vehicle_control_lat_pure_p/src/ctrl_vehicle_control_lat_pure_p.cpp b/crp_APL/controllers/ctrl_vehicle_control_lat_pure_p/src/ctrl_vehicle_control_lat_pure_p.cpp index 3338e3e9..f624523e 100644 --- a/crp_APL/controllers/ctrl_vehicle_control_lat_pure_p/src/ctrl_vehicle_control_lat_pure_p.cpp +++ b/crp_APL/controllers/ctrl_vehicle_control_lat_pure_p/src/ctrl_vehicle_control_lat_pure_p.cpp @@ -46,13 +46,13 @@ void crp::apl::CtrlVehicleControlLatPureP::pure_p_control() { float distance_to_index = std::max(m_input.vxEgo * m_params.lookaheadTime, 2.0); - float current_distance = 0.0f; + float currentDistance = 0.0f; int target_index = 0; for (int i = 0; i < m_input.m_path_x.size()-1; i++) { - current_distance += sqrt(pow(m_input.m_path_x.at(i+1) - m_input.m_path_x.at(i), 2) + pow(m_input.m_path_y.at(i+1) - m_input.m_path_y.at(i), 2)); - if (current_distance >= distance_to_index) + currentDistance += sqrt(pow(m_input.m_path_x.at(i+1) - m_input.m_path_x.at(i), 2) + pow(m_input.m_path_y.at(i+1) - m_input.m_path_y.at(i), 2)); + if (currentDistance >= distance_to_index) { target_index = i; break; diff --git a/crp_APL/controllers/ctrl_vehicle_control_lat_stanley/CMakeLists.txt b/crp_APL/controllers/ctrl_vehicle_control_lat_stanley/CMakeLists.txt index c4704ed9..f225616e 100644 --- a/crp_APL/controllers/ctrl_vehicle_control_lat_stanley/CMakeLists.txt +++ b/crp_APL/controllers/ctrl_vehicle_control_lat_stanley/CMakeLists.txt @@ -8,12 +8,8 @@ endif() # find dependencies find_package(ament_cmake REQUIRED) find_package(rclcpp REQUIRED) -find_package(geometry_msgs REQUIRED) -find_package(std_msgs REQUIRED) find_package(autoware_control_msgs REQUIRED) find_package(autoware_planning_msgs REQUIRED) -find_package(autoware_vehicle_msgs REQUIRED) -find_package(nav_msgs REQUIRED) find_package(crp_msgs REQUIRED) @@ -22,7 +18,7 @@ include_directories(include) add_executable(ctrl_vehicle_control_lat_stanley src/ctrl_vehicle_control_lat_stanley.cpp) -ament_target_dependencies(ctrl_vehicle_control_lat_stanley rclcpp geometry_msgs std_msgs autoware_control_msgs autoware_planning_msgs autoware_vehicle_msgs nav_msgs crp_msgs) +ament_target_dependencies(ctrl_vehicle_control_lat_stanley rclcpp autoware_control_msgs autoware_planning_msgs crp_msgs) install(DIRECTORY launch DESTINATION share/${PROJECT_NAME}) diff --git a/crp_APL/controllers/ctrl_vehicle_control_lat_stanley/include/ctrl_vehicle_control_lat_stanley/ctrl_vehicle_control_lat_stanley.hpp b/crp_APL/controllers/ctrl_vehicle_control_lat_stanley/include/ctrl_vehicle_control_lat_stanley/ctrl_vehicle_control_lat_stanley.hpp index 7332c85f..6be2ec5a 100644 --- a/crp_APL/controllers/ctrl_vehicle_control_lat_stanley/include/ctrl_vehicle_control_lat_stanley/ctrl_vehicle_control_lat_stanley.hpp +++ b/crp_APL/controllers/ctrl_vehicle_control_lat_stanley/include/ctrl_vehicle_control_lat_stanley/ctrl_vehicle_control_lat_stanley.hpp @@ -1,20 +1,12 @@ #ifndef CRP_APL_CTRL_VEHICLE_LAT_STANLEY_CTRLVEHICLECONTROLLATSTANLEY_HPP #define CRP_APL_CTRL_VEHICLE_LAT_STANLEY_CTRLVEHICLECONTROLLATSTANLEY_HPP -#include -#include -#include -#include -#include + #include "rclcpp/rclcpp.hpp" -#include "geometry_msgs/msg/pose.hpp" -#include "std_msgs/msg/float32_multi_array.hpp" -#include "std_msgs/msg/float32.hpp" -#include "crp_msgs/msg/ego.hpp" +#include "crp_msgs/msg/ego.hpp" #include "autoware_control_msgs/msg/control.hpp" #include "autoware_planning_msgs/msg/trajectory.hpp" -#include "autoware_vehicle_msgs/msg/steering_report.hpp" #include "ctrl_vehicle_control_lat_stanley/controller_inputs.hpp" #include "ctrl_vehicle_control_lat_stanley/controller_outputs.hpp" diff --git a/crp_APL/controllers/ctrl_vehicle_control_lat_stanley/launch/ctrl_vehicle_control_lat_stanley.launch.py b/crp_APL/controllers/ctrl_vehicle_control_lat_stanley/launch/ctrl_vehicle_control_lat_stanley.launch.py index 4e638933..e0d0b1bf 100644 --- a/crp_APL/controllers/ctrl_vehicle_control_lat_stanley/launch/ctrl_vehicle_control_lat_stanley.launch.py +++ b/crp_APL/controllers/ctrl_vehicle_control_lat_stanley/launch/ctrl_vehicle_control_lat_stanley.launch.py @@ -2,8 +2,6 @@ from launch_ros.actions import Node def generate_launch_description(): - ld = LaunchDescription() - ctrl_vehicle_control_lat_stanley = Node( package="ctrl_vehicle_control_lat_stanley", executable="ctrl_vehicle_control_lat_stanley", @@ -13,6 +11,6 @@ def generate_launch_description(): ] ) - ld.add_action(ctrl_vehicle_control_lat_stanley) - - return ld \ No newline at end of file + return LaunchDescription([ + ctrl_vehicle_control_lat_stanley + ]) diff --git a/crp_APL/controllers/ctrl_vehicle_control_lat_stanley/package.xml b/crp_APL/controllers/ctrl_vehicle_control_lat_stanley/package.xml index 69490aaf..785a6674 100644 --- a/crp_APL/controllers/ctrl_vehicle_control_lat_stanley/package.xml +++ b/crp_APL/controllers/ctrl_vehicle_control_lat_stanley/package.xml @@ -14,12 +14,8 @@ ament_lint_auto ament_lint_common rclcpp - geometry_msgs - std_msgs autoware_control_msgs autoware_planning_msgs - autoware_vehicle_msgs - nav_msgs crp_msgs diff --git a/crp_APL/controllers/ctrl_vehicle_control_lat_stanley/src/ctrl_vehicle_control_lat_stanley.cpp b/crp_APL/controllers/ctrl_vehicle_control_lat_stanley/src/ctrl_vehicle_control_lat_stanley.cpp index 10ee52e1..6136679a 100644 --- a/crp_APL/controllers/ctrl_vehicle_control_lat_stanley/src/ctrl_vehicle_control_lat_stanley.cpp +++ b/crp_APL/controllers/ctrl_vehicle_control_lat_stanley/src/ctrl_vehicle_control_lat_stanley.cpp @@ -1,8 +1,5 @@ #include -using namespace std::chrono_literals; -using std::placeholders::_1; - crp::apl::CtrlVehicleControlLatStanley::CtrlVehicleControlLatStanley() : Node("CtrlVehicleControlLatStanley") { @@ -46,11 +43,8 @@ void crp::apl::CtrlVehicleControlLatStanley::egoVehicleCallback(const crp_msgs:: m_input.egoPoseGlobal[1] = input_msg.pose.pose.position.y; } -void crp::apl::CtrlVehicleControlLatStanley::error_calculation(double &lateral_error, double &heading_error) +void crp::apl::CtrlVehicleControlLatStanley::error_calculation(double &lateralError, double &headingError) { - // calculate the front axle error - float front_axle_error = 0.0f; - float target_x = m_params.wheelbase; float target_y = 0; int ind = 0; @@ -68,7 +62,7 @@ void crp::apl::CtrlVehicleControlLatStanley::error_calculation(double &lateral_e } } - std::vector front_axle_vec = { + std::vector frontAxleVec = { -std::cos(M_PI / 2), // Use std::cos for cosine -std::sin(M_PI / 2) // Use std::sin for sine }; @@ -77,10 +71,10 @@ void crp::apl::CtrlVehicleControlLatStanley::error_calculation(double &lateral_e double dy = m_input.m_path_y[ind]; // Dot product calculation - lateral_error = dx * front_axle_vec[0] + dy * front_axle_vec[1]; + lateralError = dx * frontAxleVec[0] + dy * frontAxleVec[1]; // calculate the heading error - heading_error = atan2(m_input.m_path_y[ind], m_input.m_path_x[ind]); + headingError = atan2(m_input.m_path_y[ind], m_input.m_path_x[ind]); } @@ -92,12 +86,12 @@ void crp::apl::CtrlVehicleControlLatStanley::stanleyControl() // calculate the steering angle m_output.steeringAngleTarget = 0.0f; - double front_axle_error = 0.0; - double theta_e = 0.0; + double frontAxleError = 0.0f; + double theta_e = 0.0f; - error_calculation(front_axle_error, theta_e); + error_calculation(frontAxleError, theta_e); - float theta_d = atan2(m_params.k_gain * front_axle_error, m_input.vxEgo); + float theta_d = atan2(m_params.k_gain * frontAxleError, m_input.vxEgo); m_output.steeringAngleTarget = theta_e + theta_d; diff --git a/crp_APL/controllers/ctrl_vehicle_control_long/CMakeLists.txt b/crp_APL/controllers/ctrl_vehicle_control_long/CMakeLists.txt index e9e6bbde..085b6ccc 100644 --- a/crp_APL/controllers/ctrl_vehicle_control_long/CMakeLists.txt +++ b/crp_APL/controllers/ctrl_vehicle_control_long/CMakeLists.txt @@ -8,14 +8,9 @@ endif() # find dependencies find_package(ament_cmake REQUIRED) find_package(rclcpp REQUIRED) -find_package(geometry_msgs REQUIRED) -find_package(std_msgs REQUIRED) +find_package(crp_msgs REQUIRED) find_package(autoware_control_msgs REQUIRED) find_package(autoware_planning_msgs REQUIRED) -find_package(autoware_vehicle_msgs REQUIRED) -find_package(nav_msgs REQUIRED) -find_package(pacmod3_msgs REQUIRED) -find_package(crp_msgs REQUIRED) include_directories(include) @@ -23,7 +18,7 @@ include_directories(include) add_executable(ctrl_vehicle_control_long src/ctrl_vehicle_control_long.cpp) -ament_target_dependencies(ctrl_vehicle_control_long rclcpp geometry_msgs std_msgs autoware_control_msgs autoware_planning_msgs autoware_vehicle_msgs nav_msgs pacmod3_msgs crp_msgs) +ament_target_dependencies(ctrl_vehicle_control_long rclcpp autoware_control_msgs autoware_planning_msgs crp_msgs) install(DIRECTORY launch DESTINATION share/${PROJECT_NAME}) diff --git a/crp_APL/controllers/ctrl_vehicle_control_long/include/ctrl_vehicle_control_long.hpp b/crp_APL/controllers/ctrl_vehicle_control_long/include/ctrl_vehicle_control_long.hpp index 2d08bb69..9a91a94f 100644 --- a/crp_APL/controllers/ctrl_vehicle_control_long/include/ctrl_vehicle_control_long.hpp +++ b/crp_APL/controllers/ctrl_vehicle_control_long/include/ctrl_vehicle_control_long.hpp @@ -1,21 +1,12 @@ -#ifndef CRP_APL_CTRL_VEHICLE_CONTROL_LONG_HPP -#define CRP_APL_CTRL_VEHICLE_CONTROL_LONG_HPP - -#include -#include -#include -#include -#include +#ifndef CRP_APL_CTRL_VEHICLE_CONTROL_LONG_CTRLVEHICLECONTROLLONG_HPP +#define CRP_APL_CTRL_VEHICLE_CONTROL_LONG_CTRLVEHICLECONTROLLONG_HPP + + #include "rclcpp/rclcpp.hpp" -#include "geometry_msgs/msg/pose.hpp" -#include "geometry_msgs/msg/twist.hpp" -#include "std_msgs/msg/float32_multi_array.hpp" -#include "std_msgs/msg/float32.hpp" -#include "crp_msgs/msg/ego.hpp" +#include "crp_msgs/msg/ego.hpp" #include "autoware_control_msgs/msg/control.hpp" #include "autoware_planning_msgs/msg/trajectory.hpp" -#include "autoware_vehicle_msgs/msg/steering_report.hpp" namespace crp @@ -23,37 +14,37 @@ namespace crp namespace apl { - class CtrlVehicleControlLong : public rclcpp::Node - { - public: - CtrlVehicleControlLong(); + class CtrlVehicleControlLong : public rclcpp::Node + { + public: + CtrlVehicleControlLong(); - private: - void trajectoryCallback(const autoware_planning_msgs::msg::Trajectory::SharedPtr msg); - void egoCallback(const crp_msgs::msg::Ego::SharedPtr msg); - - void run(); + private: + void trajectoryCallback(const autoware_planning_msgs::msg::Trajectory::SharedPtr msg); + void egoCallback(const crp_msgs::msg::Ego::SharedPtr msg); + + void run(); - rclcpp::TimerBase::SharedPtr m_timer_; - rclcpp::Publisher::SharedPtr m_pub_control_; + rclcpp::TimerBase::SharedPtr m_timer_; + rclcpp::Publisher::SharedPtr m_pub_control_; - rclcpp::Subscription::SharedPtr m_sub_trajectory_; - rclcpp::Subscription::SharedPtr m_sub_ego_; - autoware_control_msgs::msg::Longitudinal m_ctrl_msg; + rclcpp::Subscription::SharedPtr m_sub_trajectory_; + rclcpp::Subscription::SharedPtr m_sub_ego_; + autoware_control_msgs::msg::Longitudinal m_ctrl_msg; - // member parameters - double p_axMax{0.0f}; - double p_axMin{0.0f}; - double p_jxMax{0.0f}; - double p_jxMin{0.0f}; - double p_speedControlLookAheadTime{0.0f}; + // member parameters + double p_axMax{0.0f}; + double p_axMin{0.0f}; + double p_jxMax{0.0f}; + double p_jxMin{0.0f}; + double p_speedControlLookAheadTime{0.0f}; - double dT = 0.033; // in seconds + double dT = 0.033; // in seconds - // member variables - double m_egoSpeed{0.0f}; // in m/s + // member variables + double m_egoSpeed{0.0f}; // in m/s }; } // namespace apl } // namespace crp -#endif // CRP_APL_CTRL_VEHICLE_CONTROL_LONG_HPP +#endif // CRP_APL_CTRL_VEHICLE_CONTROL_LONG_CTRLVEHICLECONTROLLONG_HPP diff --git a/crp_APL/controllers/ctrl_vehicle_control_long/launch/ctrl_vehicle_control_long.launch.py b/crp_APL/controllers/ctrl_vehicle_control_long/launch/ctrl_vehicle_control_long.launch.py index 19fd2c4d..d2e9ef3e 100644 --- a/crp_APL/controllers/ctrl_vehicle_control_long/launch/ctrl_vehicle_control_long.launch.py +++ b/crp_APL/controllers/ctrl_vehicle_control_long/launch/ctrl_vehicle_control_long.launch.py @@ -2,8 +2,6 @@ from launch_ros.actions import Node def generate_launch_description(): - ld = LaunchDescription() - ctrl_vehicle_control_long = Node( package="ctrl_vehicle_control_long", executable="ctrl_vehicle_control_long", @@ -16,6 +14,6 @@ def generate_launch_description(): ] ) - ld.add_action(ctrl_vehicle_control_long) - - return ld \ No newline at end of file + return LaunchDescription([ + ctrl_vehicle_control_long + ]) diff --git a/crp_APL/controllers/ctrl_vehicle_control_long/package.xml b/crp_APL/controllers/ctrl_vehicle_control_long/package.xml index f4915c7e..66b7fedc 100644 --- a/crp_APL/controllers/ctrl_vehicle_control_long/package.xml +++ b/crp_APL/controllers/ctrl_vehicle_control_long/package.xml @@ -14,14 +14,9 @@ ament_lint_auto ament_lint_common rclcpp - geometry_msgs - std_msgs + crp_msgs autoware_control_msgs autoware_planning_msgs - autoware_vehicle_msgs - nav_msgs - pacmod3_msgs - crp_msgs ament_cmake diff --git a/crp_APL/controllers/ctrl_vehicle_control_long/src/ctrl_vehicle_control_long.cpp b/crp_APL/controllers/ctrl_vehicle_control_long/src/ctrl_vehicle_control_long.cpp index 590d4a39..f5eb4078 100644 --- a/crp_APL/controllers/ctrl_vehicle_control_long/src/ctrl_vehicle_control_long.cpp +++ b/crp_APL/controllers/ctrl_vehicle_control_long/src/ctrl_vehicle_control_long.cpp @@ -1,8 +1,5 @@ #include "ctrl_vehicle_control_long.hpp" -using namespace std::chrono_literals; -using std::placeholders::_1; - crp::apl::CtrlVehicleControlLong::CtrlVehicleControlLong() : Node("CtrlVehicleControlLong") { diff --git a/crp_APL/ctrl_vehicle_control/CMakeLists.txt b/crp_APL/ctrl_vehicle_control/CMakeLists.txt index c283407d..bb6c5176 100644 --- a/crp_APL/ctrl_vehicle_control/CMakeLists.txt +++ b/crp_APL/ctrl_vehicle_control/CMakeLists.txt @@ -16,15 +16,15 @@ find_package(geometry_msgs REQUIRED) include_directories(include) -add_executable(ctrl_vehicle_control src/ctrl_vehicle_control.cpp) +add_executable(control_handler src/control_handler.cpp) -ament_target_dependencies(ctrl_vehicle_control rclcpp geometry_msgs std_msgs autoware_control_msgs pacmod3_msgs) +ament_target_dependencies(control_handler rclcpp geometry_msgs std_msgs autoware_control_msgs pacmod3_msgs) install(DIRECTORY launch DESTINATION share/${PROJECT_NAME}) install(TARGETS - ctrl_vehicle_control + control_handler DESTINATION lib/${PROJECT_NAME}) ament_package() diff --git a/crp_APL/ctrl_vehicle_control/include/ctrl_vehicle_control/ctrl_vehicle_control.hpp b/crp_APL/ctrl_vehicle_control/include/ctrl_vehicle_control/control_handler.hpp similarity index 84% rename from crp_APL/ctrl_vehicle_control/include/ctrl_vehicle_control/ctrl_vehicle_control.hpp rename to crp_APL/ctrl_vehicle_control/include/ctrl_vehicle_control/control_handler.hpp index 1765815e..5ea56a44 100644 --- a/crp_APL/ctrl_vehicle_control/include/ctrl_vehicle_control/ctrl_vehicle_control.hpp +++ b/crp_APL/ctrl_vehicle_control/include/ctrl_vehicle_control/control_handler.hpp @@ -1,12 +1,8 @@ -#ifndef CRP_APL_CTRL_VEHICLE_CONTROL_HPP -#define CRP_APL_CTRL_VEHICLE_CONTROL_HPP +#ifndef CRP_APL_CTRL_CONTROL_HANDLER_CTRLVEHICLECONTROL_HPP +#define CRP_APL_CTRL_CONTROL_HANDLER_CTRLVEHICLECONTROL_HPP + #include -#include -#include -#include -#include -#include #include "autoware_control_msgs/msg/control.hpp" #include "geometry_msgs/msg/twist.hpp" @@ -26,6 +22,7 @@ namespace crp void controlLongCallback(const autoware_control_msgs::msg::Longitudinal::SharedPtr msg); void run(); + rclcpp::Subscription::SharedPtr m_sub_controlLat_; rclcpp::Subscription::SharedPtr m_sub_controlLong_; @@ -41,4 +38,4 @@ namespace crp } // namespace apl } // namespace crp -#endif // CRP_APL_CTRL_VEHICLE_CONTROL_HPP +#endif // CRP_APL_CTRL_CONTROL_HANDLER_CTRLVEHICLECONTROL_HPP diff --git a/crp_APL/ctrl_vehicle_control/launch/ctrl_vehicle_control.launch.py b/crp_APL/ctrl_vehicle_control/launch/ctrl_vehicle_control.launch.py index cd2d824c..5697bbbf 100644 --- a/crp_APL/ctrl_vehicle_control/launch/ctrl_vehicle_control.launch.py +++ b/crp_APL/ctrl_vehicle_control/launch/ctrl_vehicle_control.launch.py @@ -2,13 +2,11 @@ from launch_ros.actions import Node def generate_launch_description(): - ld = LaunchDescription() - ctrl_vehicle_control = Node( package="ctrl_vehicle_control", - executable="ctrl_vehicle_control" + executable="control_handler" ) - ld.add_action(ctrl_vehicle_control) - - return ld \ No newline at end of file + return LaunchDescription([ + ctrl_vehicle_control + ]) diff --git a/crp_APL/ctrl_vehicle_control/src/ctrl_vehicle_control.cpp b/crp_APL/ctrl_vehicle_control/src/control_handler.cpp similarity index 92% rename from crp_APL/ctrl_vehicle_control/src/ctrl_vehicle_control.cpp rename to crp_APL/ctrl_vehicle_control/src/control_handler.cpp index 7df3da9b..39fa2bab 100644 --- a/crp_APL/ctrl_vehicle_control/src/ctrl_vehicle_control.cpp +++ b/crp_APL/ctrl_vehicle_control/src/control_handler.cpp @@ -1,7 +1,4 @@ -#include "ctrl_vehicle_control/ctrl_vehicle_control.hpp" - -using namespace std::chrono_literals; -using std::placeholders::_1; +#include "ctrl_vehicle_control/control_handler.hpp" crp::apl::ControlHandler::ControlHandler() : Node("ControlHandler") @@ -13,7 +10,7 @@ crp::apl::ControlHandler::ControlHandler() : Node("ControlHandler") m_sub_controlLat_ = this->create_subscription("/control/command/control_cmdLat", 10, std::bind(&ControlHandler::controlLatCallback, this, std::placeholders::_1)); m_sub_controlLong_ = this->create_subscription("/control/command/control_cmdLong", 10, std::bind(&ControlHandler::controlLongCallback, this, std::placeholders::_1)); - RCLCPP_INFO(this->get_logger(), "ctrl_vehicle_control has been started"); + RCLCPP_INFO(this->get_logger(), "control_handler has been started"); // initialize control message From efaa15316efaba9366a7c070b17509861ffe62a5 Mon Sep 17 00:00:00 2001 From: AnonymDavid Date: Mon, 20 Jan 2025 13:12:24 +0100 Subject: [PATCH 06/13] APL code QoL --- .../launch/lat_lon_control_lqr.launch.py | 6 +- crp_APL/plan_behavior_planning/CMakeLists.txt | 2 +- .../behaviorPlanner.hpp | 9 +- .../plan_behavior_planning/missionPlanner.hpp | 8 +- .../launch/behavior_planning.launch.py | 12 +-- .../src/behaviorPlanner.cpp | 8 +- .../plan_motion_planning/motionHandler.hpp | 4 +- .../src/motionHandler.cpp | 4 +- .../include/wrapperPlanLatLaneFollowLdm.hpp | 10 +-- .../launch/plan_lat_lane_follow_ldm.launch.py | 7 +- .../src/wrapperPlanLatLaneFollowLdm.cpp | 88 +++++++++---------- .../wrapperPlanLonIntelligentSpeedAdjust.hpp | 6 +- ...lan_lon_intelligent_speed_adjust.launch.py | 7 +- crp_APL/planners/planner_base/CMakeLists.txt | 10 ++- .../include/planner_base/wrapperBase.hpp | 7 +- .../planners/planner_base/src/wrapperBase.cpp | 6 +- crp_APL/test/include/testNode/testNode.hpp | 27 +++--- crp_APL/test/launch/test_node.launch.py | 8 +- crp_VIL/lanelet_handler/package.xml | 4 +- crp_VIL/mcap_rec/package.xml | 4 +- 20 files changed, 121 insertions(+), 116 deletions(-) diff --git a/crp_APL/controllers/ctrl_vehicle_control_lqr/launch/lat_lon_control_lqr.launch.py b/crp_APL/controllers/ctrl_vehicle_control_lqr/launch/lat_lon_control_lqr.launch.py index fd315699..a1e682ae 100644 --- a/crp_APL/controllers/ctrl_vehicle_control_lqr/launch/lat_lon_control_lqr.launch.py +++ b/crp_APL/controllers/ctrl_vehicle_control_lqr/launch/lat_lon_control_lqr.launch.py @@ -2,8 +2,7 @@ from launch_ros.actions import Node def generate_launch_description(): - return LaunchDescription([ - Node( + ctrl_vehicle_control_lat_lqr = Node( package='ctrl_vehicle_control_lqr', executable='lqr_controller.py', name='lqr_controller', @@ -16,4 +15,7 @@ def generate_launch_description(): 'R': [10.0, 1.0], # R matrix diagonal elements }] ) + + return LaunchDescription([ + ctrl_vehicle_control_lat_lqr ]) \ No newline at end of file diff --git a/crp_APL/plan_behavior_planning/CMakeLists.txt b/crp_APL/plan_behavior_planning/CMakeLists.txt index 0a995aed..f4680b05 100644 --- a/crp_APL/plan_behavior_planning/CMakeLists.txt +++ b/crp_APL/plan_behavior_planning/CMakeLists.txt @@ -16,7 +16,7 @@ find_package(tier4_planning_msgs REQUIRED) include_directories(include) add_executable(mission_planner src/missionPlanner.cpp) -ament_target_dependencies(mission_planner rclcpp crp_msgs autoware_planning_msgs tier4_planning_msgs) +ament_target_dependencies(mission_planner rclcpp crp_msgs autoware_planning_msgs) add_executable(behavior_planner src/behaviorPlanner.cpp) ament_target_dependencies(behavior_planner rclcpp crp_msgs autoware_planning_msgs tier4_planning_msgs) diff --git a/crp_APL/plan_behavior_planning/include/plan_behavior_planning/behaviorPlanner.hpp b/crp_APL/plan_behavior_planning/include/plan_behavior_planning/behaviorPlanner.hpp index b306a835..191ff0a7 100644 --- a/crp_APL/plan_behavior_planning/include/plan_behavior_planning/behaviorPlanner.hpp +++ b/crp_APL/plan_behavior_planning/include/plan_behavior_planning/behaviorPlanner.hpp @@ -1,5 +1,6 @@ -#ifndef CRP_APL_BEHAVIORPLANNER_PLANBEHAVIORPLANNING_HPP -#define CRP_APL_BEHAVIORPLANNER_PLANBEHAVIORPLANNING_HPP +#ifndef CRP_APL_BEHAVIOR_PLANNER_PLANBEHAVIORPLANNING_HPP +#define CRP_APL_BEHAVIOR_PLANNER_PLANBEHAVIORPLANNING_HPP + #include #include @@ -32,7 +33,7 @@ class BehaviorPlanner : public rclcpp::Node rclcpp::Subscription::SharedPtr m_sub_behavior_; rclcpp::Publisher::SharedPtr m_pub_strategy; - rclcpp::Publisher::SharedPtr m_pub_target_space; + rclcpp::Publisher::SharedPtr m_pub_targetSpace; rclcpp::TimerBase::SharedPtr m_timer_; @@ -41,4 +42,4 @@ class BehaviorPlanner : public rclcpp::Node } // namespace apl } // namespace crp -#endif // CRP_APL_BEHAVIORPLANNER_PLANBEHAVIORPLANNING_HPP +#endif // CRP_APL_BEHAVIOR_PLANNER_PLANBEHAVIORPLANNING_HPP diff --git a/crp_APL/plan_behavior_planning/include/plan_behavior_planning/missionPlanner.hpp b/crp_APL/plan_behavior_planning/include/plan_behavior_planning/missionPlanner.hpp index 7d2c989a..7645f01e 100644 --- a/crp_APL/plan_behavior_planning/include/plan_behavior_planning/missionPlanner.hpp +++ b/crp_APL/plan_behavior_planning/include/plan_behavior_planning/missionPlanner.hpp @@ -1,11 +1,11 @@ -#ifndef CRP_APL_MISSIONPLANNER_PLANBEHAVIORPLANNING_HPP -#define CRP_APL_MISSIONPLANNER_PLANBEHAVIORPLANNING_HPP +#ifndef CRP_APL_MISSION_PLANNER_PLANBEHAVIORPLANNING_HPP +#define CRP_APL_MISSION_PLANNER_PLANBEHAVIORPLANNING_HPP + #include #include #include - namespace crp { namespace apl @@ -26,4 +26,4 @@ class MissionPlanner : public rclcpp::Node } // namespace apl } // namespace crp -#endif // CRP_APL_MISSIONPLANNER_PLANBEHAVIORPLANNING_HPP +#endif // CRP_APL_MISSION_PLANNER_PLANBEHAVIORPLANNING_HPP diff --git a/crp_APL/plan_behavior_planning/launch/behavior_planning.launch.py b/crp_APL/plan_behavior_planning/launch/behavior_planning.launch.py index 74c6283b..e4ee028b 100644 --- a/crp_APL/plan_behavior_planning/launch/behavior_planning.launch.py +++ b/crp_APL/plan_behavior_planning/launch/behavior_planning.launch.py @@ -4,13 +4,13 @@ from launch.substitutions import LaunchConfiguration def generate_launch_description(): - ld = LaunchDescription() - behavior_planner = Node( package="plan_behavior_planning", - executable="behavior_planner" + executable="behavior_planner", + name="behavior_planner", + output="screen", ) - ld.add_action(behavior_planner) - - return ld \ No newline at end of file + return LaunchDescription([ + behavior_planner + ]) diff --git a/crp_APL/plan_behavior_planning/src/behaviorPlanner.cpp b/crp_APL/plan_behavior_planning/src/behaviorPlanner.cpp index df279f97..ff49e287 100644 --- a/crp_APL/plan_behavior_planning/src/behaviorPlanner.cpp +++ b/crp_APL/plan_behavior_planning/src/behaviorPlanner.cpp @@ -15,7 +15,7 @@ crp::apl::BehaviorPlanner::BehaviorPlanner() : Node("behavior_planner") std::bind(&BehaviorPlanner::behaviorCallback, this, std::placeholders::_1)); m_pub_strategy = this->create_publisher("plan/strategy", 10); - m_pub_target_space = this->create_publisher("plan/target_space", 10); + m_pub_targetSpace = this->create_publisher("plan/target_space", 10); m_timer_ = this->create_wall_timer(std::chrono::milliseconds(33), std::bind(&BehaviorPlanner::loop, this)); } @@ -40,7 +40,7 @@ void crp::apl::BehaviorPlanner::scenarioCallback(const crp_msgs::msg::Scenario:: targetSpaceMsg.free_space = msg->free_space; - m_pub_target_space->publish(targetSpaceMsg); + m_pub_targetSpace->publish(targetSpaceMsg); } @@ -61,10 +61,10 @@ void crp::apl::BehaviorPlanner::behaviorCallback(const crp_msgs::msg::Behavior:: void crp::apl::BehaviorPlanner::loop() { // possible Scenrios: "off", "laneFollowWithDefaultSpeed", "", "laneFollow", "speedAdjust" - std::string current_scenario_msg = "laneFollowWithSpeedAdjust"; + std::string currentScenarioMsg = "laneFollowWithSpeedAdjust"; tier4_planning_msgs::msg::Scenario scenario_msg; - scenario_msg.current_scenario = current_scenario_msg; + scenario_msg.current_scenario = currentScenarioMsg; m_pub_strategy->publish(scenario_msg); diff --git a/crp_APL/plan_motion_planning/include/plan_motion_planning/motionHandler.hpp b/crp_APL/plan_motion_planning/include/plan_motion_planning/motionHandler.hpp index c18a7da0..ae0120ba 100644 --- a/crp_APL/plan_motion_planning/include/plan_motion_planning/motionHandler.hpp +++ b/crp_APL/plan_motion_planning/include/plan_motion_planning/motionHandler.hpp @@ -1,7 +1,9 @@ #ifndef CRP_APL_MOTION_HANDLER_PLANMOTIONPLANNING_HPP #define CRP_APL_MOTION_HANDLER_PLANMOTIONPLANNING_HPP + #include + #include #include #include @@ -42,7 +44,7 @@ class MotionHandler : public rclcpp::Node rclcpp::Subscription::SharedPtr m_sub_plan_latLaneFollow_; rclcpp::Subscription::SharedPtr m_sub_plan_lonEmergency_; rclcpp::Subscription::SharedPtr m_sub_plan_lonIntelligentSpeedAdjust_; - rclcpp::Publisher::SharedPtr m_pub_trajectory_viz_; + rclcpp::Publisher::SharedPtr m_pub_trajectoryViz_; rclcpp::Publisher::SharedPtr m_pub_trajectory_; diff --git a/crp_APL/plan_motion_planning/src/motionHandler.cpp b/crp_APL/plan_motion_planning/src/motionHandler.cpp index 24b3f777..15bec036 100644 --- a/crp_APL/plan_motion_planning/src/motionHandler.cpp +++ b/crp_APL/plan_motion_planning/src/motionHandler.cpp @@ -14,7 +14,7 @@ crp::apl::MotionHandler::MotionHandler() : Node("motion_handler") m_pub_trajectory_ = this->create_publisher("plan/trajectory", 10); - m_pub_trajectory_viz_ = this->create_publisher("plan/trajectoryVisualization", 10); + m_pub_trajectoryViz_ = this->create_publisher("plan/trajectoryVisualization", 10); m_timer_ = this->create_wall_timer(std::chrono::milliseconds(20), std::bind(&MotionHandler::run, this)); } @@ -328,7 +328,7 @@ void crp::apl::MotionHandler::visualizeTrajectory() marker.points.push_back(p); } - m_pub_trajectory_viz_->publish(marker); + m_pub_trajectoryViz_->publish(marker); return; diff --git a/crp_APL/planners/plan_lat_lane_follow_ldm/include/wrapperPlanLatLaneFollowLdm.hpp b/crp_APL/planners/plan_lat_lane_follow_ldm/include/wrapperPlanLatLaneFollowLdm.hpp index a56378ae..979e2902 100644 --- a/crp_APL/planners/plan_lat_lane_follow_ldm/include/wrapperPlanLatLaneFollowLdm.hpp +++ b/crp_APL/planners/plan_lat_lane_follow_ldm/include/wrapperPlanLatLaneFollowLdm.hpp @@ -1,5 +1,5 @@ -#ifndef CRP_APL_PLAN_LAT_LANE_FOLLOW_HANDLER_PLANLATLANEFOLLOW_HPP -#define CRP_APL_PLAN_LAT_LANE_FOLLOW_HANDLER_PLANLATLANEFOLLOW_HPP +#ifndef CRP_APL_PLAN_LAT_LANE_FOLLOW_LDM_HANDLER_PLANLATLANEFOLLOWLDM_HPP +#define CRP_APL_PLAN_LAT_LANE_FOLLOW_LDM_HANDLER_PLANLATLANEFOLLOWLDM_HPP #include "planner_base/wrapperBase.hpp" @@ -16,10 +16,10 @@ namespace crp namespace apl { -class PlanLatLaneFollowHandler : public WrapperBase +class PlanLatLaneFollowLdm : public WrapperBase { public: - PlanLatLaneFollowHandler(); + PlanLatLaneFollowLdm(); private: void plan(const PlannerInput & input, PlannerOutput & output) override; @@ -40,4 +40,4 @@ class PlanLatLaneFollowHandler : public WrapperBase } // namespace apl } // namespace crp -#endif // CRP_APL_PLAN_LAT_LANE_FOLLOW_HANDLER_PLANLATLANEFOLLOW_HPP +#endif // CRP_APL_PLAN_LAT_LANE_FOLLOW_LDM_HANDLER_PLANLATLANEFOLLOWLDM_HPP diff --git a/crp_APL/planners/plan_lat_lane_follow_ldm/launch/plan_lat_lane_follow_ldm.launch.py b/crp_APL/planners/plan_lat_lane_follow_ldm/launch/plan_lat_lane_follow_ldm.launch.py index 8f6a6e6b..399edb0f 100644 --- a/crp_APL/planners/plan_lat_lane_follow_ldm/launch/plan_lat_lane_follow_ldm.launch.py +++ b/crp_APL/planners/plan_lat_lane_follow_ldm/launch/plan_lat_lane_follow_ldm.launch.py @@ -1,6 +1,5 @@ from launch import LaunchDescription from launch_ros.actions import Node -from launch.actions import DeclareLaunchArgument, GroupAction, IncludeLaunchDescription def generate_launch_description(): # NODES @@ -25,9 +24,5 @@ def generate_launch_description(): ) return LaunchDescription([ - GroupAction( - actions=[ - plan_lat_lane_follow_ldm - ] - ) + plan_lat_lane_follow_ldm ]) \ No newline at end of file diff --git a/crp_APL/planners/plan_lat_lane_follow_ldm/src/wrapperPlanLatLaneFollowLdm.cpp b/crp_APL/planners/plan_lat_lane_follow_ldm/src/wrapperPlanLatLaneFollowLdm.cpp index 96aad9ae..d8b9e4d7 100644 --- a/crp_APL/planners/plan_lat_lane_follow_ldm/src/wrapperPlanLatLaneFollowLdm.cpp +++ b/crp_APL/planners/plan_lat_lane_follow_ldm/src/wrapperPlanLatLaneFollowLdm.cpp @@ -1,7 +1,7 @@ #include "wrapperPlanLatLaneFollowLdm.hpp" -crp::apl::PlanLatLaneFollowHandler::PlanLatLaneFollowHandler() : WrapperBase("plan_lat_lane_follow") +crp::apl::PlanLatLaneFollowLdm::PlanLatLaneFollowLdm() : WrapperBase("plan_lat_lane_follow_ldm") { this->declare_parameter>( "/plan_lat_lane_follow_ldm/nodePointDistances", std::vector{20.0f, 60.0f, 100.0f}); @@ -18,11 +18,11 @@ crp::apl::PlanLatLaneFollowHandler::PlanLatLaneFollowHandler() : WrapperBase("pl 0.0f, 0.5f, 0.0f, 0.0f, 0.0f, 0.5f}); this->declare_parameter( - "/plan_lat_lane_follow_ldm/pStraight", 0.0f); + "/plan_lat_lane_follow_ldm/pStraight", 0.0f); } -void crp::apl::PlanLatLaneFollowHandler::plan(const PlannerInput & input, PlannerOutput & output) +void crp::apl::PlanLatLaneFollowLdm::plan(const PlannerInput & input, PlannerOutput & output) { output.trajectory.clear(); // initialize the output at empty vector in the beginning of each cycle // TrajectoryPoint trajectoryPoint; @@ -132,7 +132,7 @@ void crp::apl::PlanLatLaneFollowHandler::plan(const PlannerInput & input, Planne } // method calculates the subsegments of the incoming trajectory based on a LDMParamIn type parameters struct -void crp::apl::PlanLatLaneFollowHandler::calculateNodePoints( +void crp::apl::PlanLatLaneFollowLdm::calculateNodePoints( const PlannerInput & input) { float distance{0.0f}; @@ -145,51 +145,51 @@ void crp::apl::PlanLatLaneFollowHandler::calculateNodePoints( for (uint8_t np=0U; np m_ldmParams.P_nodePointDistances[np]) { - distance = std::sqrt(std::pow(input.path.pathPoints.at(p).pose.position.x,2)+ - std::pow(input.path.pathPoints.at(p).pose.position.y,2)); - if (distance > m_ldmParams.P_nodePointDistances[np]) - { - startIdx = p; - break; - } - segmentPointsX.push_back(input.path.pathPoints.at(p).pose.position.x); - segmentPointsY.push_back(input.path.pathPoints.at(p).pose.position.y); - averageCurvatureBetweenNodepoints = ((p-startIdx)*averageCurvatureBetweenNodepoints+ - input.path.pathPoints.at(p).curvature)/(p-startIdx+1); - } - if (segmentPointsX.size() > 0U) - { - PolynomialCoeffs coeffs; - std::vector c = - m_polynomialRegressor.fitThirdOrderPolynomial(segmentPointsX,segmentPointsY); - coeffs.c0 = c.at(0U); - coeffs.c1 = c.at(1U); - coeffs.c2 = c.at(2U); - coeffs.c3 = c.at(3U); - - m_scenarioPolynomials.coeffs.push_back(coeffs); - m_scenarioPolynomials.kappaNominal.push_back(averageCurvatureBetweenNodepoints); - } - else - { - PolynomialCoeffs coeffs; - coeffs.c0 = 0.0f; - coeffs.c1 = 0.0f; - coeffs.c2 = 0.0f; - coeffs.c3 = 0.0f; - m_scenarioPolynomials.coeffs.push_back(coeffs); - m_scenarioPolynomials.kappaNominal.push_back(0.0f); + startIdx = p; + break; } + segmentPointsX.push_back(input.path.pathPoints.at(p).pose.position.x); + segmentPointsY.push_back(input.path.pathPoints.at(p).pose.position.y); + averageCurvatureBetweenNodepoints = ((p-startIdx)*averageCurvatureBetweenNodepoints+ + input.path.pathPoints.at(p).curvature)/(p-startIdx+1); + } + if (segmentPointsX.size() > 0U) + { + PolynomialCoeffs coeffs; + std::vector c = + m_polynomialRegressor.fitThirdOrderPolynomial(segmentPointsX,segmentPointsY); + coeffs.c0 = c.at(0U); + coeffs.c1 = c.at(1U); + coeffs.c2 = c.at(2U); + coeffs.c3 = c.at(3U); + + m_scenarioPolynomials.coeffs.push_back(coeffs); + m_scenarioPolynomials.kappaNominal.push_back(averageCurvatureBetweenNodepoints); } + else + { + PolynomialCoeffs coeffs; + coeffs.c0 = 0.0f; + coeffs.c1 = 0.0f; + coeffs.c2 = 0.0f; + coeffs.c3 = 0.0f; + m_scenarioPolynomials.coeffs.push_back(coeffs); + m_scenarioPolynomials.kappaNominal.push_back(0.0f); + } + } } -void crp::apl::PlanLatLaneFollowHandler::generateEgoPose( +void crp::apl::PlanLatLaneFollowLdm::generateEgoPose( const PlannerInput & input) { m_egoPose.Pose2DCoordinates.x = input.egoPose.position.x; @@ -201,7 +201,7 @@ void crp::apl::PlanLatLaneFollowHandler::generateEgoPose( int main(int argc, char * argv[]) { rclcpp::init(argc, argv); - rclcpp::spin(std::make_shared()); + rclcpp::spin(std::make_shared()); rclcpp::shutdown(); return 0; } diff --git a/crp_APL/planners/plan_lon_intelligent_speed_adjust/include/plan_lon_intelligent_speed_adjust/wrapperPlanLonIntelligentSpeedAdjust.hpp b/crp_APL/planners/plan_lon_intelligent_speed_adjust/include/plan_lon_intelligent_speed_adjust/wrapperPlanLonIntelligentSpeedAdjust.hpp index d449d4c6..d215767f 100644 --- a/crp_APL/planners/plan_lon_intelligent_speed_adjust/include/plan_lon_intelligent_speed_adjust/wrapperPlanLonIntelligentSpeedAdjust.hpp +++ b/crp_APL/planners/plan_lon_intelligent_speed_adjust/include/plan_lon_intelligent_speed_adjust/wrapperPlanLonIntelligentSpeedAdjust.hpp @@ -1,5 +1,5 @@ -#ifndef CRP_APL_WRAPPER_PLAN_LON_INTELLIGENT_SPEED_ADJUST_PLANLATLANEFOLLOW_HPP -#define CRP_APL_WRAPPER_PLAN_LON_INTELLIGENT_SPEED_ADJUST_PLANLATLANEFOLLOW_HPP +#ifndef CRP_APL_WRAPPER_PLAN_LON_INTELLIGENT_SPEED_ADJUST_PLANLONINTELLIGENTSPEEDADJUST_HPP +#define CRP_APL_WRAPPER_PLAN_LON_INTELLIGENT_SPEED_ADJUST_PLANLONINTELLIGENTSPEEDADJUST_HPP #include "planner_base/wrapperBase.hpp" #include "../../src/functionCode/inc/planLongitudinalTrajectory.hpp" @@ -23,4 +23,4 @@ class WrapperPlanLonIntelligentSpeedAdjust : public WrapperBase } // namespace apl } // namespace crp -#endif // CRP_APL_WRAPPER_PLAN_LON_INTELLIGENT_SPEED_ADJUST_PLANLATLANEFOLLOW_HPP +#endif // CRP_APL_WRAPPER_PLAN_LON_INTELLIGENT_SPEED_ADJUST_PLANLONINTELLIGENTSPEEDADJUST_HPP diff --git a/crp_APL/planners/plan_lon_intelligent_speed_adjust/launch/plan_lon_intelligent_speed_adjust.launch.py b/crp_APL/planners/plan_lon_intelligent_speed_adjust/launch/plan_lon_intelligent_speed_adjust.launch.py index 86f34cce..7b24f3ab 100644 --- a/crp_APL/planners/plan_lon_intelligent_speed_adjust/launch/plan_lon_intelligent_speed_adjust.launch.py +++ b/crp_APL/planners/plan_lon_intelligent_speed_adjust/launch/plan_lon_intelligent_speed_adjust.launch.py @@ -1,6 +1,5 @@ from launch import LaunchDescription from launch_ros.actions import Node -from launch.actions import DeclareLaunchArgument, GroupAction, IncludeLaunchDescription def generate_launch_description(): # NODES @@ -15,9 +14,5 @@ def generate_launch_description(): ) return LaunchDescription([ - GroupAction( - actions=[ - plan_lon_intelligent_speed_adjust - ] - ) + plan_lon_intelligent_speed_adjust ]) \ No newline at end of file diff --git a/crp_APL/planners/planner_base/CMakeLists.txt b/crp_APL/planners/planner_base/CMakeLists.txt index 5ee78356..768007ba 100644 --- a/crp_APL/planners/planner_base/CMakeLists.txt +++ b/crp_APL/planners/planner_base/CMakeLists.txt @@ -21,12 +21,20 @@ set ( ${CMAKE_SOURCE_DIR}/../../interfaces ) +set ( + UTILS_DIR + ${CMAKE_SOURCE_DIR}/../../crp_utils +) + include_directories( include ${INTERFACES_DIR} ) -include_directories(${CMAKE_CURRENT_SOURCE_DIR}/../../crp_utils) +include_directories( + include + ${UTILS_DIR} +) set(utils_source ${CMAKE_CURRENT_SOURCE_DIR}/../../crp_utils/geometryUtils/src/geometricPathCalculation.cpp) diff --git a/crp_APL/planners/planner_base/include/planner_base/wrapperBase.hpp b/crp_APL/planners/planner_base/include/planner_base/wrapperBase.hpp index f5e87b27..e57981f8 100644 --- a/crp_APL/planners/planner_base/include/planner_base/wrapperBase.hpp +++ b/crp_APL/planners/planner_base/include/planner_base/wrapperBase.hpp @@ -1,6 +1,7 @@ #ifndef CRP_APL_WRAPPER_BASE_PLANBASE_HPP #define CRP_APL_WRAPPER_BASE_PLANBASE_HPP + #include #include #include @@ -13,9 +14,9 @@ #include #include -#include "../../../interfaces/plannerInterfaces/plannerInterfaces.hpp" +#include "plannerInterfaces/plannerInterfaces.hpp" -#include "../../../crp_utils/geometryUtils/inc/geometricPathCalculation.hpp" +#include "geometryUtils/inc/geometricPathCalculation.hpp" namespace crp @@ -45,7 +46,7 @@ class WrapperBase : public rclcpp::Node void run(); rclcpp::Subscription::SharedPtr m_sub_strategy_; - rclcpp::Subscription::SharedPtr m_sub_target_space_; + rclcpp::Subscription::SharedPtr m_sub_targetSpace_; rclcpp::Subscription::SharedPtr m_sub_ego_; rclcpp::Publisher::SharedPtr m_pub_trajectory_; diff --git a/crp_APL/planners/planner_base/src/wrapperBase.cpp b/crp_APL/planners/planner_base/src/wrapperBase.cpp index f413f6ab..397480b3 100644 --- a/crp_APL/planners/planner_base/src/wrapperBase.cpp +++ b/crp_APL/planners/planner_base/src/wrapperBase.cpp @@ -6,13 +6,13 @@ crp::apl::WrapperBase::WrapperBase(const std::string & node_name, const rclcpp:: { m_sub_strategy_ = this->create_subscription( "plan/strategy", 10, std::bind(&WrapperBase::strategyCallback, this, std::placeholders::_1)); - m_sub_target_space_ = this->create_subscription( + m_sub_targetSpace_ = this->create_subscription( "plan/target_space", 10, std::bind(&WrapperBase::targetSpaceCallback, this, std::placeholders::_1)); m_sub_ego_ = this->create_subscription( "ego", 10, std::bind(&WrapperBase::egoCallback, this, std::placeholders::_1)); - std::string planner_name = node_name.substr(5, node_name.size()-5); - m_pub_trajectory_ = this->create_publisher("plan/"+planner_name+"/trajectory", 10); + std::string plannerName = node_name.substr(5, node_name.size()-5); + m_pub_trajectory_ = this->create_publisher("plan/"+plannerName+"/trajectory", 10); m_timer_ = this->create_wall_timer(std::chrono::milliseconds(20), std::bind(&WrapperBase::run, this)); } diff --git a/crp_APL/test/include/testNode/testNode.hpp b/crp_APL/test/include/testNode/testNode.hpp index 33444359..20f90704 100644 --- a/crp_APL/test/include/testNode/testNode.hpp +++ b/crp_APL/test/include/testNode/testNode.hpp @@ -1,22 +1,25 @@ -#ifndef CRP_APL_TEST_NODE_HPP -#define CRP_APL_TEST_NODE_HPP +#ifndef CRP_APL_TEST_NODE_TESTNODE_HPP +#define CRP_APL_TEST_NODE_TESTNODE_HPP + + +#include +#include #include #include -#include -#include "autoware_control_msgs/msg/control.hpp" -#include #include -#include - -#include -#include #include #include #include #include -#include + +#include +#include +#include +#include +#include + namespace crp { @@ -36,7 +39,7 @@ class TestNode : public rclcpp::Node // member methods void vehicleModel(); - float dT = 0.02; // model runs in 20ms + float dT = 0.02f; // model runs in 20ms float* globalToEgoTransform(float globalPose[3]); @@ -101,4 +104,4 @@ class TestNode : public rclcpp::Node } // namespace apl } // namespace crp -#endif // CRP_APL_TEST_NODE_HPP +#endif // CRP_APL_TEST_NODE_TESTNODE_HPP diff --git a/crp_APL/test/launch/test_node.launch.py b/crp_APL/test/launch/test_node.launch.py index 0056210a..024e4446 100644 --- a/crp_APL/test/launch/test_node.launch.py +++ b/crp_APL/test/launch/test_node.launch.py @@ -5,11 +5,11 @@ def generate_launch_description(): maximumSpeedInit_arg = DeclareLaunchArgument( - '/test/maximumSpeedInit', default_value=TextSubstitution(text='20.0') + '/test/maximumSpeedInit', default_value=TextSubstitution(text='20.0') ) previewDistance_arg = DeclareLaunchArgument( - '/test/previewDistance', default_value=TextSubstitution(text='100.0') + '/test/previewDistance', default_value=TextSubstitution(text='100.0') ) test_node = Node( @@ -20,7 +20,7 @@ def generate_launch_description(): parameters=[{ '/test/maximumSpeedInit': LaunchConfiguration('/test/maximumSpeedInit'), '/test/previewDistance': LaunchConfiguration('/test/previewDistance') - }] + }] ) return LaunchDescription([ @@ -28,5 +28,3 @@ def generate_launch_description(): previewDistance_arg, test_node ]) - - return ld \ No newline at end of file diff --git a/crp_VIL/lanelet_handler/package.xml b/crp_VIL/lanelet_handler/package.xml index 1bcdd4c2..8eded1e4 100644 --- a/crp_VIL/lanelet_handler/package.xml +++ b/crp_VIL/lanelet_handler/package.xml @@ -4,8 +4,8 @@ lanelet_handler 0.0.0 TODO: Package description - david - TODO: License declaration + AnonymDavid + Apache License 2.0 ament_cmake diff --git a/crp_VIL/mcap_rec/package.xml b/crp_VIL/mcap_rec/package.xml index ad44ffb9..1d271692 100644 --- a/crp_VIL/mcap_rec/package.xml +++ b/crp_VIL/mcap_rec/package.xml @@ -4,8 +4,8 @@ mcap_rec 0.0.0 TODO: Package description - david - TODO: License declaration + AnonymDavid + Apache License 2.0 ament_cmake From f145cce9b5e6f94f2e70b330d3a6f996dd2d1c9c Mon Sep 17 00:00:00 2001 From: AnonymDavid Date: Mon, 20 Jan 2025 13:51:24 +0100 Subject: [PATCH 07/13] CIL VIL code QoL; removed pacmod_interface --- .gitmodules | 3 --- .../plan_lat_lane_follow_ldm/CMakeLists.txt | 10 +++------- crp_APL/planners/plan_lon_emergency/CMakeLists.txt | 2 +- crp_APL/planners/planner_base/CMakeLists.txt | 7 ++----- .../duro_gps_wrapper/duroTopicConverter.hpp | 7 ++++--- .../novatel_gps_wrapper/novatelTopicConverter.hpp | 6 +++--- .../src/novatelTopicConverter.cpp | 1 - .../launch/pacmod_extender.launch.py | 14 +++++++------- crp_VIL/pacmod_extender/src/pacmodDefinitions.cpp | 12 ++++++------ crp_VIL/pacmod_interface | 1 - scripts/build_core.sh | 3 +++ scripts/build_lexus.sh | 3 +-- 12 files changed, 30 insertions(+), 39 deletions(-) delete mode 160000 crp_VIL/pacmod_interface diff --git a/.gitmodules b/.gitmodules index 259c95d7..4e79e967 100644 --- a/.gitmodules +++ b/.gitmodules @@ -22,9 +22,6 @@ [submodule "crp_VIL/nissan_bringup"] path = crp_VIL/nissan_bringup url = https://github.com/szenergy/nissan_bringup -[submodule "crp_VIL/pacmod_interface"] - path = crp_VIL/pacmod_interface - url = https://github.com/tier4/pacmod_interface [submodule "crp_VIL/kvaser_interface"] path = crp_VIL/kvaser_interface url = https://github.com/astuff/kvaser_interface.git diff --git a/crp_APL/planners/plan_lat_lane_follow_ldm/CMakeLists.txt b/crp_APL/planners/plan_lat_lane_follow_ldm/CMakeLists.txt index cb7b519e..a1f493ad 100644 --- a/crp_APL/planners/plan_lat_lane_follow_ldm/CMakeLists.txt +++ b/crp_APL/planners/plan_lat_lane_follow_ldm/CMakeLists.txt @@ -10,8 +10,7 @@ find_package(ament_cmake REQUIRED) find_package(rclcpp REQUIRED) find_package(planner_base REQUIRED) -include_directories(include) -include_directories(${CMAKE_CURRENT_SOURCE_DIR}/../../crp_utils) +include_directories(include ${planner_base_INCLUDE_DIRS}) set(functional_source ${CMAKE_CURRENT_SOURCE_DIR}/src/functionCode/src/linearDriverModel_controlLogic.cpp @@ -22,14 +21,11 @@ set(functional_source ${CMAKE_CURRENT_SOURCE_DIR}/src/functionCode/src/linearDriverModelUtilities/linearDriverModel_polynomialSubfunctions.cpp ) -set(utils_source -${CMAKE_CURRENT_SOURCE_DIR}/../../crp_utils/geometryUtils/src/polynomialRegression.cpp) - -add_executable(plan_lat_lane_follow_ldm src/wrapperPlanLatLaneFollowLdm.cpp ${functional_source} ${utils_source}) +add_executable(plan_lat_lane_follow_ldm src/wrapperPlanLatLaneFollowLdm.cpp ${functional_source}) ament_target_dependencies(plan_lat_lane_follow_ldm rclcpp planner_base) install(TARGETS -plan_lat_lane_follow_ldm + plan_lat_lane_follow_ldm DESTINATION lib/${PROJECT_NAME} ) diff --git a/crp_APL/planners/plan_lon_emergency/CMakeLists.txt b/crp_APL/planners/plan_lon_emergency/CMakeLists.txt index 2dff5130..925af9ab 100644 --- a/crp_APL/planners/plan_lon_emergency/CMakeLists.txt +++ b/crp_APL/planners/plan_lon_emergency/CMakeLists.txt @@ -17,7 +17,7 @@ add_executable(plan_lon_emergency src/wrapperPlanLonEmergency.cpp) ament_target_dependencies(plan_lon_emergency rclcpp planner_base) install(TARGETS -plan_lon_emergency + plan_lon_emergency DESTINATION lib/${PROJECT_NAME} ) diff --git a/crp_APL/planners/planner_base/CMakeLists.txt b/crp_APL/planners/planner_base/CMakeLists.txt index 768007ba..6523e04a 100644 --- a/crp_APL/planners/planner_base/CMakeLists.txt +++ b/crp_APL/planners/planner_base/CMakeLists.txt @@ -29,15 +29,11 @@ set ( include_directories( include ${INTERFACES_DIR} -) - -include_directories( - include ${UTILS_DIR} ) set(utils_source -${CMAKE_CURRENT_SOURCE_DIR}/../../crp_utils/geometryUtils/src/geometricPathCalculation.cpp) +${CMAKE_CURRENT_SOURCE_DIR}/../../crp_utils/geometryUtils/src/geometricPathCalculation.cpp ${CMAKE_CURRENT_SOURCE_DIR}/../../crp_utils/geometryUtils/src/polynomialRegression.cpp) add_library(wrapper_base SHARED src/wrapperBase.cpp ${utils_source} @@ -59,6 +55,7 @@ install( ) ament_export_include_directories(${INTERFACES_DIR}) +ament_export_include_directories(${UTILS_DIR}) ament_export_targets(wrapper_base HAS_LIBRARY_TARGET) ament_export_dependencies(rclcpp crp_msgs tier4_planning_msgs autoware_planning_msgs tf2 tf2_geometry_msgs) diff --git a/crp_CIL/duro_gps_wrapper/include/duro_gps_wrapper/duroTopicConverter.hpp b/crp_CIL/duro_gps_wrapper/include/duro_gps_wrapper/duroTopicConverter.hpp index 9287842e..cb631981 100644 --- a/crp_CIL/duro_gps_wrapper/include/duro_gps_wrapper/duroTopicConverter.hpp +++ b/crp_CIL/duro_gps_wrapper/include/duro_gps_wrapper/duroTopicConverter.hpp @@ -1,5 +1,6 @@ -#ifndef CRP_VIL_DURO_TOPIC_CONVERTER_DUROGPSLAUNCHER_HPP -#define CRP_VIL_DURO_TOPIC_CONVERTER_DUROGPSLAUNCHER_HPP +#ifndef CRP_VIL_DURO_TOPIC_CONVERTER_DUROGPSWRAPPER_HPP +#define CRP_VIL_DURO_TOPIC_CONVERTER_DUROGPSWRAPPER_HPP + #include #include @@ -29,4 +30,4 @@ class DuroTopicConverter : public rclcpp::Node } // namespace vil } // namespace crp -#endif // CRP_VIL_DURO_TOPIC_CONVERTER_DUROGPSLAUNCHER_HPP \ No newline at end of file +#endif // CRP_VIL_DURO_TOPIC_CONVERTER_DUROGPSWRAPPER_HPP \ No newline at end of file diff --git a/crp_CIL/novatel_gps_wrapper/include/novatel_gps_wrapper/novatelTopicConverter.hpp b/crp_CIL/novatel_gps_wrapper/include/novatel_gps_wrapper/novatelTopicConverter.hpp index a4dc2a18..405b3b76 100644 --- a/crp_CIL/novatel_gps_wrapper/include/novatel_gps_wrapper/novatelTopicConverter.hpp +++ b/crp_CIL/novatel_gps_wrapper/include/novatel_gps_wrapper/novatelTopicConverter.hpp @@ -1,5 +1,5 @@ -#ifndef CRP_VIL_NOVATEL_TOPIC_CONVERTER_NOVATELGPSLAUNCHER_HPP -#define CRP_VIL_NOVATEL_TOPIC_CONVERTER_NOVATELGPSLAUNCHER_HPP +#ifndef CRP_VIL_NOVATEL_TOPIC_CONVERTER_NOVATELGPSWRAPPER_HPP +#define CRP_VIL_NOVATEL_TOPIC_CONVERTER_NOVATELGPSWRAPPER_HPP #include #include @@ -29,4 +29,4 @@ class NovatelTopicConverter : public rclcpp::Node } // namespace vil } // namespace crp -#endif // CRP_VIL_NOVATEL_TOPIC_CONVERTER_NOVATELGPSLAUNCHER_HPP \ No newline at end of file +#endif // CRP_VIL_NOVATEL_TOPIC_CONVERTER_NOVATELGPSWRAPPER_HPP \ No newline at end of file diff --git a/crp_CIL/novatel_gps_wrapper/src/novatelTopicConverter.cpp b/crp_CIL/novatel_gps_wrapper/src/novatelTopicConverter.cpp index b2015f28..208f9f57 100644 --- a/crp_CIL/novatel_gps_wrapper/src/novatelTopicConverter.cpp +++ b/crp_CIL/novatel_gps_wrapper/src/novatelTopicConverter.cpp @@ -14,7 +14,6 @@ void crp::vil::NovatelTopicConverter::currentPoseCallback(const geometry_msgs::m geometry_msgs::msg::PoseWithCovarianceStamped poseWithCovariance; poseWithCovariance.header = msg->header; poseWithCovariance.pose.pose = msg->pose; - poseWithCovariance.pose.pose.orientation = msg->pose.orientation; m_pub_currentPoseWithCovariance_->publish(poseWithCovariance); } diff --git a/crp_VIL/pacmod_extender/launch/pacmod_extender.launch.py b/crp_VIL/pacmod_extender/launch/pacmod_extender.launch.py index 36e6baab..93c6270a 100644 --- a/crp_VIL/pacmod_extender/launch/pacmod_extender.launch.py +++ b/crp_VIL/pacmod_extender/launch/pacmod_extender.launch.py @@ -3,13 +3,13 @@ def generate_launch_description(): pacmod_extender = Node( - namespace='lexus3', - package='pacmod_extender', - executable='pacmod_extender_node', - name='pacmod_extender', - output='screen' - ) + namespace='lexus3', + package='pacmod_extender', + executable='pacmod_extender_node', + name='pacmod_extender', + output='screen' + ) return LaunchDescription([ pacmod_extender - ]) \ No newline at end of file + ]) diff --git a/crp_VIL/pacmod_extender/src/pacmodDefinitions.cpp b/crp_VIL/pacmod_extender/src/pacmodDefinitions.cpp index 37ed7813..76c1eb3c 100644 --- a/crp_VIL/pacmod_extender/src/pacmodDefinitions.cpp +++ b/crp_VIL/pacmod_extender/src/pacmodDefinitions.cpp @@ -16,14 +16,14 @@ pacmod3_msgs::msg::LinearAccelRpt PacmodDefinitions::decodeLinAccel(const can_ms linAccel.longitudinal_valid = (msg->data[0] >> 4) & 0x1; linAccel.vertical_valid = (msg->data[0] >> 5) & 0x1; - int16_t accelLat_raw = msg->data[1] << 8 | msg->data[2]; - linAccel.lateral_accel = accelLat_raw * 0.01; + int16_t accelLatRaw = msg->data[1] << 8 | msg->data[2]; + linAccel.lateral_accel = accelLatRaw * 0.01; - int16_t accelLon_raw = msg->data[3] << 8 | msg->data[4]; - linAccel.longitudinal_accel = accelLon_raw * 0.01; + int16_t accelLonRaw = msg->data[3] << 8 | msg->data[4]; + linAccel.longitudinal_accel = accelLonRaw * 0.01; - int16_t accelVert_raw = msg->data[5] << 8 | msg->data[6]; - linAccel.vertical_accel = accelVert_raw * 0.01; + int16_t accelVertRaw = msg->data[5] << 8 | msg->data[6]; + linAccel.vertical_accel = accelVertRaw * 0.01; return linAccel; } diff --git a/crp_VIL/pacmod_interface b/crp_VIL/pacmod_interface deleted file mode 160000 index 1c033a21..00000000 --- a/crp_VIL/pacmod_interface +++ /dev/null @@ -1 +0,0 @@ -Subproject commit 1c033a21ce0c41cd4fb878b95d3e1620de79e95a diff --git a/scripts/build_core.sh b/scripts/build_core.sh index 977dddc9..ede8ea90 100755 --- a/scripts/build_core.sh +++ b/scripts/build_core.sh @@ -27,5 +27,8 @@ plan_motion_planning \ crp_launcher \ ctrl_vehicle_control \ ctrl_vehicle_control_lat_compensatory \ +ctrl_vehicle_control_lat_pure_p \ +ctrl_vehicle_control_lat_stanley \ +ctrl_vehicle_control_lqr \ ctrl_vehicle_control_long \ test_node diff --git a/scripts/build_lexus.sh b/scripts/build_lexus.sh index ba077b55..bee3a25d 100755 --- a/scripts/build_lexus.sh +++ b/scripts/build_lexus.sh @@ -29,7 +29,6 @@ packages=( novatel_gps_driver novatel_gps_wrapper pacmod_extender - pacmod_interface kalman_pos ekf_wrapper prcp_sensor_abstraction @@ -44,4 +43,4 @@ packages_paths=$(colcon list --packages-up-to $packages_string -p) rosdep install --from-paths $packages_paths --ignore-src -r -y -colcon build --packages-select $packages_string \ No newline at end of file +colcon build --packages-select $packages_string From bb80c4846aba8f8ce8c5685afa460286be60b532 Mon Sep 17 00:00:00 2001 From: AnonymDavid Date: Mon, 20 Jan 2025 14:03:29 +0100 Subject: [PATCH 08/13] CRP launcher cleanup --- launch/crp_launcher/CMakeLists.txt | 1 - launch/crp_launcher/config/ekf_duro.yaml | 27 ------------------------ launch/crp_launcher/config/ekf_nova.yaml | 27 ------------------------ launch/crp_launcher/package.xml | 1 - 4 files changed, 56 deletions(-) delete mode 100644 launch/crp_launcher/config/ekf_duro.yaml delete mode 100644 launch/crp_launcher/config/ekf_nova.yaml diff --git a/launch/crp_launcher/CMakeLists.txt b/launch/crp_launcher/CMakeLists.txt index 2b9492fe..4234bad6 100644 --- a/launch/crp_launcher/CMakeLists.txt +++ b/launch/crp_launcher/CMakeLists.txt @@ -8,7 +8,6 @@ endif() find_package(ament_cmake REQUIRED) install(DIRECTORY - config launch DESTINATION share/${PROJECT_NAME} ) diff --git a/launch/crp_launcher/config/ekf_duro.yaml b/launch/crp_launcher/config/ekf_duro.yaml deleted file mode 100644 index dc219ce6..00000000 --- a/launch/crp_launcher/config/ekf_duro.yaml +++ /dev/null @@ -1,27 +0,0 @@ -kalman_pos_node: - ros__parameters: - pose_topic : "/lexus3/gps/duro/current_pose" - vehicle_status_topic : "/lexus3/vehicle_status" - nav_sat_fix_topic : "/lexus3/gps/duro/navsatfix" - # inspvax_topic : "gps/nova/inspvax" - imu_topic : "/lexus3/gps/duro/imu" - est_cog_topic : "estimated_pose_cog" - est_trav_distance_odom_topic : "distance" - est_trav_distance_est_pos_topic : "estimated_trav_dist_est_pos" - est_baselink_topic : "/ekf/estimated_pose_baselink" - est_accuracy_topic : "estimation_accuracy" - loop_rate_hz : 60 - estimation_method : 10 - gnss_source : "none" - vehicle_type : "lexus" - dynamic_time_calc : True - kinematic_model_max_speed : 0.3 - do_not_wait_for_gnss_msgs : True - msg_timeout : 2000.0 - vehicle_param_c1 : 3000.0 - vehicle_param_c2 : 3000.0 - vehicle_param_m : 180.0 - vehicle_param_jz : 270.0 - vehicle_param_l1 : 0.624 - vehicle_param_l2 : 0.676 - vehicle_param_swr : 1.0 diff --git a/launch/crp_launcher/config/ekf_nova.yaml b/launch/crp_launcher/config/ekf_nova.yaml deleted file mode 100644 index 46db5432..00000000 --- a/launch/crp_launcher/config/ekf_nova.yaml +++ /dev/null @@ -1,27 +0,0 @@ -kalman_pos_node: - ros__parameters: - pose_topic : "/lexus3/gps/nova/current_pose" - vehicle_status_topic : "/lexus3/vehicle_status" - nav_sat_fix_topic : "/lexus3/gps/nova/fix" - # inspvax_topic : "gps/nova/inspvax" - imu_topic : "/lexus3/gps/nova/imu" - est_cog_topic : "/ekf/estimated_pose_cog" - est_trav_distance_odom_topic : "/ekf/distance" - est_trav_distance_est_pos_topic : "/ekf/estimated_trav_dist_est_pos" - est_baselink_topic : "/ekf/estimated_pose_baselink" - est_accuracy_topic : "/ekf/estimation_accuracy" - loop_rate_hz : 60 - estimation_method : 10 - gnss_source : "none" - vehicle_type : "lexus" - dynamic_time_calc : True - kinematic_model_max_speed : 0.3 - do_not_wait_for_gnss_msgs : True - msg_timeout : 2000.0 - vehicle_param_c1 : 3000.0 - vehicle_param_c2 : 3000.0 - vehicle_param_m : 180.0 - vehicle_param_jz : 270.0 - vehicle_param_l1 : 0.624 - vehicle_param_l2 : 0.676 - vehicle_param_swr : 1.0 diff --git a/launch/crp_launcher/package.xml b/launch/crp_launcher/package.xml index d0677597..fe4d3c84 100644 --- a/launch/crp_launcher/package.xml +++ b/launch/crp_launcher/package.xml @@ -13,7 +13,6 @@ prcp_situation_analysis plan_behavior_planning plan_motion_planning - plan_lat_lane_follow_ldm ctrl_vehicle_control From ae060b12babae8e3aa03a88b68a6cfaca88f3a7a Mon Sep 17 00:00:00 2001 From: AnonymDavid Date: Thu, 23 Jan 2025 11:14:34 +0100 Subject: [PATCH 09/13] Fix dependencies --- crp_APL/ctrl_vehicle_control/CMakeLists.txt | 3 +-- scripts/build_lexus.sh | 2 ++ 2 files changed, 3 insertions(+), 2 deletions(-) diff --git a/crp_APL/ctrl_vehicle_control/CMakeLists.txt b/crp_APL/ctrl_vehicle_control/CMakeLists.txt index bb6c5176..47fd49ce 100644 --- a/crp_APL/ctrl_vehicle_control/CMakeLists.txt +++ b/crp_APL/ctrl_vehicle_control/CMakeLists.txt @@ -11,14 +11,13 @@ find_package(rclcpp REQUIRED) find_package(rclpy REQUIRED) find_package(std_msgs REQUIRED) find_package(autoware_control_msgs REQUIRED) -find_package(pacmod3_msgs REQUIRED) find_package(geometry_msgs REQUIRED) include_directories(include) add_executable(control_handler src/control_handler.cpp) -ament_target_dependencies(control_handler rclcpp geometry_msgs std_msgs autoware_control_msgs pacmod3_msgs) +ament_target_dependencies(control_handler rclcpp geometry_msgs std_msgs autoware_control_msgs) install(DIRECTORY launch DESTINATION share/${PROJECT_NAME}) diff --git a/scripts/build_lexus.sh b/scripts/build_lexus.sh index bee3a25d..3f626441 100755 --- a/scripts/build_lexus.sh +++ b/scripts/build_lexus.sh @@ -18,6 +18,8 @@ packages=( tier4_system_msgs tier4_api_msgs tier4_vehicle_msgs + tier4_map_msgs + map_loader duro_gps_driver duro_gps_wrapper kvaser_interface From b162c8f1d1204d2776ff493b4e97c9dec5a7d5f4 Mon Sep 17 00:00:00 2001 From: gfigneczi1 Date: Mon, 27 Jan 2025 16:00:56 +0100 Subject: [PATCH 10/13] renaming lat control node name --- .../src/motionHandler.cpp | 2 +- .../crp_launcher/launch/core_test.launch.py | 20 +++++++++---------- 2 files changed, 11 insertions(+), 11 deletions(-) diff --git a/crp_APL/plan_motion_planning/src/motionHandler.cpp b/crp_APL/plan_motion_planning/src/motionHandler.cpp index 15bec036..bb8bdb60 100644 --- a/crp_APL/plan_motion_planning/src/motionHandler.cpp +++ b/crp_APL/plan_motion_planning/src/motionHandler.cpp @@ -337,7 +337,7 @@ void crp::apl::MotionHandler::visualizeTrajectory() void crp::apl::MotionHandler::run() { mapIncomingInputs(); - //visualizeTrajectory(); + visualizeTrajectory(); m_pub_trajectory_->publish(m_outputTrajectory); } diff --git a/launch/crp_launcher/launch/core_test.launch.py b/launch/crp_launcher/launch/core_test.launch.py index 53749488..4db01793 100644 --- a/launch/crp_launcher/launch/core_test.launch.py +++ b/launch/crp_launcher/launch/core_test.launch.py @@ -15,7 +15,7 @@ def generate_launch_description(): change_controller_PGain = ExecuteProcess( cmd=[[ 'ros2 param set ', - '/CtrlVehicleControlLat ', + '/CtrlVehicleControlLatCompensatory ', '/ctrl/fbPGain ', '2.0' ]], @@ -25,7 +25,7 @@ def generate_launch_description(): change_controller_IGain = ExecuteProcess( cmd=[[ 'ros2 param set ', - '/CtrlVehicleControlLat ', + '/CtrlVehicleControlLatCompensatory ', '/ctrl/fbIGain ', '0.05' ]], @@ -35,7 +35,7 @@ def generate_launch_description(): change_controller_DGain = ExecuteProcess( cmd=[[ 'ros2 param set ', - '/CtrlVehicleControlLat ', + '/CtrlVehicleControlLatCompensatory ', '/ctrl/fbDGain ', '0.1' ]], @@ -45,7 +45,7 @@ def generate_launch_description(): change_controller_fbLookAheadTime = ExecuteProcess( cmd=[[ 'ros2 param set ', - '/CtrlVehicleControlLat ', + '/CtrlVehicleControlLatCompensatory ', '/ctrl/fbLookAheadTime ', '0.1' ]], @@ -55,7 +55,7 @@ def generate_launch_description(): change_controller_ffLookAheadTime = ExecuteProcess( cmd=[[ 'ros2 param set ', - '/CtrlVehicleControlLat ', + '/CtrlVehicleControlLatCompensatory ', '/ctrl/ffLookAheadTime ', '1.0' ]], @@ -65,7 +65,7 @@ def generate_launch_description(): change_controller_sigma_thetaFP = ExecuteProcess( cmd=[[ 'ros2 param set ', - '/CtrlVehicleControlLat ', + '/CtrlVehicleControlLatCompensatory ', '/ctrl/sigma_thetaFP ', '0.25' ]], @@ -75,7 +75,7 @@ def generate_launch_description(): change_controller_maxThetaFP = ExecuteProcess( cmd=[[ 'ros2 param set ', - '/CtrlVehicleControlLat ', + '/CtrlVehicleControlLatCompensatory ', '/ctrl/maxThetaFP ', '0.3' ]], @@ -85,7 +85,7 @@ def generate_launch_description(): change_controller_targetAccelerationFF_lpFilterCoeff = ExecuteProcess( cmd=[[ 'ros2 param set ', - '/CtrlVehicleControlLat ', + '/CtrlVehicleControlLatCompensatory ', '/ctrl/targetAccelerationFF_lpFilterCoeff ', '0.99' ]], @@ -95,7 +95,7 @@ def generate_launch_description(): change_controller_targetAccelerationFB_lpFilterCoeff = ExecuteProcess( cmd=[[ 'ros2 param set ', - '/CtrlVehicleControlLat ', + '/CtrlVehicleControlLatCompensatory ', '/ctrl/targetAccelerationFB_lpFilterCoeff ', '0.99' ]], @@ -105,7 +105,7 @@ def generate_launch_description(): change_controller_steeringLpFilter = ExecuteProcess( cmd=[[ 'ros2 param set ', - '/CtrlVehicleControlLat ', + '/CtrlVehicleControlLatCompensatory ', '/ctrl/steeringAngleLPFilter ', '0.8' ]], From 36746f74e20f92d5e3e5036685eaaa0f9f41795d Mon Sep 17 00:00:00 2001 From: AnonymDavid Date: Tue, 28 Jan 2025 08:59:39 +0100 Subject: [PATCH 11/13] Fix planner topic name --- crp_APL/plan_motion_planning/src/motionHandler.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/crp_APL/plan_motion_planning/src/motionHandler.cpp b/crp_APL/plan_motion_planning/src/motionHandler.cpp index bb8bdb60..26db3645 100644 --- a/crp_APL/plan_motion_planning/src/motionHandler.cpp +++ b/crp_APL/plan_motion_planning/src/motionHandler.cpp @@ -6,7 +6,7 @@ crp::apl::MotionHandler::MotionHandler() : Node("motion_handler") m_sub_strategy_ = this->create_subscription( "plan/strategy", 10, std::bind(&MotionHandler::scenarioCallback, this, std::placeholders::_1)); m_sub_plan_latLaneFollow_ = this->create_subscription( - "plan/lat_lane_follow/trajectory", 10, std::bind(&MotionHandler::planLatLaneFollowCallback, this, std::placeholders::_1)); + "plan/plan_lat_lane_follow_ldm/trajectory", 10, std::bind(&MotionHandler::planLatLaneFollowCallback, this, std::placeholders::_1)); m_sub_plan_lonEmergency_ = this->create_subscription( "plan/lon_emergency/trajectory", 10, std::bind(&MotionHandler::planLonEmergencyCallback, this, std::placeholders::_1)); m_sub_plan_lonIntelligentSpeedAdjust_ = this->create_subscription( From 6bf1d29964ce320f3f3c07bc256e0da6d0783dc2 Mon Sep 17 00:00:00 2001 From: AnonymDavid Date: Tue, 28 Jan 2025 09:02:36 +0100 Subject: [PATCH 12/13] Fix wrong topic name --- crp_APL/plan_motion_planning/src/motionHandler.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/crp_APL/plan_motion_planning/src/motionHandler.cpp b/crp_APL/plan_motion_planning/src/motionHandler.cpp index 26db3645..5593d6d0 100644 --- a/crp_APL/plan_motion_planning/src/motionHandler.cpp +++ b/crp_APL/plan_motion_planning/src/motionHandler.cpp @@ -6,7 +6,7 @@ crp::apl::MotionHandler::MotionHandler() : Node("motion_handler") m_sub_strategy_ = this->create_subscription( "plan/strategy", 10, std::bind(&MotionHandler::scenarioCallback, this, std::placeholders::_1)); m_sub_plan_latLaneFollow_ = this->create_subscription( - "plan/plan_lat_lane_follow_ldm/trajectory", 10, std::bind(&MotionHandler::planLatLaneFollowCallback, this, std::placeholders::_1)); + "plan/lat_lane_follow_ldm/trajectory", 10, std::bind(&MotionHandler::planLatLaneFollowCallback, this, std::placeholders::_1)); m_sub_plan_lonEmergency_ = this->create_subscription( "plan/lon_emergency/trajectory", 10, std::bind(&MotionHandler::planLonEmergencyCallback, this, std::placeholders::_1)); m_sub_plan_lonIntelligentSpeedAdjust_ = this->create_subscription( From 6eea5b761ffa24aac88f69dc4e0a0c726987632d Mon Sep 17 00:00:00 2001 From: gfigneczi1 Date: Tue, 28 Jan 2025 13:04:32 +0100 Subject: [PATCH 13/13] fixing the wrong target assignment in the compensatory lat control --- .../compensatory_model/compensatory_model.hpp | 4 +--- .../src/compensatory_model/compensatory_model.cpp | 13 ++++++++----- 2 files changed, 9 insertions(+), 8 deletions(-) diff --git a/crp_APL/controllers/ctrl_vehicle_control_lat_compensatory/include/compensatory_model/compensatory_model.hpp b/crp_APL/controllers/ctrl_vehicle_control_lat_compensatory/include/compensatory_model/compensatory_model.hpp index 6e3f7cb3..b3389e1a 100644 --- a/crp_APL/controllers/ctrl_vehicle_control_lat_compensatory/include/compensatory_model/compensatory_model.hpp +++ b/crp_APL/controllers/ctrl_vehicle_control_lat_compensatory/include/compensatory_model/compensatory_model.hpp @@ -50,8 +50,6 @@ namespace crp double m_orientationErr{0.0f}; // RESULT - double m_targetAcceleration{0.0f}; - double m_targetSteeringAngle{0.0f}; double m_k_superPosition{0.5f}; double m_targetSteeringAngle_prev{0.0f}; @@ -66,7 +64,7 @@ namespace crp void calculateFeedback(const ControlInput& input, const ControlParams& params); void superPoseFeedforwardAndFeedback (); - void calculateSteeringAngle(const ControlInput& input, const ControlParams& params); + void calculateSteeringAngle(const ControlInput& input, ControlOutput& output, const ControlParams& params); void cutRelevantLocalSnippet(const ControlParams ¶ms); diff --git a/crp_APL/controllers/ctrl_vehicle_control_lat_compensatory/src/compensatory_model/compensatory_model.cpp b/crp_APL/controllers/ctrl_vehicle_control_lat_compensatory/src/compensatory_model/compensatory_model.cpp index e62eea0b..7388f9ee 100644 --- a/crp_APL/controllers/ctrl_vehicle_control_lat_compensatory/src/compensatory_model/compensatory_model.cpp +++ b/crp_APL/controllers/ctrl_vehicle_control_lat_compensatory/src/compensatory_model/compensatory_model.cpp @@ -46,7 +46,9 @@ namespace crp m_k_superPosition*m_targetAccelerationFB; // output calculation - calculateSteeringAngle(input, params); + calculateSteeringAngle(input, output, params); + + printf("target steering output %f\n", output.steeringAngleTarget); // finally, filter the output steering angle, too output.steeringAngleTarget = m_steeringAngleFilter.lowPassFilter(output.steeringAngleTarget, m_targetSteeringAngle_prev, params.steeringAngleLPFilter); @@ -73,13 +75,14 @@ namespace crp calculateLookAheadPose(input, params); - double targetAccelerationUnfiltered = 2.0f*m_lookAheadPose[1] / (std::pow(params.fbLookAheadTime,2)); + double targetAccelerationUnfiltered = 2.0f*m_lookAheadPose[1] / (std::pow(params.ffLookAheadTime,2)); // strong filtering m_targetAccelerationFF = params.targetAccelerationFF_lpFilterCoeff * m_targetAccelerationFF + (1.0f-params.targetAccelerationFF_lpFilterCoeff) * targetAccelerationUnfiltered; m_targetAccelerationFF = std::min(std::max(-params.maxAcceleration, m_targetAccelerationFF), params.maxAcceleration); + } void CompensatoryModel::calculateFeedback(const ControlInput &input, const ControlParams ¶ms) @@ -236,15 +239,15 @@ namespace crp printf("look ahead pose is %f ,%f, %f\n", m_lookAheadPose[0], m_lookAheadPose[1], m_lookAheadPose[2]); } - void CompensatoryModel::calculateSteeringAngle(const ControlInput &input, const ControlParams ¶ms) + void CompensatoryModel::calculateSteeringAngle(const ControlInput &input, ControlOutput& output, const ControlParams ¶ms) { // function to map acceleration target to steering angle. Right now, no proper low level // acceleration function we have, only an Ackermann mapping double vxLim = std::max(params.vxMin, input.vxEgo); // calculate steering angle from the acceleration based on target curvature - double targetCurvature = m_targetAcceleration / std::pow(vxLim, 2); - m_targetSteeringAngle = std::atan(targetCurvature * params.vehAxleDistance); + double targetCurvature = output.accelerationTarget / std::pow(vxLim, 2); + output.steeringAngleTarget = std::atan(targetCurvature * params.vehAxleDistance); } }