From d1fcba03fecfc3dbd98d9f4cfe350ee066a3f742 Mon Sep 17 00:00:00 2001 From: Felix Exner Date: Wed, 4 Oct 2023 19:54:11 +0000 Subject: [PATCH 01/43] Add scaling factor to JTC This adds a scaling factor between 0 and 1 to the JTC so that the trajectory time inside the controller is extended respectively. A value of 0.5 means that trajectory execution will take twice as long as the trajectory states. The scaling factor itself is read from the hardware for now. --- .../joint_trajectory_controller.hpp | 12 ++++++ .../src/joint_trajectory_controller.cpp | 41 ++++++++++++++++--- ...oint_trajectory_controller_parameters.yaml | 5 +++ 3 files changed, 53 insertions(+), 5 deletions(-) diff --git a/joint_trajectory_controller/include/joint_trajectory_controller/joint_trajectory_controller.hpp b/joint_trajectory_controller/include/joint_trajectory_controller/joint_trajectory_controller.hpp index ae370df0a6..b60158f24c 100644 --- a/joint_trajectory_controller/include/joint_trajectory_controller/joint_trajectory_controller.hpp +++ b/joint_trajectory_controller/include/joint_trajectory_controller/joint_trajectory_controller.hpp @@ -53,6 +53,14 @@ using namespace std::chrono_literals; // NOLINT namespace joint_trajectory_controller { +struct TimeData +{ + TimeData() : time(0.0), period(rclcpp::Duration::from_nanoseconds(0.0)), uptime(0.0) {} + rclcpp::Time time; + rclcpp::Duration period; + rclcpp::Time uptime; +}; + class JointTrajectoryController : public controller_interface::ControllerInterface { public: @@ -162,6 +170,10 @@ class JointTrajectoryController : public controller_interface::ControllerInterfa // reserved storage for result of the command when closed loop pid adapter is used std::vector tmp_command_; + // Things around speed scaling + double scaling_factor_{}; + realtime_tools::RealtimeBuffer time_data_; + // Timeout to consider commands old double cmd_timeout_; // True if holding position or repeating last trajectory point in case of success diff --git a/joint_trajectory_controller/src/joint_trajectory_controller.cpp b/joint_trajectory_controller/src/joint_trajectory_controller.cpp index b80d1b7908..7933e18bbf 100644 --- a/joint_trajectory_controller/src/joint_trajectory_controller.cpp +++ b/joint_trajectory_controller/src/joint_trajectory_controller.cpp @@ -16,6 +16,7 @@ #include #include +#include #include #include @@ -116,12 +117,24 @@ JointTrajectoryController::state_interface_configuration() const conf.names.push_back(joint_name + "/" + interface_type); } } + conf.names.push_back(params_.speed_scaling_interface_name); return conf; } controller_interface::return_type JointTrajectoryController::update( const rclcpp::Time & time, const rclcpp::Duration & period) { + if (state_interfaces_.back().get_name() == params_.speed_scaling_interface_name) + { + scaling_factor_ = state_interfaces_.back().get_value(); + } + else + { + RCLCPP_ERROR( + get_node()->get_logger(), "Speed scaling interface (%s) not found in hardware interface.", + params_.speed_scaling_interface_name.c_str()); + } + if (get_state().id() == lifecycle_msgs::msg::State::PRIMARY_STATE_INACTIVE) { return controller_interface::return_type::OK; @@ -163,6 +176,16 @@ controller_interface::return_type JointTrajectoryController::update( // currently carrying out a trajectory if (has_active_trajectory()) { + // Adjust time with scaling factor + TimeData time_data; + time_data.time = time; + rcl_duration_value_t t_period = (time_data.time - time_data_.readFromRT()->time).nanoseconds(); + time_data.period = rclcpp::Duration::from_nanoseconds(scaling_factor_ * t_period); + time_data.uptime = time_data_.readFromRT()->uptime + time_data.period; + rclcpp::Time traj_time = + time_data_.readFromRT()->uptime + rclcpp::Duration::from_nanoseconds(t_period); + time_data_.writeFromNonRT(time_data); + bool first_sample = false; // if sampling the first time, set the point before you sample if (!traj_external_point_ptr_->is_sampled_already()) @@ -171,19 +194,19 @@ controller_interface::return_type JointTrajectoryController::update( if (params_.open_loop_control) { traj_external_point_ptr_->set_point_before_trajectory_msg( - time, last_commanded_state_, joints_angle_wraparound_); + traj_time, last_commanded_state_, joints_angle_wraparound_); } else { traj_external_point_ptr_->set_point_before_trajectory_msg( - time, state_current_, joints_angle_wraparound_); + traj_time, state_current_, joints_angle_wraparound_); } } // find segment for current timestamp TrajectoryPointConstIter start_segment_itr, end_segment_itr; const bool valid_point = traj_external_point_ptr_->sample( - time, interpolation_method_, state_desired_, start_segment_itr, end_segment_itr); + traj_time, interpolation_method_, state_desired_, start_segment_itr, end_segment_itr); if (valid_point) { @@ -444,7 +467,8 @@ bool JointTrajectoryController::read_state_from_command_interfaces(JointTrajecto auto interface_has_values = [](const auto & joint_interface) { return std::find_if( - joint_interface.begin(), joint_interface.end(), [](const auto & interface) + joint_interface.begin(), joint_interface.end(), + [](const auto & interface) { return std::isnan(interface.get().get_value()); }) == joint_interface.end(); }; @@ -514,7 +538,8 @@ bool JointTrajectoryController::read_commands_from_command_interfaces( auto interface_has_values = [](const auto & joint_interface) { return std::find_if( - joint_interface.begin(), joint_interface.end(), [](const auto & interface) + joint_interface.begin(), joint_interface.end(), + [](const auto & interface) { return std::isnan(interface.get().get_value()); }) == joint_interface.end(); }; @@ -881,6 +906,12 @@ controller_interface::CallbackReturn JointTrajectoryController::on_activate( // parse remaining parameters default_tolerances_ = get_segment_tolerances(params_); + // Setup time_data buffer used for scaling + TimeData time_data; + time_data.time = get_node()->now(); + time_data.period = rclcpp::Duration::from_nanoseconds(0); + time_data.uptime = get_node()->now(); + time_data_.initRT(time_data); // order all joints in the storage for (const auto & interface : params_.command_interfaces) diff --git a/joint_trajectory_controller/src/joint_trajectory_controller_parameters.yaml b/joint_trajectory_controller/src/joint_trajectory_controller_parameters.yaml index 8bd64b6314..a4dc4f7651 100644 --- a/joint_trajectory_controller/src/joint_trajectory_controller_parameters.yaml +++ b/joint_trajectory_controller/src/joint_trajectory_controller_parameters.yaml @@ -39,6 +39,11 @@ joint_trajectory_controller: "joint_trajectory_controller::state_interface_type_combinations": null, } } + speed_scaling_interface_name: { + type: string, + default_value: "speed_scaling/speed_scaling_factor", + description: "Fully qualified name of the speed scaling interface name" + } allow_partial_joints_goal: { type: bool, default_value: false, From 55c3bb057ca98a18a730d238494f1a1bdd5f46c8 Mon Sep 17 00:00:00 2001 From: "Felix Exner (fexner)" Date: Tue, 10 Oct 2023 14:39:50 +0200 Subject: [PATCH 02/43] use reset+initRT due to missing writeFromRT MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit Co-authored-by: Christoph Fröhlich --- .../src/joint_trajectory_controller.cpp | 3 ++- 1 file changed, 2 insertions(+), 1 deletion(-) diff --git a/joint_trajectory_controller/src/joint_trajectory_controller.cpp b/joint_trajectory_controller/src/joint_trajectory_controller.cpp index 7933e18bbf..9cb6b22fca 100644 --- a/joint_trajectory_controller/src/joint_trajectory_controller.cpp +++ b/joint_trajectory_controller/src/joint_trajectory_controller.cpp @@ -184,7 +184,8 @@ controller_interface::return_type JointTrajectoryController::update( time_data.uptime = time_data_.readFromRT()->uptime + time_data.period; rclcpp::Time traj_time = time_data_.readFromRT()->uptime + rclcpp::Duration::from_nanoseconds(t_period); - time_data_.writeFromNonRT(time_data); + time_data_.reset(); + time_data_.initRT(time_data); bool first_sample = false; // if sampling the first time, set the point before you sample From 79a8b7c39c3113f036e54dcc3fbf1048990e96ee Mon Sep 17 00:00:00 2001 From: Felix Exner Date: Thu, 21 Mar 2024 09:41:29 +0000 Subject: [PATCH 03/43] Reformat scaling the time period This avoids writing the explicit conversion by hand Internally that basically does: static_cast(static_cast(rcl_duration_.nanoseconds) * scale_ld) --- joint_trajectory_controller/src/joint_trajectory_controller.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/joint_trajectory_controller/src/joint_trajectory_controller.cpp b/joint_trajectory_controller/src/joint_trajectory_controller.cpp index 9cb6b22fca..01c85028d9 100644 --- a/joint_trajectory_controller/src/joint_trajectory_controller.cpp +++ b/joint_trajectory_controller/src/joint_trajectory_controller.cpp @@ -180,7 +180,7 @@ controller_interface::return_type JointTrajectoryController::update( TimeData time_data; time_data.time = time; rcl_duration_value_t t_period = (time_data.time - time_data_.readFromRT()->time).nanoseconds(); - time_data.period = rclcpp::Duration::from_nanoseconds(scaling_factor_ * t_period); + time_data.period = rclcpp::Duration::from_nanoseconds(t_period) * scaling_factor_; time_data.uptime = time_data_.readFromRT()->uptime + time_data.period; rclcpp::Time traj_time = time_data_.readFromRT()->uptime + rclcpp::Duration::from_nanoseconds(t_period); From 600ba713f7a7f6ebd0b42399ce707bba7d24fd22 Mon Sep 17 00:00:00 2001 From: Felix Exner Date: Fri, 22 Mar 2024 11:50:54 +0100 Subject: [PATCH 04/43] synchronization of scaling factor with hw optional, add service for setting of scaling factor Co-authored-by: Manuel M --- .../joint_trajectory_controller.hpp | 8 +++ .../src/joint_trajectory_controller.cpp | 55 +++++++++++++++---- ...oint_trajectory_controller_parameters.yaml | 11 ++++ 3 files changed, 64 insertions(+), 10 deletions(-) diff --git a/joint_trajectory_controller/include/joint_trajectory_controller/joint_trajectory_controller.hpp b/joint_trajectory_controller/include/joint_trajectory_controller/joint_trajectory_controller.hpp index b60158f24c..6b90cb07f2 100644 --- a/joint_trajectory_controller/include/joint_trajectory_controller/joint_trajectory_controller.hpp +++ b/joint_trajectory_controller/include/joint_trajectory_controller/joint_trajectory_controller.hpp @@ -24,6 +24,7 @@ #include "control_msgs/action/follow_joint_trajectory.hpp" #include "control_msgs/msg/joint_trajectory_controller_state.hpp" #include "control_msgs/srv/query_trajectory_state.hpp" +#include "control_msgs/srv/set_scaling_factor.hpp" #include "control_toolbox/pid.hpp" #include "controller_interface/controller_interface.hpp" #include "hardware_interface/types/hardware_interface_type_values.hpp" @@ -311,8 +312,15 @@ class JointTrajectoryController : public controller_interface::ControllerInterfa void resize_joint_trajectory_point_command( trajectory_msgs::msg::JointTrajectoryPoint & point, size_t size); + bool set_scaling_factor( + control_msgs::srv::SetScalingFactor::Request::SharedPtr req, + control_msgs::srv::SetScalingFactor::Response::SharedPtr resp); + urdf::Model model_; + realtime_tools::RealtimeBuffer scaling_factor_rt_buff_; + rclcpp::Service::SharedPtr set_scaling_factor_srv_; + /** * @brief Assigns the values from a trajectory point interface to a joint interface. * diff --git a/joint_trajectory_controller/src/joint_trajectory_controller.cpp b/joint_trajectory_controller/src/joint_trajectory_controller.cpp index 01c85028d9..197264726f 100644 --- a/joint_trajectory_controller/src/joint_trajectory_controller.cpp +++ b/joint_trajectory_controller/src/joint_trajectory_controller.cpp @@ -117,22 +117,32 @@ JointTrajectoryController::state_interface_configuration() const conf.names.push_back(joint_name + "/" + interface_type); } } - conf.names.push_back(params_.speed_scaling_interface_name); + if (params_.exchange_scaling_factor_with_hardware) + { + conf.names.push_back(params_.speed_scaling_interface_name); + } return conf; } controller_interface::return_type JointTrajectoryController::update( const rclcpp::Time & time, const rclcpp::Duration & period) { - if (state_interfaces_.back().get_name() == params_.speed_scaling_interface_name) + if (params_.exchange_scaling_factor_with_hardware) { - scaling_factor_ = state_interfaces_.back().get_value(); + if (state_interfaces_.back().get_name() == params_.speed_scaling_interface_name) + { + scaling_factor_ = state_interfaces_.back().get_value(); + } + else + { + RCLCPP_ERROR( + get_node()->get_logger(), "Speed scaling interface (%s) not found in hardware interface.", + params_.speed_scaling_interface_name.c_str()); + } } else { - RCLCPP_ERROR( - get_node()->get_logger(), "Speed scaling interface (%s) not found in hardware interface.", - params_.speed_scaling_interface_name.c_str()); + scaling_factor_ = *(scaling_factor_rt_buff_.readFromRT()); } if (get_state().id() == lifecycle_msgs::msg::State::PRIMARY_STATE_INACTIVE) @@ -468,8 +478,7 @@ bool JointTrajectoryController::read_state_from_command_interfaces(JointTrajecto auto interface_has_values = [](const auto & joint_interface) { return std::find_if( - joint_interface.begin(), joint_interface.end(), - [](const auto & interface) + joint_interface.begin(), joint_interface.end(), [](const auto & interface) { return std::isnan(interface.get().get_value()); }) == joint_interface.end(); }; @@ -539,8 +548,7 @@ bool JointTrajectoryController::read_commands_from_command_interfaces( auto interface_has_values = [](const auto & joint_interface) { return std::find_if( - joint_interface.begin(), joint_interface.end(), - [](const auto & interface) + joint_interface.begin(), joint_interface.end(), [](const auto & interface) { return std::isnan(interface.get().get_value()); }) == joint_interface.end(); }; @@ -889,10 +897,19 @@ controller_interface::CallbackReturn JointTrajectoryController::on_configure( resize_joint_trajectory_point(state_error_, dof_); resize_joint_trajectory_point(last_commanded_state_, dof_); + // create services query_state_srv_ = get_node()->create_service( std::string(get_node()->get_name()) + "/query_state", std::bind(&JointTrajectoryController::query_state_service, this, _1, _2)); + set_scaling_factor_srv_ = get_node()->create_service( + "~/set_scaling_factor", std::bind( + &JointTrajectoryController::set_scaling_factor, this, + std::placeholders::_1, std::placeholders::_2)); + + // set scaling factor to low value default + scaling_factor_rt_buff_.writeFromNonRT(params_.scaling_factor_initial_default); + return CallbackReturn::SUCCESS; } @@ -1586,6 +1603,24 @@ void JointTrajectoryController::resize_joint_trajectory_point_command( } } +bool JointTrajectoryController::set_scaling_factor( + control_msgs::srv::SetScalingFactor::Request::SharedPtr req, + control_msgs::srv::SetScalingFactor::Response::SharedPtr resp) +{ + if (req->scaling_factor < 0 && req->scaling_factor > 1) + { + RCLCPP_WARN( + get_node()->get_logger(), "Scaling factor has to be in range [0, 1]. Ignoring input!"); + resp->success = false; + return true; + } + + RCLCPP_INFO(get_node()->get_logger(), "New scaling factor will be %f", req->scaling_factor); + scaling_factor_rt_buff_.writeFromNonRT(req->scaling_factor); + resp->success = true; + return true; +} + bool JointTrajectoryController::has_active_trajectory() const { return traj_external_point_ptr_ != nullptr && traj_external_point_ptr_->has_trajectory_msg(); diff --git a/joint_trajectory_controller/src/joint_trajectory_controller_parameters.yaml b/joint_trajectory_controller/src/joint_trajectory_controller_parameters.yaml index a4dc4f7651..2258461945 100644 --- a/joint_trajectory_controller/src/joint_trajectory_controller_parameters.yaml +++ b/joint_trajectory_controller/src/joint_trajectory_controller_parameters.yaml @@ -39,6 +39,17 @@ joint_trajectory_controller: "joint_trajectory_controller::state_interface_type_combinations": null, } } + exchange_scaling_factor_with_hardware: { + type: bool, + default_value: false, + description: "Flag that mark is hardware supports setting and reading of scaling factor.\n + If set to 'true' corresponding command and state interfaces are created." + } + scaling_factor_initial_default: { + type: double, + default_value: 1.0, + description: "The initial value of the scaling factor if not exchange with hardware takes place." + } speed_scaling_interface_name: { type: string, default_value: "speed_scaling/speed_scaling_factor", From c01b1ad8f7b462917c6a4e5abb947f579ef31d88 Mon Sep 17 00:00:00 2001 From: Felix Exner Date: Wed, 27 Mar 2024 11:09:57 +0100 Subject: [PATCH 05/43] Improve scaling exchange with hardware --- .../src/joint_trajectory_controller.cpp | 55 +++++++++++++++---- ...oint_trajectory_controller_parameters.yaml | 19 ++++--- 2 files changed, 53 insertions(+), 21 deletions(-) diff --git a/joint_trajectory_controller/src/joint_trajectory_controller.cpp b/joint_trajectory_controller/src/joint_trajectory_controller.cpp index 197264726f..3cf91ab60a 100644 --- a/joint_trajectory_controller/src/joint_trajectory_controller.cpp +++ b/joint_trajectory_controller/src/joint_trajectory_controller.cpp @@ -101,12 +101,17 @@ JointTrajectoryController::command_interface_configuration() const conf.names.push_back(joint_name + "/" + interface_type); } } + if (!params_.speed_scaling_command_interface_name.empty()) + { + conf.names.push_back(params_.speed_scaling_command_interface_name); + } return conf; } controller_interface::InterfaceConfiguration JointTrajectoryController::state_interface_configuration() const { + const auto logger = get_node()->get_logger(); controller_interface::InterfaceConfiguration conf; conf.type = controller_interface::interface_configuration_type::INDIVIDUAL; conf.names.reserve(dof_ * params_.state_interfaces.size()); @@ -117,9 +122,12 @@ JointTrajectoryController::state_interface_configuration() const conf.names.push_back(joint_name + "/" + interface_type); } } - if (params_.exchange_scaling_factor_with_hardware) + if (!params_.speed_scaling_state_interface_name.empty()) { - conf.names.push_back(params_.speed_scaling_interface_name); + RCLCPP_INFO( + logger, "Using scaling state from the hardware from interface %s.", + params_.speed_scaling_state_interface_name.c_str()); + conf.names.push_back(params_.speed_scaling_state_interface_name); } return conf; } @@ -127,9 +135,13 @@ JointTrajectoryController::state_interface_configuration() const controller_interface::return_type JointTrajectoryController::update( const rclcpp::Time & time, const rclcpp::Duration & period) { - if (params_.exchange_scaling_factor_with_hardware) + if (params_.speed_scaling_state_interface_name.empty()) + { + scaling_factor_ = *(scaling_factor_rt_buff_.readFromRT()); + } + else { - if (state_interfaces_.back().get_name() == params_.speed_scaling_interface_name) + if (state_interfaces_.back().get_name() == params_.speed_scaling_state_interface_name) { scaling_factor_ = state_interfaces_.back().get_value(); } @@ -137,13 +149,9 @@ controller_interface::return_type JointTrajectoryController::update( { RCLCPP_ERROR( get_node()->get_logger(), "Speed scaling interface (%s) not found in hardware interface.", - params_.speed_scaling_interface_name.c_str()); + params_.speed_scaling_state_interface_name.c_str()); } } - else - { - scaling_factor_ = *(scaling_factor_rt_buff_.readFromRT()); - } if (get_state().id() == lifecycle_msgs::msg::State::PRIMARY_STATE_INACTIVE) { @@ -478,7 +486,8 @@ bool JointTrajectoryController::read_state_from_command_interfaces(JointTrajecto auto interface_has_values = [](const auto & joint_interface) { return std::find_if( - joint_interface.begin(), joint_interface.end(), [](const auto & interface) + joint_interface.begin(), joint_interface.end(), + [](const auto & interface) { return std::isnan(interface.get().get_value()); }) == joint_interface.end(); }; @@ -548,7 +557,8 @@ bool JointTrajectoryController::read_commands_from_command_interfaces( auto interface_has_values = [](const auto & joint_interface) { return std::find_if( - joint_interface.begin(), joint_interface.end(), [](const auto & interface) + joint_interface.begin(), joint_interface.end(), + [](const auto & interface) { return std::isnan(interface.get().get_value()); }) == joint_interface.end(); }; @@ -908,6 +918,8 @@ controller_interface::CallbackReturn JointTrajectoryController::on_configure( std::placeholders::_1, std::placeholders::_2)); // set scaling factor to low value default + RCLCPP_INFO( + logger, "Setting initial scaling factor to %2f", params_.scaling_factor_initial_default); scaling_factor_rt_buff_.writeFromNonRT(params_.scaling_factor_initial_default); return CallbackReturn::SUCCESS; @@ -1616,7 +1628,26 @@ bool JointTrajectoryController::set_scaling_factor( } RCLCPP_INFO(get_node()->get_logger(), "New scaling factor will be %f", req->scaling_factor); - scaling_factor_rt_buff_.writeFromNonRT(req->scaling_factor); + if (params_.speed_scaling_command_interface_name.empty()) + { + if (!params_.speed_scaling_state_interface_name.empty()) + { + RCLCPP_WARN( + get_node()->get_logger(), + "Setting the scaling factor while only one-way communication with the hardware is setup. " + "This will likely get overwritten by the hardware again. If available, please also setup " + "the speed_scaling_command_interface_name"); + } + scaling_factor_rt_buff_.writeFromNonRT(req->scaling_factor); + } + else + { + if (get_state().id() == lifecycle_msgs::msg::State::PRIMARY_STATE_ACTIVE) + { + // TODO(Felix): Use proper adressing here. + command_interfaces_.back().set_value(static_cast(req->scaling_factor)); + } + } resp->success = true; return true; } diff --git a/joint_trajectory_controller/src/joint_trajectory_controller_parameters.yaml b/joint_trajectory_controller/src/joint_trajectory_controller_parameters.yaml index 2258461945..8718d05a6b 100644 --- a/joint_trajectory_controller/src/joint_trajectory_controller_parameters.yaml +++ b/joint_trajectory_controller/src/joint_trajectory_controller_parameters.yaml @@ -39,21 +39,22 @@ joint_trajectory_controller: "joint_trajectory_controller::state_interface_type_combinations": null, } } - exchange_scaling_factor_with_hardware: { - type: bool, - default_value: false, - description: "Flag that mark is hardware supports setting and reading of scaling factor.\n - If set to 'true' corresponding command and state interfaces are created." - } scaling_factor_initial_default: { type: double, default_value: 1.0, description: "The initial value of the scaling factor if not exchange with hardware takes place." } - speed_scaling_interface_name: { + speed_scaling_state_interface_name: { type: string, - default_value: "speed_scaling/speed_scaling_factor", - description: "Fully qualified name of the speed scaling interface name" + default_value: "", + read_only: true, + description: "Fully qualified name of the speed scaling state interface name" + } + speed_scaling_command_interface_name: { + type: string, + default_value: "", + read_only: true, + description: "Command interface name used for setting the speed scaling factor on the hardware." } allow_partial_joints_goal: { type: bool, From c0038834a82e7f24c2d6cf2e98fab23a2f7437d5 Mon Sep 17 00:00:00 2001 From: Felix Exner Date: Wed, 3 Apr 2024 21:22:39 +0200 Subject: [PATCH 06/43] Check command interface name when setting speed scaling --- .../src/joint_trajectory_controller.cpp | 9 +++++++-- 1 file changed, 7 insertions(+), 2 deletions(-) diff --git a/joint_trajectory_controller/src/joint_trajectory_controller.cpp b/joint_trajectory_controller/src/joint_trajectory_controller.cpp index 3cf91ab60a..b425732153 100644 --- a/joint_trajectory_controller/src/joint_trajectory_controller.cpp +++ b/joint_trajectory_controller/src/joint_trajectory_controller.cpp @@ -1644,8 +1644,13 @@ bool JointTrajectoryController::set_scaling_factor( { if (get_state().id() == lifecycle_msgs::msg::State::PRIMARY_STATE_ACTIVE) { - // TODO(Felix): Use proper adressing here. - command_interfaces_.back().set_value(static_cast(req->scaling_factor)); + for (auto & interface : command_interfaces_) + { + if (interface.get_name() == params_.speed_scaling_command_interface_name) + { + interface.set_value(static_cast(req->scaling_factor)); + } + } } } resp->success = true; From aa63e5d0e5e14b5f95b92c121cc5818fea726e12 Mon Sep 17 00:00:00 2001 From: Felix Exner Date: Wed, 3 Apr 2024 21:24:19 +0200 Subject: [PATCH 07/43] Update code formatting That was changed in a previous commit --- .../src/joint_trajectory_controller.cpp | 6 ++---- 1 file changed, 2 insertions(+), 4 deletions(-) diff --git a/joint_trajectory_controller/src/joint_trajectory_controller.cpp b/joint_trajectory_controller/src/joint_trajectory_controller.cpp index b425732153..5a66969fa8 100644 --- a/joint_trajectory_controller/src/joint_trajectory_controller.cpp +++ b/joint_trajectory_controller/src/joint_trajectory_controller.cpp @@ -486,8 +486,7 @@ bool JointTrajectoryController::read_state_from_command_interfaces(JointTrajecto auto interface_has_values = [](const auto & joint_interface) { return std::find_if( - joint_interface.begin(), joint_interface.end(), - [](const auto & interface) + joint_interface.begin(), joint_interface.end(), [](const auto & interface) { return std::isnan(interface.get().get_value()); }) == joint_interface.end(); }; @@ -557,8 +556,7 @@ bool JointTrajectoryController::read_commands_from_command_interfaces( auto interface_has_values = [](const auto & joint_interface) { return std::find_if( - joint_interface.begin(), joint_interface.end(), - [](const auto & interface) + joint_interface.begin(), joint_interface.end(), [](const auto & interface) { return std::isnan(interface.get().get_value()); }) == joint_interface.end(); }; From 821c88d458f2a703458432f0f8946c8a3f8e6952 Mon Sep 17 00:00:00 2001 From: Felix Exner Date: Sun, 7 Apr 2024 15:40:08 +0200 Subject: [PATCH 08/43] Do not advertise speed scaling service unless only position interface is used The current implementation only works correctly when a position interface is used. When the hardware in fact slows down the robot (as UR does), also velocity interfaces should be scaled correctly, but that't rather an edge case right now. --- .../src/joint_trajectory_controller.cpp | 27 ++++++++++++++----- 1 file changed, 20 insertions(+), 7 deletions(-) diff --git a/joint_trajectory_controller/src/joint_trajectory_controller.cpp b/joint_trajectory_controller/src/joint_trajectory_controller.cpp index 5a66969fa8..941e25e052 100644 --- a/joint_trajectory_controller/src/joint_trajectory_controller.cpp +++ b/joint_trajectory_controller/src/joint_trajectory_controller.cpp @@ -910,15 +910,28 @@ controller_interface::CallbackReturn JointTrajectoryController::on_configure( std::string(get_node()->get_name()) + "/query_state", std::bind(&JointTrajectoryController::query_state_service, this, _1, _2)); - set_scaling_factor_srv_ = get_node()->create_service( - "~/set_scaling_factor", std::bind( - &JointTrajectoryController::set_scaling_factor, this, - std::placeholders::_1, std::placeholders::_2)); + if ( + !has_velocity_command_interface_ && !has_acceleration_command_interface_ && + !has_effort_command_interface_) + { + set_scaling_factor_srv_ = get_node()->create_service( + "~/set_scaling_factor", std::bind( + &JointTrajectoryController::set_scaling_factor, this, + std::placeholders::_1, std::placeholders::_2)); + RCLCPP_INFO( + logger, "Setting initial scaling factor to %2f", params_.scaling_factor_initial_default); + scaling_factor_rt_buff_.writeFromNonRT(params_.scaling_factor_initial_default); + } + else + { + RCLCPP_WARN( + logger, + "Speed scaling is currently only supported for position interfaces. If you want to make use " + "of speed scaling, please only use a position interface when configuring this controller."); + scaling_factor_rt_buff_.writeFromNonRT(1.0); + } // set scaling factor to low value default - RCLCPP_INFO( - logger, "Setting initial scaling factor to %2f", params_.scaling_factor_initial_default); - scaling_factor_rt_buff_.writeFromNonRT(params_.scaling_factor_initial_default); return CallbackReturn::SUCCESS; } From f7d0ae0261d44447e7cd8845f841f1394457fd80 Mon Sep 17 00:00:00 2001 From: Felix Exner Date: Sun, 7 Apr 2024 16:40:39 +0200 Subject: [PATCH 09/43] WIP: Adding documentation about speed scaling --- .../doc/speed_scaling.rst | 75 ++++++++++++++++++ .../doc/traj_with_speed_scaling.png | Bin 0 -> 104299 bytes .../doc/traj_without_speed_scaling.png | Bin 0 -> 107365 bytes joint_trajectory_controller/doc/userdoc.rst | 1 + 4 files changed, 76 insertions(+) create mode 100644 joint_trajectory_controller/doc/speed_scaling.rst create mode 100644 joint_trajectory_controller/doc/traj_with_speed_scaling.png create mode 100644 joint_trajectory_controller/doc/traj_without_speed_scaling.png diff --git a/joint_trajectory_controller/doc/speed_scaling.rst b/joint_trajectory_controller/doc/speed_scaling.rst new file mode 100644 index 0000000000..41f2353dc3 --- /dev/null +++ b/joint_trajectory_controller/doc/speed_scaling.rst @@ -0,0 +1,75 @@ +Speed scaling +============= + +The ``joint_trajectory_controller`` (JTC) supports dynamically scaling its trajectory execution speed. +That means, when specifying a scaling factor :math:`{f}` of less than 1, execution will proceed only +:math:`{f \cdot \Delta_t}` per control step where :math:`{\Delta_t}` is the controller's cycle time. + +Methods of speed scaling +------------------------ + +Generally, the speed scaling feature has two separate scaling approaches in mind: On-Robot scaling +and On-Controller scaling. They are both conceptually different and to correctly configure speed +scaling it is important to understand the differences. + +On-Robot speed scaling +~~~~~~~~~~~~~~~~~~~~~~ + +This scaling method is intended for robots that provide a scaling feature directly on the robot's +teach pendant and / or through a safety feature. One example of such robots are the `Universal +Robots manipulators `_. + +For the scope of this documentation a user-defined scaling and a safety-limited scaling will be +treated the same resulting in a "hardware scaling factor". + +In this setup, the hardware will treat the command sent from the ROS controller (e.g. Reach joint +configuration :math:`{\theta}` within :math:`{\Delta_t}` seconds.). This effectively means that the +robot will only make half of the way towards the target configuration when a scaling factor of 0.5 +is given (neglectling acceleration and deceleration influcences during this time period). + +The following plot shows trajectory execution (for one joint) with a hardware-scaled execution and +a controller that is **not** aware of speed scaling: + +.. image:: traj_without_speed_scaling.png + :alt: Trajectory with a hardware-scaled-down execution with a non-scaled controller + +The graph shows a trajectory with one joint being moved to a target point and back to its starting +point. As the joint's speed is limited to a very low setting on the teach pendant, speed scaling +(black line) activates and limits the joint speed (green line). As a result, the target trajectory +(light blue) doesn't get executed by the robot, but instead the pink trajectory is executed. The +vertical distance between the light blue line and the pink line is the path error in each control +cycle. We can see that the path deviation gets above 300 degrees at some point and the target point +at -6 radians never gets reached. + +With the scaled version of the trajectory controller the example motion shown in the previous diagram becomes: + +.. image:: traj_with_speed_scaling.png + :alt: Trajectory with a hardware-scaled-down execution with a scaled controller + +The deviation between trajectory interpolation on the ROS side and actual robot execution stays +minimal and the robot reaches the intermediate setpoint instead of returning "too early" as in the +example above. + +.. todo:: Describe method behind this scaling approach. + + +On-Controller speed scaling +~~~~~~~~~~~~~~~~~~~~~~~~~~~ + +Conceptionally, with this scaling the robot hardware isn't aware of any scaling happening. The JTC +generates commands to be sent to the robot that are already scaled down accordingly, so they can be +directly executed by the robot. + +Since the hardware isn't aware of speed scaling, the speed-scaling related command and state +interfaces should not be specified and the scaling factor will be set by the ``setSpeedScaling`` +service directly. + +.. note:: + The current implementation only works for position-based interfaces. + + +Goal time tolerances +-------------------- + +.. todo:: + What happens to goal time tolerances if we scale down a trajectory? diff --git a/joint_trajectory_controller/doc/traj_with_speed_scaling.png b/joint_trajectory_controller/doc/traj_with_speed_scaling.png new file mode 100644 index 0000000000000000000000000000000000000000..ce7fcd389d97b6d4647e06a97ac3cd4938c47f10 GIT binary patch literal 104299 zcmcG$2{hJQ`#=0uDno;rM1~|GLlI4;R1zhb3Yk(7p){B!b0rN(lPG1(ka^Bns1T8P zNTEz+itv8+InQ}c{nq=g_5RoT|60$}IY+tO_x|pEU7zXN0b2X_EMwqipeSnDUNu#1 zidu4vq85IoTa2&xHE!R7f6$&)*{ef`U#@h={PExP_G*XEQq&4F@_(8b#b;Ld;ugnU z29Ag9jyqm3J7Y=NnmO9r*g4u*ne(5wJag8{?lk{K326ywasHEzj`mw6CI9^k5_V@! zNK&5<+@mOdYOkuY&c*xR+MJ9uf6gx%X-rJBIv9JJ*)kxNjXO4lEyOZL%0m3|6*H-V ztG*-YmRHZIUR~+BY~!)3%1^%S^Gy}n=zHqa5h>Zj`}W4VxOAWbxKYqnITFdfM%)kGtoe88r{KsF45-s)?|NXBpA7nRE z3HAT|S4^Okz&_RAf9dSH6TJ41*NGF*z8I9}D>XW&GplSW|z06;)MT@Bd40 zM^si|W@fnXu}PtOa$1_Vs^H54x0&0OilzpY!hZpoG{ zThwRL($XG9N9(eivHrPe+}8%UMFa$BVq;@RzJF(#w6d~_G|W8h9~2}ZE0BBaHH)}G zvXWItee5A=k2zO0p_`)D!v9$0IX7D6q90%0nORxU%cf@g?IG(X*dF ze^ygh7fo+VIQ*jX%a?Vh6)%oZ6B82#>DIapwCaC+KHARqe3z3=$z6uy2W{y;swBO$ zW~Ys;4u75`dB7;E_^EQ z=4L4=sZKvW=7SqbXJnWU4wkw6@jJWj%IjKgxr?rg6_uAS){bSX2;ya(?EU(*xF=3Z%WcXy{eZ>-rPC@;@7H#hg{?c4Iw z0M^m5{zLNHw)OPYJ`PEp`2O|#j~}B04e{#3Vg7L@r%y`^d`P^49WuJ5PE}RMWkkVv zcA!3X;kk3;cb8xO=RNCa#nK;^lgr%b;eAU@2t^A!TFG*GJa*obr%$^-zBr+~c`>uD zq%zY;mmgpE-0Vz9s@^tcW?hN)XQy`OJC9@kI=%hpAX;auYrguh*ypvurcImr1_r(_ z5sjMkREaElyyv=Bp}Sj5tZvKWqyT@lU3mxe$!m6(F+PcorlG{e#jWN4du~LlTtb51 zynDxaD@9mXSeAD=vo4E|3eB=*%TAs;^~29yFzSf^WdFc3oH|Nv-@eP?;VZ)=h5z&I zab@lCCe;iPE92wi4NGn?kprNcSUjBP({bsa_Zf5EIf*6JCrd+`{AvF1)Pu19EJ$D5 z$kG21n+x1C{_<{BIl&L2FyMhHysW(2t$J z@A>oeZ{5+jA_etO7UGm^e8n zcMoRTeDrF`v=bZL<~A*})v=GVwY8P8s-ykdn4~XilJ6|5t*zZIfBe5ohktP{loBw! zBErUipIlT?@$Bi&Smv3@VZVF#RxMq+)Osr$rG)2Zdi=QX>2*Rvj}AmA^wmW(J~ztt znxC62ytCbDn9ntOimQDWjU zyrQ?SZ>ap)bMtevBNG#gsZU?Nl)QVl0!w~5Ab|eY?5qHtm-cLl--^d)zq~bnfHEzp zpm0C<-ST(N+A9`C-!#KuOuZQC~2xu0LSb~wxEB^ZpBfARh2 zbdZ0x+i}bCDxJGHx**Hx#dL-3N0yof-F$Zg1Fq@uuS;apy|!l;6exIIzKoI>aH{dS z*|(;Yn#M-I!a_v~XL`ZH#Y>C6eSDE(+p_u7=g)XP3#jA^!$;-ikCK_O!w5EBz)beoyjH96Fl;x=<$NJz-E^7i_& zfgLUrOHaJLuWWChEdTlQn|mo%?}eLMTGmKOF-1m3_O<8dYImS;oP7UuS!!yklwJGw zvEdFr2L}hOLx)OGg=$kQ_V6gW^CTWg_j>yDvmtLs_Sr9;y}i+CNhjVtY)Z3YJ(}*sh}hA6ZC<_UF%^O?gh6$i|A(6>BZ@;A0im(2Bb-(y5$g^?tFQo*u<;eDLjE zS;mD+meXoUZ5w}eV~x5kLluKh0~SeY__*Ia#as_8*_H@KvFpKufBn@|iT@a@`OkiHg~o$*!(0fuWXs z7dbC4FZ;HjqHD!M|8yA?CCR2S+ZpFF-4@(v2e_j6d%QX+%=Jo5> z>_ht`!b)Dgq{-R!lp!}Oi!EN?F}r(g%<;*SCn62+Yic}i-MUqmS~fa5dS}}OiMJ7o z*Y{jstsJREQRsZNIp@BLZYd~^j$mXj|1s_U`(YRCG`Shv(2&@q(QuauXYRm(1ATpc z6or?NeCs~=@x{8O%a)~_{j#5S@!~*RhOc_wckdoaIgwH@XLKZ7!`E*GpP+~c-L+M6 zzM-KUMn*=#_wE^XjUMHT7s4?v?ke$S9^rzO@8sB1Uv2uucD{5 z*KQp_;bW&R;SraXmWu2sOgsGIxZ3{xKsW9H+#j+4tTBcl`B_Uq@5(JIM8)45+i zgR6S8&JS{jN}5Q78X6k*Om=uw;3SlKKSn8Dt>EepB)CRFVYT9~k%h~7w?3)2dvW|t zGU~*u-ZMs7_B18F%Um9R%%Y?m`?O+WW6i4XNRvIieD(I2vHM1kOwZfb9+ROo!Z$A3 z7bdam?Y)$hB_d0tw;kda5;o_hQC zt<drc8k=yw{DGcnH=Htfbt!8FsBcr1Sn3(kA?g4_JRMkYrC*zrBTgXC)+NlyPZ6F()7(;*`{Q(g#hqn((PkYHa0f)s4l9z zcNf>zGBa{Yl-`v+C50aX-b!|KXUE}o-W7Zb3A$Bt>Ow4NYsHO? znY){BZS+yOR9~;77OfodP^&z5x(%>SfB*jFp%TV{;hRpV?AsUrv_wEK zO7P-!VZpe3{Ql_M{bRdEIbR%kgdfVa@tB&X-@!HCzkeT@o$P3gJ7yCpu+#UES&1*Z z^(OaU7yJ7Abr1gjxm3rV*T(cybi-rSP3R96qupg|L(lcsMK}GhGHFD&a71epRdEr! zFw{yzp@i$lw8?e2u92XzH8VTd@9(xjyuVoyB@8u2(!#zN{|(zP5I~Lt%Ql zto4lgN36Tc9bf5n4|r6>LuIiR&{xW-}=lMZX% zO&d3|04BV9xFi01%CU_r0rUPwde6?}7IUp-*_$50_xqdH=KUAco!WYJ@*z(5ha?k| z*jcyn27SBw4E>~|YJ2x854Y!+xdCmJjdYa&;n3~exf9#lXua~cfq}r=x7n6*%k(8$ zto!YyqvA@uZ8k({iJ&>r@bN|5UEZ5N@#!_I>YhD>ipugbP)hsuF@lr;J9ZaD?(`Fs zkXVkIUXH@e%*pA8e_ZLkd-razdUQ=~ZEQgB?}b@ym&U6Pf(H*C1Rl8j;>9Ma6X>36 z`$eg%*RCDRJZ+2;*j4PqXg+)H>xW3I_fKo;>s7CCY#;?HdJZeH*`~=8_)0}zpY#0r z^YRylc!t{Z89{^V6Ad{fBqaQ=U*~N38|5+MNbd&Pdi3m>A3duuzoH^vRhXooj;If+ z5yyrjPh>t+hKSWZ)m%ls7p?t{yo2DzO`FQTcXpcA$Lp`y6U1}r!2@2@fYR_t9}peX zGC$|>ftRJFv>-%Gw936d!a_oPnAhx9I&feG2p`?jrQ!~styNWNd3bng9w{%Rie6q` zVs`2jBQGy6NYxr?>4ULz*q_qJUNOnoG%@Am-msqC>pWi zw`VCB=kzy@r0G1q>}m^(=jlZQem*{tc#c^Aoj~L0^1h3gar29dFU1oLlQi*FiKHkL z26MnYItB(WKffi#B_-0<^&;f`4h;>NN01_gl}kC(tB&rlaHrq$UAKfarA~bim$9y= zLys(fviFvKUyVSDrmO3AG#PKaUD9*-Jbp>Du&|h(I&}r5cFoqU-1y78udm)w6MJYK zr^s5EKG8(VJ1iDy}QeiA>CZvLzU#ENIEFy^O!5F!ODb#=XtU1Ox;q&!QqF zoA$hw_cq&l<>&7Jj%DWN4jgLBjdz@TdLSa`(6jvlGBRxVaPzan9?Yv&G49z@Vg4oC zo`Z0GDbphADxczNpuD2!ePJUg=VA>WKfkX9>+xK<>3C655mB4C6kO%+%2+KpapFY6 z(R}VqyN=zc>!WBa6s4i58L1^wlWey0TXQ<&_}9igj*c?r*H$fIWW2I5j9UR)6lkcd zbUWoZP)`qZ0NrCZwzSSxzTfMh&W|~E`j7Xht@TA&DO9umBLeop3}~pP6pJOKao@Sa z#kFeHLJIvs_=9nZ`684F;r;jNsF5E(N`C(Ml44%Q5bgaf=HTPfPaRiRZtCpr_CjBb z0vMh{yi&|eD13rc8^xeChc;GN($+T_B=q`No<_!%6fRBEUZcFqYYzxZN)^?ejn_Ki& zybqkFL(O5Kp~9ylww`0S!YPRjAQyb&#-+Tx?Rl<0Sq>jQ9AlU%K`H6$>uZ!R@bvNV zY1-rLycI+mk4Z4})X9@YuV3$tw!G5Q({tnAz4-d}rlzbWn>yf-;?h#p?Mu#N^E}vk z&P!F0`77JtLJx2HKX`DhwYAlJ z)A@bcG7nX}_-|)L{Jt92NglgY^f=k?#U5cTE-vou@25wVqL}70#go>3QCDwjh&}Yo zVD{z&yM)g#XD71<__vI`>gp;H3T{$p<>E$JOz4>ME)(L=1uvuFgnYEy^^n<+Lw9C< zj!{b7AP!@Sb%QA6hJbgkX9wbw2+%*Ci-k4=d_%GHM*SKaA0KVI(6N5Uk}M%|N`L)0 zkTMI5!gg!m_wzA!T1%{uLDvtQsHCOEu=R9H#)j_h?vYQgZ?SxB`S`I5*i3yU>hWW< z6DRbe9YR0VMelo6RkhR9lpk!87Et&X015j*NlgtX3x~YNTwa!>q~wZ}l(;vxr#~dD z#5;OiKiB{MS(e*OM%D(p1gB-{8Dm!;N{P?V? zabKPpFyl~c;=_ll$%Dg3?g0;)!f6$__4;<`;UK_PJw1+`^Mj&81f+NO^pMU6$<_>1 zg>LzBy@6a15&84qxUk*=VO67LoF;58q47Xk5=L2`WWPF((J}Ze0Ol$|S+)Q4in+DG zZ506GF3^MQ3iA^u{J`^xYJmr_olwsdi;5`F@Ul?Te>63+Mp4bz=szCmEV{JN{``60 z@bK`g1BVW=f=7`aK0Vfd8FaxE2SH0;e+dOS%p97`)KKnl4cNO)Q!44+YHMnZ{JCw*OS61el*V@mdF`V5Kj6)f^qmtRhC-XNaEL&I2F`$vvfcd`7wfwHI{gNCS2chm7oD75R#h?L0hWQI z>L_sjehzfDsd-mA`=5~gKjQ)I+n_+%J36XrX)!ft*j@o0H3dMC>;QLb%Cs}N zmgb?4{(!=%A{rw4##tEae`&J+?&x#($+b}fA<)C|G|fL(hl32q_1i<5qicU0;BPJ2 z{+M25+q%OCf0ZS0kOjjI)_!l6*LddaS!w%Dr7`s5r#sgRZ{N=2?CeapVugP88?Xt2 z%z}f1MXz4{y)Lzf?*6G86X$T;<|lLrGdnvI>z}BmHE3+wRkE_OFbRIe(G4bwn-uVz z{aj5$85kJEw7vzk$8n<=9!C7(>!hacIwVYJ-I?tjlCve_VfLoL~^Lm}jA)!*8#nJUCP z-=u=+IKA<(J9p>;R2SfXz%LBfO`0}KNDL)*|1RK1b)%420u>y8d!L^A5Bk?Vo$EYq zO}k`?{>i*RVYez4R1aWS-7Mo{$Akc=QCalXJFta3c(4qvKx>}Ui@KTTOTnGX(D}=3 z|5l6h51Le5=c@qCFCE0AhywMO+PKjRY=8Uq?e?H-<~@Z4*MEPAqC|A|hhzgR?CR=D zQGfFV(M&lR8P~_&eKR=v7RjlpDpjEyPHnx-vU1fbqRnYfZvI9LAy)5XqNR$+L4ZyR8vU}hl?S-G0uWk#2Opt${>*D2Xwu>_;=HW_Up^Se%FgZs zfTs+)gttSA5`L&?!ET>@9J$%q!~g(3W`Adfau1pQcF-ycUC$Gwpc{ZPx}1ZB#S0Ie zC=(kDGfDw!0CjI4ul@Z{9Bilqe~&9+%q!B=nZKF7p_V15MmPIkt-9OkJJj??zz2Qx zv8-?(gF{1o-zm=XfHa7n4ew4g%!I|Zf>Xk%2*s2C)@x$=6azOxn}^&}61u^#CSG3> z)IV%hPqJA_4J4Wb!_4J?UH(_D>;x+61eb-NPh`-{(`^eVtPTx@(vxD}rIL2Cb^#1W z7yzO;8IZB)AZ-IHEP;SqiXRQPk0P+A=>C?oL?S1z3@xf+xNtt`ox;pgAj-ZEiK{-p zeQ;%!-09Am$el4Jg$f{@SH69-k=BE5GBRRMUJnRX$!|F?6AMdJn(9ap?>3^KsR^+_ zZGD7C3C&$x@3~O`zKf71K-^-eWBa!AZ46(EN2Lt3k0&5yQN9!{eu>=aRwaBe*fD;q zcQ~7l_0<}@IKB*0r~N?vde{$~Ur&MAlbwWpEp`5z0j1QIb58o=h^fuT)J5P~DF&JL zhS-`f^E1>7)~yZ4qb`H)-BfAg=d z*1$6ipjQEmcX-{KkRYC5l+6N(8-Vdj6P%(KL_#Cn6|YDfmi_zpQ(88@!`QXhq1X=$ zkNCs$@Ft`MTxKS0OUui4Prbb?bn_OBh03pFVkGQ4iWQ#_7hhyh}_;k*;rOC<`z3QJDXAHY+Em8{5S< zI(jW0mN)hT&$jakrS9sR&VJUAIaxyiMX+1%`F-8(hTvw{288 z@mp2Bc&JRbQYdl=R3f!H!RakQ#!{1$nZg*|SphYtAfXat=iRrXXBT%VGVHcM&Y zt(l)=WR0>z0jEg$MYADt19pK0^dMoJDye9k2#f5pY1>{g=G+Sl=bd!e83=EqORNeAn&^^&f<3+&MIa z<9+@SO6OE>n8^sxugJB-@;y`MKrG58*cC2hJel=L+G~|`VwW2{J`%bhA08!?aB$0l zpn&`nmBeYsck{4cLdTbTx^PVN>Q4cZ_M4=@|;*9trUX?)kg2*OhaL4T57DR zsYz*BpR%)CflPw!Jd=(fXX}a zHL0*079m8oiq4mp%TnP)_rQ=$&d8A1e7rXN^)8F*s;UwnM$S?<6rOUNG_bKHk4$~P zql@S$WUhU%lbZVW;$86l`&VIJbmDutww!sQKI;Z~+#t(d0AycWVo>Avqtf692Ee~z z!!opkKDg4c=V06|h9iBIXA6tR+|PAb37`32UlbwIT#T(^k1uX+=3ck|zLK@ID4N}o z<83Ip8h2&rZ``pf^e2sd(4h=f)tmY z$l|bW&5{OCf(kY|(zO!?oC@kH4qXYLNeYyW(u#^6$YE1Buteyfit?O(Bzw%ex8}QW zHYSrW7 zr6`Oe_m45Ryen33*NU@%(@FLRI1@5BDsXwKToXOLECat(hhIj&E5V|{2ZQ~! z3(z>*_Kz)j2HyT}28>vG(DUaKM8`oz?!3H0p{Rn-<0|P>@JQ@r&x3N~d@M$39sQUP zeNbP&f+(KmrF2cr&E_B-eQmjN9O4EPg(OSa)M(FW|FeiE5!Sp*OOf4zmGQ%&B!&)r>C#IJmzY{uEPQ0TxgSZO znhaY*$H8WHz=Wpkv+F#)ylu?1(?k|7TsZc%aRs_z8FuvTO879$07>xw#=d=I1t2KD zz5b9Xd@TjPiF2Tj%IN7e;6_wwDSMI%fmU@`{|RCq2Vf!^UHpIdzS5<9C8}#V@9R2A8y~F7F~CD`LjB2Z*St@ zPeC3ivwTQH46)6dH)oycWq^ey);iphk+d9)9eV(}eY9{zfPc(qq<1#8Hw+i3>g1m} zb0*obU%UGL7FN_rl8#|!fB8>niN^AakXT^horVPuwp}O>7T8%ji2eQRdzBjtcsQ61x6W7SwS2t8PG_XTKVIRnaZ+NmHPS?_V@9$M$ zt%y^bPMqGZ6Xgqv;C4bSST1gup%Hz;NAIa#;t?R(*wWNxt2VP4e$L#Snx5{Hm}mSk;q6usMJgOj^fb`<%H7eDy;vBjR%!%8FjKgrnY6tAG}c=T*?Qp>;vn! z;Z@U;6{|}jfU1jcl9NmNe3Fh@uwVfb6O)#8wy*DEFvyABZgMAUI+s2EUD*-Tg|nm% z@7d_R!0)|{IbUvS>Hl74Q9A%g*VWApzK}WIW@lfY!Fw~ET*xwjqv$0Kjv~6<<6og_ zE;Df(*A2NEa`!F+JbYq<0ID5|ee<=^ShGM;)cG{dqOQW*X2E~mseUa{UE~j|-@HLw z2yC@Lbk(!19S5SX#RdZ9n?kBVv@Pa)V+#rj)Zy;)x`m6^Uicv3w4qWJu9^Nzd!5J%A3^ixf#?bp zUQ|<)tUVncOKYdC&4OSa^k3XT^7 zEXHCc!viDFJ%;$UonH!X>?DM<^sCP*T`I7O&GV*ef;W_)5w+ceWfVk&HI#n;fPhPI z*PcCF_fXM8;=>K~==o+v)qfO<=}fafIC@z)9|TnI_;|6j^mLN8fdwv_zJ(;t&VQo= zI)SWXijAO7e;J|1$8hiACPEsZhvX0(5)yqzgONkr6EYxZ(_av5tq!pYaJC;qS_I`+ z?kI38d$Ld~*fktM0aQa0=7OFfemGTC9NWDD)Twk1^(F`hTl88X${TX6SVKOG@~bb= zjC6zY?LQW$1_>atiQ)zMaV2@H*=J86jp5%*C^uS&skJo&2&9Z%I}h5$`U^IzR;{9x z0J8aSsNu0cWqW^f?LJc^S0O=DMLsgnUw+kfupM>mqN^D!Jv*Qbl)W@4v7;jQQ=oe;2kty+WknR%us|4}zQ!NIV1i3PfN z@nSBSlT5(8d?7tz!&?WiMPUMz*YnU{A+{6JHzLmT6p_fA)2uE76BQ$+ON7>()#`U^xse)y$g2Wp zl~}*qol@)a#qpqF>|!;%5KO|^3c{`nS!v>wWN5}i+~8ZcSaDK_8I5R67m&637oxZC zfn|gUV3ytA0m0pGIRrBGkB+aATp@CCN1nWVZ<)$YfR!pB?3aa49%6rLj1n% zVT0k!4);T%5z-cmZES6^pRNE~nGUsPUmPC@(SAUJG?2FdE#Nm)c+xCX=V27Nn21QM z!?z}B2b0=&vzff_|4mp_Ah_IkBU87cYUQ-F7+p51Q?p z{gI^hs=#@C!TR-K@w0_MfjS~@@i7S`w6>m~PbI7u?ujgtsSD6Hu(CbiXcU8c%<%hX zD-@~0v1dQMjjAz7U_0+p*NETHZjxNB* zOJHa49Oa`&R~s1{GqbS?Nz~rCdD9D7kAT5~nW1fIr`xzwQc_4Hkvu@u@|Uk((SiI; zVYTglO*w$e?d`ST#(IOtB?AZoOY=>Ax^;l4gwc0Q@J%2Eop4u*v2Du^M?%gbZxl0P@VhL(9G?PTQlJ3fF~62>{+*h8cad-0QKbJ zPPYXTH@KstuwELK%NI}ByvUPg3I*jaVvaRdZ>)g`oQ&ip2+(3!#=snY4<8;49}Stz zVgHV8fnJ0?33++hiWS$*J?^AfR&k)JO4CDB+XM-8aeI3^GI)0l3P!x^CeWY5g@dH-rly$mAOf5>=642e|+h+=*|w8jI4S1k)R>q0qg|Q0qqx; zmF?dBrbqW>N6dScE%V7=R{n}9IayYOwQ+J6u$WF<7W%@M{4nJ-)>}e z-VPa_^TX}epfq=)Z$qpu2{UnD9~w6K^U#M$-^P&fErz$_hJS$7ll*j;gs~UM1QA0+ z@$8r4|EegV<`x#x&=DavJgYx@D>&E_IXy^r0c6~!Cect1xva3}pno8AyG8LfVW0qt zA0`E-Sk>FN9H(2e1dvq~8=RjRHW1*a8s<8X3DxUsLdo~RzEx(Th0d!?@rxVh=!kou z@{=%&833ObKV30&Ad^TG7%!Dbrmw$7N>+G5(+!S@ki@ZPpuEw98OqT6q|SU&Bl7aA z%1V|=fc5>~a)r=z7EoP49e=&f+z-A;*h=c7>{}hWy@5aZ5sc8b@_>>;wmKdD67pNc z&;vp$A3S(~(Ir3iExu5KBO&mpsHyoIAmb)xaO4OBx*jL3G80>d~WtqOP+j z*xKU4h=2mEJ*%ETNn@kv@Q@^56yB`9E4wc_C50KtdY^bEtU!|fN*ji9!35bPM&`o- z#aW?Hgrcx)h{0k(%+RU5A|uUG3b0+oVJwRd&UDPrt>ap`k{-yZy8w7y8Cn|j5{wUZ z<^lis_X0t&KGg`v)EYmuAAP_h6&ss`y7b1!dsdhs*<`+*@`hGmF74#(%z$ISoayH3 z>WvATz!s

`;__5ackga2f61McxC_yy}g{wHI}>gU}dgfr11S6-}^>SfMQVU_US* zMMYKu$8;S*6J_R-duz|0h2Tx&i3+kdRMB}%4XBy<{9yCihxekA8bF;FL4y)lvu0r>Es-yR0NkG1GCDo;`t95Ou@Q)4 z(E&%TeJH6c;=V$3xIlaAAzbT-M@dO0-?GRu1o4Uy0M&BnsRlFfp73eTf=0gW7a!F> z?{hJ3IMszuZ=Q`(K+%CZvP{y5jQ+4J_NI@1cnhIuM&7NCOqs?;M&9t`LXH$V^pqE) zPI<$pW`M3+O!WVR{eV1`JTGDzhfT0w$*T}{Z>w%-rQRU_lgm7DCQ3!Q`3`GR96q=r|b2YyFH%YHO^HzeLwNlZ1#woI~rWdepOX( zO6iwEY*LaWoZB$2Lwh6qkeOWIY2Nr9zA41)q%$r0s#YCt0seu`Kfgy4DdO9_3p4Y< zH$C9fF%#W8?$Sn*WNyCUiYKl+$G>KlW;vwDZhRgGkTTR!xB|bTXK~=V3uR?wIzN39 zdfRye=7WR7!6S3uOI9eVA{5U|MtGX@wXIE5YqycdN+($^5rIXy8b_Ld_6ITQR8BtmYNSEEpc72U4t zA_kXu~Wgh7scGgwCtC_4uRC94EKzK2VLo z`HbXbN-LS|q|-YFS2y1~a5oV3!9-g;@>7vT#4S91`si^F5|iYo!vNEjy7Y&)ZasFK zJqfY7Y$+ShFv2t`*g4uWVO70Aw%T_WS=-rNhvBY_v>6JH$fg3+iZe-%(ZPwwN(8v5 zs3=m%$du`zkFaj)n`V!mu(eGbOW28IAQ$h zmp=Ueikqo7?u|q}CWXkV|FAOCBP|iYH&5tb%ErdLC{>5HNa!BTtP6to!wDx=1(N6D z6|1ijEx4`C*h<)>Hri<4cPQSixffP|5i^HPEM^GhkZ^r^tjnQruDTPefH9}l{r&yW zPS%f}Rk>)p)*H2YeZB`U4igubKL`zRZCzG~el5`ML!JO=sDdQ)p@xfv(0h5}8JeP( zM`uX7CUHvi9*ya9$U?rL+I-?Di~)=(_z}~ZL{O25C3FQz z$h6i`6Ay`0e!BU}6Knq~9S}0GK4s8VAsrJ3uPC!s{B4Z8Zy2xO;k}sjE#YO z2Cy)oHFd?guP|-rKOlAgp##Ls6e%yXrm$uYtI^o$l5Ek&8*qHd#0KDAU*AcR&M?k# zR5mi=0p+|5#&hMJVuF9;ts-#Yjd15dxC*MdoB7G)eQH5D>^L3UEPu z{V3zRNxaJtmI3M!c<6_Ie42oFN(dTl7-rIaTDe0lWJVnz#mwB?3x}iU@pT35>5^Lj z!-8^hoDjSv(%rgTc5L3Pw|$8ZL&w)%V@98Mv##%-=$qwYX4zt-^QFOv$G5f%Iy!r1 zmW&L0r6$NQs|L~udwI5Tg%~6YoUa%9pz80NXRTFlqRRT%RPtbo5VvebQ?g(lx44KY zVjru}3}d)-*cNEhKJ4JTpD$S@@hysuE8^XjEfx7^haa2(vHSQgxmpuUrWk z!WWIVV>S{eN(pNYmF0(CJUfcT6>JpI`>k~VcUW|d@Jn^)4`ozWf)T~&Y^I6_a^MD; zwV;tjBH5hDvi}AQ>_=HyT!5}&r^M>`^2MTTLZV~}fci1COy2@JfI=6o{UD|}2yMlu zv(uEYDh$^WQxA6QUyc|?dez5GHcv!F31TpSu?2!`5OA2>)(9Ql=ShwpO6e1;aR~9p zgeW4A>jO7*wW7OGzcip(DR%Xz=Y?rQEfCIb-XwEEaXb-mjfsK?VsF4CVlt*a^W0~- z*X#*mtAj^S3&M~FFQB;R9#ZlMZD4ZJ*ImYYa(Wgh#~2 z&MvTVqqe*qMhlJ>xW;NfP^)MJBPb~@UVuu!6PW-~GU3;}YIse?!o*iljzg_0@%3Uf zlo5={y?PQd91*wXz^=*D5bnr62p?v!)L*c$22R8RD{ z8;1GQeYI=CXSRroYxI59<@FGqZhsV$pwv72wx#`xa}g?fS{p{i#Hs z$K)w^uwIj%fq{QbO--hI<>G&iLOGX<;;6R`FG-4%DPHJEXRHcmCszIX^@~hKmVFs8#6yo6x*}D|e z7)+~Hi6ziEKsSTlgv2#Q$2`$X1mObW;8fs6js;DQj$Q)bB+({ZAi$&GO6H*m{nZRfugK`;Wmppdd4@~!$g!^11VPo*p?*{UDz zScSz06%vQ#86tPQSQ6XZ&;4wcdhXG>I)=UHx zuxdn#aG1wM5VW+W$Q$a4o;VEeoP?9^NLyfFApi%E@UT5Yo7qRs!;U36??>0!UF^NIK|QMF-WMUjp+t^j4uM5+V_+%bHxl7qHl+e z3{`^g3L-WOWp3m3HA(&`(ij2Qe_#F*9tG}_cvkF2R1cgA`aw5*ej)&i?U;v>gOs~3 z5bjX}T^=STPkbi&(Ht1n7^@-479?w#5$*#U(dGKx4Or9~K}nEOcW z*Lbj1x9gJya*+td`@nG`bDZGRY(q}E)BKjRfwzgQhWt0WwmJH9UX&C2* z6oAnaZ-(J>mbS{%F@~7(LNQw-D$0N|lvo@RjiIy9l_qdpk;qy8$Wc&IR+b$s3@MLd z*u02}jb^CHSzLF`8^%8?_5loHUOvwk8E_hr!~|RlEpU z5Vbp6gCHp+o(c1pI3VOm0%2OdZHd~&2(fDkP$$8%c!y%f*GREKD(-b23kFHdr6FsA z0W34Sc>!UcV(*;P(Pyc{%X(uszAYGZTYkGh{bgGlFBF%HBb_u7CIwe<@O7t+m4sNx z^(qD#HY>^D2Zslxi9#@mkZ<*$8~@usQ#`^m-5G6{#eZ9r1KP>9YSljcBc18vy%{Kh zm@+xNu?0_;o*L{ZjDU@#f{uCY)Tw>I*|$DQ3JG~D%#IzZtEu5fUAnvJ#PWRiSs1Wr zD|mtdV6z(LDR*GaE8V zchd<3_>Y}DsfPJg^7EiC)q@>bi|vF)3@4Oh24Ip|SzBv^GrW59<{I(B1oB<;F=-s^ z=jS)FMNu&VVX(cSp`ki(MmBEV{1o$pH9(dD{wMK_Alt3GbpmFFtZlQ71P4yn83%_O zA17cK!3N|a%Zkjp+t1#xF*GiLwyLUqPuoJS>mS~ROE@sN78@V`9+?UOn;$=Ztf9tG z$12MX-}rv+R(SYcVr+n}-B1;TNVZNL;!Istqvp?4CT6_*V9X?qY*A2nh`A4SmH=-` z>&%(dx-3X#s^|kk_{#JKzW92`d9RTq@Sg-35~9YC zkg>z6T7RgjBCDy=A);$wpay$6X5{EP?RF0QTr0qMA&x7t=tg5ml2(puQho5w)*u$i za;5B;nVB-`OmKiD_*-$4wDZ`>@1vtPzMeoVPt-^e!WTDUZozsA?`mqa(8Ht9AjEhk z~p0dnl;hoFF%U#bs4VL?i-7Q?mdAHp47 zp+;}R!P69ej{E{LEWESRUz3hmTdSj$$v}&(tgdF8IJkLEWTstf^J2k<@{e-a?;byX z>{F2R=#eK1%}#PuA|sU%i2O7(B;neqBQwXu9CG_MP&Fsg__qwipMn6^q2Pa-i0`|o zo1fI-w$egY4Er}PKi_gr(O*f7s6&2?pp3agMuY z{C3x7%@O#KbkHA+3;*RLwsxP?1(uzV!a)&z7uJ0>8!~!U*JAzd9@+I z%WDCdQU$#5F%W+~Xb;L0^76k6^yvGR*KyPK?$YrkIS3t~%YHb|l@Np{RSFIG5d^}s zXMZ#=|B_GiGF-3_olz3AdC{Up{#UOOK#q~7c>L*upDh2q-2PuM~CjoAeXHQ$eY{v+2bCkf8S; zK9pmGuH&H2f7luNOoBwLehZCMeI>(6TiZc~_vn0(C$4i}{rpBmtRxpn(v2j0Wp)Ha zCr)-AdW!&hGN!G40hsY(DTvYg%(w%?sCQKSj3o0|*4w;Ab1#kxVo=n;EC(3WcR6pM zWWiL_;>Rl2GP2R;x_~ER-;3SD=!64QR5GM~@mZ!0Dk1_GUycMOoCdeovGvpXl6PIq zA{rga%+}TzA8#eTaSIl7ImOU%&M+JfALW^o- z7$YC1{`g8Lmk^U;rJywwRabv|(E9*L9Gln23i}r3yz>dC#!xw@W1}-7m=z?SS1Lba zwf?L?#+Gt}23L_;N8=K5EaE!%B$DG$_V3en<~v+1c1%%g-gh$i!||0wnLxX0P;ZBJ zx}9c1a_tSZflv9bZG--1#sBH=E@$(+Fa7Zq!WG(?9|l|g`+)xbx0DOs>yEAbmrDHo zZ{K*k=nwxFEd29IE_*Jjg#Pm%|NWM~UX~#{C&zqhq${1*m&eY|j?g%4JO=F5mY0E5tNRl6fN{fsPbYC*9j(Y}?MKn|KecGS=vAjvy}55xhYs zX;P3ds1+BInJGtRr*Eiv0~!~;aJByK9w%}@H_v&Tfjl}??v9`18EI)Gw(9+Ec$!9QabNqmwgShmy-|}Mg1n%*;sGsXmRck{)zHM=IZ~-KH-m;F?I=Vd?YAgfY{#P zfbn_r&fXb_$esp+JQ!{7=4Xc8{8zITq)Y;+O325z|;7r9Q zcCpr^%Ra=-MQYC>+YSv$M{SoB%{_ba zgcd%wD(+IV^((ekGc$t^A#;0(M9C~Hdbs^#oMVp^4ComdExn;eE1O1>P z3f2U1(7~K_dmMEAuu*lbJpLLt`yLb(%dOjT+1GdX1Dj!0Z=j?4_-D;E{Q$l2=E-Cc zCU+=Ge%rR4LM-`JQeV?NJ;{G96v^iVUi@0kcemd6?&`@9P3OWZ3b{7(GtaF~o!V(= zm|N#&eQJ9{ZS9TMa@)480&*bvA}ozB=qH{c?iyj7pY)ht(&^EQ5OLDz#eX-u!FV@& z>bX~c%O<`s;OWG~k*ON}cp`#mejx9}F|3v*cT!;-5zP~oTnbc>5T$-Zd6aQq00LSh z1_$UaASb8adj}7a4h$4m$aRy!a|T96pEP9riEBw{Fd5ImwGBdR*V6X`E0GWiqB{uL zkvq8XP8j>qph>aw{xSLY2v6{9kFr4alXXw%5xgNI^O)R;=gD=n)UdP^5fLH7yk;2K zf?+|VP*`rPbtJujz{z7U2t0f^2*n7rg?vVs|13qui}+arNX#Mp4uY-Afu%7QwvZwo zIfQq5#U_&MTDfv%@z1!N?g@M+xmg1T3|B>7hQChN_!N5t;+6{9r2xm3+5$HhGS4BA zgm8Hz3Em=9P6n8PN~q}gWrgs%k6BvMU)LVPwP#w>2IVAe4G9cGoM5X9wQ?9@&^}eR z{lcdXh7qED*t0Gp4L3THARQhb)ZH7|oKM8gAGj}1gB#EM%gixaLQ!M_3>eP>X;DmO zmJ;zBph`uEOG6NjBO`d& zAR$&O0`=04W}jJv6guwdyo8d2t0yGhhq1G<6=9GKPz&XPJWMznVg&f!Dt7=hAs0fJ zr*OGUe7l5}i0F{zz+abLB_{_TZu^V_My3NXg$$Oyh(hA*wZLWS#^Yp7{Pvp%D?+fznMeSVbH<*wvSD&&R7Va2p@okmn6LRP4g5)y}bT;-Iu=4`uX^$>eA5zyzsN>XnC@Fs9ihmVWKtOVaUC*=uR`irml91La1= z*|Mh~s^YL%&Yt*Ft`aTt3!<+Fw&RRMk3YA`qob!+25#`FczfaN2hG0WDuq;BQMU>T zgKuGBVNIBix3>t-fe^PaB!W2cpq3*HN^ULz%_+`W*Nf3hES<7AM+s&U;IN0qUnheu zesHtM4Ico+sc& zt)NIeZGNV3ekU#nAy=3zMaTm(?-H%)owFE08bRu)8)_4|fG)$XBM4`W5}8eLf+|8T z7Jz_(IV>+g#kgNP$(T7A4utwk1QjrE%tJ&5BO!4G8`KQUlMQ4o!TA3h91 zoq1j62xDQ9Ms)`VH|RfunUMT6cZzY8w(CjIXHogllee| zwyptd7GvHUg7>ZP(uJNFCdBZKyAskez=hICSE0;z;iiTXbbSEpE9jcw)jjw-OhGdk z*{T7;COIM`EFc21V<3k@_b|#mzYKL{H^?{AwYn1TkwS976!A9<{*$p9gm(fEFML({ z3nC^NUi0`hx&#MuAps@Qqpxem^2h5bz*YCwu-y|>^36Os13|e@lcnUm~mZ?keq{# z9$p06We^grop_@pUWniwbvt7P)U7OVu5 zi#)+$&2VtZ{S?^X@@~1Nbrvg^x+Rw z5F&tP_Gv)NnHN)9DP|>$;jwpu{xH>rj4M}8hoq956)?m@t}FowWzC2{R*$IL2$%u$ zErzm)3Q;w7gQTsY$t?v*^qI^NwI%%sNSItwLFS#ns$OeKER3F=K^;Y}J>40fR8R~H z7oU0EldpY!rfA~0^{ot&IT_K!+o0H#!wo$sxoun3>nETgOTr zfm9qkH$8sJ8dFn=M%g$0{oSYg*I9o|T?;{iZsr#>N1`erRfL1RixOG8Hd@_*i8(tf zOAGKo1n8}ah$mgGfyi|*Q8@J+%;dhmYZ!N1!x~YKYN@8LABGFHEHiLuE7Fj96ckL& z%zOqeQ}yIRf1M9Xrv3)YSFc}3;@Q22hTuI`T&%KDRyGn*3eiu$NGBR>2xMo#npv4f)3S(V#E$~_QA}>V5K0(n$PT(Se zwwEt2VF<$CUqo6OS|0PRUAtbV<>M{aVato49wHa}$^49?;}eprgYf#`HPVw)u81mX z>+3&*lbHP-MVX2D2JWcT$Q4_aBswU<&kt@f7L%2A2j3lonk<9R;oTiBo0*x(aHh=v z!`_>RbDh3#|Z!`th1FV}rt=XIXv4M;2V10CzxBdb@hUhafF z!VxZFJLU>uB#vx}=%AE_(z3FL1WavgYqawi~xab|Y0nn!xCVTJkgx1-{c#HQ@Y z$J3#Kq6lpAMI~N28Yjw|%OWBoY$BfnfhmJoqLOde;_2bx@nW6Ro9}v%*wNLO0IKPMG<$<^ zb8|C+x!GIV-@Lg6mcKrZ3*Czs#js(0nxh6@!>v5!P8{2Hs8@Pz#LuP4HOp- z4^@Fd_CBMs_At{!!tggL8L8=-*488Y+Zx8bOP&I9ckYUdPx50E31OS&+LsW8om%#! z8+l0t6a#;5s6v!1ZfeSUGkv0Ib19a?UWB;-V}KY;6bmq2BZ{PzCtCdv7M2!QR_;gX zpP3g74C8C3aNxnhKCZzqdc`htFXhn-IVb81SKfDt4YpI>gxHQF@;PEVPcy8MoE;m` zLPuivmx>o5caM5jPc3o*+S<-t(vtvShRWbJ`5{!r5b$ynjuzl&Vzr@d_k9Jrk;*Ov zWk=3o9;5de#Ly+e=fbZxFt4DXj8to&z zk4V$53Nt{Erw*E+Sord}wH%v*!x1s#0IY=byRZzwF9nB1|-mQO5 zBrmk~XRrC-NTZuIzIbuz(-Fm|d{Rx8lXMsHDEbYF3}}h!4zshe9tWlgOhl=761|c2 zOk$W5-6osk$8X9^SG|Al`GB5<(-eFxkQP)rCP7*Q?TjmxrWW)F>}Zl)p@&l=)hR6{ zr34nh*uVo2#8*{SRlTyC(>_&|F`YiiMa(rE%>I4IFoq3in9UXgRGUuBV->F^2uHN z{PdXFTkti)@1wd)`}V6S(%+?JTyJG%1r8>$jm5FJ%4U3!Q*a4oqP^3FeHa~SEN-G{ zc@vgXfp69-PYZr$yDN_=9-ac&KKG-*8i+xn|dXG;6#f-ZnOfBCcZ;Q)_yRrLK5 zZV!i+2^WsxC??7WK>nl^3QayC>b#VnkCjy* z8%I_~m$#o6{XmHGlZIbu=h^4?PPE|Q2q-$JT05trGE`dl5TN-RWDU@)03;I!e18C> z^$V^x8%y(~@$qXZp9}p{X1ZREdr z$83VI>*~gp>zv#fjE=cTt(dnl-vEYfZ(cQH-~H%n#vh;$UqfQ8i82&wg}+fq9EAHe zVSfxAwcl7R2=IUg^yn+i>FcnOSg;5|`f)yOaDCvzeDfArI}%@#9$-~>V3hDJ#EGXR zd&v@(pB*__55%9-I8Jb!O(M)oaA^py2u=ad02ofpP7ftxjUB1T{(0vN7Aqtz9tg!c zgftKNJoGD2z3u&xcUDOEzg0*gb==K@=elNGoW5 z_}7nP)9NzUE)fMY_Cq%g0mX^+wU`Wc_UEP4-rLk(Rblk&L0vqLjuzmV7w;HDpay*k zF*v}&q;J-}xjRAKuD$6qa!$2=bNJ8&hnm%#z1N5Y2av@JSlSRx7V2hnx_O3fsYJ*T zmkKCDJ|RVcY9>)eWAa-5^XbfZybDnnva2TgNFO?Q@J86Re7oty#P909v#PNvL%dz% zjS$BFGRf?Kq;>)tKeC1(n^*4oP^vVhB^8_EPy>_$hcfZ`Llt)bNz5-fQ^Gfot(dEM z0*!I?>T`OI(f|C5xwnZh79P`WUq+V@nPoE?`)vqY4K>$l_Dx?028hxkfbm)qR94VV zJ`M<2!ZP#s3-qputREp4h|IHZGq+q?V7!bJk|&vX`h&wjjy_~f#95M)lEUbe!5cvtnQSVWt2F!&I>8GWo`La4rPFXke5NjYb$KTir z-mHG$1Kv9P322(p0$+r ztC^Sp>8`3xe2TJ5^#pdxBQ%_@Je>F7^OLfCZg`Bq6o@^9oj}A(I0EjV;pfMpzI4x? zFt$3!#t#p{L)p2L>xwOg2P?m=$4*H(Gp~APNnMjIY`#EKd2y+H8*xJbHiN_JT0{{U z8xU_EWzSY;nZkk=%~4$V5{snkT!xDsG@*oROEhjs%i*-4Bmq476bf!&hSM}2roc3z zLc9t_P9~4!{t9B+gKCYC|4kT$goFqO5nbYrqlzKV^J>9wfeQoM=yBgsb|uJBiTUEU z^3U~KhkVtf}Z5isH>~%JlBIr#E{dX@3pC7J8aG|Y_Zh+)!#=^Tp|n*e+^<7 z3v2ieq=jadW=N`N%9c@x`2bWAq=+Odl*gcJdOtu%wI64CJ+=o6p7J0$*q;07nX;D{a3i?#Dta>ms==vU&emFN=? zt6Us?u~!{&HlZ{<{)INF;tBsUfUyB}WB*YIwcp&Y+fR%>2p|9v(j#e%YCGW(qrClu zE?yBqDzAMKr@V%^2eW>c5RZ_=LB4knO<2SqxV`Wqf|I*;FdE_@nUf9$m_MDoH(G4fZIL?ThI7~tI>_Fk79NS!4ikp6%iK#3a-X#2i zKhgn>JE9ah-ziS$O22MzXT%e{GVfjwzS1+L835BTG$W2~#DxMZM&*t?XcI|f!|GA+#s<8CX<=gASN$~==eeO4A;!TVLZnH>IT5hPq~$0vQo>sjV|`*l zi(bu7;EZ%TRjJfFNGH+DP_==!W$GC+JIE6Rk+VT>^#}29L63%pG2?6q+t)u>f<1*W z5aLXazHRM8XXFCZf66wsChCwE6Z1-#&XIHG7ie$`cxttoY9ZQLD7*=|@WzfCC&AVO zz<-rk(twnURG4mX8sf&V=x7Q3A-wa>{H zQep;-ZA8@k6saKw;CFa?(!nC_dt{_2JHJ5^K#7?746y0WwTo~~rP`mP0`)#!;w2%wi5KrC;5D}dNhKv>Be|&I+vq4k&wys`Iug?hY!b=HYp}eK zU=zrSDEj<87JQ(SA&~|ELs1YM^gvq#<>i~lm{-RVA-8$aHc%rdh8|)j$vqz=XF^h` zsHyq0zEjxAkUo^X-;q7eO0V;znHdjG_tQW=NW1~PQzpXE=^_>zL06!Fz+yWyv1$eK zyO@g@WWu1wTH_osg2zR5-QQ@<-&W(e3ltCkbsb7oLezw7&!^Ly5B-LYXSU~#p4E@* zK{f$cU69b0&=xX;Cm^ThD^F02l?C!rw)A}I>QV%e64G#Gs}Do9&?Fs)l*7Bx@5vJx ziazA$wXk|3uy>RCam@0&@g53H~3h}>&ofl7dGOTh2JjLTyV-v|Tb+=sPQU0+XrA8^BPDAbhC z(&O3y80Q!eG8kBBfN@TNMkzLh^;c3~?+2`b*Rb|J8XUdIzSz3*fv^$241%QD)vKNl zVsem|d&6)8&q%NxY>cI%sEWi#^2c_~#J>Y&Jlb(?mbeL3S5-Yj0jGea1S6X*TWTOH zD0%nJ6@o2!to<--`wq2}H*&4N-=Zj7z53#XG2{ih=g*5$;3%QGqUcfOCO zzlWE&Q;E#378Q(_#NOpjpbh#KreWKFl?E@;y|t#3Y7y}KlLqoHmP16yOP&%A+y+Gq z$-B!;&#`w1t^kadkeZPB60pm81m$-izd19Y7EdfYeBdn{Ac_WdrHMh$kCrxJe=PCL zu18mlbOHj5tBthU2$X|lo-mSNO)jfu?;1Cd zO+7hEz0UFd$B!_aJ)YoWfR_x#%SH1Uz@X6O%Dw@sB`zttSWlbFe$}& zCq=Lr-9wPU6y1a*l{)=>sNYJvP_3K|9eo^%gk^BQ;8WB3djQkuL5y3V1ubI>^^T9V zsoUgTO7vg@1FkqrmO)<9ixZP)$d*0s=~D{WUT?Yy{iyk7by3Y<8}N!g!WUDydf`Ay zbm1FQN7{$Zs`vfH^jFi{X^umOHUd|>i)lqJ-Znj)v%0t4joM|?)Yu63v{~&l+W0_n zERrUbmDRYTY-TCBQt}!q0A$b4kfm6rJV9h2(sb0Q#4j~qD^^po!;B4t84V>LjBdk` z4W#h5ql$Nb4M<}A+>Ang18$RBMbtLf`4DwPRUbqwDnf=%ZUdw#%180}=LTTllZr*I z$uyF4`I$fGL~!24+5bBvvEx$>6EuyG+kYh26akEd+Y6$!$y0=B0@4sgZ$>@{M4)D{ zWZ2_1%-EOw(!HZ-#0zW-HA+;$q9)vRVzPj8O?7$_5@R-*X7o70e^&Z>L*`p zNlgXo&fT!m7KIGSQr^78wm6UYUFX+8?yLZP_vc8B{MLgPmlGm9zL&Md>T~fUn8@g* zb(I^cz{(+SsxOYFrmnUYzFL3aew1xm_UhioCa@4d^Wbm5XYa9B4Ud^x2EtVZcf%3y zP;!3(DxfrmzjTIHfPh9CS7;GNe^oH7#gcL!Z_t2;_0RBoh^~JO-QhcMKw(1lF=`-d z__zUUcZG7IZw+AC#qyc}bC4QE`_ZNF3gaTv2^{examA#CK|F->m9YP!uR5M&*M-j) z@T}dc6QCyw+D-fk;P2-LzI_0|*k$l6x5b%a{?>1kG4|Vy^@OyPrUu6aSy1Y2gi0dy zeHh0&cq$_m!-<^YchK_NE*p4wQZs z=)iOp?LSz^MpaOtFfua2JpT0K{1r8kl+umVYbAUw;~ttDCqp zK=3@E;m}jSEQ9_4FK>Y(92MY-_%!mwh5!CD$yTw2`*kfXEM5Sjg6C~wWa_2=?R&N< zcMkmztU}rq^2I4^AcWn7e*sui#`l&=OG^j%)`QYVD7jTz;Y31^M2ul>LtI{2!@hqh zc=LaX+xcI3c!jpCzo>D^Kd}Shs!c9K`-mfxkfqwDo*+d9)eym6k5_y`1kPDvIHBT3 z?Qp!ur~mkGLpXD`ZsM4(dI3V?JOH_TdF^$Up?!qlR!;OEV4D;I%7R)`DeMOO331>y zxG^*$!y4^IWR6DsY`-_r{3j>V(k6K(oFGkKU`Is4I?Ue!?5_{D5Wg>+b8m1l7r16#lCVc71TJDQ3a-{}bP&6S z$xVIetT@ z5QffuaVB`k(bCySPvforsbF5$q^}#f`!ABd6fC1iM1w&ZFotN& z5D5PFEZ{Y`%0?XaFerF%EjK^^)vH&Dl^tZa=fV5HD1L?eqeIyeiNKZf#)DO68l=vaXS+rrpy#7hhJo~c-El9CNVL(neLMX&`qq&2c_BLp21V}|aL-1eXz$MPKgaXPw zQPC2%2nvW7xZeeMG=TCA5K{d0iEu#hSl_EoGp^oP1{T(B)H@n!hAW2xb5;h>KL+!`taf;tV1-c8xHHEnLQCJ{jL={+-qDQXZ zA+~_TI~HRfG0gj4SHsq6)o0@}=p-$9ip7-q619knn_C3_5%3kz!t$qub3jXDl^Oy5 zu%hXG|2~q&Q}$CM&ycY=PcMB+7y(!MaXGDQ0FU$i`(R?pf!*uFp9kFp4#r?%d&s3Q zdIqSrdAikz7^%5=)`@K-aJeG2OWm-XfnnJNMYFT+mPXkV?L1p1U&Cl6iuH_yw>D$)79=62B51;8~zD zMJWlQu$`~il--X(v_pB1jyv7p_8mL$)4;^vqyq^fLMvz*<%#rE0=P7sxY+_akx_G5 z$)OjFh2$qQ3&@VH8a>88oMg28tY9esq1T_n_}ynBY+UZ&-$fw>ElX<#4|;HDu=|2>&oTwh0lo>+0f3>KZ+-d)TE?-1OnYE;hDU zm0@LNv@jtPybn-q35!+%E)Ttr;UjKVg#JSO(9B(Pb8}m|37enX--%=e9M(Ol@}!3F z@*?8aU#&#&P&Za%Mv;T={|CCUV*$!}T|eUA!NvC*+8M;2nzV<}nw+=ur;tl_Ah9lv zALL+1r;prahI9AZ#CM{h+zpaH01CElTFQJEm(#w|=+vo|=pgF%`yl>xPbNNLAUX1XL(W=lL`wF%XisgAHB{&H!Wyy_%|CD!Q zWntl|!Gq;s(-6@g(RJg(CNxP%@`NXYgo>^ZE`{rW&_Teu3vy7k?@vIDMH%Q@_HHo~ zTsR)bOurwODdvOMJmlN)Uk|X+{rM*a+N6#RY4{Ihhe5=F%H|GMC?RIS+Dam#d&2{9 ziW8Q--Ehf%ns(YI!~^{DWi0mh48h&dg=W2OiI3cuT(_IcR(&GS*Nx%5XaNx>6~P|W za8sQ^h0DCaS3a~5+n!JX!OpP5g+MGEmNm&Rn%_l{6hBVoh*w$**lEkGR=SB(^{`}y zWUg_5Z$UzQi;IMg(k7!xd5&ZAY9;%hZX1@F2O@&TGjlwbk<(q zS}c7%?gl5K1Lzh z8RRMh0_2j}#90PnV=?MCVzY?LG{`j>cYG7-^nfl-Koj`_S3{7V0x|f81|TBtw6Egk z3{>^RoewRUUwl;3TLuS~LP3y5ihA_gr{zQyjL?d_>;kwxk3o<^Hs=hd9Z)Vikb~e- zTBV5ZuQM>$m_0NRI9TM-ITXZjYwH90es&V<}syY}6`BVLG#w1H~4B9os!sk`&h zs_~Y}$tUBPNBBJiD~@$T$T9y_yp~0`<|YiQX7VPONTOpqIW-ll6d{EpNIJ_47efV<1|Q2nP>MoRproj1f1T;EnNs#7eK4(1 zn%|A3#ykhiyN;em99^7Bq03Tcl|e`3k;^IIWLHkq56!wOWi=*uTeXQE|@-5qhG3FUNNp>02$@anO58!kQ}(m)2uFz62_hfE_@` zMnzWLeu!@3*CbIW0gp<4K4%OJCKt5a8>Z&!+$5sa2 z3H205LH}bJW&%dyd`ml@5+4QC2SHj4S5y+vBV z&W%MWu$5ui;wSHt?xbm4%O=!fU;}Q!HnidQgxXd~XVjEpRqveEL|Y7p_RdL7tP)PT z)r&ty3HZaABP0l3B~bUfxnDR4uJs{-rN93-&ruWgwZH$3vRQ2Rn*YOpd$=|Xjvpj7 zE6DhPj&!LmPl+y145q8{r3v^d-u1aRendL|_4{}43VZ4)dl>@AMC2z(I?Q5pcJM(T{L-)8i{Uy-UJLHG{}h8X}a8n#;IA1#LE_@>?zflMq(u!IxB*ubc$t(1{e|q0ik!ul^DG}uIk`|I zLMK!c3vt&v@Nx9D{Pu!t7KbQ=E{9Kcb~g0GQ}1)Ibrm9{e0_v$uj9jGkc5C>;bk$G z{uXEeoZK?JQrzheo$?|=sJeLdGyGjIl z1P`9ohT-?R@f_846B~06zrE6~^+x(*9DNuc-}v}=NHm2dmB8);Xb}$%nWPsQiwTG{ zXV6ZnMUbUpJP-~0K_^DX53*=io@OOfn508z>r4uD601unK z{@+9A6kk%kPGkIySE2%p+vZd>Sb6TA29G8)BCpNf`lzbH)9oFP`MOh1i~;QoA{Y5ZM3+g(+8lmky9xSEWZTBsw6T535}w{ zLgq$cA9mHjXU#k2pnU)f){C6OfF>oW`kfemfsrobCxj_L5PT3HKj^q=7$;&#;3$|ea0Ce? z0-G;i{0=wNd}wTp0ZkO9A9B|VOo3cgC-^N{d*Et3~VVD!x{^rw0v%?iWgL8amd&WKtv)A!N}Soa8gN4bxYNv zWH5sLQvm-}S@ ze=N>tp0caR0Sawnaa|p+L4cc^8zg}VI0ZGGY3QWbIB;+pwZ6J`0@vRVw;Qa(r@H+@ z?l^cL#|%THkHP&puoMd+y+BD&9Q^kpPbCg24M45xz-u50Go!=AGn&mDj}KR(=mEu@ z-@|a6(oKs#Q&1|=`TU1nCeK(aSXbs zeE@t@X5gC?OO7p40$eO`A;vDaLi5QLBEpRUpnx#oja-#TT%gL)?|9>^0d#bCMw5pBrPC2GFnB4P!^=6V?G@Gc~^ zf)>a0_RQckG^`GPKuob=+jUr*kyaXk3o(-VRP<)}S?V%MHLZJ1VR3Z+^iqklkTas5 zsKF`VHM?~S#Z&mI>q@7QhdPJD_gi^Yx*WRHD~g1)4w%qG)5~a2HbFp8&FK&&8x)E2 zxaL!{y%*C-7k#u4?_RQgf#Z{=8geoyIBhKtA#Ho*Fv0E3V~Ymwjfo@K0a_9 zRWzH%%jh=Sq1-K8C%`gEM9nKaoQX2Y0Q?1c&AB>NZTn|m&x&DCE$~BAO4$DA zpKuR6DrwV^@3;8r6w$)dyMvt3eLI73l&Rz2!lCvQ7yv#Fw~h&#-N4qWBLS}bQ6K`Q zGLq_U4gX5--=XRCZ63YdL4ONxK5~Lx^VN&04fy1gy$;LitL)2S}*CXrk5@#H>c=3k*dC8d<= zczP)%U};hBOFh0IOYAtDNoA;{ah#sQ{~=$mH|oZUsd(Z1-X$p+!Qtdud4&%P;VhD{ zPaYhUT@0U&8n4CNhPT`Q`t1&SSz`4_Ea5MYS{C5rld5Z!@LM<*fB=gE`vvkAjQ>QL zdvi_TEA&8SdK~k=N_6F;UYf>ygiLcUn&Q1O%--N8!()aU)X%U^3T4*06A%sg`etoc zyk+5!4@bDBdvx6Z&kaq8#r%#;{Hsg1C*FO|$>F{OAF8fbM z*HL=66zNkW@{gWcCOTDcaGO$J-W+pk;}yBIMkV6o=rw|Vbu3bpCb-Un2oO(BZquCa zg(o_TTM-puIIv zS#@iE`W2vaMnyv5#mTOnmjhzKbn$njydFOZgH(U5>Abwzc|hqj=pP;bDHgB|jd=D;*eMH5WW8FI6OX zz4UTRz0SR;^RB%H%{KoC&)E8&{yKi5CQ|p^o)p1KK@VF-FE{Cu$3;1Ok`F__Im`)t zF=*cy8THQlF#hm1=0(CWf7+5<-E*0K*KCKye?8bvvoVhYGaZg%UncH+mVZ1u+CC@3 zIz9BmfjPiSWPDt$Mx;NG(Yj4n&*9_pB-Tkg+KTD%9klPv=aPG8&As-TSMT_eU+Etd z?^PM_^5?8XYHw(b+oc+j<|9H^tNDAMMD&Jod&}@hr%3tLSvabCjaB;C1+NN`PEXwH zT_-YqflpE;a+MV|C5307tqr|=&uX1Tj5g_3f2=0x~Tk;p=sbVF9t z-niPwYl@pxte%8_Oxdn{;EGS%RG$txsOG=uZ#TxTNQmq`HA$bkXNTRYd_iy?G73ZyXyPIw;@T9+h*BHE_?0AK@16`_~`ZKi&OEM&5QPWGwHeqx=3s z>xzcAKR>Ku4c*h&#~RSds`GAxj_=%gIjwl1Q)_J6&m?j0k36rm@NT>MdG_z^DZAut zG1~RL)IKl9<(P%9Z*Hs3O7`A67pr5kR>>U*)RW_*KKK&;kbh%&3HR{fAm5*M?K5<< zbD55bHoO5tNz+NG<&NBT=UW}SvmE6F3=Yi+Y%t^zdDSyyDO)11B5Xa}^i$O4M}Cxa zPH6A5nanxH)LDL!*>96-=GAK6lc6=yl1WaDPwbjYRAi}Qn(=>K4D;P;by_NiJ+(LS zUF0#I=2InC9M62u^kCzf<}J{jlm4D=wNJ7rN$Ox6qfpn6r=Ba$AEb+Go3l|&PJS>o z`crPw!r|oD7`HH^XPR$=+x=dR_TAZBhXcb+SMm3{HSTePFU7$%i;TzaN09^CYVS{%Hx(BPwGbc z$I}ujg@Wz%d{jK%#kqS=Z)NxeUrMMBo;q!$Q)ZCWq?`VPn^z%;zn?|t(829zjeKJ| zB6)aQ_DZ4|we2OJC5?Jq6fL%XfGn;rp;}f`=!D-ZpZ?lbANjq^&HY!Z8xBPX%}8MQ zi^5RWqPoC7{#NZV{#VX>LTJfJsZJdYr0WuXnnbh1AnwF9Q~fg6b&FXaWvvw_lNeq7 zxrQ4_NxolgR^;;c9@8u9)VJW!J&&D0(Y>%!c%4s%<&iFtHqB{Mi|X_nH~;ZgHOYe(JK4r<4GrLxK8PEL}d2Z2qF98Pur9`V(R(Z8`#?uLz z>nDZ|E&lNNYyNwfMr_|67ihEg_>|CD8)@$3Q`SQ*mSNFdLUGz#(x&S*K3u|f9sT|! z73zB~Muzp1tv$G0mwY)D+&L-UqyIL;GG~_2<(jKP(A=G9{kn^IZ{`yOqV_u4*c4ka zen@$2i&fXFjzlNUa{|fJud0%N{XBKc<_*uzxY_imwJMzC4^>?=bl&$yglko@=W4~` zr4%RK;Y*c?!@E@wd{Gj=Q^DI82}^_?zp~I_hZ_&s zY?OI0bgX3PzIlpqaha_Ni4E*8D`9SvGunKkr#kt-@1N)9;9wHlvMoQdJ+83t)U(@$ zR8~>mrdsmz2j_oYVxN?c=Z{EQ>gAJq0r8(+nk7cf3e5Tceu3`m{7hp0+cFwV>5MHB zK2#bin0fbE-YDo%EB;JI@U>1ZH8*RA--v2!fu-+x#%KF#axC@?-2MFlm#^<*61yPV z)N?*lb1Lq$N*(8mbL(vR4hn2eq0B#lcwKIe?x8rhK8I%NwMK5ksymmm?1icqr$E$2 z%kBRAuE;zAwdXGq{pQZ`nk9I3zrKVi*nFH!K}f7zLt+ZOhAi)v3?-Sw&Z$clMg`*S zyo)Q~8?|G@hODOA)2r6_tE%}b$6m};E5Dac9^g;%0G>?Tv~*o3E|AUiF`%*OL-Z#XIvdt$F5f@4MoLd!HmLHXb#q?`lujIjQ*-{w zs}ck)A}9B=?HJP@eSAor*}J4izxd7kdN99M>L+W0#%F!7C>^bXcDK2FZFPsY>+cWf zD=ZJn>g$ToE)NlCy?B@ATwh$qm&$Ng=Z=M+FY`W@@#JZ0Yv*<@B~E)ahKp zXfM2h`n$YQD{iX~@a+NtW0$|MP2D6`nd>Nna6D@_ij!dUpQo z;ThH0Gh66?|NK90J^IdRh7n~A{k`JZjip=07)L|K(HDsM+f(>k@E;V)Ikl>b1)H*Y zMMI|ZRUh3p?NJyxOEY!l_Tq~0ENOLdspi+#)>@a4sKd}*IvJZW^-hb!XuA=nOOiZ> zXe`T_#3zZXlFpvQ}5=$n)nGg$=4(#Nzt&qqu!Ko67nQ z*`{5&^3~OS<=*+=q9p6vS4THBlQG;nlC4>Bq_!f=*y8+KhsE8!%RBQ%x4T@1VZ@6c zz9Zd6Yka?+;vEhA!hLMjDm)17GfzxfOkdZ^brxm?YtuBZNoKxbXS23CG?V#N{@)LI zMYl0b=WA2%RE&~9%Z-2?rg`BR%#KM{_*1qsth3%bzeoDEWtb%BgsxM37;&(4v$}Zu z3hUmHywp=g3y^~7$}KmBLfkESp7!jSw2Uqj;1~B(8NU|P_4&!$9{txkB-T+Lej8{# z8+9t(yTNNmO0K_bzyFQC>Z;$dYS-;7hAmOr+P1Q*^K~0;Cf-bW$QC)sXspQPuX*b9 zvXJ{^eXF?^-DB+Q>-Vj_dX05HUWNRZc;)%GctMeoc7{pHWJ!E(YkJw3+!D*}J2|?S zX1ckr6r>~j^~F{+!KQF0XkzkhL+-e^< zCoQ{KSiR`8vj6VgrK*RMs;Zne%@6EmJssl&wlY6f)tCdy=epu-`73&xlQ}opA8P8+ zU-%e_?&ljfrsbMyca785R2=arW~-1)8f}mLxeqh%+< zttCIQ^LEysO18R)g)sj)P8NNMjq#p0mnmD+NzP1s;b*Ne0*glkKW>j9V^S{K8nm4;{Re%9lT#Sjssi+nl9!CPy~D z>3U=Ab7dMb)0gHyryP#ev3FjJ@`@bMKDn&D!R^+~sf(gV_WiRTziZ*Odd1@#<7MHa z*7q}*X7IY|!N$Zm%j^U;_3T#|o$mSGZ8i0g3!Nn=i-hnNVb$+W8?sccx@}%NuqTzj zYH@T9d=QfCFLYOK4QMy`(a+~nYI%+`XhqzW86Gm-+vh{8`97nDdf$)d(*$_Wp1dvc z-uISvf85Ozx_m(xz=fx|-QxRFe^{3{;H7xGWl7xGN%zvIzc=T8RzysCy=H!@?nY~7 zrpTE#h0Ep3DOMTlSd>_%=P?W?FK+1bPRk|P(UhE~?KXI8v~QDQk5iyZbG#v^5mtot zd|-TifOp&B_b^JRGcG!sIdfR5+svaOr6crrrf0ySSUt>dUOQ_ql5iulTelI^gn#QrHBa^G z(vuHs^M)MLa*VfYvF5ArnsIs;HRqA%nBM>rTLRbbjAsZs93KTSYt z!&o zV@%T^DRi^(5rJ(B)1uUvm1b0zZghlmbZ59UZ+D#Lz>c(;Z?cFx3+HzAI&8zj)Jwez z{+A4Mr|u7*i;rR`I%_!BWREAE{}55O##aX38hKNJeuwE3*Nh4)mIQg%8dOurhs=k_ zYC0H0)Xhv81^&@2)1OfIy6u7xu*{Mh>R^w^h%z9zNrqL};3&9ZtE%bRm7uN1BRb^201@*6j1Da$sc)wne6 zp=+{!LgSp9u+y9wr_zg~3j+e)QL%mJsePLtDz**{mvoqz7&m>4F<*7!_j6o+Y1u7T zXWFV^6ia(X-}^zS<9EwkUMqK?qE%IthhZdI_o{?E;rF%rajDB(Fs}3_ou0RTSlUCu zP1grp@ICWio?^$Y52@frXyfRKkcuOtXWCxy^$E=xsjHtkv)kz7F*Lx#jaK~V_Ge|0 z=o%bUn*3OZy2+?(hpE<@T$9CEAXqS{?V#v;seF^dbQd&~O%L;PBC zF&UTQeG_tn5ep8VB-stm9ha`MerpBKZ6Rl$do|m#GItwrZtINe2~u2~>DT!?esGWziG87G=H?i#8+v2bZxJs<1Lp^a{?v?N-OHMGZBB=v7^dvDhTxXdBX##x zTpr}gdEwRJ`c?{fwqxV`vMb2HRjHDnU^7+zCJKN zK5u&)(d-Wq(Ka=)m7g4wui^CnI(6~t{(_$$lR)mb`?Zxziv zLFK>Si-+r69*22NWEQ=u+O*(vi(})gyrzG}53ge<^FE(LiQcV0|7Q8ufp+cIjJ4E9 zGlwi2N2Tq5v|sQ+03u%oAI+>^T@)0w;BJx>v2E)0>mM49rjKSTk0WvF$b15H_YzM4 zb*@G}E#LgI<+^Qb88Z%9o>p0Yc}E%-4}gHCy8Z^b-d@%-chp7rIOFfX$*z6zZalX2 znLE~wh4cJeSu~bxBA!(KNgQiPgdu)oS27gZ7KOXA`)a{ z`?$wBZ8AUF)D5-0$J)u74-`BrjLx1_#^ohZef26qj9+5Db=(x_J0QBfkn7N|kR=*v zCd8w(p*%3=eZYYgN5#dYcO&`VMz7Aj0+TB!^S6Pm9Z@M`B{sUBfwsJAKTw5+Z|72le~&-upey&-S)tN4;eb zi2mu$pwV{aNutV(LP4UtN`v|ye2?xQ^LwI(?Od!6)2&-n=8-MRf}dgsjz}By3!5^m z7F>)yPHT7X=8{{5M33(F?X>WM!_LYM+9$czRR@K-;rQ^ppg<~PnFP(QQUS(4p9bDr zraY#m$1k4EcA!{#zatIr;(TTKJ@$O+d8AFjcPOvs6Q8-|WW?WWSCg}CDnePkOLQ#+ zcfAE71VrVWufKLZ<95F2s=<9`BAu*p%g-8Xbj7^aPFl?Pc4_hKXEv0t3>j9-)p&T! zE{0uix~xm-*l6Hfgp5k9^y}1*`;l+xu1?F%dFeQ5miEUKbyDmYdljEXfBr~S-Nqxo zM=9|!ay~G;>(o=k*JN|lDvvKQ%d4j5e&O&Z_f_Q`L_T<%Bh9+eZ|%ZtmB3X7$-3A**dlH{lAyfUEl| zU5WWYm+ox{yC-(3qSlE0bP4AbpXb92Rl^6rZnESoT-E({$oSYWzXkg z^*>l>v1h42T$vN|>hbch&V|xAJTtV=y^h_%L8Gys{iGgalz3`_z`C_w(p7d?zC42S zhwHuo8D`!PUg=|5mNiBXSH*oOpwH^dQ)(X>jJk6)wd(sqRH}X_@4Y{6_CvBpt5Hbe z2l*PIAT`ULJXzbJ|GF(4cpo~SILNj(>@A5}JNoTseU??)agX5pc@ zvv1#)GXC)NM^|YK+_{uLk61hV?MO1Um0MiwPA9KS4@=*m-4X3<>Rz=k&MoV!ol2YA z32KbN3jD5s^<)n_?d{&d?}O|?t2|U&)^YZfbEVzW)PlQ4>g}0}!9YUUb~C3^XP*6N zL4TMs8o1-~RgI%wdRx-{rK@VAt1s0}%5#z@+DxA4^)eS9j+p-Dj5vu8`;@13 zvS~sF!oo6b4d1>olo_ME&XBVI7o8}nkA#zE%kxuodJ&|9Powuw}2^QO4 z7k-({N5FiXd%ee+ni!A!f|S3!U!t7%SB&76+)*RDW6m-&zYnI$&;FcesSzhueZA6l zT$Mq`BH~VdZ1=f6NwaNu=#=I2LsS&4l#%F;N!!+Zg4%IPt}935Y<`RWv*1t$p2Y~| zGSHMR%bjK%w@lXFk~#Y}m%l~~n|oQ;v@Po2ee-zFBu$Ot-97is&seyE_swN=JQr?hluwCrtzSlGx-m}Fkvq86vV8HqyuyX@ z=MrzVwPh(pK5^f4CG3!|h*I+XYkfRA$c~&i9+GYLk>1*MTSUZAe$tW1wTkLRRW8?Z zB8T#fBc<;#E#{#quWC+v#NLUDs@TGw*#6L}E=Fo7u2}o+=$Cj}EDv1+5+*5?uR&s% z@nNOuX+6uyOsk+?RN_)yXI|3~hrthuc@8tw3KKt*O)XKpo#*Njq_3SSS}0=F z-xZ`@)@yzl^W40v`tQ;c7O|QlbgxFzZ7PG0)2|6%w(w+s*EeaT<;|$9%E|dGWbag} zUan&Ool`^TW%i(^{9%Ee^G{aH#HIb}sW>fdL1VL#V{ny#dWyd$_o%|qq&bVuO^f;D z_9H)kQ)A4VKwbfr)JVb0w91Wl=2+w3(IgB^yI(X#*}Q80qj)kO`g5}vzCD3sA*y6= zFh|pgNv`WEp*OUPOI>LGkl>y$K+C~;N#+g)Ws4eSEf!@d+5Des5js)qFRL{HqK^HTl; z3P*;!&UES>QXWnZtxyd~EJ*U8itUI%w7{2yR>K}9i=r}V1fTbV*R}g}2NO#zBOch; zXHogm`7o&8xaUVK=BWgjfa}-S3vJ)dJ2EE~!Sr*J#xBHZ{NI(DpLx6SFhffgsU*#ZS>q~F^0mZ-m`%KN+^>-5+Pd&u(KZkM z3f#VFZ^oJ})T#HE=yFGHR`}6B+t)g`2*h~aoB`yPYup_Bk7>R^QF9!f-}{sG2NP|6 z+~zC|IO2~3O>hZWVWMn73dzr}uUZ*f-SIZ|x`~I&oxG@;!P{v$mEDV5kzN5wqCkC& zci-HIx5L(#a#2Iq{p)fyZDv~k>|%Xf*<(!!dGlWEItb(-wr_)B;-iBY8YQhVjWi4W z8fM?-zdb^|X|QLif$H zU40?#_*|veFT}2+^F9U4f(nO+FeZGk8ufOeTbg6}Hf30w`%1e~Z>F|da+uN@TRZ0d z%4CB@!<>w{ga=Ga-=L5trn4V(j&VrKL*OV5Q_j6df zt0K7hKA>5O!Smx~eof!MX4vSJTx_*0-R=K=OyJYEz@@@8I8X5nSVBdE`kSY7$Qz5f8dOJ{G3EgnPd+R($ zqsm6QO;gjF2jZ@5cTh->Q+9J77dtAqKvSVqbGuhjcD~f>qmt)g6bVe+*v-e5^8Pq4 z*M{d!T88utoYJ4R&htA$Bc0=M3*mZ3;U`zr;W|u(%xN8?@Xu#Fh&a1alX(JauU71s z*+Cz(@uQork z;aU(ND5U3aoLzc^)yQIjd*ON4LG7hP$g-6^MOJMy(0B^O_Ssd<%{@G&FfeFx zZQ#1kpEA_=B^9BQ+@R1u)i z_Ro*x&5lkS)>%&DO#=@PREP7Hn9uzMhJsZM7TcUWiYIoFi0>6~-At+DYqMpl z488C68u17k4&Se*Yy{(RvOK6#$&C+`Dv{YtH@sVbno-tk2sCg^hwf^K^Z~N_0@LbmxIs*u3 z0BI}xXJwty^%)k~8pUV6GEi>Wx77zok7Vys`szsKpM$L~#evG9<@#I=@3wCm`le~* zFhc$Owmb62{K&mNZ8loV+68|6s9Bc<@A#H1_47_*>R zTD1lphj9ZzK*h3e4;CJci9bcpTUO#ehZjv!-}98Qvvl5rUViRZo<^%GE0ZlQ^^KV2jO`ZEVv=Onr3DYWq&T zP*$XuH~g-^Sa7Q7am7OB7wdOC!U66Rj9LWKeoN*21WSb z!ly-pm`d}wX?bAK0dIkn3Ui5997$ zuZW21Q&i>dP`*-O-(U>JYNz954?pTt$$7PN#VYn8x9z27pN{$3WvO$gt~7F(%+Xw%yha!K0#GVOF(o9e_W9__2W@aB4iRKLCet?1H)IryjaRaW1(!B#fQ zFRo_oj}t$QH}v1AXV7?`^pL~P8t*{9K3Wme8`|6)pWT9*-Fa_rMsj%hme+5 z5h(%bZjh4h{`So9e)o_5816l>`|PupX1zp&jb1-<#8VqFt^^i^&e+!Nr^ED2|JYvK z@@ufcgo%6nDPy(0ZJ%%=mKK%bNvf2HE$qU3y%bG4xy7P4jX=05-#tc4+c^V}#dOGZ z#>RCh7~SYy9P@t^xAkqfje|&{hjuC`WtPj#Zl3d;Ms{&;ci48}l|{qgua-<{Z>z}P zh6p^5bLf$Y3vpRkn5z|wF!kptLwQAMUTP%tpckx@CEkEQN-Oj-goQuVb zic{xcrat;V}@P8OZdIlXULAR56?~7!$H{EN|smZm{na{Ugt!i4$#5vO> zvB%GW7_0H8&k+Bls20DIY7q7tg^xC*+l~cq$-XcBuNMH3(TzoYvn&I(S!?~O;yG-V zDLb`}sY9O5V%Ey7MW=Z(w~QIQ9J6P}kRb~g#}HZ?yuUfiXZCpqhazt{b9L!ivjM$n zjl8ztUi{r}r$J~nxLRCPB)@!zjd1I4z{p{Fl)>1ohSdPM&kZWLt@hc5qIlgtX!)R) zbXLxjA04Z)&0578tujG!8)P6=f8S+~9_a&fEA$EdHlO0MGUeWn*GjqQCHP!5n(W>s zP6?*kQjUoR#(F9hIr=6@xwLiW-nXBb56Z!(g*Mqab}PBZyiW5c!z7i; zhDla@q$xZ6fw1|MA+OLz^5NZo%StBGA|I8qQ(}%6ky33G;SY;~k34y8mz$K%6qMSr z5qP?y$$1I8QoRy{d;4ZzjfS(QWLBQ&<-mnPDNxX~+o;?*6n{=JTk&-xt`@DDe1lhy z${_aU?Cp5DVGhUnl|kqKZEleaIbZHg9MZ+-%R^2CbLoDUh8PrtG`2q9a1rl*t1O@|#Y z1Jrf~>&Njr$~*G%+Ga}K;mv)dY{XU)EcwC9sa^X4sfGruMkp3q8}#W#BN>aX;r4Np zlFr6=%cQfJ_c~|3&HJn=TaZxu1mivhQp!($->UH#b)iv^`t8<&^_#oiSQ{Bw_BN?UGST9(< zIonz%*SMAr5yLVdYT<8B`V`HdNu=5rSx(F-sybfeVuCwg#cSZ$Kwf0n-q z%p%;iD`Wx`d^m@<=(}~9?hdF^Oilf7R)PaiS-w&TfcR|yWDI*M=|deky;v!fR44)9^XP%EcelZMMY>w zNqxj9iSd@-*}C~V-n^3?m5?BDycm%nJ(8{)`%Y1`HIpvdBKjGincpuvmNfT`z%tu@xKX57h9XpUM2Pd_^f)SowmbQ zcg*8s%QbY9kGELs*(>^SBTeJwLA|O*IgOn7*3V%3Yj*pj!A(QcME8^@Q@~j zS~-6;24N@lKcIK=QgNuF{f7SX(wJ7Svz>BbMnuG%CV#x&DqWp1@@ym5#H;-R`({7k zDA{$8YpK;r8ukBHbU5d()KVjCi|FA1R~%i)j=r;8oST=csJEhdym3%UZ)?nyH$>N( zK^spyCWmX?-Be?*cV;79o~-h_yiko|&Urf@3{4Grtqgq&z=d(Zc#Lq|*+RYY4%)PN zn3w8{j_TYsyFS3NL!lJyb9sF_d}eLY`1)H6O_v%jE!KZac?MbDLJ{Z7j7U6ZA6 z5x)?%+gWD7mrF?>L zev_Obm;Qd#h6JKE1nX2%#Koxn)0u5O_mt;Bkp}gN>vu=DcWNv#c@HRqpAc%EJ<>}|gdg&r9s}{n5tWPz9Plw5C z-e#z_LAqRa6aoYE+ELu3F<$&|b&=gN1%OO44n^bOG(o_?omDD66JqfzlpkNB+{`zN zmKd($mCKi!IhbYc{3=(RZHYA?u*hp`9ob%Mxqs$njzmusGED~NJF%l5J>$raLi0NmOkqXdJbx z_;JL|Y3}F+@)u{%QWNd}M#i!p8p)(e8FcP~jl=v4UUzwgIjaMDEg`+_7__6gk9G4_ zCN8}13$%yE>*};? zEs~0(U1l~0v}z3VA_DUAP%}kGa9Ah7MG^E1zIAnQ(>g~=^kIuq>^4;+dEQA;6(hy} z%w-aQ|S?B}6IhW)IH>x1dZp zp+8#Q+$GrY@Q#b%nkK+4=C0yptxYFxr}S9mt?;U^ulu8`qaGjZ-_FS>LDvV3M#-Nl zc|n_vh^V{T#PV}KRWsqgQ09aXBfakG%eRGP&0=oU{OAKv7 zzKu@+q1yW^c*-4@t|?}{k(sSx6)7(c_>=RDO$uW#Lo1T>8Wk($?#E}VDab4vE<}ZG zZ+(|A8D$ev+c01QH97r>atR)FzX7*^9qzl7J(O0=c2LjcMz3mA1*{x+xf+*dZ0eR;n|a$CMF zW>uxOV*|nv5BKjxsNLEdhG0(7r2$(DZUsBWvdc$2(+b~|5Cxk~TW36c=ITRzG&n8j z17c&x^joM8#WhMg3MyX3-S5eImW8dvWCrP`8v$BN`LJoAwQrzSYxf$Fd`8At4)30+ zL0zX}rgoWpQ#Iw;jHy@PW>t};b@!oSHX*lO=FS`QysQ%Y87&&2h9yFjF4v*sK`aVs z1TnDz_J4nn*YAY4^eeDmmXiC+O^$FH7rmmga;EfRDL#@0Q;fBX&>iHrY0! zUdd7Un)01hRuGYiam>z&MzC8OreotO=f=nX8+OQf6Ql;obqubyNmi;x{r{%=IWr{0 zX?F77Tz|o~lTs2c^D=TyO*T8w)T4!+4wVd_+(%mx7aM>i?b+sa*55s;F{|uXS;qB? zII&b)=330_{+{{2*LgRo6l^uMN=E;vC#v8RyD}Hh)je{k$UBa!WUPQnUym>;;2!nj zY#Z_`uk*~_M*0|@SsJ1i8NpHXg+@er}^-4+e-A89V`v_M>xGOi*7+MM)fB>M6I1HI;sCg)B9EEs@Cp(bmL zu}U*0Rh1@|FM=f!xoMbI@)sW*Q4iDR#jj*Hd3Bt{5jTAXc2{kSpcUjAPVcrkx6Sd~ z{YnMHYTxSpXSDw!{K;>pA)W+bm6;H+_D0 zt4hAe8a23k|4%C@Z}|x~)*VPVu8j3oe|a=IJeS4bh@c&=4_xH1e+W63{yVfuzuGR* zMLb$*+*)Fs!)F}II#-(|AEdlw++G?pUR6Fd%>-XYEnuQ*TtiAUw7~YI2qV~BE3NXK z@+G4+=(_6-7k4(P)YRB?vBb!qw!u$deuzlR5d8FdmvcO;<%@2M+`Wt!lUR9sr7^ z!$&}S@P)&7oeM@p6+D7?#j?E{Ckkhx%okFzIoE35MZJ7Hd1b*?DZbb|sU!%A9Nv;H zvi^cv6bd5rhWHni6?M(A87;mTF0(Qpmk}N&l6xnqXG^mwmUm*6kJ*rKqPHrYN}YCA z@=A{n=*DvLWf~ml+PbY4H|jaKo^r>4@C9Lf*snoV4P;B`1H|NV-YcdUq-F=A#o0JG zziO-ZmxVG|TGZOPP#L@=2bIgTI8ycf&A;?n|@P^Pse0s7UEE9OY> z+GPy-K%nTA!do*#eDTaOHC4D5Ld`|Z6Th~Bn8Gt*fvB`a=9C+!PUmT~%5O4|)hNjZ z7HsB>HVIVdi=$WW4tnLNN!kMgTgqLl@(G!8&Ii;e>aE=Xd#pM4N}cYdNYdG4b!>i& z>&&W`^%VYXGnn3t$4x}iRDG5*VS6fe$0`%$&=LtT!W`jm+||TIDG&s8QORznjk`SJ zYAX&4Kf5!qwZ3+ojZPL}JK-Vm#3Fwhhoq_ESP>lB1Ehm<>HMu+#*b{Ej~=p^weyi_ z_P-OsOe@Z24x2&X#WVtLd2UYJ@i?l1)Y5oXN=%1t+t1xLyRkZ+UT;fluOd zx0RfzL7Aq!lDZa-{ok;@)K4+{>XaD4QlOJ5tFkNXNBB6koQGtum81O`H^D#Y>oJ!X! z?YtxP#Qp&$KWTpsW}EI*WDsWQ1blb*2H9$IG*lL-?$3U)3EK&v$Zot;jx@;#$mwiD z$>!~Pv=CFLMivzOfDV@i98yBEC&HyI9~M3J()!xB{&ZJ`z>dK~*-*JV^>M|~iGDg& z)M=$o<e?#?#mBu86*y-4p#A=6w=EDVk94$N)~QtNy~Wg3)xD|6uH!w%&D)bh zm*9lI{sSX)X-^BZ>-xG6wj)mam_|3R^(Fh5ZYA}YRjB`Mc6LBj&R^a|i*RUMB^iR& zru{D91PPW?SSZfs-t)Ds$TrZc+5X#LidnhfS3*#hAq6y(Zy&E=?~dnnhaKB?*rxc3 zo>C@S@`A|`Nco1DYIB|}MH?IeE<@nC%lMssl`!qI4RNW1&;{W-A68Huc$&3sprXuS zo=o$Y>gKC84L9I~7xHQB7(^F$Go zX}55VGwdH1o~_)V6EP{Wm`Ocr>*TnyRxeZLcV$vl`W3p2j1t$YDH1r~yOv z=!dH@gLQRITPt~->2GqjV&k164C-#-zDD9%T4HQF<)9-4S>C2}OqSH!FU)4c8O5#S z^D^t&Et^@1LmhEc0JsL3cyJbGjN-+GMe-d`CmkwGbwSuE4h?lEZLEv%w$@5tbGBD; zajC{sUBx)2#%dIT3krP6o+hz@*R6i6UXE=e-@ewq_+*a4zYuGU6r*V~Twp_2z^y>& zu*jrNs}ev=?`Hpz%8I#vN?WG|cztA0mq9(KR|PfW0?SQlc7t!^L6B+B*|4A-*w;d` zf@J1r365Y7yMT3cOGXraOMQ(48r5o@N^xx#)2!kVbk6rhiE1B<;#r>vwmJo&Y#Kb` z>M+_so7H@5jk5WfgY6cQ`83lzF5#1fRh8}9bf&<51oM84t`$)Zekm-JE4_4$@K4G| z`qDQ{{dSj>CRzwb+xTP{4%{t3VBrZ(E5GGuh(n&c*c!DourcdoM-`Mm&>z)WEV0Pp z8fLb<3?aHe3MNL=Z}|R8opFXJ{SLO?~Sd>uiR@_$krxO=x^rMUkz`up~9ke!o)6i@`J<3o(yS(a&~CTliUIl zK@x`X2Hna8yWqZn&u2$Dq5jeU%qIt@?|*x;=?OL~+J!2c`RL0l{c*w-5X2~Pq{eKu znnW0Vgv81~a+R=OOS&7c!9hmYhW6bghQOLq#}WB6WtqQpdQ@DALy_-cQKz(D(q=Q2 zA8V$^mOZ^jncf^XhO%0BFvBZjt@=u!DI_N!YN6`4FDvdTM4dl4PnyjTkdSO;QDbtn99?wg8J&@nm1- z%8nClJF^JW@TyYa%?dD-0->1Pk1*MBtlH@=NsfO<0$q;l1xK9NR4J$%O$7WxRGysG zjUKK1fT)Ypty%I3uUSGVLwn zhXv;tBA8QhcM>-G)ao`dEBEcQHG^{2%%9|;tv1fZzk@o@mPlw@W@||tyt3X#{6N_S zaXnONM!;9TTI$Xy&UMAwVxw)d0pg9tB5@g(P5QS5Uits3;D`$)$~Q;2+}(**yM(K% zY!%Wu>WLoJz0)@ON?#E3onEax4K=t8%;2WJD(9pzRM}(G`p!;m~sHj#(6r?6zVc&MLy;M=50U^Y?f~0Mw-nNSP52 zrAZ8$LxllesuD;_o*Th{C_f@!RFx@1@eJ|qom1f&gQLUc<^#|8vV7Za&rLjxm-2$UwL&fZgBSDk<8Jc41p@4()RkcvXu6dk^+ke7~Oj#0Y~6E5HQ5xQd6z z`#VHXEy_G%JWJatj^%|?v4v7Vdnrm7ieAP3NqqF^(VBZrEdY$7W<(MJy#2=WNnH;gq^|Qn4>}35&+ZDOT8cxK%9Xvv>3M z9JC4;G)0Vo-X9r=9|OG9j6WO6!{r)#*@jW5#t*77FWI$N?7jU+tW(etr;HRSN4V%v zHB9?|+On)WQHEpFjZVHHowsl%NyMzF3UG@G+4AWpv*XZVf&{?EVmO zoqMsXn;I%jf7|0V0Cn_a_|y?gToCYAfN(Y+z{CN0^t%l%*2Jk8^W2uRcx;BON+$k& zo41RKHLfaxG~*8R+ua)`{KiQ6ba4X&KGsRej1>U0SpB?%LqN{&l(xIQ*gUzc(QxtN z(!@M_<@7o4UUYAnIz^$BA)I$|0YGl6YIS;I zVl8(3U)`=9Rx=tA!D}zjg$4I3k}!yamjK7B_o@*GwNgv)_WH5&3pCwln1$n zV%slz)KO8Ta3h+bJ#UMPrQu_~$kj2J=LW#_AWP3nxd z0C-LoaIHH52s9iBE}N2{FhZ>FRY1kM}!oV1WV79unBM`<=4O0xkN4p8clC{)jM@i4%n z;xo;LlrG;`0L<~0H+N5n`pU4Gr+)>;+k@z^Lnf;*Vu=)R^fYW(H z#c=W`W?3mJ`LsMwRcYK11*RXX=tLb@V6;k@T$xf>Z0#8!6jwOyZ=~~`9$6c7BpfHQ z08NJMJRxcg?YRbqk-x!Hs#g?AI6EUXcaP}by1rYP`;3fm6@df~e&pf4Rc>%eX};lC6@DNZk-ZP3MV~fN-YXRxa}AJ{cUq{{w6&4kF;r4T*)@JP^}Eg z%mn8sh0#Ge)``b;<8FFM0gnWuc1C9l+1|uQVq67VJ;HPOLq~0>lS+8xzkc0wAOi%{ zQcm-(h3%#7MH}4sgNX;3a|XS(i@01*(^=tshVB+RP+z-Z(Dqp_@Yyrp;nZCb#gqWVlE>g8v~YoT4ir$@bJf#7YY5v+m1f@6xuq0! z)y>Mvk^}X263p9aX4<0_WZ!#6++&sRh~Wrc4dSOC4q&nAJGi!dySx`|;XMc+j=k!9 z_wGWkaVOQXR*_I=P%Hhvkl24IR>O)4#mK z)Z?^6Wl*(%WTQ}TKJ|*n_~^77>$m(kaLDL)2a9cO#(2^lbp&f$*_Z*>GN8E`tesqwKwct&Hc6533s672G&%7byvNs3<9rK z3U|dnzoV_B6lA?vzBbb{m)73Ckt0>X77Nzkh!dSQPO#*tW(NM1iqHApooU+cziz^A zp2s?#otY}@Qeq+JjS;5iaN(|9f`?gyAFg7@B9sO%0^1;rY3bIc)LXvkA>e!w`q znks5q|KTdVRz|$tYHr@ss;B#9qXn7|tWZYlhyt^e<4<1w{Lfq>UOlh&NWQMxDLq5S zqNgvLZ-`=C40rgs()Y|1Opej~vjxB*&E{V$ld((8nr{Ee-%ebr5e#>MLifqWK1wj$ zE?_pCQ%y~y)qX;NtR+rO3GN}4;ZgLw{&UMbaVb4mr+Q|hS|^=XBDx)wXaxVeM-MHT}TNIwQFoj+}$J0xaEicI?@i!zNdOUaF6uXkKsDvA0ni`sM4PJQ;Gy9MV+r>0qHlv)sLHvs&ogc02uSJ$NNNA{h zT{uZUs~3a@caOW$B(l`?#C-Scwb_#$+HfVPX|{RxCjGr)Sp^cL;~ND!?Zt9AZ+o~K zH9k-XA$&QBk+r%l!*YmOYU!krz3_+=oQk7F0iE1_(?IsyYrsYYcd8A!3A&&2r?zh@0Eos+-%1+3lj~=o3@J&rk*#`;*odMf*8!rBQ zpCndl!%x|5-z_zB;jIaDL4^k}L@FDzalQ(-^^b1GgYpr-WV&PC#c!2NC@a|xCJkNS zK@XAoY=}igWqor1+RHmyg_MtCF6wYqBZ~7RjNQqJ^fycUob?*B(>FsJ&Yh#5o=x{F zHOcPjkSxuxz~f~qk%?IDZ!&*P0G80B4s&R=_Y-ygZMvdKW<08%SZaJf3Oi^kxv#F6y5HF)_l{-dnf(8C9|5LO%b|M2<@_iC^`FAXuibw0}yloY7eonig z4X+-f&(yzp04OhAYE>1L^hhBi)dpZa9(oxUv71k-Gc7-_bn5X$t^l6^2taxTmHEq^)dTuj7_^b(^u~W zM^0f4eagnqpO>yLr8~*LeJ?R`{7iao2Nk32iJ>(b>q1w$G%~l!o`Ka=Io--yp-r5x z#ojn&MV~CS_kug7qBB9@yf))AH8MJTo0OsP&kJ+Xa_OKAJe3fQ@tlT~WYlCS@X?C* zQVi(GXK&t2vFG5Z9Iee;Y+FY1M15Lv`gCvTso6Ws;1Zjr=Q_5#x)m0H7TQJ3`zVv_ zkEiCb;>6#VrP{2@MXXx?VeNg!49~O3pe@G;4u5|S7CR|bWstPpPSK1ySV&P|F()lX zov}d75cF?ybQ-ivixxl9Cy zm)A<@&X4--uOa0z?Rzp@`F4NQN~2C^$S_{Zh1wz|)wbADZ??`sj>T@ZFQl~GhRv3H zwz^lD>{eSuDVZK47PTm5Kd4@030>vI#Z?Ym>fioW9^#VOrq~zDhuAMm-}!wVW4tCT zobHe!H{s$jU`0F4uNJVK3#l~hem=Oemo;7epr~wa#R*F+|LG(u0uo9Q8Z4?LyODI1 zDZ6CYue=doqIhS;J^zdMLqy5^nbUIbJpB4}*|b~4V0Wdr4Zxl6Ginp-xrXo8dLi01 znKWoLKs`NV(H%)xVnQv-*(rW-M-Q;?vG;RgT|_MuhrBls4)q$1ePoy;lnGhi!?kCk z+;)n`&~gd%B2@X6^S_HPLrpnn$h}T(#~4-1IqS%UF52vwzZud1xV-U<$_YWs#iyFEhuJG>;)qA)F)dNAlm1Lp z7P+pb{aqG}Xk#x1H4r$DiA`^E?M~LSyY9WMaNSSO=O4(fw0*7*Z6nf>quXl|A214Y zT7PnfO>sBYqQrgVsR43OB^5-36=I=tXh?Ohd@NFL)k7>c9ro5xjDqxov22@gsF65`~p;P1lIwECfQ9DYeezL z=DS5dI{WuTR%jng+@|YjNv7|6REHYiGt3^}3>h0z*OrWY9ac~fQ(~5_$d!+@>Z5E( ztI3$vBbjg8q(!?G0pG3Go#mX7WKR_2&{Tb0f5s{)UEgfvh{WY=8zdDnAI5M&bAn1x`RFUDTsZlD?x*XwBB-3GK*7<&nmym+O0yFPO z=0yI2yW5KkZtGL@<&IT-J9o0ZsU($lMp+#Lj8VZ$a1*-zi6yQ|XJk}yu)m$4p0~YJNYV)>E>lr z6mjz&I*Oq5k&Jy9&~@qJyy3g^5_2p0CiV1LYuj8-!PcK5cgaoBfs+`=%2-9J;+r>4 zVSF{LE4W>MPp)l!*%KmiWtDEr*hSscIP1Oj&`)|%Y12YRm_{>L+zMA4Z5ugXykk(X zp*gfyA9TkYQc*TL-zLv@;N)x=9-_Au^R{yX%uZnbm^+PeQsb0KbAG=x->O&@cKg|gXcV=H^i!J+BiLy^AZ=>2H#vjH7Al|dZ^e9&(O6M;&~*&u4HC^G7go_J}HFDDpOvy^SQroB8* znrix>uBQ?o*Mzqs2*Ubr7GG2uNBE#%w7B0I3^cp`PS% z-t)a;wldS`u5p$jx4o%C!EG(NL6z7>uB`pf`RE|LJ_WFZfTt87yjy`h14sfCR8>C% zhlvsNB*|Cz%gI#^C%xMM0FKPVorSGxhRTHW_@dF%=kdfxj0~o~R4E@A10#xZfwno~ zf;g(Di&Ab02#tV|Mi+5k4Ok9pAtp#Y++AgBI^Xay(2%eh`cqL+JptCy(Q3yqP^Ih6qy(u9e0=myfBjdy zKFqgNidM#Dq_d9i%Jn-+8kpDXT)ZeB<44Sr15_a<{m>Vz@P2;&HB@|7Q(YKACRel7$adBc|bxpNRwE{z_YPB5cLBqUMp-fTY z0^{mAX_Nz`u5mq71{x0_Q>r0^vr+&xw$i}Cy6)$As%@lRDnBUbWy3@%uzNn$_WLi< zI}}biOL4tLg>(6~ln+qM9e_rU;<@Rj6T^Zx9K7~q!~?fa`B6NAJ|gY3avD!yqrY02 ziEO-5N$LCr+a#SU?1_A`Tu=%1p~)+?m-~XUrYB2*2|%eO85$QCM{Nn8mvTCt^bE9} zPue(luCmg=kDS83D|$dgVmIp(LUx?CN)c7PxV^Tstf5uwqLwKW&l>+8-LLFH`1f?Q zxlxH&phXU;&C4|Kn<$WqZyzy3rz#`W)kLS z@~C8A0K1;3NT8*sqfxX`IbX4qh=Fje{^h>^K-Tpj`q!s}2Z%yX(cSYNDCE@ByZXRj zrf+WEhWZ{Q2Q;!CZiQ$Fc>J(iQT!Lnig0Qb%+{V&sOqc=M}!rFMqLI*z-SqPo4*J~ zFJJ}#c#1gbPj#$VJTK;$Q)--Q+1W|bU5YHrlt>qGwR=5$-u~m=jc~oi3#Sy$yLZTy zO3QVR5~LQ>LZ3H!coWi5{nv$mGmSVT8Xh=dPD0F=TXmpRB zT2e8MyM%=;@h3}X(()7^sTO@A^*33fyg9^6aI?uX5jnWX`7c+{m)^f_#v;FfX9eUU)ZzF#|aP?Dw4=#)pDJ?OhxdGT8De=-zLO>KDKr$Da$5p+Y+@P8lsAxhD?IUA+6 zey~(harjKRJ&3ZEJ3)rbePZYE4f<tbCq|wIo`h5Qz-BjI-_jXe8edjuC0Z_0oV;z|{ziNY@SL~;pte)Q9-s)y_Ug27_ zxzpa&F&sQeELnA^mt}VvFVaX5^88mPU-xyj3Uc};ppPXKgn$0iAp~3P=>M>3Hn2{z*CF`449r_-VE~3l!b)SZf~rw%fbJ!-m*o%=Ch^e z=RbO6OW{h`x=izx(}5`aJ9jjDCBvO>E8yh}3>taBpY>6%}XyuXIV{u1vf--i`n4 z1091t5+FiIs=btZ``^lTAkg2U2ZCe2hW9|l(kb`zQZ^+66_xyT<4?KXGlq87sguMy zUjS|+$9`4jwda$S9aWiE*@^rA23J(siu?mCcX zIW>oL){R?K6+O3NlvKq%-L?Y)X{bJ`%FEw;_wJoY;|=2U_qpEQVvm7KP|(CAr}ME8 zlpMF#CRQ9b2L?;%A`rGzC7yVtY*C>v9)7x0?;K`cN`hKSF@*Ks>*VC*Q8p{6F*dao z8ZWDx*e^YsY{uDGZvV1MuC_!>5#M~dI%KQ@OT!G53WB&G3%9&UK zMf@P-XXv@o&n`&@5HUQxMJ^+zPtBf~EwMeYAIDPVeW(8N%kp9L(x%A+MBYChmyR+zl*J_2Ah+nP2SXhBo<)Y1^zMITp;V5dEnFTUWLP^gS zxCD+RfiVVVk588-aq&{2#kR@K_wUzyy^|IgwzKUVIE*CS+x&F}zYH&nh!Wz{u>wO- z2at}iR4_e#`uW3$i=H=qya}1$xH+R|;(P9Lr>6w6?~(i3VO-8SZZE;ZZiDCUsnb5* zeoviu7_orkE2r?;PlGc#0w;Z0Kp503ckF@W6e(Fin?BWJs`tuaE14~0(LW<&z7xyx z7fgG3i=6{Nfu#riOt<_{!bFE9ic9g3lIs1yu*KY%apIS^e+Xri-9OSBHFj?v8=+Tt z=4gKt%jVxeCun}o*%AW_($%E&HK7?_`f!$x$!XgCX< z1nS1OCmR#eJ7`E$X{q{GfWFBCyU6PJY@!m8j90$_zc-A7DnDsK%YJ=2hFx*I*z0~g z;*afLHpP)`ik-uNmz|%ZQRB8$qmfPcX;{oPY>2x%=FEZxeW4;hZ{k}TTM{!1#B!*H zhJI=Md4p}8I55)jJ+^3K+PG2Jql##h95TOdjbyrb`7#hm>DdtezYYb;0BhL6oj90P zgW&d}<<#M71+Y2}jHi;~wL3&$S0zr#ZVJ?r@&nKX6&3SB`MBGK6MMu}F9=b)p)DbX z!`wuO5g$J)A~^0h(5lJp6x4YK1R8c{I&&#b$+eKXe>h>w$iB@$)o%{Wa^P@N^}Mes zV5}iF4h}owy*I!i1dv)g>|3p<*Cp^D?#v`-ugbmAp(r!hGHAQfiV~A4E1(ZLm!(=b zHNJw>D9<+p+pXzYY;0_{)Z>GFxD)cliJj(eV^PQ9J&A;WKc^F2-o;i`{t%uy0F1vb zVBJQ2wL3EyWvqbL2S}OgK!JZ=>U}d9$}1W9!oH2f%`JxoPbNktyIyO+rS=NH>n(s* zfr%A4@4ms};o&*4(}`v^7$`Qvv#UB*ZiH3mijI!HyD%1ipi%bLY*qqSD1Fn&&gl7x ziTG)=^<(D>l)Kl|eE$4>I|TzL%H4x!%mMlcETD+L4ZO;l?YwwA-~L{@=DoM0apIzT zV{~jU=FfEAz}qy2I;Oo|^or|E{q%{dVR`W2k_Ql3jO9FqU7+LUj?D|=c^*&UKJ%w5 zJ?^kRY}se|KZG;O@tC&1ibqr@zVOe6^vq1_y)|7XHOBvayrr|56F4xzA9*vF^rc^` z>qwBE=CW2@@9Va4)Wv^iwDRz8klnunH-JbH62h+8+jGFmQ7K4RJqB2a^Dl?X%*z?! zZ;{P~gL}5$uojs#eg%HKCXP@GWuhVf#=pXR;D3xOndM7EWi<__=(qxaw1Em*q|W9J zK|7Y&Xl3sNHPuuO$*S`?gvz42}ih+Q|7t;#`WKEyif*EJ_~61u6h`> zZt!2R2Li<`?Ha_xum$B`u=IEAs^Yiny}IX@3ig+g1&`E_MaC)@BWK={yPY_nZ#_gU zy{|XKyytJ=lOK1AJa{5^27p;4sPY^fp1{ zdeer%LW-D-c@R4)c1kX_oE8BBU}0bnW;y%}lql8{-`;6_mJs^MKCo=p7f2%9YTP~W zMDMcO1Cru5f)^9++}pZa6cbGU3=DAy)l3loNfMCQqP%4$##<^^*_i`xVI%00sSP2% zrQAcxS4}rk#$2N^rW>tSf>S7-g*coaK!9e)buaQQ|{F-Z#MLwBW{2-oUKEpCjZu#9*3P&cxD zlp#y0$dls&-y((&?3pB3ZNU+w8JLCmJ3Ug&VTiI`}>`u+2cST5z!$x?0)HLx|?p_ChwOFgF7H+ zKi>jns}TeWHcNd0U%t3&D{q$eYhQQ?^xK@=s3DcT+A#wbM)6uQMEFp>j&3J+yg1I7 zpioAM|+{LFmKf=qCRrB)PAt^_id}E-ZGp#>&=wIu~AFoaT7oWjsFI zucZz@4SD#z^)*kL4;Y~|@0Q=c^&$7+*_-fmaB?Cc6ZOSHZ`B95)pKEDZq5j`HuTjs zH5Gb;tTM`Z5(5|T{=9r`OP_GUFZ0R$dz9x%z-Y$%_uhp3rw9FYSPq+QoCOPqBqE?J`c}POdUTTAGrtc>P7uCV>)G~5*|+= zcD`N2jdYLSmz8FP z88=BA6%XEi{OV$&+X0>4FaKntj)eYF3VVBdh*&Ov`=VQq%?kN+asjRh*EuKB0(AF@y>3Kf=vqvLur zP2yYNP&I6i69*6b8Mv1^3x(4D`-;@$`rX;N_wWJ!_|7>emp$tA-MXf+u8z$%wr-TL zT6OCi8EtloQmg|>U*c|O;!-gD?Rxy8d9P?r;!IyC6Rvv(4PN~EY--juUBZs?Bzeb=u*vewNGehV9F zx>uO(g~|=0(75|yB%|7MVDf}8f*%ed*%6W6gy+hY@}*uW66(^(ye$%RCXe4ZpT5i6 zmOqiq==#i)Unp(fCou3KEiF(riadJx4GY+&+yom`y`Ueh6XFw@L_Xl~HJ|THy&@WT zm(JrS71b~9!+xEC`&3^Xo#g2eF+?oCCws_PtQxZmw_AUtv#IYO20`H!I=e?T0<~Mm&)8J zC@7TkHN`bG@3K^{o%g%Nlw!9$#Hji8Mr@n%%Z~e0R>*j6_k^EKVmz#DmVQ3E4WEgcH>o~YL<)(BOf4)lLqr+PW&IFX(?vwXsKih)1AcRqm)8|Q z52K`_dJipKmZ!(N1o-&RAg1cf>fq zfeK>s{d!Gi8!6oN!7xJO^JbrhgX z8m%h3SqRnt!J&SG8oni6Cc(|8of$ai<~qV|k+sRLTFi(=e;={arwwx5!F^axs-r6) zbdi#cEeu$a|5Q6#ySTXA=6B-(+Gst9x`810`@DnvhqHZQhuu#}Ng1ed=Cqz`hj@_b z;*~23FesEe%aDqGZe>-}`4|GYqbg$sw;29JLqFophIu2$t$LRKc)NUb!koTX4ymKE zHO*3>t6Kx1xWa~O`hZ;iY1~7I}z~l`jd}AO( z71YF$22kM77kgeWr>=06Rt z5}@rC`|>2=%;Ma9Umhvo|NR@O2m=DWM=pDBVO|d;Bh!HG5BOU>omVQnK%r3;m$z2< zbb+k7%641-#76^2xoS;_8vCmX*=pDxv~#47U$K6>tK47etyu#k>-Yo&^+16;Sg7Z< z8LnYi91Q?~kAO}W6{P|3^K}{eh6p~WxC+fwvRjPBK>&6ZZ4K19^V8AMfk9^j!f=#* zwX@^Ef(nmfj-t;e98&1s#5;fC!c|;cu%Z9?HCRbTZV`n1m>Y}IF_bf*m*v^LOL~)F z;fc*9$&B)uL!1zY{WnPxGpJ%n2o)nQkcS=a6hbDqvpU`Z#O?zS3WG7XN{EE2t^!~y zLa*qrEV)!*KPLkoW2UVOZPnG)^8d+7Y_Rv9h_*;AXxtZoLpu7igx}BG-(PGllv%s<5 z(AE|J^t8Z4EeXz|si|oq!FgqJXL#E_{kAOHU{>hfyLS(0>)*pjpIVS|Sy3w^BVc0+ zT@UR7Dfru=u{oO4f}G9p_t%+2>4yaNV~#XH%G@wK91G;{FF>&&)&1}4)nrIA!kM*5 zpr$xzR@=*;0QJa+1bEV)1#En73i*>XT;}H=+EuIHaBNd8D`Fo#c1wAciY<~!h)=9r zJSZk6MhV;G0o2GvZpTi**DhjZ#R?<)`RmtBVq#GU*rEHo{!RIX7deV_^uW9htnHB9 zQ$d{BgH#EE-MHnW@E8;X$j$}8)5ev-vo=A4&;?U;vN_rd;Nz4 zUIux61qhZi{Zi}e>-Qj%fGwW*`}fnJ8GJd8UMVLyBBBA9$REeHDQ3NR2O>B*J?&Xu z>gnws&wawYnNqUT&Y9*gGX*6BqgZ<&{^z{O?V*aqb^X2W4A3i}tyU-{q{jQgb;s z)r>5DSaine>(JvNlTtY4l7i23adGJz7+CK7QhaK3|Ps>QkR(U7n(>viV;BkHOHqHMk{>Z@3Q0V+}g z0s;ck9V#Ut-64pCv~-6B0PQ z2a&Y2WbNSKkXVgrvgVtbpAQ6Zlx z@c}5TN<8+d9BwYf7*!vx_{^F%9mZP7)WnTFLd1RluZofaoP3au2%*VrZEtt6VrOPt zN)O*~`~GaB%;@+M*KShVvz0A|A|*br6WMnaie%tfUf$j%mU&+a3m<|^PQdp_1gK^+ zvay9!RPd;(stPzSkb;ZQ-Mu~VwNDikuKFHs-L|#0jp8s&PE4en{nUEk=H_7l$HvxHS5qYeZ*;C~Y;QB(yXTjh zdhg)i09ijzuCr^NXUl%P5frcL&*QnhlFdsz(sCG;8n{rP-~)M_(oKy|$nNJj;c zvVuy>=g(KUxVe+01Pl!gXRrECPn!TJF4Zm4F4CNxwKX$igpk|BM1as3sN%+h3z@L+ z@U?0-ZtmVa@|3tZ_hAt*VGwgoMOAp{=3e9EmGQ`?480 zdI=r7gu6GvilR{B%Vs;lRON8~jbnDP@`BJmL{Kl!2dC~rAqJy<&LBHVdF%^-H zmKItj;ee&YrC`JI@?)1_v-0rdWJNiLpmJnPd`!@oEfWYFH#eO?EWm!0(;0vW5WW?B z-j2f#Ao1$@ro(o%o12GGsW!llpG~;G1RflA90!MoYa1J^>W2?vg{4s)=!Yh0psd^x zbi{=G^yyR0{iYs2kgI2d`0{vnx35p#eD<#X(tQ!H-A4d*z*dDtL_E>ey$iyG`;3g> zfPe0{1otZ+!Ons@D~PUsfMcJW+zF!pz~JDiA0Mv(|0ftLS0ArKOAJml02=}GvwB6E zAkcjP4mpU~JL|xeWM@ZP+hW>odV{6&EgjBfAh+64Z} zE+J*2(G&$R@vCkTxRWur9|l37VC0ZJqQ!)ciHXqFbw_?36s*BtJOPU6<-Mbpl@3P- z?jVPee*O9ZuqY{G3mNzpa7&`&zA2S?c|4v6_5%;KB_a{NMh&o;_Pu)%^~ZZ}!`?Xe zJ^Kz!;s+XytA%L+g9c~NoU?na->e+?lEj2zYZu~$XNro9%=5&1v|P@c=AEYJ}U%K%;~ah3-;lCIO0 zELtL5-OX2a-O$TDWyhYQeT?tL@mTTSuZa;6KLCrdth_uuNaw&-_4M|(bau}C47>>- zw{w`!p`sBuA6ccNmBHf|UG42o#H0|a1SnB5^6}kD=x}KeS2QxZ2NWq&pM1Rh-}&540lPJv?sQx+Sfwd<|?Li#e==Hj8^UT2 z_pa-Z%i3D#w;S02n|uxQ49Lj^m8*@H9yoyA2IWTmnm2F3vpzN8#DIyfuCCr=W9t}x zIWy$oI>&VXzP^L#4hGoSEX@;u;+-(JCiihlZhvlW?vi{XFVS|h4bvS_(^k@1QvgiB zH8302i-2%9QQUW2=h2&XO}PFn24m~$mC|BTJ6!<0I0z=9nAI+TzXk!~r{G{mvDjDA z6|dasn;Z=nO~ExYFb6@`WlHeCj-H;rVUO^2O9TV7HDFW_RtsODhV67&Rtgy=j3%YP z+F;$S?)*)!99%PB*mB1yK$s8{DWcK|ge1UFyXB38EMAp?M8UiY6 zDDn^$9TN+`2aEU0`*viR(=>yW(-UW0z&qHuh>k>PVcZa~&~!*t!aJs2__+OiFqV!qPWu zb!njUKrrLp&e|YYAYUa%l6K}#f4f2ep?l|BL2%XGIqU-)9N+{DHJ~bR+nn~mbv0ya zr?u38>k8+fvyxI*a5=@19;NfuBcT3%m5fFG+r&glW@e_mkJ6c0d!6@=#a&$o3QzCe zS~gzdUEkP1SR9$BHQ^>htjMsBf}w zDn$dJs?<%Ax0P(lVu|9#ny87=L%9?*94(ccoD6~hp|0Cr zY$<_SxEj_x>UW&j_$WK z1#vm}Mm+k8p*VKpk`c&69G5<2R6MS-?NB&wqAP6Yumi2wcIcjnAd0{_`0TiY2!xb$ z`oODl*m_A1l}!7psmyCmd9|c1pJOEAmcxeyOt#~IXtJ8s;EPf}%#@8vc)`Xy}kO@$-n zoF#GjnrC5YW#0Sv9rl!?q2^&)5M}gVryUWEG`$dD=%| zyzQffzvWAfVBK~zJ{^-kfg=cqtsuq47f=#=3oy(>aB}yqrBf8@kds810-zUdwV0n zfr27Q@BPgQq0j4!>b0XbFqm#|;}d`c5FDb>X!y?=aNPoMVw7PeI755s%UUGDkzofH zgP4n+m}w3}I1by3qKF@mkc6@(N6w~9`@EosYvuZ783@-R54f-e>faZ={$tzs?Fyt} z?s1;PZg=tgPa$p(SOv!9B${AY* zK_FbJ4f4=QaKQxS8h}Xt?Af#Ig3Hrb1?TouHV~44TL`WGmoDX9w0gBp^Jgc_?ai7x zyAImbL`EG`idW$D8mz}5=|e*>N$LQfFW z85`4qCKIrS2|)Z#C{z#jBykFesSocNbcw!VwbN^}zv?vYL`g!$`g^*bW2bAnCUL?> z%X4^*+pzeKOIB6lRC!}*%0c~(r7fbn%cFdF$(ry*-W`B-|(oG23J)+S!`Ys1PGp425?BvZ~Jll{X(#waKLp_e2 zhjIaTO-`WoM<&|SGyYaXz*eqcp>pOu9_8{1T6NTYc_Hg5(DF>g%?lxyR zjCUwtUrr?7=rmR#470ida&mC-5`lI|+2AUPV2~fre{CFgxHKy=Yw_e}Mn*GR7*4dQ}D&aXo>Uq;E^uJEdNa**MxP;Y1)``_`h9}J0F8`vi<12l3UI)(TPi7(xq$3y=6JKRTZBS+DI`bV06n!X7+;#SPG@iddV_Gb)TWg|JP5vN8S6!jHSXUetZ5>H>xGGv{h{Kp%~7p70tOU-vppgJ*u? zAb!V+F9C!c_IVp><4Zg3rE;J$Bb4l>nz9dmgZ|D-CrW!-|A!aFe2=`OKi~N-&w>02 zN}U!1h2+?g%BkJ8De0g1PYi#O|GDwqit9vawTJV&k%}}$6xXQxOKS5rwwd6Z$Qg+yl^dH$B*2kT-$gM{O^)j7^D~{kalqe^mAQZmgk)L8JEd z@E@7v9lL=kUo%iLm<8};Y#X^VJ{8E6Yy=tv2o#b<;`$4;xNSyw#yu8`#tym zhoKAd*7-vLZZm(()eIh?i3CzgnFIwJZn%!6r-y?}%MDnil}y~Hi}8{&k%IG%#9B*T z$D-uT4Qjuv0{Oz*eshjgTCWW~5%m=1D&O)6BqfyEx+Ch@%jn^{_^XPLI&}e;QZ_mN zJ+ZjjSq9x}A+6*>0z-S59hbYUAr(!2yocjD6G|E#B_9nalh8TRuvUS2oP1 zAI^ElKl<~YM9hW8YpwAeCZer=_l3jQ%`OzSJH<~lV5@x3DCr_906G477FUNN349&U7!G4;S?)NyJNm3zE}CD1h3B58sc@hW2UpJh(jaB429*BOK{cL(#vEO}?& zA!(O4N0`QQZ#bPQj|sxGeD`}}B8jMPW7DBp%6Q1Qq4u_lw&Tcim$I?)QV(r-Je-{| z;Sxy!VX{uLo3`lcR}Z6lBgQJ}hoCg}-+%udY$z629P1f`9fGT~2U^9H6#TZCfc2si z4Ln6xp-%ZwwcP|mXqTP8^~cL(p!sfz=y;Xx?_E%DaR--O?%TuWB@2lxbPn#wQP1mk zLFOUOA>AsO7rX6sZL=~;OWmX;CvD6BP?L28#m>ITAGwp?h?E};Yyb^3s&jL9utHUF zRrV>f-UnZ{=tGu5KEvqgswGr}rNLzZM`)F8M=6U&ZiR`Ud_aBE+Q?L1GUrG35@M)n zxS5yPvT5#bJ1prcmn=gxPme5jmVJx3+Q`JRJVUfoPoNUaTyZt=EOYbSG84|#YKF!o z7ti{(&+hK-7+jkVh(t5zdX7EADF(m%s_R^=@r1wnWeqOMjX~{EFU_(si1Jh5_Y56w zE+Lo6v@ewpz4)S$yvgR6JHEBZjZ9Dyzsx|DaRrsM^z%dDe)87Zla**$dsR|cw=boT zWT*>PK&M`$n!~WAhnB{%Zrg2H!6!C(g_s+fxijnKrq^fe>MqgE#iKY{5`R+8kjnb| zijluMbA^bg(VEY3e{){mRvdIXf)Z41zdZ=$f};I-?nkR1O)F(&eEOtc&GP5Z{l=e0 zfuXYsIoq3Ggo3y{{mUD;K9IdKr=U`j6mem2{MQRGU2AQ0&N=rzjStiW4rgpqO1>{Z z_b$_qptbNtL)lBiH-$58qtrVWNKm*$=uT4d@<+WFVOyJQcB9e!Bbtmk3s$p z=(WRRf6aD`d1ho_i;#;`Y~s4?p>sL+ufg#ls#0 zy@@lRxd{BQd1o>ME7uKIL{eDpgY;y*pWO>x*L}=*yv5vFpk6Y%kH6SBn$I5KCXQ#y zyTo42w8w!cG{8K?J7%gWl-s2F8a=pH{zOV~=D%x-0(!%ipgAd=LKECf!X6rSCZUd6 zkB*RYTi>&Q?fb-6BqTG#1R9x%9lw|X9oL{w%^LC`>iThxWHKd;0Nm0d zZ*-)wG(7ON{O>Ru*0!_h1SZlLO*OW$~v2Srb<`MzHRQPe+K>KEe&Ds9)1H|1LQ(Z zxhhH=;L_5%GJ~r8OJkGQXA-gV^}fQ}XD4#Dy{&dUi*Qx7I>V}VSGY&bCf~}uUB>B> zZ4K56Ea7Um(YM5KSk8Q3&Pdb6P!%&{SFW6;DO^K%;m9V(ySve-BX2_nt$GnamE zia0@ZVuwE?h1=i(`|{w>`P9Mv0j%daii@-#%A$}KU9@zn%3NGrLlc#(u1h10Enn_z zd$~k;XHjQOx5&5|?>BuJJ(+ylSExhi)13?=8}NT$f@cD9rKW#poRvr0y$xNCmyN9K zraXIh_|1>c{|pCOCPM}5F3;BLIt`Wqch(FF$GMnI59)~6*8%j<~gDkXaXZblcgkrcF zbY9j!Hw!&}`XPDYXR1>Dw+`!O@^#3}MNgWl;%-DuJ~X%6->7jgFVIhDFH~Su`0@>a z{p$KUmk^B9eEAx;qfikciCM#3_y?C={(_k*qn{s4JhnzkFw6(XI{E(!| zkdmDKg&DH81|3YETE!-~GSi=j(~XL1o^pw{Eq)}k#@otT<)1z^W9HOUp@w^hrx`I) znXfGmry~oW$!Bzwca?Q_g~m_~TtjAGnrIK4zK+_8DkL`p*UI2uY~-uza-TWn_>P1o zyN%h%svJtRn(icxVQkZc&ga;Y3x{CQ^#eU#fyW{4mN;>^O007qNG!PEi-Zx;|vpRvPscdRriw z`5WI73kD4$y?IU0>?$X{^l!JJM+yUm@al!Ts^>_!J@w6dIW2j#3&n0a6+{FW4nE>ob+W}-572X&!z7UFlE-Z4_{po$a$fWW285axGd+^`G z{uF=B2;OHzfXc&bE^i@}Ggb~uE&4!@HF{yZO+af|#!M9VXh6LHU^tlSUi)L%;FX5DVnvgt3p z!UNF6=KU3&_dhOYKke;TN1(Ft(5)YFxeS^Co$B z{&@(r`yX$dIkQ`++X(;q$cvsnka8^Xa#OZL=3kQ;Vvmj!i}D}&>cmV$?fzlHV=Mia zJWc6zv{)iZXqsts)+ic0Dp&*K=*Rz?rnNfprSG@Mq+)WI$gf{_qTab@N{noLi+=Iy zPuLFB<3mSh{0Yvg)sreias(RS?nc&6qQl<{8esI|qYNY>eZry6^XvBR_;vpoFZh&i-46|7FCCjn+PaHFA9jTm&xrdz2$n4(jiBSBWXErNCo#o(PP?m@5L`QlY zw*|_Y+}8;!o5E~&(_@v>XJ=Wy&q^NZF9yB-YDBngz5Hssu6oAjxtuE$w{}vROA!-) z*wHvAYSG{L^_B|y-%^T>R&$6K>q;Rfd}obH2FSI`&{L9{9iFUob;1{hVUZCNX8}I`ox9BLB}`W z8bsE&70xP2meJNzpnTSW_A>M_fM)yPX8c=ZdY zS?`l%D)Vlmu*$QMZg6LI?oZiS*~bGs9ZlYJ}TwfVrONH6j( zr9vLrM0x6j7G)jIaMb0G;J%_4)RhWwBj)te=_GmysV8IIH)>`R?1m0!F4l^ouCD9~ zYa@$@a531EA)AQ=_XZ8W=v6Z|^+u-7z1Dsl|i~IuNqq_$Mu3 zLz{go=LSNQ>UZD8r1*BO&6jll30$#PB6+ztauIg)X7t3`2Qlq%M-xfO$++l`S_)S= zGx*C^I(?$VHU!Rz?<<2e?0R?tzP}vcNVvZL4pzReFOSFl*t@g%;0vE<`d4)OL!BGn z4HLTX79u$vpQt1|`6PkwKm8gB7lo@7O)ExryYwHDmpi_NX20Uf3)Tkq3*IjjfhmIN zQinecD4Qv&e!ad>kaFh2Emdl> zpyCp{@OX8e{c5t%m2$)|9$y;Y{aekwPn5ht{TVWj6R6{m*}asSk{6^FK1^}A$DR?P zS*P<1Qtj;>M#H(QkN22vYnGU;EV;Stx-!fu+*k79AuIYx1HN6B-MW8!Ha;uUWotuGgDtJoy5NvSYU6KXpK zKJiC3}P8}4Y(Wx%|gJg&E-_5wG%(~3X zH)hnA`T~U$aLWCTm&{o}sGLK?z{G|=fn)*`wDp0A5rIuCyJ>&AROS+Elie)+nquwy zBfG+H{LO5jiOwFO&F__Y1et-NT3juEbn%~2gVtEi#h9;+n!cFYobPYL{t zBOfA3@M%EL(qhRlXeN&eEcnhLqdOI@>0i%L%y{qNx07-IXa8E?CkA7~z)LTXbugeS z(lB8oqb@J`m{@!|wBGw0ca@&_1)kdW8^4;8|yz_jXB@62B2TS|EF^S}2*onHkYs^i%IhxbsBXFd)MK_MFkr4J{@;ksYIGnsDxKn`^+zju8IiD zi#L>+*FVC0MN<2=3q`-235MJYmttanQq55VfQafG*?NE^+hC&3SdtY4L}Lx%4fx zxKGx1q>8F4Plj~=-;n2)Er!CBH1Q3lOP;&5)W^HtPl&fngOv;i>S~AZ2&MY75IB)| zqPsu4-d|YrGBLarx+47~PrL>-!?Gai7K(@P`!uKS^V4W*ct^szrg-%O7>*i=e~U%u zK>lw`Qa?|6@YetJb)tG4tfS$=>YV4X%xX8WwX9DVky`qRvtzgI{T0$T-}7;-NLOVl zykw8nT3rb)KKExFhnVk&NZ{{IKc6!w2tH_{IHVCzRA} z^v3X~`S00n8UcyGX4y`yT!~>*);+U1H^tE{T3#-(tVKQVlU33JB~xH0kXK1@huG9wy{p__9jgHsE`?F7^#!N68@Eq*1s`543f`PBryG@j+ zMVn;>j}+?2WT=z^;PG72)04Pln$co=Cc%sE%{>m$jjK(*2T=oK>2J#Szq+YdDcXoy zoLFfl5DR|lBKe;SKmWV*bZuT^YMGV0PqQ}cR#!7mB8YISf9}5d`QJa7#@~5ral9@M ziwwQOKYLI7J~+Db2=jF^_+sa>=qr3~!)#LZqUPIhv#gh@>Z8V=t5dlTh&6ouFPlsE z>@>ul82;en|9yP(f16aoG5uX)ZODdz$S-9u=`EjoXzoBkHM&4?m+$xmRh7NZz!W)L zFKT+UAKW+hnh&{0h+`$mY|o<=5!~X-7O;e}f(a)0sd8$2NM9hVbDkRUF;^Y%h!ovU#EN}V8J2q(xi#?#~wgk7~}yTz;XRpLy2 zeg1gbdk0cfo~3)kCJWk>jRO6oB&88gZ07%y;r^Uk6D7VxTNoUKgBH_nz2?Q)cq7q`v%Fo@?z zm*A3@mFqbgM{2M>QZ@(7l}T?Xl3IsU1($hMP&$hyv9#|YGQw4o6Z#zquGUD}_oMvQ zzvrbx)JL0SvP2%T+^m)gO=_q#QFdkc#S{eik zF#*nfv$&4dIU~DT@U*4wL~4{Etes0xAU6?(V%I7uK07|1KfqiqC#I9*`H|n!{rGJe zqYlKx;aA;mS(!ij@d_ZBM{XDCDr=H6iG<>snj(ammjK_bW7Tq@F7{oz`xIti%%)*%5~f>nR1_GGqDCGr08?hLZS!kX=+O_g^BiC&%` z3M6!xAVRB2wi6B`f`+?-f-Pbq`enLXJ!8+Y^(%R2XX}4|tV@}13N^>8#Mt?1^nlBz zX;6OJ_SpQ@(wnnsSY8nCqH^Z6i1MG z%~USBC-CbdGT7%nOiah-_)=-BZ!t=7XiKB{=W~eQ>Dxqw=a>-h{(<91Kp^8lpFN*r zVYA6IVc#f9ncYg=4-pOdRi7wz5vX1(k&CY2zb}dDOzz(zF4`Jz&uevszb9^V>FFe= z#gAvm!}myetJZb!h}}TlcXD<_;7C-IrABK@-ZuQQqx&razfHfcU2s$YYe+@DhI}j_ z&zbpl#sIsOJfid>SD#;Gt1W|X-xSa{Kr5{zROguUYj>aJtGlB{{7lXkJz`#^`%ypZ zSE;R9KDQygaG&&R zt$v+0wNlR-+GtgA)bO}g%c0!TOpjymaWeD?5?m+zvwo!cFa!d2w40F+$d&eI5Bv9D z`3g!$tL7zj4IQGOMLw%TKb2Yo+r0dthmku>MG(!GpUDXm z5&^UJIT{+QUbSK+&|*1~n(8k*b`cceD8z~*=AZmLkDs2Qe(jsb&SPWFm6DgpM(Um? z;GV0PG{&*eaBCGcIpc}$uAbPQA8B!ENr?~8ro)=I|0X-0Utgw7|I7)mtvi^1(=C(yC z;YWLaI$HFb!|9tvGy=-rGO)f9KBoR=h9`W__;gW28YJu!5I3SktuyBPIZ;n^Q%#s-`tTk|FBV%!c?=d&)j0!O~;dN{V%~S24Gg$}0~IsGL2f{HZ?#EKVj~sa4KJtWPYY)jQ5|{Q_`1al#TN!D0gB8cjPX z4*|;)i!+u*qc(%3>a9o2j$e#dpW>wxnGMqoH#tLlo*xn2}Zv=Vj7bqx@9Q2AO`hT&%; z#Or&nBTz}Mrz%-g!v+ZOPLxS$`Fdpa65B*A!eaM34H)!h0e<6*UHm z`#XUmU7e}ChV5)_843Tq$`Jt@b&tWbz(9xsOP2dap(d94k%Y}ak=ky)My>0EV8#3U z4{+}Ir!(fhD ztmC)~v?cu5qu2`mCMV|~o3fFiDxSEma}4&RJvFJ+ggR}OQt1gJKE9*E2;k_;MsY}Vc4lgrRdy7SH^>nK!=~YIwMg3y&@d&5e=G&jhl6PR|YzbChs3 z^@aZ)>`XNU*^Nk!mwTyi?kX5`32Io$_}BnGH$Qdr-U^EaQJ2DP#l&0%2DIf4E&uQ@ zQ>}pSFI)9QVj({fcKOtj?y4aiOc|C(7@Fo@OS#vyIQrZs+jCB5Hzm&rd4+;_DJAla zqAQG+^_}lvEpcaM zQIVUZQumSU$57wwau*t_#h;B3fXc2_vFT+Wy(hG4TK&VavJw7-&z*&R%CYh_RdG7+ z6}*eeyLbxPDp_r@T1MJmf(#Ma!Zz`F{fXTyPL`>#CS*z2JOv(ijIqNtDjoZqD$Rap zSb81n-rd5@X$;7^BmDCU<(VPeycd0Hj68)}{rRYS=5$l-q&gePlJMJgQ zYn9|jArQ8=A3n$_LRY>VGOsoC$g;d&6g8O3hxf&IPt9&VOuh*gq+O?NbDLe==_e1o zk66w4m$|Mu+90$TFUU7pgs`85an*v-td%C&)yv)4eT9^2|eqj1Ydj@d5^wX^n3e~=|$sx*CPi)KkOpk-Md81-J2SSv1W4GT+cPkXse zQ>yIR_FQ8xmmE(j2pzFs|2}m_>`m$urst{+CG|Z;b4LBGx6`!*JFWI+*+@4;Al6F) zyV2p?2cizHT2(np(WKOAHm~^R6yf$Pj=t&R34)Le7lG_Q=b7Yqys75RZ5bu>`A(X` zFf1?rX;|{CXeI+qrP{%w0JL;M!*c^`zuZ7jZ7|xK`jd zLi#j$5Hb(vvHUBEr4-R#*<2|xH>KC$v<*%c2(Vh4w3Snkh4@OpiEq;}N^9v>D92s7 z?Ig^j?rBCj(DC=Z#?r4h&N{1=_yJGdF@Z^`_U1B)_-pxU+jZ=~^KJGu7K%zulFNs= z42Oix@g|TW^0$dwH*e=~*VnUn?tZl;JU`#}x2;wsHT1IKO3AWMuSw~N0F%Wjh)P75 zSiQ;sPheS7rLORHCe?IAWBj{aZ(}oG7%<)-=Lv6N<1SNCRNM4 zvGI4|XwSv86N?uE$mBjrmi@%lS(Kv!LsXtE4Hmt^g4lhy@LOB~E|0~ z`ryBi1fz0p2Z|dwCG}=$5(d*xDvL4KS@f&J@Q0=I`8a2PWG4ub#2OaP{`z(MBadq zkl-XbAn<*T)~$5neIT1fLe*1rooZUtI(mJysE8^ceqM6-68IE9r|I4943^$HID3B) zYYtH1bav50cKST0=50`~m(qd0mLTHaa8I``5INZ{YHEzY)xvLjwjgngrlBlZlh;U+ zCVU|c<9k#B-rI$jJv|m&;0_>j%BWIUNWZ-YD|j|CFOu)d=S>q|ae3Xt~Mw z+ZYU9Lo2Z8lx2c9$~iSPHPh|T2?CXeN__)o%U;I*i&y)Q=bugwa4E+bJFpsMAZ!!s zEr5N5`5V-FXtcEqs3Zw65 zlLQ^50olbMc!$L6u{rnew`ePYNMU!Sm4^A0wCMgCH?PGVI>dbn8~y2G+#n5p7atGW zO~fDz3SOAEq(9VqhdFMP@zA#}STH+M2@!jZR~(o;{wm)|GK0Y|aB!4N*v39kd2*Xw zA3Xlw;Bj8)n^u5`s0r$5x4gV7&G#I5mj<5WxXm>i^3z7V*9-uCbKVQXC3VFdN+^V~ z_?bjV5;ZxKt?=ww8PVn5n9`}uuYJ1xRmG9G2Q>IyL9yx(4o_?>4ReDRE{i0F)D#p2 zLqkIowm?DWz;%T%%;j+BRZ^1(L8by_&KX(NF&AvbRO1ym(Vf(!6f=z^ueT#Km~70H zSKnblkwg3PYavd9zjui4vAJ(<<|VtkGj~NY1rcA;8oJ%b|vix-sx3$%Dw z4v!oJj-PPkcWJ_=GPWvorSV6Q$m4LolJR+bCg30eZ(6L6=e&{OkGDgmdynT=|1^O2 z!UJ~IE2D7w+qZASYigRix>iUgmUrr(R=xT2!((;wyZBMVIaw<3NR=0;SP;>O>2Cu? z8Arey{BDZJ&$kk=dr$B8YmM*%r$3&XYRHXy&@?u)AnN$h8v9vXMXmM+=UoZi)rBo9 z1K@&&-xHF-MYT~6hceJv(gp3<7E9qp5V-hKG`%K}g$qbO-9P4Q0bGO797DVqL_lkm z^U~1TM7?6Eaib3oP`tbLWj?zJ`a_k#i>iZaJCME}BaVlT=X?k(Zijjj$PNoAp4+v1 zjyg~kHmp;QeA!UpI?SaZR`;0ca#erX%cnd>e~gERhQ25&xC%(0lPyYaYO-<-rCuMc zR?>R^-r1yud5oP`mw~=1KXQU8dt?0K={71(j89J-QjnW$Ot)l+xUV1N4FX2pD)6{5 zJ)YOf61-0HqJ?DU2`oN08mmm@sa4MIIr7ep>B;b0D|`LEoWwk;5q!aH0JmY@21JrN z0YbgGw6-SHgQ$)tys$8-BtHME7G3+oBrIrjSHj@n=&*bX9EHsLE&KW^;MIW&pn}oJ zl)e5uNl1f)M(hA<3P==`Iw6%Lf^T{te&{ng@}hEEdr~Rv9N{hDcSGx8-yYXtg`2F| zR-9;@$}NJ`0AoYcK#O$9w8PRDScy&sA}z2sq6Beybg7s+IJ?cbVHVUf!#wUU-lMpC zHy`MKEdpi{7WLfU#~#BJyDC-CPx+Dl92n5#)hhhm9m}Cn`J6)Pe820f}9^WTUYgn?koPid{_-|!oYrIAv+ZcvxnVYPp?{QO#tLD$T zN6;yLzg=Wd;D7GI>zy!Khr&_d=H6({m^b#jtA~{dn&RtHtDz@>GeN}jGfYg49|PJL znV;EXMKFiM>KNpF_PJ`^#aIm-6oy|NLOB;KxGZKH0zDeVuInR?zYWM=%=UQF{Kx8A z3Q6?>?BP5Kq9n>#3~Roo)6qpu&8s1oy7gZ)97JvSJjaTSDWGgcO`(td3|{f6A0l_0 zGM%k3^G6{rAKY45f=66P)Q;BOp&uluyM7v?m}nu@nME&OQ3G7fTgIPC>O4x+V$2)K zs+yk8y1an$3E2xxKYmPimu0yCXq}L8B&+I{u_spQPuHjk8eoSOmtZpFv@m{0B~O)M z>>{ydxLS_WZ1A$f&RF{AQbE!?li39_wvcD5lQM@vjGq~WzSb8|Bt`FBY(V<~>++9y5I z!5UZC79*&~ysV+oE=VN{=jhwo)*4pimX%ypp3L;|&|fv@eRw^!mTH0%EC#UM(_Q^+ zHHR%S)GW~~a$el@=pyaspvwNBKvH2DQJpLv1VwIc=a$9X?olWyiMlwb&V+oweD^qw znv_I!%qwBjHU$!iCmYKP~qWP<#b$?oe5b5ySBE8Pc-LQrxw zN#nM;Tbc|-IZitd%eNxr@SagdI=`o1jkPbXQ3mDz!L1b|&WStL3mv zElOx~UCX`gPHeR%gC(V*faFY9`4fGP^atzeq8678qzD77nr0^!UEIYrdQ|s5TjB*z z|CeTDK3JylN)5YoQ~fxYBT97Vx`q$7BnMwl(_&z}4{htgd5%}cn>A8bqU)WW?Yw_l zxr5#cDtz=5^P*D&y*7rox%*d6EjY+He45jv;)mFtK@_ZR_-@5w!3{= znpP1InSIK&+aR?9Y7qnB^g`uqvQ0VGgIkwxs?%AP2`NzH!}fc_r+cAF8Qe%WxKgk7 z6I3RLOHzUmzw(y0Ftvt8@LMF*j0OGBZOf|N{rijyZ>nwc?@|{B1KryFcMY|=wiQ9+ zIMp#TAABTqPv__9%Nj{4X_fFX737Wa9pR{Y2`J0 zQrCpRp53!X%g^;d2|mxEy-wK)8%0CGLxu2@XE5_LM!Rr7K! z5iGxZ)I!9uCGTcE=Op!A&vy-30^{o`y8n#gHha|K>You|hfL!_Y9UjLv?Y?e`CTMd zCJEm=p;Dor%BeA{Hwb#VkX^mh9qF|f1+NTv!yHc(m z!0}2Lt(?p^C^hxaUpr;H~A*aW}+?JU{sC_I|^p#le&X+-7w0DbW<*&^ZW zBd(Rv#D(HU(CnhaIuiPe&6R8xht;Yy{1;_2bGYgpG($PgV!m((;~|Rl?MbmUY=P9p zWuR^Kjp?V*SPzf3jFc3I@si>sl*i)F?J2Me_Y8(8DGM2?gcp=?+bnb2S;UF-?=da`(RM> zsCBdF*%>_pXY8OAel%V0=})bDyK|~Y4;C?#x7#0h)CvzB_gse3ojdY z^~iDidV_0hu+=V}S%?L?#LBefw;PLipO9c&W*Uh-u(_<)r>2zX6Rp>Q&F?9!Jz2Ss z(@izwSzqs|2WgdK!v!71PURxX?;c5qbulo@tU(S#a9aJ;=SSZY201%MhVFr}Bmbemq%$B_-Pr4f6MWd|G$kMCa>NF$=An*(0*c*&Tuk zU19km9_y0NfJWK+QrruhtAjA|lzE>(iGGfXXG9)6_$ojc%PH3NBr<}!sc|PIZzAVY zn9Iw2N`S?RFLebff^Xcs0e)E`fAyg8%9!oAerI^N$0SX*K`+ys?L3VJ)2s(C)o*+i zP9p!b;wT%bPe`P?>k3+51`S!Y(jxQU*kz=z+jak-MVeGHg4oWFlx+s23ZSyepqSKS zaEuiac~!L>WstY9&59AM3&F3P`ahd9gTpBEzIKUgHH6bgm;SPeM%2oYBn`a&^ZQJh zZV_a2QbEC?gMq|U>h=?223sV*-wIkeAr8)JDC(!*$`HmEre&Q^ZO$S_Dgv!#XmR-U zkxyQxE{>H&D~(yk7Vb?o0> z#9wq0s51Ps5wlY5X>RY@s_prVyP}@0RZlge#Wg`Bs!Mn>}YgUBv# zud9}C+o-=XQX>=ORX1llNA}193U?n_HvJ3)g6tZe=AC^-V{y)T3ch4D!rG$dzBWK# zh2UO)IX4w_76>F9m_cjBWt*YY-j0LXmkZmAPLqCLfdA5|8v!&6A>*%-ZyrJ_@UkFs~ z+-?dK;PdEAVR*TjMsn&s(au;U9bxy@@-B5uot}(mC+}b>8xv&2W!kkb-{0L{%t;}< zs{Gl8BFV)%uaJad{xI&OaRfp-p7*Ecm7T0PNslir&BN5LJtv?qdBv{v4@XbieK4O}l~2nR}BNYyD~?7dLm!v@L1uWOAo>u(CUrQOp@kFJC&;`xubtIBOw=-jUSXbwSlp|x<*3Nxz9?#qo|2WCtpV{@h$jRJJQIp_)bcw!B z^^+&+)0-AZ{T@T-*7GfvJE{fdZVwh*pjdoYrr4l1Q-68cL%AaNZ$QbwTSHxD_9@oN z6*BhOp7SR-XK~`E2@YagE3Fotj8ex1-$-nu#Z<6o(PSxmFwN($v&~7;K@9k9!hw}b zl^j&Q=wyf+Kkp14eRc7O!zAnO`4_y7{(CYxk&}fZI11PgxjWw%!tkL%yO;*Jd%i7A>g*oz>lPU-84ZOU*oUJiKuJGWnUhl{EwecP!|1T=$Xm3- zRgQY=iF!+AJ|5_tPEF2lV$HTdbKe3Z*RNNvPfl&4j2Y_i_)E!xdTbE=B@7BrkBa7E zImrI6z4wl4I_v&M@$pfg83leb4mxxTg48Hg0wk6}1cXTMM5IZL(t9i;jP#C_fYN*D zB{a)Ohe!=AfKoyW0YVEUyeA3s+`I0&|GfXbcdg4Gt}hzTcb|Rs***I++E|}<^{OXY z^{*fkTDic*39N9!NrOrQex~JL{F!C>+0gG@^0ZSLp2nDyx^-MrF=B$C)^OG(cIsnL zh43|oZkpmc4}kw%#`1Ry^l;_!#%hTVzkSKHa(v_*w&dx^48txFkHfHOPGceV#Q`-d z8N2*XvmI`3u%e2XE>G;Vw4}i1hhoDb;9&0}f1LjnfD?%r?9uEk%qz88_9O?1{qRD= z^lHZm!WX94;f}@bBYGO<{O&GL6kp1%=N{2sY9Q0Fkvri1JdUfy6GhR;Jtlq(u?bGRHEgXdB6X z69Y;e(X0O@3$#zvcc&FJ0dR0vtbo`+P43Sa{%jfUDWi{nZh;qP>rHhhUyXV`Q|13z z0oNdN$EYY$zdSFasB0Dv2nQM@7PH7umcYw7&&$g@gsggS2HB)bUgb})3VabO4!jyv*6fpm}#6Jq~mSMb5eK_cu`hmZ-==K#Rw)w0Mhu`b;-~r3f&;BDFF#ws) z5o=yxjkPS$NRqE8<{U0(hj_FviTk%)s^4@0@y%^$S=SUY!f$)e@VClmC zY+%b;fgvMTBQsznU_=b4}aC}QgY#)kt#_yW#??`8YQJDn~P zRq^JHsIZ=}VuV8uw3^T*bvaAE(|*bZa4xn5**@c~eo`q_W2)|$Kru}DQA2HDgy zA=S2G!i9wX|=_%*oilKL1q{oT~0y5eRb0k~-h%e$?z5wXfcW@O+eJQ9QO2 z{^+Ij8}L3xYa6T040IFb8yCd7z6mb;R`2dMa#J_q*OQyl1nkECh|y2$&l&gY8RUtz z=O=>EHAKcRO?}*B^BJ%A`O=k>Kl!B(k?nJPRE2-umw?XUA_bN zT+B>)`4TFRs+4j*wA=|>{njv7oA0&k#}Z(LW5pDGj>pe$>D#MQj{sVgv`;?%R+KGNLLnd`mjGJEfufXp#f zH0&TBCbGynZq@}kMxKb@KNw5}WJw{TjK1?E8!W6m!*oH7&00&OF{eMi@F_BI0tp^W zlGIT1sV>i;t`o#!S)_r?Ucu-Z%SBo{ZlVB9y3h!ooEJJ-v+_&lxlqQIr+RmW)wc$> zDM4VVOWY>cP6h0j>;)YG{OP0DuFegayasuN=AX}13lPT{c8YECxaEN@Hn~J7j9!DSqvX8od00eRq`R{{Z!{=!d!8sd+V^|7SA{;z=j@SQN=?=U8g%hhRgJ zwNHY?J+F;Dl&OebY_>ls&+h{*0BDb@lyfUr#;>I&RL#8M5UP&-(s^TuVu<&+@}l-> z8_tvGrcasOIofSspu{zXUW)D6#N)buXS(HV|1{;Y1sgj%>wB+1;rCs?yETPI$Onyk z*by|z+RnKT;bh${Lj%y4<#X2S)R`ikT32X)PFR|N(ZJWvCWE!_XO?a{WiHABx*AXY zqry**j*S-VrN}{Neq@@SG%d^13aI+%(u+@2dv+*{}5>y%)*30p7TLN}4aDKY{I^h6gs$+lk%D z316m=pf}T?#A>q8un*z2o?Kn6*#c4*>h^c*owLV-@@7L-6&*SGAVP5g>-2M&Nvx6QyxDF<~b|i^U3K z5oE2-ya?Bzd;bMRo98S$V{;sY-2PcV`|+J?e};6e4vEhlm1D(5Ty>ml&YCJ0zOifx z1<~0wyzXf21Ax-Djq&jO$b$(OH1xuz4S9m@^7&3ik_|L6u|S&v;|guw{tD%~kbAJR zT5!Alk%7+~HmRP&sc+3ots5;I0hl+o$nx$o@09TG?#@_Pm7KiQ=VNX6D&=v2- z)FQW~k8_!qPEiXV-Le1j#bC3QeQxR~xf5;IpE z-rB!aNzIp{_C6G@=&%r`&;7$Nu7YoQQIV(rov-oquTT??{Mmx%xODfb;m8z#jQSu6 z_~TcArYt>sVSyytgu(`kYLA z*f-VvPh$sLJOd85ap&n<1h))%t%l}gFmS|mc;<71LCb>S(6ady)1%b=&#{5h{SfRj z?nvp+ajXg`4^19WoaA23RL*IrCJ?Zvm5%jOoWM-`wq`e(?`)M9^^tK)O#o*Ul|lBEN!#wJG>ncAdmsM@DIBj%#H8SGBlFUdQ_Gu3|fvwzggFExxxLdUQC4t;l}kb8xHG*c2T zi@yHXuq=VtwFBImg5l&!dxP!)y^CV{-@e{$@+{B?i6WH;P4hw4j6@Mz0o$<#ba-%D zNyz}&V3=oNKIjvQeS%_-b4EIl&v60;2-=gPm&}{IwCX2_o_V)VSQH(+mAbI_A)vM) zAKz$FVJyMCFaLDlf(nHaB`R1w2n#DDJw--`i)A$vV6D=Q6rX{ZMP`8-y? znD7>vWu%C3>d15Xjh6~Cy3s#~=-o$H;zayqn5CL&_u!i}{sd}i$X<`hRWl_e*1b^; zXRiPV2LLxAMdCtOq#)c?3|KwJ^5Wp^Hc$ii5x_7J*_#ZuM@>~p<3*~19*^z@fRxdt zuMD{6Ol9SGNimHxO1%TLZvObgpnF@% z;IKZn!)!MCD>D_vrhED7>y>TtI2S1T1EjQ+-8BZ$Y}w*84952SFPBsQ{P)m-ZB?ha zMX6fv@|=Rr3r0*2Xs)B~Rdduj<~+$mI8A*Uf@XZvibQl4jT?>6zLQ}o-fZ0t`bo&@ zR0|fMRyY8xht4z_Jfpp}wN*@Be!F%Yp8-E2?w`oEI65>Y-Q;8wJ>TX48bRo!n`5Hr zAPZu%MZJZE!B)4;wN|PA9F4##pQrMk7^n^yJNiuW@$mAl4~8gBD$OSi-s_28T@JE{8t~mIAk<^y zR^i<5_KJoo2_HH~)lLqY+sUdA1s#fO4DDu><>-n6WEq6lm_y#diaopwfYVg2;+E$# zjt=ah9t&k7By+cpYxMxnqQ&cA!X4kEAzrV=XjTZgSUum<6@|iy3RXGBT^zo3E6%I= zMgod{%U#~l&_nim_bVZ@mbJUMbKJ4Z9L*A*sZ+82uf~#1_Ve{+rJ($5Y^u9I!XR!# z21d4^Z;S!&sEaAm_<0m1rgb!M7Sb4o+8So9WUOMPQ!a-^OhXpMxHyH!6`cyGwRVIBt0uk2#Ox7JMYyR-DOu~v}{KELX+OKlL(})co9m@?RDg93Nvt%tq*L$aw z*%xR1F1-7#&`7j{pOl_@-nIT(6n$m25k6NDP~JJn_szvde!}W?=1lpkvZ&Mf_1z0x zW}xO=lpPIV^c(G$hb?bg~1;{ldvUzgf*+ z^=P!sL?IUcK1=QW+l0IRafUv}@98C+lNAd-k8WkuJ;I_-m#vBQoU6l)918*eQg=(iJ#1#yorHR~-8Em&ddzrd6{0Qaqn^83Jo|`oB zwd+!ruG53-lB9R79A+^BbLoQKs1!-{xic? zUsBhNnH>S_eNV;Xn_KA5hbCztc~u4_yoRXMEIegnE57s_qiXW;ilc$P4R*Oy z^9XPq%NyAZJzJ_(&}(16kJCMc3d4K<<}WJVOs9+a?A|iPqpJd>INHIsFldiV6Op121b^O zE`om71zj7TL)mYMy0p<@dZrxRB_iq3r>GZyoBPQm zaDu+*KEPjKk>|zS>Pu1PF-%XHtt+H$-0a{^7v5Z*A76 zK_*7o>DL`K0$P#ECo}2!Z z+&FByD7%tb6}V5}o?23bLi7h%(bqf`>P!HP3+E!{XQGWEIS-aG&ce$=T;4z>vL_1h$;PVo~U z*1YL)33jD%SyFyCib|W^7=m``EmQt?1x#g~68*je&rv%&S2jOKnCv7JN!vw;yAw>3 zF7iikwObRA8Icz);`bwIS}?P%ioq1Z4VB*C(}X2?85fD|f^Ivb$Ty|Ad_i*K``Y&c z%&AfOP>=~}PLmpx6}FM*jyCa-HDo(Usk_RLfU9uw(ZU`Y&nYA$oq{+Ny`H9^z7;cW zQQ3c((z@0}9>RGFa|)&>w7g3oPvPJ$mN0nM(vd8>eoaAD&05im_Tt3oQ3$;I#VX0( z{I$Qde?rG-%l@~j#cw#qLThqNE%CU(d7#E6mz_7UbpX~YPhr;vEvsEEOKGtorFBIM zPbEUq1)#DdzUP0euIyz!G$yYH4DY`7Ai6&tBM+7`DKb7@$Yre5LKwbnJj@4&@&>Kp zt9-J&EmH=R?v?I4_4OG?P8@a1j2?VENnPm;vENQX+3oRQ?XfPW?Wv`yOdd7IFqxhI zD;WTC%iIgGi{rG^4B>=zrceapNqGW^BCh%PNeY=iBUqe%Ul0}3hFnfb zI@$w*VthJq699-3%B^$dozs)XN>bl0b9N6GO{J>rd5AHzjKnX@b9*#bGwDk@SVp0{ zIPk=bE!f2MqKD&`US}-DD+D*|fX!WwgVBU4l{`BSXw}p~yN21U2>QF8WnxUJJ>MgS zdN+Q;Z*JDs54SM30(VKmvPuim=D)A6$JF0uX z+X1)Ye6S|NnzBu$vP9_uCQ?QIUJx~vkN#27#Ay>DgPQxPo*LRDW4+OxnWb|wUL!|2 zuwQ+YKIu=*J4CgQX!SmzmbcB-rS9hf3_pe{S!-emf#U$J4cX+JGvFa~+f2{U{2Yo6lETnx2T_$P}`UR+#UihF3f$m`x)SKByliAqlH8VF+# zZwDP^%~U+5zsj7^(Mkv2^2%OZ#%%9NEWT~oGCsksIB7CTC4P_HP>Lbs`rIrb|I3t% zYjLm^C7`ta_ojf4n`yJ3g>Vf{rWWI)0hrXce!Y^kw}a;Z=73Ht?QU~H$BZG1W3qbr z*FzFF4m>IagKfB-;xymPz^9AkVO5Wdw^%Uz}7?g9lg+2hCN4yU@B0 z*5kXt*>N{Y2l&XVY<}CE+8PX~qBjA(dxv9DMM83{#DF20*Uz%(sq^z(vKen!?SyZS zim1Une20T*_T0pk%!9@5<(KpZL|_U; z8;`cf9s29tL1NhHz6(@XCN*4xWD%TwXvwloo!U&-bMSgmX`|aPdhJvAxO3LZ&Ioeg zM~|hi?c_~v4KdYQ?C%okAJu^y z_%lbq@Y2HyGSKPk`>Uy~f<5gs{?74;VeT|?Do6LKh!;yBl~@9hC1>W|qtC&cczR3N zKK1)n|Kp|8+#5T+zV5rcfY~=;88RYS9MJ2Mmi!4JIOhz+7+rF_*bfO!Z}w*L=zmyR zpw+CwwyRrEUc#vdEy5pM`|uENI{QftI!`1`0xfW41q^_1p*`MN_Q&GHc!?8ibQ&^R z=yl{lTck60_L;?N+q>f+5G8#HwmrmWAoknF^W3z*oNKhlhWj6aU@gYRwIIF?p?tG} zW7mo9v-Tmm;(JEL*9oOc{8u7VRlZ?)CSBoPyw1@Mz*XvjamTW&t)xJy%d_cI-rdTvtE6F+}stGn-@($g#2I|8l&H zeH;hBwAb473N5Im$}iJszC;@4ZC-rJ4U!N3$Y*z4CrI|m6?1a5Pk$b% z@9-j|pderw{GH{KBv&m0yZu^Cpd$!18J&1lySI3Vo&Znte>@*R2O?|u`@N&hJP#Oc z_Mm1UCmBbcGeNB&+(%G&app4DkC&;Y^(v7tEr*gsBu#ag$JZ-Y!C&l9n-b&eKF`JP zQm?S`A*7IQ4mnr*?GuyunOtTMP#=f5jVG5qTQ2C3`(wU<%^wEID&Ci zA1a&&-bf@yni2DukIVyqtUrSuKZ&qRxqvWFdn-wK&?1--t6QM&Q8m}PjA}~oZ1C#& zD0px~kP>t+C4wl@gld$j7I$L0Y>pBviY7)@zulvLw(y=CX+g$Tt68S3OS*Qth-8$+ zm;5UWc5tJ}b1B|RlA}Y7e?O<=Z_L0x&R^F%0movF7K=GXUJHF!@srQhBKe;`9~SV{ zX)PI5sLk+t-dCRJU@fAhLDt4>L?!HWpYflH3)Yj@!XEivN{A3=im_Ze(~=plu6PXU z_%79q_xtbKI&2M|;vU$nnD8A2`5{wbt-Z~G?v?&)0H;BM;=vocCu5dJ@{O_?k~3mv z93;-Oq|ePEX|hRX!@G8NlPDWTCg?X-h9Pu%DkQ=X-ln zL-=B8C}9ZShHGpnpWCLjL(TI_riqt6mKOpv-Oo{g{*_B{{zH%hZRw^jxl3?9#)$%f z8b-)_gAnc6W}n0E?5^^twc~|B4CW*!Pokk&Ez9S0Ki&=M=!lAz-iUQ~pZ)mKfo{0d zc~e1ONJ^hWC2%&ej7IYLnwbkNuo{Sn=3a4DJS+9R>GzU`sG7kI62*I57>>laOdMRI*c5ziT@rmfE zLn$Q;8cZ85*Rrb$fHhPFTp!<@%v}JtsH~giKZ(bOhK8=V%|y_q7cc``r6vwHN?ZiE z#}p~BL+!r4pQ*blJ2rWOm~3R zQVbtdI}&=gYl(@A`!(IY-dN1o*`?X$@tw}UYk}@98JpOdja&4X{#2jkgnc-9Q0fdL z)vN?Q-^m1DSorA1l9l2zM?yiI%PLMBx!SBz)8Ic4?}*np;)U9e)fE7qG#DX+6!~|E z5bssL0AZB7lYF|@J&wAicdSL!SjY2iX|Nor%28zT=V7lWN|EN<}a73qaWg2=t=8cS3@7nzwPYf)O@5eliX+vrJ1 zC2vz4-29s)vOCSdqe@J{b)s&NGAPRFIwEu4`^aD{$RjB7pyw3xi02ZSM|??rPD9*w z=8V9Dur0Mbi=(R`Qy;eIZMYMlXz$wBSJ*A0muKgdB*l%JzeCF(@N`g_-{kY8&au{D ziOKYliNjn%C4jH6dwl_GbJ()kQ6(2b+R5W%ImlzW`_99~;Zvvh7ttk6=FNGnlmu!!9^*@YVpF7Jx`}6s!Iw;Op2b?f;m68>zUyMTl15I`wVupMJ^m?fpSU0a*yMI2*lO|Dl= zK0Ut4BkK@559}>Lk<*r}hVLD@pfF#mCv_bboJ+wN`N5)3$JKU}2U4_% zd!EdjEzUA09~GX~wemP@?9Pn3%ztrMA4&FY8BL&3xs5LHJH2IJ9#<&Z_E*C1@WdqK zVl%SP^x8p`ehc#^-PK`6A_o^EQsufFqd4*Dg7B2;^jmV2Vy~dpqeXVrwmrkEK)c8` zZ1yR8Zi*ME@%AZ&19frLkn1cJWI#Y1V{+&|eoP7GKK$j&dygdc7-KnW4 zbq~w)$fFobBgG-?s?*{4GD{h0`p=y)V!`VA#F27m5XJ!rj;Da zzXun<487Y=U!HSINfrY6Nzh88uGjaJ>^9pui^yA~ZcM5I2UG%5GjVA~ zVP6wk?BNZ~sPV3Df`RCm%(@|(Rv1YzFfi&sc>Kt=$L0>^Tq7F$(C7KxQKUEh)hXZY zk(rI*SDrGi<4P4BjZ-<}w2*{DPcVaq!gBS?;>TR84TgQzQk(^W?LoLdY(OyS#rw<4A z0G)KNNoM8?x2hou+76Lok%L{|1!asS7s@;_5cQxds<->5f~9T_2^1y@S(@to&xem|i507Y z+8PaXfBU5rJgGNBAklY#WYAHc!3|T^lcM=g!lo4*VDohcYq?H(0GIt52}C)a_gJKV zm0ujW$vffZJT~e70Ol%p%RAlg;XFR2MV}O~HJ2o_u6A<6aAzuKv2In7o@l09R3iC@^ZVO#T&Abqz|i`xqr9wnTd~&($>GM$B87$LRPYQ~mu3`0waO36ob1?D!Np zafElXEM-OE#+F@8M_&>wErGYhoDTY0Zzr%WfBa~T1#Y(MR8FIZs_NvDkMF8dO%TW7 z7ur#EJO+*qI!*C^4jVcAFqkraLoH45dXXH;Jn#b$9Wj>q%s;KPN|Y-w5QkVAbn-SJ zqfdwo;y=}<*N;@^2%U_=iOr0`-_g`Llvc}Sk?0=B9#Ck}XJ;`_ZnRvJB*aB)tEN)N zwBhRHIKz$;3YfKOPtLS)$ax-OQhmaJ`}9jRBDKfN01e!S_Zm#g&sNwMX#t7~hUCVz zWkp}#Wx83LV>{<+#s z2^-y8?i+ZmNUg7;9nA^?3HAbkHwBf00&`3D@hg2n&*aA&0{e8pR&%nMTITvk`3Ca4 zPCJ6lE}k_1l|8CsL4ebS?wBQ=MOGTMEAg+K`9|1Thr`d4)*v-hJcbIdtwtAgT* z)}WGlI}chZxlgFjvTPv>7_{42iP7-7H%be-I+q8K}9!CytM8LC_UPP zbdRM!xq2!5pHI0ImP8){RCV{g#XQnd5w`bv8-MMZPlFekzDxyxHF1jW^AZOEt>N5Z zDjX6m^uwlAe}VUQ(s_((EYJISX;xV_+p&etl>?#_Tl;-TI+{*%t|fZalWWG^4z~#Q zKmLBZ2#{Y&>*rIPD>{Uyb{jRN>V=Xl{T2z48GtMkhn$2?Zf+J$#wP;Tzh10gDlC!) zz>2cYBhLzY4P4$hAJGrp|NccS+Y@}B6!g>%o7iK_!B)7XZ61IeE=Ja&-=-XIHlbu= zR_&Oe9w#ih_4Q;|Fd%;xw_MrD3MWs3?(LN zleCxkb!wAi_-OO7`SB#f?EkH- z+!f9!20wj~(iLu5ZZJm(DmXi;r>%HR#cy*L>%<_tJ55nWy<)wU7ou!wVv=0rGH%!X z?xrR$vo`~rZL7)B-5Q61TyUm~wWZ^ZMJ2l6V*tooNr}?v9%}=D9=TQgJiv)pR^2>4 zNXN7sDVrqyFTw28EWyL;7m)$aO#vU|UB+g?scOga`7L}H;`-+eWBO*7Q-zF>fnan> zK^#CuvfW-89d&IWO9$+(71xY84srkUQB!@V%VxE%M058ZIdFbXg;X#`kNNYnPSL{g z+u6FrnfDj`dOMkQAHieiA54t~o*oG^BX{uhLYk#yz+*hCm;;{PKV;oQ@MxRKyjbAr z`uYEV$^S3&(leA}%_2b~N2nv5Tjpo&f9WSN?qV3ExgGot1lq)dkFEK0+J7$#^C9+V zN|oM_YRDF3%>DNLL4ZUqy+Wh70j9+a4B?wCDJsyDkp zC^T>?FnjuVbg<0o9-4My@bUjcQ49bGB{4;O|4==P8n%F||CfjkHqXXtN{K@M{js*d zqQT1xfKv_@RCW^`_#eM{to>hQ!+bC($kYc>1;_D4DpPjrdcs=rfA4xcl4SJbxPpSU zYS@K>{QUNloXTbGGfnc%M5t`N?YNfd>0HvvtDcF~FwP`O|Na22aImxjb6c;qy) z?nm?&8DRr}$*^sKy|5+L_ACndQhO9CkLde(I$8G}zP-OwGZnNC4%+Vf%yvK9oDP@F zm?h79{tQq`mUVXO^Asm+QzEcok^smZ0UEui)Qlr#U`R|$V{Ak2UdX?Y zfu{S)PX$mXd}bo1>T;b3rO7v}K7Wo<6Y#Z(X~W-|2|veo>jnS@$HyUH$#~el#6D;k zn8#;i2qgn&Wt-?d6+owvd^b8o23pWZ6X>Hu#pUA4PCpm6E?nWeKK1@QM270{gj<(n zm~zl;jM_ZtBIdUTX|4$0{lqE#DfZUr_J&n0&>2q0O;u+I6Zh}JV3ZbncCo?g!PvM;Gd^54wh#k%hz$9bAGL`~13LqB&3|r7_nl9c zbsT*99sW4h2FMHoi1mfu=WNXlr_NrO1#ImN=5>811-@Depj#QX@dE8K4>;H-5*^`m z1;#_*!Fro7@WI?ckC~)$jSzJQco`kwlQm`GT6Awgm7s&&Z~+zE*oGce)aE6R6$O-! zfIMQpe+eN0Pojs>S*NlyAp=_H)MFo}-MYE8G}HymeN8)c7}#6zH_yMP$PvulW7>?& zT&f3)j8NZs0D-7fAhwnE_yZaq-TT)sSKYq9xj0YXr{F)G5o}yre|uhp0XK_O@&+})J{SnO`Ezk;EoB|$=+6!FfO~K?)DM%kaf%8AI5qte7lT* zA9}bp)8j2eO#8WAfLJw-yEaIISx*OJlwHeM+WwH-5nbzpo$OJE5@4xA zN%gQss=SM|<6yp!I;dyMfSFeh!C%C9G8z+i&#U#MDjba=_<{111pmB0h7dimb{Ob+ zAJUs>=9&!fQKh8Y09@}3wj@>Aw}P9!>^IQ5mjVT4#hC~N%h}!gye{!Kty_fvYp!?3 zb}xKo@W>K)h6TWh z3g+O)J?r`Nr}G;CgWSH2-}_FUQkMb6E|v?>aqcdg18+39ifivN&bD_!TGAL};edZ#5A0n(Fg3;1!=?;(v=@GKAPdlU z8G;p?4Xl775F|I?@7it+86m)FxB&^YAJ9_J0+9D{Lf|I%0?cH9w&^#=h&zBjbO#>* z$`}UvPpvK!*vll0$G8tc$HW|Xe=lr*B`#Mhbv{C2vK{!)36eD*ghJH0dyLaEr z0rDi_771|Sle87*;&lOUG=TYokb#SjG^2t`mB=t#x`%sPnp!Ecq8PVM(HuzgZYC7M z^*Fh*O2!X_3pp0v#A-0qE)I-E+0s}pskL0J8qgNkN|v^bA%H(L3c%>T9N-wm^T$=;>`Ro6V1 zXvU;25SaTgl{O&iAa1Cx>XK@R2Z~%1+%Jd)XiEmk)(i2}e&f>y@ft^z+Ox;;!=s#o iqa|fVNRebGG8(o>Wi@1%LI_D&84*R45k-aU zz4!e*x~}u8>;8TJyuXiMkLx-+&*J0rc^}8|dOg?c@HuiwiHUv{Jw;JW$_EtGDQd}S zilXhNTZ}*Ps*_g2ZwqbZlr`w^%bD)9H~xF6)d6i=iefe-|EG!H^Vkf3C~3D}%kG%v z89N6<8xzXH(9Y_-rQLZmqqP@JY;4UeFRa}nDj_Pdd9A6Pot2cB*q<*DwX``aM*TW` zpQ6@M$_o25E}O(kD;^$HsyFTTe%vW(luQt$F@^;}s?x7A%j zZAnl5d$V88-oFBkx8FH-t0m4<^4V%nb&W2k*|`pfoV=6v$2Eh5$6hvHcx_QPJt`~R zoIL)+zSn8YDd)5t9nHG``Xyv-Bfn&?!r#9}UKq)Rc>nz?K1iHT_3tlH&`=2rH%ws?Em6 zrlq4ZRD3`|VfhPY1%)8a#>MN_mHAoFva)s-j9o3YQZb^h(c~To`>%!ZrZ4*cJaxww z&&>k=e(%wB>v!+w7Sqobx8s@@ynFYq_|~oRii(TfSv;3{d3%@9;b-wDJ5LUYZ`tA` zQu5dSNvGor3<`4Jc=#cgRM7ltzJ(1L=3cuU`hrTGO%xPHE}oj+t05(%5l`*j{aW4a z*9C!Fw5 z6DWLk@^yNd2g|_luzbza<53zyKYskUS{^DEdYbN^U81pImzo6G)H%KSbq-C-50*ZP zi+fXCylBtN!1aou{eCO>)~==SAG8$@Bx!f=-fh=i%XBzGR^*-de=k#+`|@!47n;fX z9W@D|6O4BK>3d&aKxt{|0=DNXSFXgr1j;^+jqT9W4>A2IlrYH3ddo1yW$n7? z?D`!nN410Q-d)PK@bkItpU-7P6*`*ZTMSDAcm{@ss&z!&1LsawkM41vu#$EhTKMM8 z8~#@YCvV)iK~X18oVYa7ajU73iC1=Y-s~7R)se`%E_(iHHI{I$9IxljQu_Y=`<>3# z%5!;B=BlLv{QNZ3Q;jFl8QChqLN6VM&s=SE8UN-GCUf~>ZW|2^jktt_;FqWSf5(rB!4|Ha7gnFEd*)9=yO_FCYi(D<%v$AElaS7=pph~%Vi)`9 zkJ6=Ev&&;E;^Y;nxeTb8AFp~K3z4L>%pyv@qi_PU;ENs!<%mes3o;FIT9R4lu` zg!%3JyIYUuIy;)(4-90%zb^?DJ$WrFOH%4$k9YWPhl0XF+MSk7?l*7V{H(o~j%LrE zJv|K>3=$F&)v`ELEbQ#=I7bwP19?3;Z*En4MR=hfr`Y$dF5mq8z1u9C^n~?K+9$5` zRJUcKzK?W%n&?TZj8uPujbW@7AcyWio;fFVB5;O}- zOX=1t-YCs%{`m2T^K@_KOS{hHI4j?O{qp2j4T-$i+d!?IeT~9EQ4S6c?p|JbBa^d3 z^?>1lVAk$oQInX;kz2h9OcSp^;HXAf5E^hAj z>G`4CGxH;LA%RKSX#zbxJysnb`L>zYGVZN-umSZ!>!sC?Zu;y0)EVE-FI&HN)zrCt zUCcxsJ2qR#ymaZl=3JLJ-lrm)H>X_e)zL`O;oub0FDkvY-q6sH#=yXU%5TcKT$ShM zMm~6VU9!@dGXi6M-x#R+EZdEGdV1pLKF1p|YtM{y9%JO*!KfN4x`>*Xo{n+oZ+dyL z_g+PmJHwrj5Kmc`sYu)Qiiz3r=36LIOW6ckb^G7l*|_Us4_EE8lfpci%M3T;rfggqB zdEM~$H|U%>^kCOj9CdS%?y8t2_*)Nr7*qZ-f>fFW`0oWCJb18pw7V{@a_Q2g-abB8 zGcva0{a^KA+h{a5Ga0X&DcV(=uMBd~t?#{gM2M-2nGz|>PLqyc&E;eO5P7D+>OI#j1ZzjXZ$w^(o z&%!Q1-8tH0XluJshUQeUFGsvqDrv(XA0Lh|>NPL)WGbzwc-vKzV0iAFucH5|9~I%d zxwf9UQR_s?37*6E@87AlkLySYiH*7vDrOKsyJVTEMU3Dl^6<`ESXj4}acsNrl`B|S zb1_w4UvFCTru?CSy1IJqtsxZMYl(@QrJW~^m}|)3$3|x=qiw`QM}K^BY-4BInO&iV zg`S4J4H*NYqs7DRl@b?ww4_~UxRP`;-@duN#BVnA>OW6oWNMpf;GNami>ycE)SpNHXPS^;WB-3;i5%9rbfFD96Y%H#EBJ~MMUC;!otFg#$9Vla9AX4f2pmOabhQh z35VvP%w&CP546QB>%~9QQ-q^4qJp?c?Uk4-J|enYRyG$tvLUIo%I7m8&f* zlDQOmx2$t}Cck|7!Y3%GZ2kq0<>)g# zNh}w;@I|sNJC~ky{SQ9dso%FInzEXiu-+vlWi&O?Nge{(r}uYSp0oIrZgy<7q)lwT z%PMYeAUR!g?Y6SuTR}mw!JGVje5!QX>r;)n_P9zrjraLuOYMs~^8H7lmzcdi6ZeiH zZ1usJNn5ioIExvzOBopCJ?J@5*yyR0=g+U@Czp+3b8B zeKG&bmz6hp_f$B{QA1>lMclv7y^KdHHlyeJo9pBaw%-Kaiq2g1hZT${zIL0JMbVAf z?q(J)WpCA8D{{Umd*$HZpw=rp!E4vAXS}$--F(Fkiw1Y?v@`qS)PMXe_R~r?y`|CD z+UgFB&W5TIygXpdnl+aOzSFD_(Q(HYSL@pS`N?&hZh3s;=O@Rwq%RGq zj=o)V<)-WuolVwi)Z~0DLW*UxY?7nR)dx*)vhGw-;)VqaH*2L(z%(zNMupx6@c3c< z543RzpK$m0XL6lvj|XQr^<0gR+P!U^ab2FMI~@n#{DI#&RdW+9%;~@=FJ8Q;-g5ZxVdu%VP|{%a zPM&04xzcCl)-$FS?EsnR)qEQ^EPVFtS;yC`t%t&;_=79a=yqQCx)G$pf&mwtmz3>G3c>I{>7A$xYrEJVCB4r|I6_*2Ae>2kl!6Ft#TFL|-c1f9>K7H!VwMAi4_CoCR9#MsS0Daf~fWBy; zj13z$M4tI@57?a-H-XVM)r&ehN->0}6fU@<7mFt4L1MMcHph6^|o)hr*uaroD8 zqHW*e`-_sFUK^uy^KJfB+PKPd8LODrNbkk*Hav6YkuCSejT?hTwM)A`KN(hU{L;{n zJL3GByde{gKZj0Xv5|!ZlexKhXPQouCoobw-3EL}C%*w*p8sMH|0`5nB`h;@XLfcr zBafmiiZ8asb~~=*Z~ojn*WP)@!p3IYaYSW*)AR=bHnxq2HU}H?^Ycfc9S{nNLNwAK z(C>1#v_0mfeHze7PGwpm9W%2Rh}oTuhZ%WPe1<^GfNt?(Ddu(0)OS~OJ3pkCdL&D_ z3gBvfb@lVl$(eWVumSePR>rw7+3^gU1dY7T+tz&2B+8|B<6`;r$A=Cb3Ve6EIJa_k zW+t{*e^g&+=^weHO1H4Fk^9)=LwMsOzA95o43;cevOz!~+PdW}|MNV}(MSA~Gcz*- zKfHJsPzz{jZ-s?;@@PzRxUgv>*sg-FjmuBBS6#2rUafOeM z4@#`it=W}AZ!Qo2I=G3Q9_M0joVwvy&ljy!qeaWv*s2mVlj~NgYNwi%uSm!D{HB4c zcVA=#bmw=7_tW(>eihx29)x8w3vCb6>9%a3I2-Ka#2DVa4688=GBR z2Y>E=`TDi|6OCw{jB{aI&n|OkQJ;)ez7vSIi;|UBtHnUXkpFDr;Ds4F{yCS&*KOEP z^fBtA`E9U6W8;=}b%bJshkrBojz8Ub*_B@e(g7N)jpHG=hrr@$52aU9EWEroQJW(# ze0!BF^X&F13yYJ9qroctK`JJK`;SRaH8H<^`_^R0l~ZmlzPqigGc=?==kiWzX=%_P zA5!M2@131X@2Z`+XBcAUwTwrOz<^e1zlw?qlV8jS8GqPkPVeW>QEdqiC!hHJhYyAq zF6ehid7e8A9Gf0+|Mu-`_~B7lwOzKq7(v{=_x3V@IXaKlXi{_i&cI>%m$P4`c>PC> z%Has$-2?IwP@ANyDzh2v;RY6|pr~k}|EleBmoB}m-GS3$TJw|xtsb04!oEx6w26sw zTVtlB5^x!SgQ2nUbuh7YA|eO-!_HJbWYX2ugiUGSj9g3q2gV+25ul9}n{|TPSF6t zEr3pSgG*vTXJ@BV$+OOt$Lb|dqkPUx43g%Amq1;-x%F(tfi|?~w`j(sS8NJa`JAN7 zXb3F;O)rulVECa~t) z*ZsK+s;a75T3V6dh}9WK6Kcp_da9Yc%tMYwQ&ZF3)AQHvTD;{d0Lrj?_X?ncY&`UU z3jEY)H8Jqxz@bASp6VmR!?b~0H@9RqyE0f>T54%)8@86-qHLUK?EAiIzhYMMU*+-n zvqnzEqSCBTXBU^FNjlrZ?%s_8Z`G;1_Nb%}r~6}yp*&8^*K9{N%4&MdLhqH`QdH(^ zIO-RB>aRAtPBY=tp_x%vP)^=_`o#9@*DrLNA{0{V{wA567U3@0b5+rc2)3)#*Vo^q z`D`^%GS$i$vl*p{n_IUvb!bfAWoAOca~Y4XFNbgeC;@&%0qXWpjlbua1C_uUh40=i z1xh4Pe-IRik{mZxP*?~Sx9(&!+7LTeC2Ac(*VJC1{fw>}R5~=$>o;#Q3mt#zj$KMa zEm*MNW2`b8J|aK}jd4jp%`0BJQB(gLHxwYi5YY+naj>PtJg0oimM!1AyBSb|@Zrgd zCY(qT+Ljyr?7jdY0+DD`M>er*<+;j$Aw@?=r*|2Cd2V85XZN}5+l$NN7e>14m{Es2 z8Z*VHy`rJ!{HN;@wQ0|uJqv)2=C*jE^KnG_*yZuQlg0EhGSDf`aexc9K^-Y5>h$l=-~^PxnGfF9n-XmU zWWy2_*41&=*4Cz^rQK-AAB{A+K<4t|2Qt%B^NwSQT85tP?va+wx$4QXRG75m76R8E>~>fN zn7AL+aiBkMenIJER4xGWrS@q`bmR{T3R28I34nDQqx+~k>gcS3DrNQS{Yp@ag#gdAiy5!zBrT>kpM1s6 z$H!Oy%3j#W*mw|Fkeq#0wr?XFEK{E~L|=;K2?BOO)pzJ_matbA$HMnBfy z%p9!Z0kM50mRe}&C6;wDwOZDh3%wKa!`a+0Fb;Q_%VSijvfTUd-JI=}5hWR4H1^GGDMpIwtvvnz75Lh>OHQj!PwqHd>qJ|pJm4T{_H!64?fZNx_{LK^vyJU*tKJP%hgSX^gTf{)Me&xMz;Q|-vrJW1U>ecjLL!noqz|v6O{{F#T z$Bnky(kA8G_`}OBeFM}>HJ2fg__w3~Gtl`^x z+s)C;Mfi0iq#duJRz?}*xrS{syPcl<=n%~*K;tl37b%pVCD=J2x5n5@TA3Gkt~|K> z3UEMt=gt!BC!f5zDFzgRjxTACN4)sw=H|3=oVF9ai2McitQ-uOT&d4`UicnEyf->V z#v;67p{zLQQnVgH;Bzb3fe9lT%8x^@AmJaQm~K7rd_gZb>QuXS1!Je__yHZ zIy(j8<{1$YQTv*sG|TPlw{Jh7amL4QLZAK#U5{&*RiuXg*Nc1lx9Z&Pwe1^EmL1jC zxD3j(NK8x&fU%{(gJGBT&xOzp;?n8}U=+9dzIUYO%Q2_EZG|T7Cq6qo`8s;~%o$Je zpsJ$x0}ccP>7lIe1{O{=DyG+aeUS;ZQw|u3KGBvUFNU`fb!1bl3C>+U(B82Q-Zxx9 zmkKv*+{i$!la&1OF^YYYjLgZ2$w?m&KY1^>G$wS7Oa5(j1@Etn*u#mZ!;0VM^E|4m zi}UV*O-&8P?^?*SWK-$u|SIsEHlWy#0P*Px30B}JaGuN1 z(P=N?bz{diSO?Vv)q#QfiHcnOtOO$1QZS}lAt3@H)06EHaW369^K&jVdr=G(PM*!bN$2IumqDeH5XpUUy#1iL z9B6~bMx-DkJTEyqKJ-UnPiEd{b%Qpa^ztBjw)s7QF|uy``k0Ts#3-V?QTSH8+H>;J z!TSQ|0O7W5-D)4AnWS_4{r#PX&A;sK&t4DRBEde)t&fk;c~!$&lICL4=~abxaIGfO^*J*RR9G4X@#w zq4qM|RTJoI%1Ov*#$sijuvwK>HV*D`1slYVj7@I2g)J1Z`R4YkTlFS z1sjBoD#CXR7k71a>9md!O>xJL9gF%bO9T0cKcUkI;-psEW<&HYR&H)#${XdglP5y9 z?qJ$CV)Tt=f@YCt(>cq*#v?)7lL~_?It=5BQckSBcjk14E zIDjlEf?8q_lJf1M!#X?v)IE0psI@XTna2|Rn zEf|~tiE=Ng2<24Ac>|QUW2eG5>!cq@H?5MJ>iP9cU@`L=z3)>20Rij8#gC|kOC85M z@q^gYs=LwQbsmmnxW$P+hk5u|3eaFP#;gIKY4#SqeY@gIU$;};FBe7C=Pnh~b0SZh z{LYEZ&5j$;?1f3uEuB};RI|#l@l$lJs#(_)m+3K`X-8mz-j-CZ_>(vAF#kw-2kdxnJsSH*L^jX5fB*hS zGitd!wDh=#8_)sJg>+=(iNB1+NBLU1S5 z&)y2F5PT;{T9wo~*O4KMp zw|R4ghSqAVN1MD54xH5GdUnDOhdxv}^nH~?P2&>~Sd0#HyK4wk)3iRtFm;TVjqN&+ zOe9`svJ50-065t+d~2X>b1P54bDX+rx5mas+R~Nu>HAp6?VHvZ{aY*Fy7iOPLwMik z&u<1ZRPUIBYsA3kzAZZqx{_z@tnvBti5z&HT;c_R240=ke4>HY_OWYG0|=Bx{1F@NmD3428t4q}?hEy@FR|i1W3$)o7Ik^1yRZFwTbl=(Cf}}IT)eImd?z4lLIqV` zPf_zb^{n@;k-l^Vz0|nKo3;95)80eOdp}4=+#9ZNNxJeN%B`iP<<^4-H;RfB!h79I zKdpZbD^th90~$4O->vX)CKT6o&HFrZG`HbJf1{qp7Z#WLbH>xl+*#_=&N91B{P0?k zS=X*D)}`<5=Xa-TZw&a6j?6aOx_wQRSzf6yjCVs-vYMT;M{!>#EX;tQhq|Mh+Kt+b zPsPp6yk=%*1ZhF;OD`LGF@4X$q-lq6W=Dr909ogQjoSg-zP)x3L%SZI6MZt46*+Ec zNV;!Tsx+t_V)40rQ`c(^APj1)!SwCvoJj&A0ZR!zavJOL zK|hZHL)c%jGd%Nb@~3C%$3#rc(w4o3uF?UijG*F`9a>ib&D0;15GIQc*t%+)Z*b@OJF7xThEvnv~1@UGJYGNQ7+0Bilo7S8YG{9Tr$|fNDhdiI0-- zYK_r`w9?KnO^x^8ME6*?Y108Ax51x_{}9wXp!eIOEr~+Q)~a>^iPM-ZKLCg6jVCgm%-#yvTORoj8rTF4IOo z3OpvuAafZ!{Z@I|EmUJVv2t27CZ&J7V;y`2CYTC0VQ!!Q@_bRV^Dq-(VK8kvcyur9 zcL}ZD)RWT*#iG7mYqgXe9oZFdpavl;t%o6$zsCsdSYBQIcI}pf*D~YxXl!Bst07os zUvoMZF72p3)eqtYP^K!w4#wPPi+AR2km(Dv@7k5$2-1H;4pr^ox-k!9)Wq5t+GUf=iL z1UVe2gsSDw^s=tCww})EQfQtoh0cUWH321qM3#^Si3F;h7;Cg7aj3+pN}kK`W{IsN zGCkhx#>&Y#u0H)~Q^jaaB6EjBp3?sPe5hz3My8)0F+msfa+{lc{L$hbPCMdH?XTzV zy|S#1T?%^zX2M9o;pXlWfuJ?)WVP|TJG7ceNE_|($s;T*3@PwUQTz-qw(XDSl4jE;$^7y>KVpyt7CE_=40uRn73e(?QYGjQ~W!t(@Dr-XWQ ze{u0w$#xItC=N@GkFRoR@Pol*2!oeY4^+Zb>lVfE_UOvjY7zbFQ%8h?JK#`-h@SLC z-+ZvkdI6rtW-FJSJ9o~2Pw2Q^vIkg3*y4CXri=Dpp~#%7zUDll-bSJcPnNmP3@SmB zX~6u0d5K$p~~bP~Y`JLi8XY zgpUq>e?yzYwjI2KOTuU&*(Y$EjRB>J^N8;dI*~|+$2Nly%1hT-sem;y^t`;hNxih- zaL8xr)~O7Hi^_a{@QWj>n>1( z?}f~J6f`v0f$BX0?o?$;NHzz;ixB`Nl#626!>j;Zh@o`2Fv3Pd2mgt80%*twarwme zR|pw-LQD5#;`T(Og>Um_Mg!-;MGy_6HN_$Ua}5W+zu}Uy+jOz-s}I`W14-M(fY?Q- zo%CNtadL1m_g7q{%fi+Tr{(44 z`R=@nHH?>$mQKMrHDb!RuZ!*fqqEcJ)_NtP;}j65ez1f$2L8?dhYp4?3aq+53&J^& zH{UgM4aopGfjfpkvBViyKXwdH33?7x+S`5Ocm&3iLv0>?Ze>A&gn`S>&)7cEw1xzw(ZNVJQ#0M z2t`-w&dp5AW>4%}sEMgiAUEs2P;>e<>iC-$K@2NKr?tio$B(AN0e7nNk*#z(I)3ep z_Y8S3SVt%vZxL2|nzpkW!f|>-=%>erjqzA0o8@C<`=jL%@E@ld`b+g(#l7te_%H>D z+G)^Qtl)})I&EsUMtCE|ZQhkc$*x|#O4(&jBmBeKYLoT(3?jW^&8Cb5q5y)p0|fpc zi7+Ui);PoDID*l-wq4}i>yuvTk>kdYFdp6DhtI5be+Lu1k9-t4eB~Rtd8!yvDW|C3 zUchzqg!o}*dfzG0xSObeMo5<;CU$#7|Cms)$JnyDj+mQ~2ypiH`jhPk3=AIPb@S%o zyFAaeF0bg>xmWp6q^?f&r%xUc5eB)+_kFxO^8EjD%%Oz(32Q#{#_!xx>^ZZLn4{4y zb;_47U%rqc)vD^1y}2RY$%F9lVm!+9T8Q+VpaKCnSt~AHyl8~Ig7^g|6bclKbxtE4 zeCTwW;m<=EeF%VfS6>2ZhT0`3Ctt{v^r#&rvlJ{~?OG|?p5e@#bPFh-z zVu4q&9Fdowp$4w3$Tbwaf3Jo%>`Rn|w6m2ejR>cD6J>?e#UL>QeL}QJ>IhU`xtmBG z2nZ{~b@wCs47B4PKYywlwGV*K4;FJ8ctbN;>LJGm{I(IXX=Gn+ey&yb$ zKhQ-6WQNgG`GB3){%mRSV38wQ5YUw$0ErLO9R}pQQn8K9bWfHz%}k_HYe5%dO#r@D z0JSZ+61Lqughh@{NlA&7iz`g*Au5J9iuFcNQXVq1q9Pj%dbZ0(H{)C|71*z{8yf}S%1q>wUU&A6^Yv>H zrtwHkO@$O64FezsUcqCHhhbrxP~ED}xlc1L3rnFbpz^V%-&q+!`JHxUDx zcONIEpsMO9kfE}02>PR{MadFg=e1B#hjY$CapyakhYjvCH#@Cr;&^i#B&r48(e5V0xd~k)M1g!ulCuwy^YgBqUc+X0ypyh1{=%N^X$I@)K+Z6W;TozG$P88XUUwk6wXe3@ZQ|3&nVB6Y|e^(-m zv&pKjbp9TKy2O^cJk}$)wfA~d=ehA_fkiog#f>6M8HrDZj0;%-Rg>w0-06_hhlcWI zKmQX&tm00Fq{f9*WmIA0mM-+YdMFG?Ps05@)nV1d1=jdBOu`sZ8lQKirF#KyL=AFp z01B;?dZ2C#Pn$p|$XOz3@9H6v5l8~GQwRi{QMRp6V(ZFjH|XF2D90a|Gw#9^=crM`uYmijqkKqHW51 z9XStkTRvGohkkQtc^h%0QG#acxH$B?W$Io#SW3H0rK^pfUju{+Zn+SCgxMiWlK71R zW?$@^cz)F`tF;unB%w( zoqCyxhi)lOnZZnt8qbLGOmGb!*R!*;^XW_8M$8(7kB|>iuzaxd{Nn26Egc;b>W$jE zx`ho5uiRrC9sk6MSUEm5iZegqt9%o<=XOIwLjm04wIz?L@iWU?)81VU@b=#ICzbL$ zp!L5J%xY4H5eWG1lvKj_pG1|)tQP(hSt$IkKEph;snN_R=-uh$985O=UwHi)=W;TK zLS>Aq=((&ViNqDrn?gJ01P(pG2Zw{q2Dg%ov84CF6elsn#Kc5$?D^z9P5HecwfRAs zgR40ZY`hT!Qi%RfU~S|CBC_=m#-wFrn0U%`dvOv7$%3cE#6wT*jXFYx08njp#;TNf ziJA&(01mewv2ft?b-@54h4>1UxM~(YHdc%(F#i4GyIf~>f$_jLV4?^dm7N)o*TPD@ zf6oY4vgpaN$FZZ}x@U>hf|ydgL7r@FvO#jjp1W$Ea5xDs6W_kw1JO&8HHSq~2&R4J z%o!K~^3KlL>HZNByl6kEPNN8xAEiZ0Lw=hP;fYk!s&(jyZ$M|DGJKLcv3D;8^_s+a z($9ZcPVgmQd)yG}Q#2w%yR5!bfMx_zjWX5%ViJ%{m^3~fJXJZmD2Lg&xHv|oBk;tK{;})&ycF5dk2>>+@fQCp$7qj$PBeCReY)8l zjXpq49G=bE&lOfFPQV8vL3D4{^+%A+AnBoG176jT&4NSHP*b2;4Z=q&`0#-VcnQKX zKbHJD^q!n({%99)RE& zp3D!>BP>021@%rXOq>SNW(UXy|1N;; zi^74(Zkqn+PRF6s(0U1a2W#4BLf_b^&IPvW{ScM{@3ziuo)& zPk1>Cjy+Pl8W+b8pTZBPCK83u^xLcLNETgt`EnOY_}l(^PeY-+t%T4Du3Z8<;ph`} zeta%scOg$EW*7eh9S2cc6_xk2djZhM5rmS4#WYBsBD0G^f`3ZW(Wqw&ObxHJDAJnh z-x!sblOw(|m5;4JMbGBE=kEZ1qE{EJdj552$M`mUQgD`!^03= znS^K{n85Gw$EJ$KSR$$%b?V$XA%0_;d-U(jRCW=A{uLgqOhQqozeFR;PMYIqb>u z60UXFO=gJ}FNWMsckte}tI(g&qr3r~~8vT#~-8mZFpNnrbdk&z-q7Z^b|N$Eo}=95lIeLWY*_2dil#up-F ziUC`aXxQF2Z;B1+k>M2hVUR{t%ZWS)_>EB0i&CWEy}ecbrx}gwnAkc{jsO&a(;x<9 z5RmX^D38mCph=0Nx)JCDIhbg;EEt!>=-s&w_EWFO0fksYOr*KFX-i@T37<&ZH0Dam z0F>~xsE8O-C?>W5=x5H0?TF=|*N~Sac{4K2mzkMaD_&kzRdoP%5RhUVq0x#c=pboG zXZisR8zFI_GyUw?<7LEvKwXR15ON;-a(42UjlGRc0a`f`CZ(MxSWqFs9rpn;qdZ(e z{UozPXDc2E4(XxCRv}?^W3}XRQpCW#2sebnv$2`wJvq0@w12?|#c8a@M<^#4I8`YJ z+aeke{+;YcQ|RFg11;`$oIEk?j zJUK{{L?@wJw(KoJa=tkcXa)43v>td2+lu-x_vbtwA4BJsArp>>^+W-1nl|Uk=%kzS z1@{B@BPbx2dkPPC4Dz zNWSYevK%aWqe+@3xYnXoY}4uq^@4qJ+745J=^;< z;nlrOzwdMSrq^HBJ?kpdTvC_O{iS=|b{h(lqqp6OYEq?v04N!@mL|XKYF4T)un(ekOvO!K$klVRrk?$B!(C zY6y;7gnHow8o~;#K8tC;ME#s81B-4{2Fw)P7;yxMCnpfQ1Q>l88RYfw;4sS@*n%Ar zUGP_qcl?@MR6fck0u75OIL4lcS-tJPk3c(6hNV!pLp3VZ+R*YJt*shWQSrw~+C3~R zsQks|&6_bT%IC6d>C!iWeDY)j8pSpSyPPxtltYb%Oxz3+I)(-6m@WQm%8U~TJt{8F z1E7&+la$jaa0!_rV`OB+3zD2NYLvW?n6!yCo-I-K2^<1mx{euD470@A;PV34p~XPI za}j-qVvFhJ#n34UWx(VzMtfI5=fm*tCITzKX~1RGbuppsj+%qOErve)p#lHI&!UDN zH`?3U(o&Fa+4BI7L+(vSKxMxy?x8^mrhI=+dW_~3v}PU25+z;idf@TSOoC5G{_-$;fKJ75Wt z9Y=Bhg2Mj&QSd|v`U5^@K!t)sx?W5yx%35r0T_QGvoOTir1CL|4y1 zp)`1Ub8ukQE4c&Rm|)I#85|Toi1IOS@uyfG_38V*OeeBf*K+3qR?~oAtLm5${{=3q z2?63@0J0%t66l-@DKcq6@*tSIh{6UuS7-k9r36M+XvpRze~BbGExN7Q(*_XTf`$g2 z7%rS53FEhnX7s0!r+ES>O6G7dzJSsYvb-F-Ii&0NtWMpt{m}0)=|uy1U2vbNi3$I~ ztOs}R`XDAko)d=Yf@^aw4Xz{evhdl~Nl38bE{f|ofE4@6AD1!j0I?Z^;*0mXZgGTe zsxC)DZz$&ZV6_XW`j^)0iJwnK*c(ZpAF>E=JOk{B;9g<2R2&s`ZY5QV?)qzNuvddPdPf=7D76HLw#gS=Rv+{nm?;0?i*3>1JW#9_E*=Y5ub zxrX0jJFm_AKHNLT~=yM)-H=MnbiC7F5{7zD8s2?I5U7{>`o5t!k_ z#4!vzBe+}to@OBNGI(D`jYr>J>Zz9imVFw8(J~t9l|z33#%90c0Ta`jq}>rq)LUh; z8g&f!SRCm7QeU4B;zZ{3$+Ll5PtdoJg^HO5fzz`pnF;u-JC=aNg4y0 z3Fz=oO6h>RPf|y;$;SBj>61LhI#9wM4@F?!xl0@E2TcmitO$QNh%5nB8gXbBE=ED; z7P5fp$p{Cc5TzNh886g1RTD7X5*WpXmX-#wAFi#x!|;~)l<=xl%2953zvf)#1RbP? zlr}|3+A6jfC-iYG$j5XDnHI$+AXyGFWTDtNjf4)7AV9I??ls)S^N3IU3rjdOAP~g5 zW=()TA{n}8kske6S64zZ6rg77L939aCT_S+k6rOSNI)fUW(o0w!xo~o6S)L*7+iIL z_sq02R9uWUKY)R7a?Js;D&P#VV1k{DY#@%bgd*urwB};;6cRDUtq{toWCEhEuMaI* z!z=-l8wU;_E`cEe{o&D;sWF6=lps!!(JZ7#VHfZc0Y@CO))~s`D3+k1hS2t2qUK%r z`tm9Sr9vPNq-?1xlD5CrN=vUMvK-dJ8rM;fo`ug-{O~3jumC+5vIkbHN;cR-4m4I0 zxychg?ewJ)k0uh5a|?ixuzWYcjA7%U-^YBmC)<(!uluf=%<^W27$6xfLZ;rRn`_mo zpU4wK$ShXkb#Xr|JGt=WE4w$y{TU?mLM#4`bOMCV>et$SF-b}OP?eY94uUJVE&{a0 z8>QG7>Irp))J)8X7UDS&@sZTn>gwgt$P3XB0sUz)bER=lUF#h_D<&H9QAvM)-NXb% zVW`0y?9TYzZGMCt6`=$SB2ym;ijTc^2eZFRfD1^8iNqT~VroI@;ZmVH(TnZ^#(}b8 zfNwE~-6QoAPVB`<*7dRWux%ZdkY& zmnVFO{(9Bl-+#p5N6TTHca2qdH}#n?1#4hF4t)`KzAQd=?33>@r6dfW8et6Qx7c=Q z84&gu?myGunqIu_=?!S>B;WyEa<73wUUXsA0gTp?U^YPQF`coYHdU0=7OVxr#mV^{ zWr|Tp*5ZC9h?&I#63yvBLF~A9gItM$2K+3LtH~Wtz!28P1SIZQvxhWm@i~Zk0FxX+ z9-UvkxqVX#3isj}XKAaZ<74}C+wR_JJ^7z2^!n3*5e<>{tZs+shQ(TKz6RQFuuNYMYa$spGl&6h1_vBVU|H4cz}|GU*0F?>{;^w5kk)xIq&U zbD<+QUqQz84XT4^1TaQ>WlN>jAOsB(UZ#$q)z>kTy8)Y2|6rl2%O>Cj7$ZFHkv>ai z)PO3_l|y3~42j{RaGA<=s+gYasFz(-A5yDf)Zg`OQen0;w*0g9g2lP8_rdzz7fMqW2#Wb$AHt-VEV zchg%5;hS7dW5bSk(SLbuCb^YC-8sUQrvC$l)x@;}_sVu(6$&jU$y9*M;PNs3y4NAC z!^6Xch-%YN$koWKOJcOjt`F{B`Yg|CRhG==5%kTN4YJ(B;VPNCo7Dyao<$2Fd{PoF&Y zaCWZo(1Nr7Vatxfy&TyNzTIarPD~~rbAm4gfkfaP#}1ueA(u~{lzFZD)vGk*X`?+P zB!&hBjU3|dz5Ac5CZqo%%EzmsKI%fcjyWo0VPOG(PF_i=ok>X}ciXqTp^(tfB?uX~ zEMsI0>Pvu{M>q!XHmK3lzzKaNT(W`5-)L(WTH5O>X%YAInIV}F;;kldxsWy3pJhQ- zR@SPzJx(K=@NO0&)dQ)OhQc)!V699tGC4ar&ct0rxDH%@$=GQBN5g z(_)qz(?O(t{GRzmu3OB4jG&>Wd#X%>X6*;7CS%lKEV!&ex1~P#(~6LEW-)_YGWJ7$ z7G8o}$OllWKKVcK_e~kSc*?LYwwo`8(1OU$ zgbkZrHsP_pOe`{($(RAhy)XN)3FB;Ij%*r0bBTepL4X^o9kMSz>nu>*=wLhs{}A}V)kl3C;|Q;jRe7AT@$+(sa;y?>nnQ(yn&Esh5uGXVq9p3lH&lI z;LNXpze5Il%5oxCr*h-gI4FnYz##WQQAAhHLy#Fbc^Tvq!k+icj_kwRgaolTRA6GP?vfHw37wn6ra3MN6JIP&0<_SH#W6?L#O>*{dBv2$ac3|w%bNKW;`eS6c~{a0QMI7yTywa$HO>4tB%{D*k-C~l7k#qd{8Cwq1cpU z7a@=)Vc8^|?KG+qcj(lqwP1OX$;mgt2x0(S&owR>s?30$g#FAfB3$2}ci}$yc>vbp z77g1vn-+aOJemim6UR$60vQ34!pHZLjR$qU2u#TD8z+C;cKwua%qHy<4J8YWDf=T? zH&wgcRHmDbSe5;(p3>$&*guRscs@>ur>7^Xv47bxvFFJpO%OA%xiCfQx32QaHFp;D zneDi3#*Y{TfQST?>t|oOitQ8Xq$e!=r|iTl0L$%FuO7{uYeq>ZV?T=z2pxk-Bx!#7 zojJhTMDzTd7c3Q0ja;Ti-awzDT|4hJ1vmG5%uU$>z{(VaNdK7txiZ6h-wUuEFnc`` z8Mq+;`S*wh-tHOzb4GA^B3@#){5v?0R?4ZX8V{jkU_-74X2;TA4GCF+!5A@rHH-_3 zkjY`BD2b^Do?6YEFGokJ0B%H?z{v+XxC+@V23r-#dl5w@k8*Q!aZMO2>WhWqbqUpz`sSNSDPC;PB}LWQ35l zAaH*D2t>2r1KcpDa9f#rb$lWogge?SASW-h1zG-MDA zhnX-x>{D_jC9WH*x)g!7VRQ0Ge_3)qFglVmId1J7ty{Gc^{Fu!0=ovg&uWa&p#3I-s^-4d9`l7q&BF|`|56hky4 zYAD$Z6CDTykPCXqbAcgPh3DVNta>6*>nd(dB=ZL3FOcj(M)JqHk|U05p6TcKqDubG zCxGI{4WW$1$!OA(u{=1RDW~2nz|YgvamDQ$2;N3PGs4X#EI9K^K(T&TvR49iFi3YI z%S}d2Nzx8Vfc&l2ErIjS{kUV{-|U#ooB`S0Dm$pAmSWMkgXCJ!CCHVAXrKJSytqk< znQ@H&@9n;o@N0873bi%mU0tCYqF-qVovjgW2L${uYai^=H2a_U- zOuz5RKD`%Ztk}V2;rQ4E4W`md8zUD(o4ab~r@NEAw-onvbZkQDL982LAqI-@P4!7gI12EIiomll<2;i$KR&O3 zM+QAIu*(_OCKX`MwzjoFDWId-i#zIqCU*s_mQ>eBIB^h&Or@Me%Pn-nN#2?Ii7pC; zeHfQyk@%=Kzib>TI~^$QI+s!s_JtC#!JVa`rsg>EPy6DsAyANfR@-xCT*e#?jn4=t zLEZ7tp@4Ypv_}Ku;|S+hp{bHUrGJC)0mnI98sJx?LGs0rtC!a?|DKA6{-OHyp%hLH zD|jrcq@?7za&i+C?&ykr-h*ns9EeHXtQ*B5s0$;!k z_`T2XINpEW|DKMk`x@>#`+oPi_h(pZeb&C5q8bwvv=bHb2QU-KhAMxwXJ$dFA3uIS zCPsiia=+m%Qrk5j65hzly7#Zg!kw3BzmwC8kbNNZKlf{Lc@*D$-Z9h;yL|`wvg+z# z7$9P#AWA`D|FgkkkFvJt<846<|RZz*RN-jj_b~iZ&hu!k#RZ;&BO^%h73)D9A1!QJ%g_KO@j{^{Rd5Rj<2yxw{iRe z#6Z5P+u>_KaU1(eu96~UNDo?=^S}0wU?TzF36yyK>Xk2|4Wm|jO^xES3oqrXVvcH| z>9`HW4O6Ph^LD}7Lo|Hz^P8l}Bi7-78RP~>M(zO+_yO^9C;zG)wCoal-Do##U_??4 zuX&u2kx_>_8YT`Q1Mt7mzKn547?g9I=wCQ1*S?LqOi5W%E37wrR6-JRUsYmNy7KzC zPCeA2*IIJUm?;d*qApTe5m)|F9D*;*Lun4o8YTaJouTa1v%5VloC`^E`NtO{W2QVr*wE^f2fb^+I1Tq+9EG^b+_w)CklNF{TIQPlTg}5x|m>v_nki zumM3$7c_qoLu*f9EY-=aajIE1RAL zHU^zMPz@d{7fdzy&`UpT)9go9=W7hW%#M83vBkw0By#Ks0sA>n8~`}^5|3>YzI+`7 z*G|-a#5MWONJ&Xas56^gU)>70w44HT21c3;wxcbPOKgI;Q1ubVSJi(wlYYe&Z{NRP ziLa`$wO``_radZN)56-n!GFhIx`C7H*T9x)33yB2z@Z~89oT3x_)%(QYTf4B;)B(D50xSrPDP=SX*Z~j&yniawMQiMsVLCw zcTg?vH?G=Zdc|Ug#})lE{zh)n{4kqi+AU1{i-vF=?-0a}X zByL_&OZnJ)2|JL8B3p|**b(T3(aO34jxf@HDWqjoX^#GAB`Xx@&tXS4I@GT3MWw?B2jsx5bXfcUq44znP6Fe=JPii z?k_NwIoUhe&f|KN=naSqlGnP;&q4a2YS@55;SZ1l`$ijU!l;?>0_ehhL&$r=J{Ppn zei)Veb5cq}gPGiNK&%77XpqSdY`(Axy#i-%Kt2~iJD22Sh_~UGs>`LU3QV`b*+9Ne zaie;I3j$1Er|dryBlS>RLt^^JDu{6}g23y88CC^*3{fm|b5kJ`?X`D1^LwH`owD0S za>=azbbcF{XM#D9i5(Iq@vXrqKOGgge8yi6U)Tx+B5B7^w5jv%X&nyNi1fx3JEN02 zLt!IO5hC`3jD`hRFt8iXr%$imaZ|!A4;6DdU(Ri>z1f?XH(h;BvSzzuLmo!%H<{gzZ1q&y3gXF&F-V51ZuC z3wNiTJEd9Tzkx`>yOHbmAt1*)*ayOanPSvK6?ujqvc2nQcKcxH?^YBiN=%j!tmXHT z0RXsb5DJfIJV6slV^9A89!N&knr@}0@*?7TfpIcKc_iZaX9prNvAzR^1jLdG^I%a~WfC}Ne|7gsy#efDBbe@=#d{G6;2R#Vcqhxj(*i3wbedwLr zfI*Z8+n^8zl|@XliRm#n_v1#EG|=~kXvw6^tScc$2D+-+WU^!F6>nZ`@~1CfzFcmn zkWCy!;7B$Ckq=~s@4zO-Xvi!$!0{k<2w11_c#I1unkF)Yj&O2u{p=|Asn5dP4ytHV zTLs|)e}dHh_;E2x(qlVXKxxnbpRk6mW7UTNwDNr(5!~VeI0oGeAOBo$tOvoKJzgG7 z&Wh4AayynixPbl(p^Vh`L@3Cc&sgr(*A8@0P{<4r z4^1E}NN`u??!0d}dYX-u71USSC!v(2USDOr4-zl?*{Uc9(ZDm{?C}I$=9dk2DR^;} zcnF{&C$|>7_>Qt(++|WB(JeUMOFtDy$Pl1umw>ZmniKpm-KKpy~;o18`7TpRN0O@p0bphJi^&o|*iyS5r<>fTf7g-FVYEw-`MOsYyPc>&>Q{DYvNKaq%BoHq&Q;8@sWGV{hev6SwHBjR3@Xq|P zjSbLsQCvp>(19I5tR)etJwdv^2g8KS-~(uebgTd&NRKazQV$5>ADrZS9$r<@6Oq{k zbX51&qCq1#4iUsbWQHBQ0s(8eUx%q;=mh-Aym5Sg;zQ=SObI}UOMz2NE}TG>1}%#W zPLS1TmmHd?ADF`+(xW8ydVmqWq>n~?BEJjL8gR)&2iRJICf`BbgLNl8z;cg?<`$R& z;je*TL2V}KAps);U$mlRy8+3m@0*5p=N*(~WGowi!aWr9crrpO2m;~~NX*%x7AN*6 zM$NT10W}iSBCzG;s}uVHGKhJP6}`h6s5x#ypGc+(Nso#m?2%&h6RT~YdvK!+F>VZm z00z;VLCfL)O4C32B+EgdASeomJ3SVbcqap&!5I8{SP@>$9K=xKPa@CsZ($4Uf-3=j+cCt)FN(QZ54ajP2F3;+#e6?9jPM3KtQ~R1K5*uxRv>H}5lYC= z1aVqIfFtSyVg)kb9{!=NZ9CZ=($Y68Y`aP_v$H)xkfCykfyE*aVuL|uwmyqr$-g^X`M)Z4smz_X@z z4S<_KU_%Da;K4%a;jy%H2*?(BU1Zn?rf_@|19JIT|O|j$XphasQ2d5M2OCHXKf1s2H zTnoPj+j@^JK4l=vc&s;Ay&W*u0N~8&&J2Q)n1ql~9&+vpVSz-ffBEulY_=;6=E>vD z7V&PC6=RgIEadI&bI?!(>&h#hII(;692^(s9Xyr*6cP;|p^jlD02!YQvYt1F z*H8oy3djIZJ4=Z$PyjgdbN1B63WBQg0vAGh*$Sa0;IQwTnlwQ&+yMx77e&^JV*s9I z2=0O~BSjQh;B41{_4)*y!3vICreunWY)E1)OjLuYHcNmk!M`;@)dYxn0#=(~H_-hn z6P*Aws7bAp@Vq%q&>1)f>5xATvP)m!!l|wZ2;?J>rX1DuI)D~f1CPrMi%4eP+5*g= z_!A(x;@i(i21B4D5gZ>M_d-t(OcW#WaIvBPxs*=T-CK_kbsP#Tf=^)J*{Bj;*J~(@$emJrpshdy-@s(wQv~#MRo&@t z3~kIDUXU1s65C{nveHstGDn4o0$0MavT&A00FV5{!a;#6*x#b#e5iW5HZPF@I(p#t zixtN(DXhAd;{?15DomD51vUd+A}<%4VtL09VyGK?m?)LrmzJJHo#%`9e+P*rY>S?0 z?-?CdN;7OI3Lfk9ZtHvzyMd631Ks%o*RW5?SO(eIM9&4hpZE;Ob;IY_0LF95e&}o% zvDCq%G-$Ur5#S44<+8UYFl6#eWPU$JYP~~V8*z_7!Gw_|ewb*eK7L^mNY5#$LEXOD zV__oP5(b^bpMZ<>NkXFpmCoKtV$49ocD$jJRdlP7~7I2`dxYhn07Ofqn;PC(D}0q@SYVUPJj z7Ek|c3t&M;(hNf9+&M#IVrXGXfFd^ajbHu&rlQRE(nICrxtS75qYmw(RdS2D!~b=~NiQe}TBO3%zI`b{ z@{q7W+_@fGw7h$ieDY5z=XNPXiDV`e^Bg7wFn%?$*+=2}JfYahkc@Q^u@{Qr&_i1z zaV;H+7NQr#;O9AB6~(fuOTU&<(K?|ktnu|LC(*{jhc`Zk;fwBpP!RaYZGU7o+PZJI-9dG%lE! zXF1PMgLOAAk|Gpr84Ulox>ZDvFoGulVm+3uor!*yoo`aDl}=eEqXOE_D(8#SS&+ zzR3+IRJRt~RbkTbLTSpZWeim`5EPG>-*b-`jYKw6oq-t@IVollkjvmkulDmT=+}UJ zy=p#y7X(VEATy`Gx&j9LC@6gSGgA7WI8~o>N>Na0-du3D?Q2L0>wnGasGb}yc9Gp< z%}xfbk-OAnThJ*fTrYTx;)}1l;Nw+T4osUc{6}B5{0|mu|JxYQ|9}6*LJsrTP)tC& z#3#x?lql%X>P`O60KNIL1x_?nm`ng_ocdujo!52m|4Wg%4NWstf%Y;!BZ~6!^3r&@ z?H61Cdx9T*2bZTmeV=xL9$0*tyY)ZXtb5-n`dBAx^u{FXir*g`9vx3 z56eFiMq$8Y2}A=8fx0cv@b0Tu2XmWAAqefQH(bJyNqW+9bXYi6kB*MUB?d2znSw<} zmCYx@hbK5|SpAoLyWqb~2IOqC099MRD~d42$QA2lF4nhp|e<=Vsx^^q=|_AN#6lhpP)y0 z9Qod0=F1Rr;u8}+EedDWU^^D0jEjHz^e+BJu985LcM5$LkyS%}KpI}m#+|?ojHq6` z@p%lPkHCO$87kz1ZLy%GIYdQSfKZ+yKnM6Y6znS~z(0^-8z}qX*F=wEoXk3q3ZxB4 z1c7sigdD+@EFm-(3DCr_l`d?$;+V==Rbx&K(C#TLRq}^XG}&a%3_E;fc`VZ$@Cy-_$-TCA zcKeMgLUzijbRQ(zc2EMu9Uq(T1AZm(dLS4iNKrEBMDZ5MhaxaI*prOlLQCL?3tu2R zAbW8hO&m+C5YF-wuMc8esK_Yj37p9$p9z%_jMrk}k&)h~gs8qrf9cqX6W*B?I}$2* z&_sY~zYD6_RP)3MFA6ZscQHY#@(aBVvCLY_@d2`N8N55t$Vytw*NNYHMHcF_I{=bU z)nlUmE|FGL%p&zNK&nJ!=4hQzhkYw>$*njcVT@A0kIMO>$!qZh!M ztvE*Rl~bO(1+TH0}P=D^RBVjc0Ulwq7Z4)Tz>6saQ z)ayhefP4E$X@<)3Lt%nTP8Wd*nloZH&1l~)~v z^67tI@Rmn{aQTvgk*$doCXk_qS^*pBKj?8d@CM zG=D;?t)AKreh|YHp{e(>KCnSc1hR$Dyq#vHFkwWGeYqtk?Zq>w1;{OoVAE9xUghPb zxH3uqfbrftOaraxidA7_V+(c0a>zU~#St%scL!t<#3cgdDwGr3@X3%G_zrzVb&i$g zfR`vZsruW!z$k?;*B$G0!}XL272Rpvm%=X{glqFCu0v6RmZPDN zy#W9@fd51INuByLW z2*8IP)HGcr=8#Gp;wFPsGF|tgXUPTPCl8HR*d;T#e;(WZkSUAw@fgTV& z8^uKgC!&c%4|iqo37x?0f3*N4SK=3jNI>lJR7W?0r}N3P5#*$ji~lXkpo)-Q3tEhK zWKuu`I5y;GX`8a4H-!}nbYN@Z&~TBlNkUMcOD4B>0r5+oC6jCb(lNCPLA(mNt`S=X zQgze&lVofc?K^fiv}sAQ`O@*%|G7>JTr2N=$NqZGRPFC0YFzUny@anNkR@Cj>T=Aq zs-T-BX2H0K*BzdIJH&^vG{Z-)K=d5||>ttmMviA*m6l0FK;V8!xn@x;dg`HHx@Vr!GJU%+#!CQwzO z<$g;Bj!`5Kg~s~USX?9M?o&4 z#w<=N?oIXowuShb@8Fe1)S zh-UQAW@7iITx$on2pXRlc#+Gjfn$;Rqa|FB^-1l^y1B`W;MLNbUWF)aT1zjw_U3i! zn~XBNe76m^X6Bkq^B&rpNPFH==>+S!UaJ#jx=JS~f5ppgq*rwoOt6(rN$p)IZWKT1 z8yEE}P&@Wz7L!T%aN(4k^(4nslM9fAhu9V&l>)E*z}5(Xr8++AbYImPJv&F=TIEb^ zt>e&70IxDcqNMCum_7O~R;_RN3Aq3QE{CR|7H}Mp0Y>YN(+y1pdr>%iw_}DVx!fb_ z{(UKkMe)zyh97UfdlL~M#_{Jm^ZafmjOBa!?~>!&DJ~%!BD!0vFwpr|J3O#E@I7%{{kxIcQA9zmhYbvwY`6yplSGw8G+ zDms904Oe$`1?1+T^n%F?;9#TxPl`-5sF>Eptw3Zqfn)*xnxm*!#_-8;!8l18XxpLuC1QiW5NqFW$}GiwZqEObx4XrSgdv$<;y zgMaVLX)*82@L1Rb-5ikSkjF93zDR;G?z5)pg|k;sF38|fd7b`Zn108-LmVCpU{T>) zq_^V~$WJ*1g{q}hT^Tluqhm_Af&*?#{h01T9e)X?!00(bglffu5wHJ@e?B|x(C$7M zeiO{WlbK3(`QH$6Th$(&vc$a<5Fj$)1!7z6z?UN5_U$UVKd=ctfXQcp*S`*c7cD_F zMibZB6KP?Lm;r~MFmlm)`{U{GY(KE6F&>iNuw2<7CZP8{-IQfCW>Yj;u}9mc`XEH{ zk;r1?1^fm}FyA{G9($*3yNe%~nmSk`paUS+aE_J%H4$snabP?A-FCB9&b1Cuik&F) zd%c-;f52_DoBSQCVThA8Q(F=*{y4}Nfu5b#zR6b3#{|FoS8IOo)rEi1_{0`zjj@^3KmP71P zIXy-x``FcX%gy}P?z@aX1OpC1At51&j{@NzNCnoa%U|rbNS7TfezBO_G5PO%F{?N{ zJiH9!n&cf7wGMsidU!RRTw(7b6>0jBkqqVc4Njunv%BWIPM8CPT?`o1` zn%$a(>np{82X!Uf6<8Suh#6hQ!&BRxx&o;+<$`wOul`23^*FwLn!%g3-R0N*8j;TR zQ0x-ZQNe<7<;8BN0DJU{J?XE1Q;Xi(EyuTpdclwZdX~1{&)aY?+Pp3-KSs`@oXw#X zr%$hOk?l#wZgOfD z7e*(*r>=>bpVD#c@P-*6Z{L=n-Kkr6#)U57PpmmkcN8+t1E|dnAss<=@3$x8P1f^7 z+2v1=>c!Xf+Ht56wt;y=IW5!*m6er-C?a6kCK;#d)0>vtCi>$IDtYL#3fi5J5CT-O z07*L^*U>bQ^HQ|5Fiegh)b{uBfvmsVHCloAVzg)YyHdRS089}$g7Q&!clWuRYfWyC z*zbYn+ibgzfJ;{jYxydM~a1&;N)2xbwsR zmw)410V|S9)JMAtqk&9flf*0CM!CrL6@x5atMwd+nn#{TE=VA1TRuwOfP|xbbdU82HYEd$wU46} z1J`bSV+L*MCFE=m$4Go=nfu<){(ci*Zzx@fw;{Y{olcZh*VITPbjnmfrWG(;urq3V{`f!NYkYDE;Meg_7s(J#s+|`1NP%?oW0TNE5@vu%g7wCD2*2^76z~;TPO8uA{Vg4sjbYMc91h z=yqRbJ=go-j?gk5LEdr1l=svT8#^3XVx>;1m+L@r>rvE`=g7%*po{x%(h6BB4kiuG z51#$AbeqK`w9jvA!`TXd`tHFLd2Q`1;vvPKiai;m9<2!7a|-zbf7X69#q-}6w!kJu zL&uI$L(lCXS~Pu#@iFK)QYBQ&T0gc!F39#p)<2u5{@u`;!gW8cPIZ*v!mzy z^TqLExn3(V=LfRo4!P>`I%0|??rs+X$q3R}5p(MRCBOl)QI@{Ktt0(S+1#X_)6jL| z1Vcxrt;Ywx+y&XPy!#Q=8P4~DNq-DfB+6rPhKR}E;C(7Y9DpD&c4@^A0=f|xy6u4VX^kKiG?ADte>8#&!s41wONnUHB%YoJdjHH)#-PBZ;EQ_CP+BCuz{;%-SLTSx5bKN z=816~mBVOA1=`6KWR4QNoDqs($}ksP5jG~M@dkA|MjdN`U76w-P%O>VdO!j!cf-#8 z<2uMT-sAh{cih@W`WMU?Jc1o7ni99H#aX9R+zN`mhs;!xJcg|N+d=Y>MVkVcJ;Xi1 zeZ*4+tmk523=JYzV(7mInl^pEWO$;~wJCaj?Yuxz9Km&ZA+FL4A#v{a>j1DdH&H&K zPpO1nkfybaAr69I%I$)>ZyuoSFMLbJ${8I|FJA-nrv78}ZHMIp#0YSq`DZztQ|9d2 zoO&4_*uP)L&A@Z1xMLp~y|;KXa&l1=DqYISc!cLU?Vf4a19ai8a$}79Lc|Z?s~Cs? za8u@W>()_K38RSL?)YN`rpPKm!hWo*Ty+si0d>!K+}v18rLa$N$MHhj?A>zppDO;1 ztW?ak`q8N@UJ#I4mu@wI?YKi-H_~busx8t{VCVocnXt`@A~ztzSXsG{6WFR}wT0G) zM!cr7vh&qoI=KaR?%LraM`kSTd#|^AizV3%`wjW?{KaTb#%L5Tk3frQgDG9VUHk!# zw-8*b(q9em0g0o_YlEOuWUNZ)2!7&lXpnJNOgNB%uQ_p_B6T$SkR41N*=CR8cP{E6 zLZWKx`EvQ?E!&?mh5E$?SA+LTB3KDipr)q`i-ZyiMOqU6R0>Ew!hpyw{hmf>G6sWB z`3Q^h^lc|j5HZ*LjKsLgUj+(sw*zbnNQ@B@Zq7GMi`)qQX;X8g7Xqmb#{hkzdC~{v zHDfY@p78;YHRkddyaBvlMF@x}ED9#R4jb!$1_Ul*jNu)GsP2FX7x{1jXur*-Q6bVq zjm*J7rbq9JCh~WlFSY3PzX@a9gd|rWqD*;I*D$SvI*>GesQqsM)uCV!zWf%iz6wne zfkeW!tv?ROsL@y=6BA?N-{=4^7xiAtqM!t~TdtjNk4SN7bK=H#>3kGvZh+npE)*en z!=t%H3;Z5Y$cqOsHHtmrAS+{uCJ$E?u3Vb$mDI!?wM(;&MU(j+0KE-qLLTBI|9qBR z^OF=;h+dc}h=h>x)mwK6qhryB#yAh~VqEGS`FN4|dS`D8-Y@<#7XtM4!l9Xhg(En9pqyvAnpr z%~~$#e=4&{MYGv9>Ucc}1sqvYuAWP2aqElsS?=>-EU|H$kf2}y1pdL0k9hEQv^yi% z=Of)UVLTI{VJBXEORsf>6fS@33{g?k2ZyAJA?dot@T8x8O8#^~wC(TO=C*%StZ%>Y zxAbHCLjEYd#nJHF7AD}mq2du*+EfI6MmL5m1E%fi9wB13+BNFjFct{}T*N*(l?=U&HM|+7~Z~ zuyQd_TOm)|;3vE70*&CCKWEJ(H$lTwi+!+yM=R%-ewrBIU<9QVzQ4YV;7_3q|2G5J zt|c8ae%{%IYb9$XfxWnlviEj(lY4JSwT3ow^0gwGEX>ZfZ>+Z3jUfsk8lI9b(x-w^ z;g*MLKv=i>Hh(gE$6=D2?M^~aUrIyk!=$+7s{u>lV@kr|HC}F6gPT(N; zKGSO(TO8dkqAY&=pBi}vaWNG)R-;NQ7-4X0R#1}bcJ`!Q zdsu0+p>2X5L>6r=ytMrLCjV0mA49Qq%$@h?`^~gIa%az)U=K5O{QZsPDd#f{7G2t9 z|1GeTSD?5C8AmM2u~44=Dhc4J_G8&dcaK=dX3Hw4ys=|MN^}%!!Z;#i=%N4bNnXGO z^8zmh9Ijijzl;_4I*0>sG=L^Z>csuOkrn@&bo&nPuMOrcIroAU zMem>y^Tv>h3W6FemlY8rX~ca0^J{m@sKzsAktB|y0_+%{#|3nYG-7~#{(T!V+V~ad zACpnEqA~FS6|9UoXmgbC>G?em7X)D6CkIk(u@jQ)1w}!5_m66-V{$<^5h#PkwYG2D zEmzc?DHZfW64Cm-!)}ju=?+T~*AFMfR)Y;+aS<3Pc`T`{aZg`FZ;Xq7(c(nL+}`zcPNf%wRLcw?$O3fRlq)`VVFsCDN=#YJppa9iF-4NCdTRG*t zYdbx6_veZq`U^PkHuXSR;@vB|m@dPXd7t)^9CtLij(|o%3)Lvv58huq|MjI9&Ux#W zx1n5w$7(c&DIcJ=8)?3pF@gdvGSd82>c6lTc{R!>7@av>08)$r+Z=%)fQ*~qhV3eV zMfqJpr>Xysm)w4w=?99$Zv5O}@OjhgL+__f(-tbI_Wc+;PBq7Kd@b!O=Z1H^KD0UR zs*7B-c|)GnbZpla^oBk!_ORRPxYxKHi(go@iOpQ9n{Rg&bQfF7ZGT!E;Zf(-Tzk>y z;H10zEn1VsMG3{R%K23bt|za!n}6MI?eL7d&|v4f(4Uh)OlTzs`R5S-y$PV z8=DJgIynVK&UxrLInmRyH{IKAvwrt()~5ZOj8E>VTpU!2V-2}NW279{uzzkz>&Jcf zbu&U)*%y0r9=R?shVZf3vZUfVn8EUUjItbiC{5df>pD8(RAfu!SOZrcGwx^m#glvA z&ss}X@O8AA+UJkyn-f~sshQSiuM2&mL38K{`9S?CS*DEwJqv$U-OaHuIcF|VSrMY| z<|;n8NBt6z_^#42DzBFW^v(?u`I8!>FVaU9J4%~nuDeK2#k!65jl0P3j+PDV;~m3Zi_sHPx!?6nT5G=* z#W08-`)%1rVYqa~&okPKMM5dZvrE*k$;13tv1{Soif?n#OM@2g-D86PNG$R27!Nba zTSQ1HIv!4TkWsNeCEjfxk~q-wQ20Spn6;kzEoP3nM@OGMIRdZbuUU`nwz6nz#)fpV zY@YqDa(_9Za7u}=8n;!1DrgtQ^q)JY@KiIH@#Dw3l#TnFnuO24^ldm3DdIk7|77XU zsym-Pslwdgz_GnbENf+Cq-=#x$Skxs-dBB0tD5e5sVqd5=TQ5~UdeST+uo<&QF^lT zSJb*AlE>O6J)fOFv1l6#dmtFP5q|B{Cv`Dp{ci9VYuy*F_04CwSy{S(F`1WDBdR(hgg{wQNS?7TSF2qAEqS&j^D496-V5(vc%M!k*AeDE`=tD%DYMe-XOTng z*|)dym(ja9ZEYTxi1zY&a-%1l>@b;=On*iyLf;e`(HNph*SO0htotfN0)64+D?8h3 ztq=0T_&xo3Q@4~?-{dumubc|Br?y>OFMVqIgOi*n1Mtx#X%zvE8!=`VK4(|gY8;En zwdeN?uQeG`ty?|5?u+I%b!+XM!zRo z;rzV3!j)BB>AWg=DeC+Khb?|LWd!-B6tw6o+Vthoa_Owp(OoBcKPjjR_zA;p`nsLG zcbMelyk5V3_IohTu4$(=6V=DD!hf{@TvpvQ2Sw(pH#g06I2Vd9dhoiq9BhuV!@Uxp zq{^0YaJE}-EFaMI*7o*WJ~(^fMVzwr0ga?&E18*5;o*jLEQe`D6Os&g+%`NDVY*=E zqq(Z1>(ouf-Kk00Ks+f0R~ombrV`sdOtnH6_~_<#qdQ=!FZ|)kD0S zZQ_*|;x@}EOT{Q-b6v4jQ0%E>N{zDoWM32YB0@u;Nh(}0BXQv4%dHOmHos)s8Ej9G z_rkaT>rks)`w<(FWOaV&{(je)Pp4cPGI#NxmHd7{T{%9&dc%uC_8v8#***M*oQ!A4 zo==otE5dy+^p4p;)}X~UQ!yL5_Lo%&El(RWUpC3t$80|%62)w*u>AC#tQ%#_d*k*8 zsy}5~TKKW*(P49iaGRPNTLjCwQ!Ty5b_`wXn-*8Ny4Flx$~81jMXr8P6A+uf{Qh|Q z1+83T>BP$?H+-+q?94sKm%Ao<*1<$MJpBA?Tiv>i%d7Kk#<`NoUn~2T7|X$g_TJcR z$6;N8!M126SJ%2vyF+(49od(|S0*;+_Qo_1 zitOSKzkm2ycM@;7Qjgb`((ea@o;{0}Iu(K#k(AihX8GVoyIa{h#y!f$l}yI&^ZUFZXpG>YG1VcV~Bh9f2Qx?@fO@e+w{1(dMt#i+TGTj=qRdZ=Z~>*HqiOG;L{Z zgYFot({8y__gXCm)I-x6-OQ-7Xe;bbhl*Z%I+EhUd_ds%6@ z*KfdSV-v-~C})0_I2amX7u?ilcC@Ve4yV|o1CKYn30ucZYt-^pO{y%IEXqy`9cR(U z)v>j4_CtA7pU+09XKb%NE55()e2{#KTI~C_LrT1x553utwx~xw_n+m@ojmDC&Up*UBa@f@Hraw3N&@x|rD#LBAA=&e({k)s1GE=5$a*hwy zVC2b^OWt1Tftx9h1jp$QW3$(HkZ{C!wP2t@|D?CF_|ePU;RSh~4MryCrskRa3WoKw zvZq$FoyBv5eEkrBw2J2Ze@_hByno|VRbBJQ=CPtwS&-_@YWLMaf<7BYlsd#x+?2^D z4#*@Ac6nJ5*8SPITJ}nzm+{!xdJ)a5}S&8Q_Vl3;0 z_7$vnae;E(m*waBFF*H);K5MdKc826qFpmv zB-QxLCg8>P&Z6A0RwwK3?+(4_bR_UA(2m-*V*h$U!;C|GH z_ifumTv!_}wA=}6j46H)?*Jng#=kq+H&6WHkHhVjFeud)H)9DN_>yRUdB`oz5fa@-@em_jgoAU=jG3sYlGO@bR;x_k0_!3}Vx{pZ)uF@RY@yaNLhY z`S-Q$G(Ia*B?B&}Rz1zpwQ9@a=X@a}3@rL{rmk+u-(L8XrYz%T|3ds&AK4H033|(y znQ)_Q;7jLZ{ZrGNIO?%T^T&-#67RdlVvQ<$y8l^)UFIr^w2#xyzw?Oh%IFInvL|HOd z)+!oKRAk)r=UP5-RX=rJ_dPe=Tv-{$IdoT0WO#mzgMnH!ENRoVGc3QZY*3qgACMt6 zsO5>BaG&5)n=GC0u_(}XTQxqno?l?UdRgo>`_}J``=Hg0RY z_ri(SXc9z&k~W!t8dU0e5xZ0{WpjBx{Nk9b@@^72$Cs|EXYN#~4DTI!nvmaFFd8rHWGi=Yhw#e$zs<~+fsjeh}V0@ceLc;XUBN0`Gxt0~o z=Tuwky^I@UE4T&4Q3e0A`PqWbp$wA><{FQZh|c7{5U7;6yh|-N*ZORZy_umB*UiTh zxy5#;93Ly;sfSK!{wNl;OHms;)m-h%&6Q0(v?i){x+6fdf-p9GqcIoWJlGQ{-0>tp zvS-462(C$o$VYr`xjo75dd;xZ1uYS)bs>{Ra?0xr@M7v$gsjoc&}bYR>5+4IdA+{}WHJQ7c?-*WU}uj0|rzP!9Rh??GIITULkey>TIxGo^X z!N=97`i}@e^!An?-D@`VMHK`w(Oi9=KTlh;-FchgqCK6<)FZ0DJD%Fn;L}cX^M>0k z?M^;rHAj4uA`VEMLX;Y6UTZTb{hIL)f=c&tuHQ#a=PcX)wj7C zb5f;x3v>q#eEsJXQEbV%ym1xF;hvh@_MT6_zay1XUa2%VuSv&ZadVjcMsN%*_Bkb~ zO_Gk&ZxC;P&JjMJ7ZOIJ5)u2#FD7GyQN7VFT=$@fIt@E0)G|O&yFBgQHk-y4i!s@N z?Oq0ubL~!DJ*Q8dlc?=-0P72toMZbyuSHA&)Zikc>XOv^gx#5m)A@U$fVfz zFTb1~TAu;8i&}d>)ZP$%Oc@P)Va@V0RfPX2%Ts@ET>8LkIuzkJ+iUy4if!9#euIgu zh`&KYRr*c70cGPM^Qtr8v@8R*hh+w>JUC>3*_vi=#_E@0$G-HCQ9O=wZ(@U_ zi_Kc{`q=MHPkwDuZTfceNx>eWx#C*S<+PmoAmXJV)lmb(BTlonx)u$$AMmN�&ST zsJ{8JI=*tZ>>xF_$EtJtr5@w^e_a0lsoFdr@|s`r(r7!Y*{O@ax>+xFHPBja<)zUYnj>@Cw(p#a!b*wx`Du}i`To%yM z^(&t~xoYPh*c!UW=F3O@oCOCeO(!Ff$Uw6@l9Fdc!+zpa zaNRRavZ_kkdfxk9x;(SX)ke_PnFE_ib(};@Td#(@_l#Us8Sbj6xit6Zav zUUa8rZyOQru>7aiWb?M~?y~$n@a5NSe`8$Yqk81`@@bD(_w)RfqvS;Q%zbO~26B$r z*p@f_%?lb&K0GjMkri8XG_QVeCe-3d<{RZTIkeDCeGB5 z@-8p=bZTS#@#T*@7UM(R`@U_<+OytV;cKu@{kM}q$EN?7i*ux%agXDKpOE9V8WCmY z#-7*BTKy6O_AF;S|5LcyGOS&7xGK7`3@5<(>t6ps$hXMaM$jEAxO!1XQ^Z)J;Tk*k zmgp-Ilo?jIAvkte6d6IK`(|cl%LV@Qk{6G*<@a?`MSPu8oBSn5Cz^o6pS1J$yO}Yk zLc6OmOMSa)#JfX)(ecG|>8(p!TG7reJ;0ZuDv8Cl9VaCeuk@PjE_*eg3{dNhD%Q|* zS7?bS`=jn@Au<-cSS7k})c*IkO@BKPnFg_^8a8^_#_OF2`2~iXg!)8+tH(NAWUf)3aKUJA!^;R?1HCJ20y0cBP{?yY=XZ5m(o*61jP&B>P z@`9u9!E)*MAdQjF(hld$e_L6>_t(dH7)ZWTFlSP@La8I+{X(G5RN_O(I`Zs-`kz)5+d-{p*-HD_WKg~0*Z0cEczUBN4QomEH*T>$ zuT6C!&69NI8l;>k@k9YA=N+dzGx{bvrsh|US-#!mwesrZg&$Y;x*muekbL<_Iz!}9 z02|vsPyV<{Kr8d6Q5kD7N_VN3J=G+Hd(G%mUo)eA>F_qIH*R4UiDy5TCatpD1jnx*ZmTt{f5 z?yf}TWU@*0nF^_sMUN|NzvSn`)JV3pFEa_f)aQoSJ-SLYv!@}PP*@y2O`$BvQ<5IA zCoojgn>KgCpvrR!l_r~|GCAMg-4oT3PQphb;%kqVX@={vfcfLBs*(z{<-O+bIh`L^ ze~_H*d9tfj%eR}gMfsl&vy>X^d8V01f4!O8hv#6y0WE1OTeoTBlkN7HTG_gSo8Sfv zrtQDms@2x5)1LkPdVSybZLlyWNiCw4?m{~q%@e8bj7l#x(H*2ZlDa50FqGQcQH;}j z`q#CZ%8&X}U(+a5O=;D7G>na!=nG=pA52-~1^fBgt$4irbY3kRnV;8*YZ8+^6|Pd}n>~xY?(h6YUyP?w8(}LpSQA-XVHCVdfe)LdzxKj&_oE8~jgM=S3OQ81)%Z$Ty%fGtqlj zqdTa%Z>sa+O|l@fD)wDnmhQ$}b{^9=m>(Y8#jtrZ2`X=Mmu^-Zy?A!L*JJ5K8gei> z1IWRYIcA{EYSGg@qSlhrI@V+o7_D>By^Q(i11A%KdrXr_CRUS8MF@$#xxS0yG*FiF6Ayb+r<1k=%RA(P3xWQm?AS))DOvs^u*rd%)Tz z-*Q;@p@8Q5%|p#nAs+t03`bmYi~U~JS)saGrSs@`Nbb|Hq_;D)O8DH5qtoz)LYzqzuawLZlwl9nI8L;uG>$=#;&>8uvRt#T0q zUq~q2(vri<)Of?N@!hl6absFomE8+OC!Dmi?^}KH*07kG&*3_yE{P|H93nm(;;5)i zEp7JNtLQRqE%C}|wUbl6_i`w#zu~8yjbeWDokKMXzpoD4oXk{HI6! zLh-wf<0v)Vy|z3qhsi=13K(yit9fBfmtV6Un5+rg?d3ITl^YpZ-~9ZBPe$I&T0Qrf>yfe!YV#|=1 zt_E+tOdfvVsIU#!XO=@qa(`-u4O_l56O?*?=kM4hKd-omahq*0Try4xjFHG}VRDRu>I+$G&B%g3D{6X?V>?y=GMg=gDfob{DH9Gnqr zQvUeKQ|PAa#YWo={K;nA6BqYG%T0IUR^1gNLnh(oYE6$O;*(PfeDN7j-UryMCFu^C_SK3aXD6cqMVgtAza#38IM=CvLugRfAxM;l|_z4 zZ;5`f`uqC17M&{bDJMuEHE$-9b)Ok&ExqU3@MuHrnHYs3 z+(v*8Pep4~-1?}_fHuRhr$v7jYPIo4(;>6lAIfYNYNAir*c2`FmcEPYPrVcqe7Zg2aF*fp zfv;%~)vYth$KI;GRy*Hrk7-kr_}3?l(ulR+;2u>%42 zNMOu^a-sbEH#W2VZzf9}meia59G)ClIOWs-rcc@5|68RmWo+oN<Dh|H^J=W>3bxAETAWvC5ss-`AwMuh&!aY2Fim zu6_BzUCR$1g~`C~lRM`{1OxhDu`)B}5|DP{tHoy7_GZsl;lh`CUR#9y^Le{gNtV|< z`ZDmvZ?L}P6ys@80hJohHoD@QrFG_;lMd053sq|?wH?J)!+4;WEq~MP#kc1`_|#& z6~Vr2T0S*89UPPm%a0c7{hD5FwC#{(XLoq^L}Gw{|CY4cyS;T~Uq048m79vC{n>dc zRRmhkFtW11ZeZU)a(JKB7d5ga&YhZk_p4{$MG3Os3cd2Y>ePag>i;hCc;urq zsjT;`bqscXii$E6J(;+|YPakC(za=lHEm7;?DGSr37--S1V}kzps~Wz&i+u^*Yxgm z_XStg%p}7s2mVV3z0)K0Yk0OypX}Qyr)+9NP6_K1#yfv}-b-^u*|P{1EG_P5=T0;9 zx^QqwU#UnQ!`SUrtr5M^%}e>H2E*Lk2Phthbg%)Jyf; zCG+!N|MTdhny(#fG{$;b=i6MO9NV18f=E>^tq)xz<+_n|mO)f^+bh{1247F4|L$*_ zxucGS-duU|cgrbZ$)yJYDydwy+G?>gW|KlcC-z^`{UiL^A%nM+D?1)qT#{LPA5KYpDAdoa=8>l(hW;A zZt0#L+&7o>|8VuzQB`hTys!l*3P^{Pq#)gFN-{eR`Y<_uO%ap-x(D%9TC6f+%JGEbDkOS)fY5|HODLRm$`=tGh zsF;7S*BR3AX*J&M|S%5I;$w*`!7Y@Rx~4z7#rx`M=A(vOy^?a_kOe1?EOYK)mX0* zI_WNnt;C12FbfE6yq$GNSYfIP8*4APg00AHmk$w*gcv3&hab_1$5HJ)RoQk!EDPRozO*i0Wic>?j}{w8&61o4N%SLU8Xb+Z_d_~jFV)KMM?eRJDpgK-br zO>&rX@I)tZ$QQeNC09NO()#Q)Bs9lY! zp@2x|PAupD#)A+`(hrjX8K6^;AtZf@Oai;3!3<{OHd2+Q%PTnZAJuk6-lu2>(~AW@ z^E7AMopVAG4c&TOwFDK+Q7(L7>yZfx!b^(p&RR>xg?PcVM*Pu(-nsWO*`9VVHgQShs1l7OJ7pgSnRFX?i|$IY(4k&w5hQDyKY&>8F; zW{KFy)M6{2Aho)SLObnZAh!NwwAI1bT?cJrCewk!IPSV14L~Fyq=oQ$XJ- ziu;ga+z-`EK7M@pv2pVSlRSfa5TEN9&L%hDa^@nF=Py)ZtN9dWOsXL;+XW)6vC2Jk z>d2JOex!n?XzIrRkQW=yjSu>u5zc*{-?FQpQtfLP1LAv0f318|rt(d}feRhNr;JWf zKozm>C@;xA2kpBUcD|7lFc5*&2E30+B$m0$OM%NmU*Deed&@I2yd@}{c``AF8qc^PYc#{nU}%i))$)k9#MRayTibBZ=6yOGI%Hx;;t--TkhI4C{g5Un zx~mp^!a~YB_O2c&7NQDc% z39q386&ryUuPUSH$+%Ehw zgJ_hBQ6d#m=s@iVwabytR(oItJ_nuM0O!FJX-pBfe){!n2?s&~o%f$rk82tZXZLV% z8EcQin16+@z!)=f9-c%nO(Yx)RsaM0z>LQQ&gOFz&@qUGgY(TO6r|9!J!Y%u6%P+; zOm?+iEo|B(hYso4ljCsAb%5x>FO1P6dS*tG(nT5onxdqv&hpM|#Y9bn`sMM{WOABL z$$EmiSrmy)!A+F#DPBmc8fZoZPyWcu7=qQ5bQ(2#sRE!8y4w&WX+Q^CU|1MqKOvBc z=FHAthi55#4fazeZdcvZlpamuqv`5OTq9`2QiyO01hr_l zR1dB=_>xgVUL39;ZDiRFaCOBgMfKUD{&rjq+2VI(fBnr(g?0^8|H++mxa{kpD&@B7 zA8!g%U;w-GjH?W7l`X(SLU#&{R6kN5)TkIBH1~mZR0r*tGQI<#VfXgCdot|Gd_kx) z*@ZSysfe!f(5NA*?}%h&#QFEiCt2dB#*M0`cl66YZ7QYwn@cW@q8|BSF%21smZszI zQ7o91pR=RTZLAQmKeXO|At(=$%BZ({dHh$jskyl;)Eg604Gn-D#(G#a;Gevmwtrvc(skY43i1NqE`Zo0vPtPU zlY)4zDY=@3<;=V%T8__gw{+itFXsK!*c@AP+3Tp=3-jC*(D5f`I3El$@?bVKZ=?O| zKpGn0IUrQ6@})5<(0q1ZN*}R@@Dv+vbuPjfwrAq+OT^j;XS`b`f+^&!?OZK!RW&L3 zwO{vdu-GtRraC8mq?yYFN60KQ8;l^oD$^BaxZPq!L?yrieAWq0^{cR5ctb|v_JrQw zA3%>H8)Pas1cL6#jQ;qUVASuV_wSFKfM?<%8R1ODSwnpLd~ql$u~-#oQ3(nQW)+4BIK?tgYy$h&BiRl)KWuvMzLB)sR9zR*^+r_M9Dm@ZDjL8!@ghqp zuU!~;w^JKAtj?{zq$o5fY5jQ@bRWwSbs1-Sa^_tl0WJut0g1p$oQva$H6h|T5OLrL z?Cyr{4oWH1zv-mt;>AX!^FGUjg0LXShoW$QJ#RJrElRm~)nBQw3p8=R7tZ=Oq;Du} zWH-|>VOYkf)G8}66>K-^j)-1iKhu2*AaU*BWl z_xV!%St3&Jb1XSPmBRM>GQg<}!j%3SABgE=-%c&q>}TKIH_@9LWodZ4CuXi8z^VfI z2zqTk<;LY8=}2rb@tiCI@K}8EMyjL?-){DS?e6CrM#zEMxP`(yv3a%XKMEc-4)pq> zUvMFNb{7qhrWXA9i#QZu760s*Oq{;Gn2;1n!i}TuN8MJauHkY+$x> zh5nQoW56BNuCRCKs&W|apok>${zEAJ^VW99%SgHHo9PELZZoYM283juk9?yZ?}@&cR}x@SYk<*wXr1E+MVt zYNqzrzZsV)lmsFE0}vaYOvK0jiZkl3aaa_oOSY2(o?;d$h!2egn*~}6IEM5eDo8yA zxrt#;xFr0dc)&YX^6~|EMhFDG*2#x5D3>BXV2sIyipX3mDZS@=-;BS!3l=g4l8_rW z8z1wQjbNo|wO=^rJuSjp1g0!p1GmTV*J<;}?|%^10c5cH1*rs4xr1UJlTANCXR2tA6kkGpjau3Jg|S4Nl1Lr%O*)K_OO2gU{aE z*LX}M*&2`WM@Sc6Pe*35wD$rd17pyiu1J^Ded)M0ao-Q5%x-A7iKdL$bv+I(o;jOP zq^6v*1)%MsBttIk5*7kL|Kx8V=#27u2xXOYk*ZoFvxjWS`E z+Iptkk&zLktAKZgl6+_tnI|}i-5)n+@xr*tleIkH%8##p9De9w>$6XXM*KVrkBC)k z!ZYjaA=-jGu|Jgy(?^L_ZeArFsX$s08UhIh%yOLFN;;rWy*5`@_`BQ!IK0|URB{ds%`XDxlHg1@G96fHj1Ar4PLaF*-D1z97#5h|L%O_0VJ$JOo| z*k1yS5S_IIyZ1)z0BX#^ID)HUOnVk_Q<&0P2!V>i%D}5?fDlNoRQ#cb{T^v^ z^O>Gf!-*Q8oVSt2Maw9y?|eP`%>9OzD#R(`>S|^Pj8+i4z?HAISlSLHs`WfE&to%% zEIxD3px*}dn@+ke!u$BPqzo_Z0IqioLdu6-|6+4AW53D$s!W<_qMFfez%yowu&&so zBN}tu=EB!3&Us3kJG`9S4rO!jxJw)QARAXQ?3mla5bUUdCa9JT;{Go8-k@O?Np z#6#gi;Sl46w77Jx)AgLH`Nm~E$qFmb$E#e8<-D)|S&|D%ugtYCk-D-kq}6$QTB?l+ z&h+XB6DQm4VE8(8;$rBaT!8`^L!N3BCa2Zvx4A|dU>ofQ zs#(@E-Wh0BC2Acq7_OP97HF}s+X1?Ae)d0pe3>@;^Y=SIi(gto zXne$H38i%9y5ZPHN%nvj^anhxvtNn{<3~H$n!g56 zT^S{ph%L*1heG^A_Ti%26A4;0rRIm$*QBM7QKfuO1fVp$+{T_&IS{$_B#la1+yeDq zL~Q|4Jf0qa4cnPWk*fQNPXEle#YT3k*A8P-Q6QXGNH-tsUs?D@e?A#NGJMsJ2?-lw zaHq(f+#2@d$&tx1 z3dR9QOq64yEPQHR^5cGmIvRU|FQjxwa2F865zK?2z`$?Hi3?;-*;n z`6t>{9Gay|-1qO^aPeIk+fL*haq7i+hl=+c_IB91hY;@RJSm)tH#Z`MKYPo|CWJ0+am zqxGLPiupgH|JjhoD85AqpTuP0_wKtH^27%T%Oa5GC4@^D?Yk;7(Q=DvJVgbC)tyL$ z_tF7X`2sMi`0>hafH_dc+auUCYI65pj;9NC{^0Fbl+7HtJ)#{s2oAynZ^-!C9^JW( zt{}^0_soILx6mT(&KzACz$pjZQMPXJK|tvHH|*z_BaM=5+Xs1n^nQKlqU)SXMh==K z35u`zQ6WrIFygD$xo-w4e8HBwA)3h0pJlkD&D4Lmka_03Ed}7pW^N6+lv)4&fb>+u zr!aAP`J1BO0>gEnOVxee29YXvWdtp9mwrQHxZ#?)C#C48Eksr|Y= z79z~!;5)!=>AoYQGnujfXV#5{o?&yK{g=SyWIk#NF|IMHO8xcGOU@P{aRv)d*ON&t_}e5ba1M^_3T@c%Awz&mKG(U2=&-v!Mx zH*yHc4B-NXoGqOter3~!m_iJTK4vxY9iZXZ7i0S5AWwxhJMej9yo^PkrQV_7jx4JY zF?XwLf1>T~FB17&{a+w*Y5JKmT2e$=G5thhCm<^I83ezR(1TZ`cU`W&sOj1=lMBf0 z&^=3*FF=&~@hkeZ<8Su`Kl4GA&eh6ZxIiG_B3KR%WFIbeXt;FZ10-|zDJ<6ocES_b ziN}2J;O@f~TyzB~MajO-Hm5c}BkE~=f+@6yRqw@^$$VMmQ=#fkASyH6k>^}44EZ_; z?E5YEvpGy!-C2z>#=pM>l6%`xhxT#`mlj)S;L%6Vw~&_gP(hG`H8V=DKJ0So@J_K9 zwYE0hHfXjREwgNS!R?>bhTy@T$g0fME4V&9f7`On&3%;29aTQS2R#+t>TMi;(8pV* zdUHkhk(mO{Sa>vq%z$1azz`aUk1y$Rxjn>9`TbWvjro=BgKpQvk>xTRgQg?Bbtu4) zJ6+wGr8A!hNBYJ{Emv&`9rS0zW%^`gNftpSz0U<76b&gMx2CD$Tak^k~#aQYZ%RH^bv`HpEBnh(^`EmYeCOYH-dX!8yx{n3efy zsxxGU`xB`jm>4}k!)#wKRM=r+{yvmtE0D+e_CniweQ4m0G8JwOHBF$zoNE{Zt`;63 ze2W3}H%jL(Px$1Eiz4s#JV<|O1>l+{d2Zk6Lbp5Qr7UnsXD1$*_ZusrIIn*Z=A3lc z>f`1x`fzJb(?j$lU|uO-r33xsXuhqC&;x}$;FAqEzv6l@GA(rHla;?*%cG}WUR)rc0hI7tk53>l#*@ppzo=`twDiIhIX z4Ai_S2?v0f`-suT@#j_ckTHAT8M8qHF2v;nIG}YTxxQf66D~L6<+L?gkH(1ofPYc+ z{$=@~?m!$@Xb7(7&nfnm%N-r)$h;s^D~f?xn=ecLMFa%17XgiCx>8R+rlJJz_%#he ziKE;rs0>4lIY$^2HWzF5HVOws*4vqY1LFqzd}YiFcXlAYHo8elddgXD{`)c=%wLNP zojz#`aQ<#6;Q_NILvcBUAcq9x&}NC!76d2GsMnp1;n&9rzrLtW4ztdp3bvF40RcPl z+-@h%zzqS0w2|+%cClW`SqU;QoysR45|Gyg4vd$PLPg!U{C-VOa{tb+1#{ zn`J2MMU~YwM}r5oPx_M}SYkC=dS|*j*(P&&^dy<=Nu0}*BM-b)PJbo!bgfg!$5kYR zTLz<1nfHG??KhpS3d*~*N=WUbbN@L>5%SDSQ`wZD&sq`o{F31p`_Jqg71B-C$2Qw- zv}%?cMQG$muM_49fpEe|0B?^#aueBoOfc&oB(`}fcVb&#XraECA-e-QYyeBmoRxgN zX>ymbC`WEXCE}S*m_d>ct_}0+MHbT^n{*$JpKQN?z0Dg!4sAKA3I`*o16n^jKaYJ5 z#qdFJf3%}wYJdMq51=?cELzHT&3}N#{@7Kp$D55qnZ{u6T42%V1xa=Z6C>n14tug0 z&-2fj&8L*wu7)qqmdY^&l<9iNua^@TUE#4%fhrjvN-^YCi4tJ>oCP+Aya)nNt*sm! z)}u*Ht9(0OZXD2b`B?c@5=+nok`&}N{Jesy}v`;a()#D#o=s^ z7r%#J;#br|F9~Asmr;dx3ZWu+pzxqL)rI!y>vhetz0*^-o;c0mzH(G1oeL@R7frs$ z`QW7zXu;wkIO%W$_vt{QXc9PSmgQY!t%;w<;G50Qt`V6T2hU9Re0|O1n0=fr^_AbH zqIHh)Qh=p1hiQAN%}&#aThxD7x8q6%vSFFXbjUNcj*N|~1BPd+#sI%*lj1pr?&9h) zoPTyutP^wDpdMzj%5E=3&0vjyQXCH za~Tb?yqU=VGBoSsMhoyyi&O;L>-DqbVw^dWuCUxDAJmz9n;t`|n|a$0_r+*%9k<@s zhrGZiB0)PpPq+2v*-sHKxU%3inXZ?;jii!vU0Q+C0lD6R4;)ulhpoow5L4Y9fHt(g zqW#>L628xGaN^aJ|FRUSAd5V*hYLeI2HMw@2Xf&9Bno2`)JP1Ug)=F^>Nq?p&>#668$9VJ;P6;lsi69+^Q zKZS0v2?fGh1*+tz6zS9c#M*p&v+t0z8;D;i^ZA`>rAmrgd+i`!PrI2%zt=-`VL0U< z_wb_Px>V!ikMLP2>_QcG3R548y1e-(JF!n?*GL12@I}=fi?QzSktgm4P2 zwMQ@8t(R0G+9nV$Y>gA^PGt?2S#*@cK7;z+iDXb}nm0`)o&^uA%+YvcCL5c!4LWN5J1?`-7&(!#fIgY!$Qw)Fhv9`#7@SvC9`H)Kg42THmH68!m;LU_-S>H91Q3 ztH3?ow;AFW6Ng&DDV^O=zxpD(`(Z|I(vDFUpMBGTlrjpj8!mh9by$?OLB`fTd0S(-q+LD(3a{YRiDb5CziM6{>UtBP6}F z(r{Urso|s#S=pZ2zsM9zm)DznvPS(pSuxlm=6e#y4l;ku4l^=xDBKfc-g113Qv#+^ zXgfO=C=`q}ApMR?6TiRp0xj7CE?wAgpGLv*s7Ntb7nCYFju&BVP2<9-SF;?0hMW{1 z;;_%Om8@B9myN7hv~LGzGoEc0@eIc zgHs(KL@VF;!~H+G4MGq2E=z1W6PM3_?rW6H13^xMH#t)yy+NOEU-{o^zv^y%)aL0`qTtW!vxAJIsL!9yV<$| z&{NbbnTP|+>f3O3#n`-62sEvq`n~#Z&h6&PHXRJ6kRu&*JI20@jH=DBF@*cghGS!s zCDr7A1RlM(eZ;p51*nnYQSjtSY#qnP7Vg6})*`7F$fzW!$?~few;qI-RGA+>WpXrH z!h*v{+`fHeBY>NT@4_v@AcQ!czj-&pI`|9-f~wh^Pgi%i!XqSpZ&YQtjmWw)mg*TJ z!z!Sdr`RQSi`m4%)c0)C#DH3;GfpD@)22KYHa7ePC~JA6xJl15hIWRS1Z{sm-8PfO zWS=$Mfnk|KaG3C;2UO)5iRBGHYjqvFN$VtZRznG7RALZLQ;lxi+mP5SuN(6ia65oe zY3$=UJ2x>FgBtV3k(6J7kLeA;LA0vaXxeztJIUR;;Fly{7kkl* zOY|?x;3nr0;n#Q0Tp)hx49n^M`x9aUC3pnOY5g4g|2_@hRbXb?SlPAt7nsf_jPsvU z*onvE#NNAJ%VIr`zD{B}R~k!Z4JqdEfIrS)m*>PX7%w$#z`6NJ|+ zn0BStZ{^^UUSQy2uQXlNus>;> zF5eT9QcYcYF)3oYy)N0-tH!ic*bKK|zt%S>CAh+q`nIJKKtj96mworXd-@&D7Qy`) zJ-A1j$K;||)Hh_mS!4Y74Kk-CkXTE*Iu0))E2^lt5nqS#W1|CGMmWj&-(KIzh)w2_ z%ml8ZJE7XA2)(&QW72I6uJFfCw1tAxq3}VD4*pbt-4l0ltU6glWF?(|10r^5{Yu=X>MfVF@RyeWiPBdXk;VM9a=@7lc&~${xAzAzoo;JNjdegBk@WfRs~} z{pYiFeL61#_9lTH2QT^flEIkp05BbW7%I=fo&dEgN%1iqe0(k+DqJ1clWcNa$UoMW zp$8Le=})A3bW_i}e)U0egqut4C8oU(+f!FMAX$n6lKrAVVo*UOPgfjbym9Migu4Kf zB8C!_!AXPd0ukh*EM{YL&>kdYWMn*ECnhkSnsytk;!yAk5tA{lb?p8Y*ONPBVef9_ zFw>^GJJX%CP+Z39Y6$VJI%RAoZQVW@iZyOwUP%;HBILY{J zKL8(4H0!2O11uQdZ@#_)TVY7SSAt3Y%q_d^pnEYZQ>H&5sZ66{!Q0~+2Bo~b!sh}N_}v_?fh|7Tm-{LQ z0-B{$)MChOo5EZ8F_Eol??TR|)vcKI&h~&Bj&)<^v785RKXY2SEFj*0S?+ntqAAk^ zUTm;18#vx0Z`6jom>kZ-uExf;u1LFwj4VX`q!^`CuUGO5iJHjBdj`+i6GE7#{S(bP z4JitY{o9aC(gyzbS;bt@pl|B%v=C6F=oXIGiG- zi54(6wANf3=(}9Tggrajexw&T?q7m)%OP|*9o!|RK7i}k*dDJuC+gNPUqeH~TZ|^R z(c9e(RHab`aZ)FYt_iFPat8Yx;$imxJPGyhgI!Zcm7XR(Tc>9_{LCK<-d$Y?BBuEyqtu*y6|Anh8P(NHq^`N!MYB==ujU|(5tls{JVIHFiq zE-Asv&jfaE#{+}9R1cVlo8DWxgQ*V}Mstxe#nd|TMp59-yNh0;WLdCFH zYvXFU^P$f}-a)G)oG!Pk&#w*#P39V$O{hUcbS?j=CSQ)y2vlSlr+N~@a)ds5ATp8r z&Hlz3sM+P1YuuJbMs@@3XOZH)X2AWevew_pQyXPgx(J|&T^?R5byBKwO?>D%+n#p=D)q`^ArzvR1}>+ z6xArffghji=I~Fr;!20KUmf)^^b*pOF6UWZ1XO1#2cXBryEgU8?}v5vU-RYsK-oQM z(Vu3kLZQ4QF!bfmLa=2${>h07|Mcy>WG(!6vo1u!IRM>uK=a9rdJd}3T7QOP7%?#R zX`x#_S(;VW2g>$wpXRt&Zrq5vyEpFQ(UsRBATGMPW|-s&BVHMak}*1|FiE$ijRr1z zeI`fzLt8G3;a6j+te}CH8j6Q|Y;xDW`ME`E!bcXT6L)W?xyL>+iV7 z4j%M491S^v!vaZQji3dmr2*k*nd4WA5nNqe1=6dhs3Wc?VcmRI)WJ<|tPrDD-eJ{n za>onWt`1eZo&v~Y;=yT6k*@z}O&SsAar3C{mI*8)%ey=A8tLne+fv8*1=(*K^PPh< z8-5heVZL)uq@E=|dY&m}Jvv%>)9#J(ApyIW_NRAO(S&_W$Ah59kB5b=$QpeuNxgi- zeX%0NSXg&S>MwexUUkpJFJDgTqqPZR4A?(p#AoBX4GLK8EQ_>2d|a^9`4LP=Fs8rA}fQ`V!nO+5ecGqo9p%~`B?Cb+Q zS@ar>Y+KrbY)+Lfb%LNa*?5K}%f;!lSnK-Z+W_#VS)U#buB})fS6M*&*0OCycrCZD zxhvdzgygOj4csEc2NzD^yo*47|4Lw`h0o9Eqj}YPq(D(7GpJLP*4PPfecc@J9nXis9 z88Q5^K?msOrm=-%ga4kR+>ZZ1A7x>UPf9JOS8XFx7hKVdAVi@tXxY?P;W{u(8W0*$ z1s|)m;8$*JQti(3@bZK`nQW1{1ED0{kf8KMtLm5|vTU#Zk8!R}yKjIW3OWQ`K@iUo zJ#{o3I9S1Yw3;e|kbDJP0^)+sA_CQCZdQcBwRAE-6LYVQDro{_wxf^d5Pm1U`4!ab`U2K05Fk)>gfzEnqpV zhiE<=NMah|sd%?rF8Kf4Lf z_K@^;>nH6ZA*#h6Nne9sIiM!CoFhzK)XOFou!Oz65j{P9FmX{6{4M|y!%hFOy0V)k zOiVGgAo!Y>qqTu(z2C79O2~BS^_fg-t#q+DU06dkfi7;1)$Zq7cgfSu#(u z8OyZ=;efc``Cz07A#*bMZN^A2|CVRlyU}Gl)7i1ON^N%oIO#Zj2Hf)R-|_05n45n8 z21+E}KZSm-aqP$=NAoO$1J7#P6GSjR5tx}6`@@(F~I!Cb}uCTUI zx_2Kx#KhW)^INk(8~hv58A$}Bos6hXD=f^QGuLRAn6^0Ac|LDBaY%h$lE%_MbUBOd{M}o;_mrO)Cs%(5f{tZdc63@xnl~)#AO*1IKyosh|R{n zHl&fx%{5Hg1zm;y;Cfnxf}T`58JK8C{WR4HyLuWfn!GcM8Y(-EINqHiL6)33IDCxjYUcYw+c)U0HCU!{oRD1pq?|Lp(#L4L){2*kpB6r{@F~s%i%L_E3 z#g!sW8kox;aQyqXOkem_g8QZ9@Q=<_lu%rQlal1&dMd6_HQf*Puhlv(2$9v>vnG?v z=}8yZFRjOk_3I(chq`*Dk7&Pq^&<}skP#Bucj!*(!b=-OvN^g0y5c2sx>8Fnh1VJ@ z#lDDT&3`X7C)vZ!%{fhgE2^v&2}~rVSwKHu87a5}z(61uQ+-@o)8wPG6vO`IF#MZV zEH}3Yl5iN%!1?b6WbNME^9dt1w5hhNK_zBOCiiUB^P7+wRbeL$Cf+1oY;P$foQlVo3Dct8&+JZO!f@ECfuR&b>qA<-H&Lwwf7O({|U5_^*)W z8ajPfqDN)38fdU;2GEU5vop;!HWMQ=yTe`yboc1r3)y)fdMO3F=k7dO0?lnn+l zxr|(UTdWsrZWfTbE|+0HU<~lHK8&Pf+nOA)3+=*Ix3@)3&QV%?6P0zwkS~m*I@YO{lFdO|<>HCNix&+VDTGr7K4z{3}vvD*5d3 zkVAnJd-YSLj;!aW&Qeu&XWn(2JRfpo&FKeo$`-?;V!-i zwT492Uc#Np5RbmYu-NVgy!Zq?2|Kf@oK`6tgta2<#Z?$3S+JZ3ghy^CjC5}1v<%9n zkbFf1AB=iEBrK2*pr*sI_!Trx+vQD?kU4DcsEC8&>Q^*B_fF@7@0}!KfpOwMgoHwEpx-}N(1A3tJATeBaq!*VoFmChb-T3rbvD%^iGIQJeXbhjNuk>)6JPQA4 zN96yCc{Bl^87@HLS|QH2A|G!1@Tmd+YR``-IDmc%1X6fWcplVPu0CTSAiJMv4UB=y)AOST#vvcrK`F7H1e7IM%LvS!vs zC49fw>X&W1%rfbgJ{{Uaan$vFuq<%vMU8L8A9wh5F@%3QV|oGhXmuCR(QzaK6qYEv zo&S*QNzCs>QxJbeES%zony;w+3*fxm%^ix#J=pmn>+?@lRr3C)TFJF8!!nhZ4)%CY z+R8TStSP83xBs@6TEMA$oXC0bTb%A>HCO3(^qMCwX3ixeEGy0SS8=Yg?0Jc)(ABZi z0Ls`tDaSxLzeL~j)Y+=F?Q7V9MSf%COeR-;9FqJI_V5)H~uGwei)W86r!iINaPB0YI0G&-@1N9Gd$ch|B$Kv|D{9g+^>p15O=G@k~H;-1DM5 zXOu9>mfmj1Hf)0e+#!0{o#&P5`{-eYbn5E0*F&*cV3R_lKj)`DS^lfe@0;^ZemC?R z-Ss;AjAb<>y}6$qjExVa@|Ad-Y^kgM>VR{5_H29m7U8#hXa*i9&u9OurZ*Y8P`f+! zyE`XC&KtaX;MMnbRAf?sQwynumDn0tGJV^s)8JcmX$mEgu`X?cgja!SpIS!l^cP8O zmO3Y}d7gPS_c$uLNF9V9^C(8Z@m>IADy>*Z^z?rl8F%SkNI0ayMUk&BjK;~wh3&9}#RsAo+s ztl*wmRtDYq<VBJn*;z{*1Un7V|xK)RM!Y(P-WbD2zp)tpnlBxzvkJE)(v$xTC2T6X#)8c>EVA zTMh#M{Y21zKVhJk45Jv&>uBaQXG$i^YB3E+QO_&M^TgpB=Wh-4Qs=Jm%!TtubdJw0 zj@Q$(Q=u3YCm6tjwiuq=n^+T$lj^I;qj<5S#(f$(oLNgO$g$LR@duG8nVfina&GGo z5sy=?iG0%edA4n4bUQt={`Ty7#k2>{z=E^6>R|+=Jv2y!Er0etS!y=KO_i1c%gykY z&UbX%CNOz-u&$^W^URQfsD9Q2?mK1n4Z{&R6HDrcM!Zi50kc&<0nme>x@MA=QyD=Y z;fJ{{uI@_xt|-+Y@&SWA2Ov@S;&AVz;GM?xdOw}hwd#yzEc8$IS>_4(#K9#=eyVNBQ|FZ9$Tas)s=^mp z;fWWxFhOiSbQBUYg&PL+ePkCUMu_b_MJB_(4gsj>ySr#padf8yXg=Q9KbNtUvd3A` z_WCo$YBV|^IBu7y@uKPIXt$gak=&gFT))S~JMU+ufsb5MRfgYzyZEZHpQ>r$fZpuENw6D0Fmqzk`DCWkYh zU=AifOzgJ{eatgw_u<Sdv6=WU|;+OW2!sUqK(lh}c+Tn6OCC ztNc-M0|N@MXYuU(94xWxt+8GLq8?k%4@-C_CMHSq>aWBI^CEgoqWAnw4@H%P{+_x_ z+4@Yc#^p`M*#%;}G-ia29!U2+!)Nh5*`8*#n&So6D70v6^ReC-&3$PR#JVN>`-gT; z9q(+mNxCjxB~H}1Le8E>>DHFHW#h4ujg5_Djs`|-?^`)J46x_7JujB+`Tm#1#Ymog z$%m@B;ii9n2zq!lZ9GG#$*{4tJqLSZzl4TTQBwy%o33)CiEhB6&je{qMx$~Sywrpq zcg_098Z%s}j12HQNRN~QRs-_N3j0kE``scb*RnBAJNV8nm06Oh$W~gw-Wo3J#YfcA zNkB6x4L~7<1Q_E~j_|ak!qgCytJI8EuMD{>kzOXylj=ybPgN2^0br&G1r=49&d&#k z&+y(jIn`_=1+Ut{y8HSv!OrUmyCDBBqTo$7W?~H}5p5>eu{mhx{lzKbg;hg@>rQO| z=wbg*ZX`9rz1U$1=3aqq*10p`#m5GsA%zbELMph|sk&Q1TJj%DN)r7`$>esf>}y1KeHk!qNa=2 z5sHn*wvr;tde;>%Up#-VQv>pT81Nv7K?p1`-54(>0aFEjZaX9npflq9TWa$G(-@>R z2=N00vu)cyr?8Sw@D2z@wR=tYx2&$PLSh_COGkHgz8&diLB8KGf{H`}Y9H2*H=q1S zC*STk1TJqxr}0PEo>Z$Hw5_(ZarsoaEL0pqRKV-p@@?dwEsZ!Ap zImi=KOgr12T8_}@yDU*m8OwEGp;JAe$@7OC@n6 z;q7`+TDnZcX9^R2X2Ll&5a@Zil=|CujJ#O4ds@EIixGsnqByZ=YZ?qjV0-WNYo+I7 zHKiMbxjLbYj`|xZf`-a3pD^|rtoIJ;Rh#Kciu6=_dp{^pdhGymmqA|?NZ|pMM&{n$ zr+Z+n>$BMR&P-Kem}RZ4XF7*Q;1fTTC(o`hisC>U1|F$W}o1Huh}gjna#< zxy|H8SDL+JL%ZnE0PMjj&R(&JG(z(mt`M!Y-<0(Eh5U_=l{Ll9D>7C;(f|m|p<>oc=jHOnwR`RrRL7LI!2{5V;CQrnfk9X|CmCx^q^3S~;oVH>GSFy;9 zfPmm~t%APKb;sezSxag*wrKGFlsIkG4AQsJ50^mbE;3u^_AOio_V!t@IfCMeh)s>$ z{p*|%-37j4S≷Lo}=iWT|5C!$x45gXv1o*UMebn?R@53sGbf*56X%v-X*T{BQeO zUO+DCz%)mL>Hc@`8jkT`%5!2<7X2Ny-JN!=>`_f z!z-|+Tu+Ll0@m@lR$pbrlj?kJ5M&Y~Sj0tfT&rs@PpoUCiKr&F)5c4pUOFZhwO1zfQZ2rynQFD8UYDaC<9n#{cTnkq8Vdf1|ff z<<^IZ_S{Qkw40Sp^qs&w(y}I*Uc#|qVC?{gHCnKlu*+0-5rVu(v37oES=IV(vr*4CB1Y?!!rx_|M~phz#EvE@64GK z*SXG_^+@n-n9tw5E@OQDh5K+dQ9gQMNr){niT6=EChkbqSTJP&k{pZgy5)LED!O_BhDK>ZxKohq1 zrjt4BR`58rMeXZe|Le@mAHvSTryj>oI01AK`_#VDvf?_5MSF`{>Y5umS!0|7oI6Hw zixKq26;=5ErvQR007asiR%s0E&@-_rUma)uIqG>j#2W*T5&5uJsqn7K;*_1{;ITDG1>C<=LeE1w zUg_#mfM?u!QfXHFC`r~_I6b=`;(`p)3h$4`S^3V(hbd=jbrz#fn#0nAr?-(Y)tA~? zn*-l{9Kor`V_Zy7jaA_7*+~ic+&?%7K2?0$z*YGo9*qJY^Xw1xA>wB59~R)cv*1T@ zNZhLUStmabWAkoKR?=6R4nF7QO;|w2po=Rzp`pu@MJ)Olb1uN^+)a(ahVNPe;P@X? z&y>t@N7t7kMjZZ2T}D+K=1o!(D!RI%eJkf@UB2w+0#^vzGATBhs+-HDW*@us$w!QR zmwwWFEQ9(ZfwM&$~0k5Id1-uuQ%7> zVAHP*-Y%n>&2HAH;N^raLi8=c+L%lUanfbZZpEm}#G=Es#D%5yA#}|3`Fa2`Gqwi@ z2WvLEy#)FFuCA`N@4}teib6J?oZ&*nYh|nRI<>SOWUjFe(4e3ivQ&|zP`?K-QUD0t z=^BhA9_!xin)w0nAbdB-GnY>uP051xsd*}ar!%^9e4g=cu$RgvY6aNMU*QvvQ+pRq zs7;jyK9ro<5nNx#$wI#d1un0w=4SP!w5!EgY@0=qZydRe=d%3E&F@We6ceXiD%nu53C3E$mSVIRI z^kEd%o3#ZbaGB}3+mrxdWr-y zE&GUIjEfj7>One0Vm}Qk>pc4Ovh^C$v%Zo8*F%bN1gN!3%P!oJ_I6U8%3P#=8rb@H zG?vKq+mZ7olb)1oiU0Dd9qFdHh5i10gKOCSG~KK6C5>|Ct=KBRvS~guaoL%X*48Eq zA!g@ErPVJn6h-0PneJky6i`ly0sv&=>n+nvD~dRUKJRur+~3B7xx2FTVDhswlSTIB z50~d8MlTB|wpZbxw$*T3o2<$T>6Fhz6wVNIeRzZr9$f5#zBr0=^YZq;T}Ye(?uU>e zURX%b+T9{PfoIjhlel5wtnrUtW~#G>!%GLZsx0N8LBt3MYY-)Seg2gZ@6SLD!}js> zL#b>*8PHjpi|gpdU>zsX)M-m!>kyk4*MlZ>wWtQUiW`n$yPQ99L$R7cOjkcM^TSrQ&MCBY3lkWAl&ZnZ!Jf$17@2i z!VE#p$vnd)Mv}}UnFY`Yh-?8_=-=a&lLkn*yJT!JxuKkR?HYYSuLS5-&t8{gCWa@~(i z<7xE${{73QMm!Sf!BpM`IE;o$N=jCseB|`hP55Gq6THq0vXqUQ5qS&{NRHb+Uq{IWH(2 zygff%Rfr(iSKi!Zc(O_;g3F`z`9gQr14HU1kQKzcq$&`iEhQ&*P{!ii<9x>=i| zv6~x>^97SO6c7g|$wV7WcwO?{FV^9F$%+%wZvuogbQbWXICovHk|AmZPf5-J=W zCuCYcnGO8QNSU;_D6o!;TDNvN_EB6tU}Edg>gwul_-%Gun7B(mcf2>exxTtrxJ<7ykd}k^ z)Ba!^=^40@nm)BcEG+z`Wz`&JPCLi0S1z=<)uJn%AJH+*MtEnvoAMZvIPrssgrGPd+1p9XmjcV=essXD{@G3B|;Kh zziwkGd3h69uH4bi?8TbpQ`DzF%!WUOk@J$VJodZF&-a?mL|?+C?%Y@dade{;GB*7t zK92s;i~HS!Vqr=dxJ5tG6O1KiO9&AU#Jv)XghzGIEK1+)PzCaZ=-60-G@o;GAgvuX zh@p>DAd8d|Zvv5M{07IJ_5IgKt<>>XF<=;8@kD!hA(5@R*9Knu7|qSiGj{DbA_mwr zLHbP|Er~y%8eHoOA&?4eLQ#b#7}upWAU9%sr<%XQru42I1;Ie{O(_h|j1I z9Ua|0I0%)15&8X(2pJC#56c1?Cjtg_+*=R>_c6z7+l5NNB~(kVKGNy37D2K9o{0HZ zao(>Dfx%&)F1h6s8PmZpD@Yl7WHnh4P*_qQ3^x19i#6y8xSD(}TO{B(?`<+w$7pF? zHdyOW&6cCL3@L)4>EylfOm$MAVm|ne)NYZ&ur#!zV_F*J5g&;3@&>L3`V?T24BjG^ zztG==kx2kSNaVGpVq|0l4(;2p^`VcEGrIaBUI3ekMHfQ$d}Zty<#Xp&`=VyN4NV8B z`lt{mz?VwmZP_D%J^7TUQ^SS=I!1Cv(Y0=V{rb>X2aS;Lj}{h zi9k|_G1h1q9&K1HzucNCcq_UQt0DFsYi&5T1I#<>5#G<=@pQZ`oo9#V=Z_deOa@YVz`p{puzA7bp%@DCUOR*L(PZcu-A2zA z-_Mzi2Hk*{UJH&l5(lC2bUfm6jHso=zRdr1t(~XZE#(1U?y=M_bo(Iy$9dZSKpfE8pfFJ3c<3vcWn#-j`o` zU0t3X@}5ad0(;l^_&89nqVn>%Vq#*N#VuD?!vOr9u;Kx{ zTEN`Q1eyml(^LjRr=*16;JRzF`0H!Sd2RZ=3P9#GUG9z&ygGu-IKkvZZoKsMserC( zZ58!7{ezjrYb$SO_X6BtfFvv31}iiS>mup&%*-J}Lqqf1vDn^@drwGl$R9Z_{sZm` zkTT=g!l6$WZDhI^MsH1Ol0WS}R{B8Q|73qXz<|@k>LI>uRC01iLe=)Ct-q#;K1)tE%QtpQ*N1q~%p8uZvatJ$bXGj%ln|#=_^~J& z>c4n+Yda0Qt6+jve>~wmC;b4|Km-b7CEERE6=CBia&<8RXKoi=FD@fQ-bCO4m=>y5 zsE%xO<;+saqdEf3cjDPRnf6B{yqA^ZOL(|>eUAvG3x9G5_Qr6Y=YIAOwy)LwLSa}2+ zS=XpyDlOLTIJUP3$QH%<-#;;eKNiI5xl6>Rm`%;*Trv>Z4n2SD0M*;}C1_+jKg$w% z0LEE#sPj2l^Q|i;BO#Fj0s_F|)6>(1%}sDhgSKgqeb^V4)=*MTWcOWmx6A5DD-
O_FGEg?)Fn1fjt_V=C}~jlak- zHrh9CFA4=gk?^(4w2Rr3aU=gAH|*s8FCYqr3;7!y93Hm+vD3Bd@9M&Y!p;iUUbnTi zEw8QJTsAI4*Jwn9*a6Pn{=QsMQPHmLtDZ>HmFGAR5O|?R%fg!X{;hFUx;3sOAe|=m z`t@f-sK}A0_l@Urq?@{`DuI8E?VA5UDyd%9J#|V`dO8*hVJixQ*MZ|-A_YAtC87Ov zf9r>dXMRO8ui5eai;Ydo#3aKzyApiq@WirQ6IhUvwxr3mYso!rh#K2}h zfYg%|=%ve*u|{ARr7y;>JzrXSycbBF)pZX)Y6J>kpna|;5+rFRC?Sc2thYH=POH|Z z2?QWeNXu4xv$?P;|77CoNyp2Z)csmrc@Q-nko)jQ5)NuL8eukoH|H09c_Sr!%*UtM z3Lf;d6M235+`~z7eWG#WL;~1zX_>cE+%bO|RTIDqm7Ydf-Ar8lwV>Q>77m}CXL#kk(R6jubVUa+B}QR^Vur6CP6nv0-z=(lUH#(w z4~sMy5*<6_*_r@!W$SO>(o2_SR?rG<2Q!yGFiVoLKlgNbF7!n(qZIH~INl&#NAugW z3vw$*E!Kf;>=`b~1xnRv6movv`uAzic;KeK?^g^wVgL3hWOnlUExOiVa&)@FA+01y z(YEFpJ7DS@%R|?GKdg5CCcXEa?6rZ=C^B}qymzY2qQzH@fV;D?};BkA&)dkYp z5D$}l#|j=;*{0;PQ~}QGEv+K;S#5kfqM!9HjK7MD ze)iUybDfvaJ8yQ~=G^D+4&ka8h~4X7eX~w*wNU~4PmH9bNF@K?A~fsp*Jb(kJpQ0> z@OkFVqON)cf+Y$IDEy4dg__0aCI+}F&b zpj$aL^{-!%xvX0I858{YRwSu%hgax5yQyy$Psl+?tt#cRmHU|K^AP}yK>vxr8f#iU zDV-j|$tc@dJ|m7G7B-WWN@@XDGE;XwvTJcT)WO?;2btQsr}Zr;H&I zOy6uu1Iss8URk6y21mACTWRf80RT2id4I6U(_V)~aOQgeg5aguGyy&Q%Zd>Wq$4-q z5g}su;J@Hh7wvxpOj-VO;Agw}xu(X+{Kx!L(S&%Ldzvq#Ij{cZ(@1~g`nvLR+Z9Ab zNFPZ?HVxJzlEh{BD~Ve*Ukk+3BnvKLKc8T3KiB5dbEOOvnfu9oBA9Imf^Xsxq;r>4 z{&5Q^<2-{F;p^*b;NE_$vK&v60Vjjc$lLkDN?Kp>;jYab;Knj#nDCxOHarWx{4V1} zCJ-AiCFwFRy2yuAh58_vB3VF^MIFChjYS;K<}Rk}X1~3;&DC@pA9QGd z3%}1mi#`eRcb|r{BoCKk6e_$gT^gNma z?|?p6Nb_pDfKcF4;C2m)3=9lh_iq~aDCikiDJ&39GuPIhTH|07`(8%Qos7)a6glaR zT-5i8ij$tYQb<3$(!1Jk-;LI0ViFP#f`%68Bt(Eb)-p_??&=FU$S7bC=;E;mFqez0 zvY^jad0Xyt&l!{K6?)F8Al#3dzTR9?8CVy7TbU zeKyXMrr_C*qTOmL==9g7iEcB=?4OJbYz*at#`d140ja?EyZ_+9hk+D+;Qel`ZDzd* zdk+GeBK@ZGPba>hcE)|DZq4V|{keQfP)m!=diRRE^>54CB46Q1XC0aA8cB)kl$>Mt zWBz_``5L&Kl*_;4{Vn00l4J>PAwjy$gy79@^}^1eler}?sUVO&%9sgoslT-3^HxdX zEbX$~+Hxl9?e2dNb+EYdE8+h0ZVSDTx?A%?GhQoU zUvwY+m%!3~$GDSvVon$4es-}tNcaRTgeV9bcFXaCFaisN5n=YwuhSGA_44UMPWlS3 z+Kge~%L}^qH*Fe!<>d+v(*0`oUF+wgxn()3 zDv@573l|g4Tn2R<0qH^anu@|f z!C)euEE831n3i!c75TCQp^7XD>gnXsu?pEtt7S(AD6Ef5^S}4eCtdwtPZ1ZTi)O*# zPp}D!mguLhA{WUgMKZ~^vaP`P2hdIaI&y|+{m8@-^77O@c>6gqqYD#%kg;dpa_rHC zEO9p7_xvA3*8qIp9M^9Sd#FO;iDLaTtMrQ3UHD8@N7Grn!edWje!YdE?=Ga zsvCAKzp_YQmt7wc<>^lcEahLDgvxmdp$roHq@+KlTGCOQJd@?|@iciWf~pnjqzhW2 zIn&d#`<#7|NoSgzXF*R;cq*b~Ilj^k*hK}!x>8YhqY0j`XEokjUwEDV3EY}*Nq=e7 z85tY<3sm^p(ntbjBK0ha#h5YX+pqaE0U<<>eK-Jk^2=CSUxx%33we}TpE&?-Bnn8o z1sPGFJ&GOv*6CVhgqVie-&&wXb$p4bNLIRr=xEK+YStx%l-7-1z)h0T`uPrXcJ8mC zYqA!BFCtg3rUglkj#5@l>_z!)i0gBTFCO}b2A^>^^uY()dc^Zwx#Z5nK@rgP&04F{ z1iYKaO2fp|`#KyjQJ;|Wr2QcsEBo>x+FYExdHF5UBN;nZQsR=8HVp2+N9G|-I=pBr zoT5W;TiRq~`{DW*u{{JE#OZEylv=tT;BCa*ot~J>Do~aM=xVwhW#E%y8UR;byzu?QL0 z)@>z)UCI4)p?F6n{*-3DvM#Hrva{&Cg4P6;CVk750a8VqN72vOxQ%=WYjC7okkGi)Cb+5 zUP3wZREH&$-~N;D@lJm}IwpX&bX(a8rl^BI7*$%`^F9;YEWL@`+KK^#Hh$sx@K#^j z_+#?vDm9M&^jTp zd*I`|9nV!6*e8y`uaAk@th?jOe79yp`Vq@*W5se%DaKQKI)aXrtRz^QYeY-$5U+mg ze_TA07oVU0es_zv*wj>w{!t-Bl|Z~_Co-*)2%n93iRB^HIcnK z2QkKHZ;?s4(Nx?68rQ@2qf*kNp=W?sO7s{x3`+PsgOEf&zwR*W*iu*#0Ff^Ju<@Et$<$nwNlX8pR*L~yDV?Cp;ggA=({Tw_GtN;aY8;Qw;ZwaRoKlYQZqG!)AS zRFqbw%kJ|!59dye0w6syia(v#5Pz%j8m7HuuA%Nn>mt3kwN^o@qPH=m{kQ|G=R~`| zU^l~?^2d}=CS`3hwbB8cdEY_iFft`wRbZKy@v6KhIuZOICkD7P4vlJF+V(Ep5j=Yz zfFq?KenH0)`m|63)+mk%E;bs_JM~Na?}`7Z$emWDX|@qfF0{ELQPU9Kg09NXPyci= zH@+e<^!iDkviz)zFLykikP+iC4GkX|VTVRCFHrwyDq&wlm0tb37Tk`wxa3$V<$25^p=pqe!?+D) zVo8NhUnC978Z$ZPiKCMZrL1nfPe5=*IppXqbso)Dhn+I1*)<%?;VJ)xhkhJNjg!JE zdttT#W2wE72o62~I+g^AGa3Eo-r}r{2f&=6X+m;q-Gsf;AFskx5N?8>F=_l}=L;zqjqZMT86aW71;Uw5@)q2;Fh{ff`dcy5u@{baN9vMepmc$;aE!dU+PnfJ3t zAX8<72b;f$TT%|M0yJYG1>AwGA5V2S)S)@$IZCw8vvWVq+CU^rS`&pL$C%=B6R%mk zUZkPkctmGpNZn0Ivu;ZUCeGC?=Lj_<)+PV_E^S5Y4M+5bDzEBu<>p`2mR)eqzYlFI zhXao)7m&LM_<(3sXMBKhAQ{uOyk^WAW3Y#GJIr#{ceELnKOC z_X*i91JiPt*wimY{_Y4sdO7SbPPq{Q1g{>+NM+I;&FMT6&Gvt12(PM9)966^SBCK6 zYpqQ@t?`}U)VZgsPmlCpJ+gSEK-=`Y(YLX|b4JgZQFxak0+0XOYrro|Mb@3SUO?6XIDbBftp5`ukw#Jl3(b z=?NHtOLm9R^;CH|$K?s5p4*NPmraXQp$=(VRk@VNCU?(LeRywY828@=F|7hM&QyPL zr_(-V4BSR0-oXdkKDJf&!pS>Gu)&NCKTV3yR}C!Ezz8%&s(4|rzmjMQ)Cd{|7I!oV_g#|JuE_OLn{{b^z65rE8@e}`7IZ}U^S-Tj%ktMv5 zqhC;1@1a)8WN?;yh!VKGxcGf|ZEzD>qUZb!)CuC+%`UE9FzI@}s>ce!)ziMjil-34lJV;5@H315*0JZsulsex z#G5@H$Fk4`2*H}n^!G!!BQzoY#8)eG&v9JZZeHl4Bs1GZlTNjO?XyDyY^XO3Boj_mO%_?WL2G z6Odc!hjlpkxT5jH{&5dr1c^xnrD^_X9d@@0Vg>qmP{?y3%r*n1>rLX?Ys-1DF;5yY^tlih*ts`Z#rwHIlp2NZ#x$28& zWC1nVxFv1*&dT-|g79*Ec*LM^{!_;}<#+GES%TRY>R)uDp`?r`;=q+z;m@s=jkw2D zJY+=HG2`-oJCVJs(Kj2F(n3W&=X*H}P8+5>lfBbm!JK(Q*g-E?n2ov_>*JCRPFpuF z@AZyDf<($eqq@N}I>f8v4UeArbXYm=Lbpb=Z;O}vS+;q{=bn0_DZ#VzFG&MvVDb`j ze-@Nh^A09;@+ze!xQ^wIH#M6svss>eFR?Gb))(7Q^3%Odl*{9sx zKmOp=ZPZ>p)!T8^&6li696;-pD-W*o-EwA#;p!XLpdBkwbMk6LP+a0Qn8Y(4T)$cg zpi*4aF+luHm`iAAsJZ*_FSj4AZR$KG*bjS22|GF02VdR6C?Dt~6~M%miaC+`($Ek> zNmXKtExB+?zg&iDc5FQMrb)KSeT2jt+|!-xiPKbwdb7%lBsnGFB;> zR03#K?^~U!G&x=yI!^u!GtT}rV}VAr4=}Zh;~7;8-uF zDFg3GBly~+6^6ja6*uj}MJ!jN-vi!I3o>X>Q^WXA17Mpu-*Gk6rjtq~*c*#7Z50xr z^uB3e>V=dUSxgj^cM4Q6qm9yQhlGokxm8Amx&jLQxdCw|_qx}WGp4hb7idi4^gZvZ z^5tlg1IQNx)#)o^@{ z&snC*-{09bfh|{M4?D1>B7aQ$tU^rys>a?@il4RG4Trbi+Ac*yr0qHl@Y#T_XqP;O zWa4gQ$Qo~y;U@H5u(2}3lbkI_p$gP>b@unapqELJhtr#bnkSE!HKJnhf6eSKPZO za~=1P>Lwq-OxOFbP_}sGnAz#9rkJYze_q!Z|fT8zgN(# zJYU^FoI+O+t6FTkkMqnTKASLd6v`%cMOZql4dgod1us3HB$B@GUjg?#BRM<1k#+X9 z$b$S~Wj->j<3S-b1+N+%;9$dyinSBv+eEC+95W%_3k8plAII|Ven0PwxO1RXv6?aP z!75sMcwZFNpV11WAQQM}mlY`1wYvpVyUiM;HEBa%vjk*KQEO32fyYo} zV4zT{P1mw+2IG&6eZlf}cJ6TGBhh^Cc}y~-6IjCgVAwn^qy+oj@v z55dSIC{I6Qw0FvUAAR04C88kdY6Tpe1xS7YgIxjXp{w4c%FtrM6nL^WMh0BUcmw57tL8es4vC+U0vX!jd_N1 zJiJ3#C`*r8`^G(bu0%@(k6r8gLw%e1yl5}Ra`So*8@#bz)XGthGdp;}?9V$PK_G<$ zWltn5ICNCaz~IVxUKqwGnqz*EQX}uZ!#4l>Jh+x#hFtjKr_&=p%f0?<4`78>1}^B13h6N7?sqvBSmUhjJ4(WC|q59X%} zVao22!ZT())-bn^oD!bZd28S+uFg!2?$^W=#Wg*xD-)Ls_ODR--GX)v%x2*zZ0}@;P|YmvHEyLV_{bUopXv& zn4L&RNA}}=fc67Q3kXyOa+EKJdgZwC$5~pW<)s07SIe`I04S&eMnMr~z6aLNP5$^{ z26zY5^3R|M@RynNL_d$dVAS-qBsN=z!m7?AY?(xEKtdDcri_bMBhX@eY$Ap}#{w?9 zrpiA}AD7og+fh&EAsQ>d0#xLWg~_hXKZZ_VQL#AWk-8vfxdw&0{~5Nj|XW-OP#> z$rRbeVU^sc7mQOJmqvO`9s^E9iYt@P`nw0zK?iJj7_2*$ywBg!ooaFMFAOdiPRuu^Btbj|hfSuGT@ZjS6)6s_8J0e}w}ymjYJ!0Tto z9%rdDGJ4Fmi&sp_uA#iq)XlE#=Z<}G6kLCES0rOLvaGC^HrK@$STUQpP;TN#?D1MvoqqwT`q?j9A$EkL}hOqgF z;aF3q7k8`Ztq2XN2_&#`r~aeLeN|5H2(c?!S%tw9!AyNEBw;e98QRCmH4Y8_+ zu+?ci&3yUa$Q^ehyLiStFYx_aWC9!&dDPI&18qNf@71UCMIOQRrI};i=NglILb$3) ziKYV#8^7+)BHL8t$aD+S<#eW~ZT{HMKG-AQxY%X@-XPdHupe7wcjA|v-0_{5U3bW} zyj+Ig4k)R2x-n5{z1oYV6`$T!`R2C7_xt!O5#{}puU^>vHE1Y=S-rbhjTy!-zdOTL zSfK+g)DMqPkGR(KUki)>KXhB0d#f%I;!O3GaMZtwCOr#R{uhqbp+z&%+{8Q{<{BdzZE zr@<8P+fKYuPw!aQp+XojEWW0Y%8`mb5s*}z)7sPq*;dKbnRj~=lJ2f&Yzzv2QJ_w3 zCa^B&&5g;Nw=1ynECdC#da3G>#Ef3iqZ>}h zIN0y4H}8ZP7tQj*|5>wGxM|8Z#%s=xj`o6S`N7-;__cOAIy^WaQ%=Du)0fcqRf+G0 z5gzyJPp?Rw>x^m<&ydph=T7>*V4R<>f4#am7K6(74j^NU37qtI`C1OF+eN+-=q)5! z+%+wQjg2A5Wk*?8BCe*Yj(;t76wCo;F$J{BN3*$p@ObEByun+M`h2yTr?>tlO5mOR zB_HUdk9bAkLI`Wi$v#Ujx{xES5Sryu3gJpZEL4_YkF!Koj-kYx(TN| ze|xyf#KM653PNJu{H~HDnV><{QfGDs_ijk4>?{bm?92k9SO394G#mG+(u43Q9LC5R z>to}gWIv5oRWQ%Rtu|j4n_$ zA@{!@=^di9%2^WNXHGwU%+1UsV{B}k>xj}oa8evmEv%Pog1H-eky# z-CU?1?xWy8PtD59t8nYl`oR_oiNV@qLtOfk@&^Y}lSoMzk^!e1vrLCl-&t)0a|a7D zu09;$9NiU%3_Jqg#c+u$r?cveHY)%RQl1v!*~58VP*7)VdG#ZL+ib&3i$zcmiSfkJ z3%3LNAX-PNqYh#Va?AcUf1qg_#tvQ*r{0W7?o1vZ{~}iTVX{Nf9EEyHt)2qOX#!@% z%cXjG!vfO9xa9*YC=(&b%RaZ?_BfF|_T8b=s%2*fLo4pwZHA49^H$zpOuP-}Lbwyw zyAuFhFnA_H9YW9v1g^zc6FF3P$f*TdZ4>nsGuRqj7~^5(EARU_J1kz-%dXM#Fs>|F zZ#eE^hn9meMKNw~rD$EbCJUJ-B6_UKB4;~4A9;GjV`}H8ZKciw?cbYW>7$EEoW@o0 zAQ;*j$USnhwwcjf8c2=lXm584Z+}bTp*A~rJoLw8K7a25&3X4G`|fV$-zuvNU7XD^ zxiDoFZcf^EC#(gMS0xN)3Vz`jE9R}9gO&(?+k))uRwu%D8o8z>1uJd-WD|u62!cQp z);OLYgNm0lBGwy!!!1~>vrVl3i?~y$Zgp<w!3~8))tZwA$Kv>o+Nk-%mVG{jG&p zW3`Kf9@66&Nt&Kl)1RXQ3Po=sH7b*^KMApt{Y=ZtOLmQ~=sShEXO`^o1YsT_IyAo{ z`e_0AT-%*zMR%)KGG?yIEj8fvZc4UDbPB_cgbJRGE4gXrxcPRY#q5X6gG=oMb~+HH zg(gR(m3-;xsi#G@k8AH0W~H=@%yBVotXfaA-#FWTjP)RtBNb`nRY`B}I)iJPu&~GV zx{~)?ehkRV1A~d%-XXV9UYPsn+=RiVol}OgOp9Kn8rv(r%!Yau6KyqzHLVMLWJ`~0O>KR*bRuoe`NE^_Y^ z>r1ClBEG7^a(H>42=Y92Dm|KDn<+ z4ZlvE?7YJ9U8St6|4;iBu-tl^s^5~XuRY9ee41vPn-19Zxl+;jvUvvU5nCE_2Lo1l zoe?gh^%2)5ko$Rd#6{}fs-D!LH9s}Kxz!g2jiPO#=9j$&dNp?B=!Mb7lv0kIyFR(Fe2hXnP7^Lvn zH8ZpUH(;RLGa*9CJd8bmlFpXZ!zuXOhhO{p+VIYSyTrVkAb9`jQ^-V7B2lrnF}R^_ zHu}or?QPogv^w5np=ukEI5N^Q;9|`Dh!`1(MQj!(2nx|5`^M=B)Q#mv<0hyN zn+h|jW&eMCg3@vq{=|LPu`7EY6U|j@C_d@nC6h3*MIi!ibbNTk}m-o=I}f@+YbjO)s@CjwvRscwkzs&KHXZ#yObxEUXMO zmv?L+T{d*`18VJ(Z{t*!^5ngoUpG;E%M!^yMhEif5_UIsu7X(}B!w^2+|W=Nv=*Ug zHUHr|DQDVp5U=s(hqj22RG;v-HU{iK<>v_JLbV!Jy@Ka8vnF6@YcB@LZF*0{ho&$l zZ4;FXA8|Q)q>EU4?@qCB5lJsKHB|x4XsuljFqj3^_d8__wsGmfSmL9OTmITy&ILtd z9AMepXTr>HdonXU&K4zlkhJ{Sa;==t!de?=Ut9kENMpa@c7~T3o8DSwloI?~rOpIj z(5@O?{7ou{jT;{v41`^tt`WN2ETl-RC*-twWLmY}kUWtd9TC>pN2+pXvFvc-CN}7^x267 z4rO1$F$v5U1dOVdqs#$S137x`3P1mp1~j}gCszj420CuZh<*9dAQoRwbpRhRECo@x zfEsNr$W?;9K^aG){wOGMJK+%L(e)XAxs&5K8NMdWSl*j@<)eMY?fZjc3xoRbq$pcP zfs0T8P_;}vlk4kM9xv8`J5Ia+0z-EZ>qK)NtetuSN(LmEclt#7=34-uiX5KT?{4@3 zwULPmj;qnqbX-<_D+s2YOxm?_gAsRCj(hbzwr|;~?Jde4Q&eE@TP9H}-m<%Ke0h`H;#Re{;@s+9Km3!i;=;YR30$*qH6{>L zq4Uvc;N@S;J)!%hr?%^C(PDiO{2*Ey0KoGMRtXyA_y?Ez`AZW062vghekr1m! zD^BK8sOe8)b9Dv1kdSM)LAyQJ(7i~m`ZC2sOdMs7lV}X4&<=@Ug+17ps15*w-zS`n z%DEC~0XYgY4Y7~vW2L3`0xsRk&~OArgWYK%$l*0JX_WR&9S<t*!ASt(nW{Z(Fiov}sms|D zG%8Zr`kB@e%dpY*eg%V$aRr7R?7Q&vHe5mJy??jn{rIDw@WOMeb;VSz>fb=tkLrKB zz&>iR6*v|IZp;uDhlvburhaDHQ1of`u^N>!s$*w6BI6DkiOR zD-}CrMckF~q4J0bP|TnbI_>6L0%`h_oBfTBNr$0oLwLyP5g6Fd0SS(ypk!S>6G~3Z zcW)2e{Mj1^&^M;co>?Me*8JR&Pe~g`mv*el$3$5yO#S;ay8RJfhrgx!#!C_kQ|f>) z+$^CuEnNdvQk~vsD{U=Nvu=DV9-EDEY;u1tKQWtB=qu5jpbev_zOjw^ z#l=kh7^;!z1k*l~rC12lTxcu-ywOe!&w1Ad((&!n19MmZ2hQ_Lg@ow21#<^G!A0{O zw|Z@!gMSCZEOb>6*aqH({ zR20+x(P#s`f`bfE-fL8R<*V$eDTB4(dp<`g>Y-ke5)vA6rft&wvNFo=)Z?i(mAMuC z)25A8)cg7h64t)wWaV0R2db|u1WqwOtW0pz$=<$k9Lp35rCZRD~wnT`NAP|-wfwD%hB`9%sSKehQr&~(z_+)$r*&_%=Exa&r^jP%Um}^U(j(WsMo6lP( zHtQC!F;TqXRB^WYX=z(SZB8;d(E#}hb&(g-5@xY@!A%lJI|1gq*finsgDt*E4 zi7>kmiIbchME|snN*e&Oz_wF>kg$ePbyM;~VPCbRvtjE~I_f{aAU1OWKv*m%l?R_c z?`=W$b&9i?F66g3h?UTIg|{)oyEb~526|p0%|zaZTQgC{Y(z`r#Q5wr^)6_ugppUV z*o-$cCPG|z);4WS8C{A#t^Q5^lYg?~Y1xd-+vBx(Ryn9@0S=x?emfU69j_*R@sWDr zsqkGKPSScSCJiG)9TKz(sUtaXqqESNF(ksWVrFNkXgqN50&b z#qod4y=SH^YU>*;;KgJuuE=p)!f$o93$(7G;Y&`o*&DCMUeJbm4Mk16@?zG>U5uNt zC0F}8KT!R*y8#dADndl@+QmG7&U``thX|$w=$nf4{)Jfam_sJ#-P5xd{@gAmShq6m8 zn1`mI&_qIL49WSKI?br}wMV({P+!~Y=EL#%Dk&(_>bt#`C<6cO_vl>T+pCzEW9;l0jv?(L_Mxz z^!a$&WWi2!)=EsS<&b1)cOUc6e>1e*o#?RzK!3Q*zf+GDy-Y8+r%xm?6$Uk+;Rh(1T3DjIpTTcJq-G3)} z8>YOgsRwE2`0QtL)^M3y&lBaDJBBoCjHQ`I78=flNpV>YZ88+oYl>I?a;g23(*?EG*!lfJ|87sBuVoHBP_UWhb$-htzlZ zT+kU0LqL(m+~j!UyuCNhVj?RLY2P!Yk0ZTtgz_p|^j9eoTsf_Gilp7ju*e?g=eh%nS*S3IQ zw)&chjB8vNFsd(Q`LDR>ME$kavWDFM5-XGR2MHXh=bNVs=Q{SPfw-nhE9rd=9A0p} zo4-{5=ispP&R+SU=Z%V08?^YGgZhlo8e0Q+seys`mj}b3!Ac%@C#Rf)6HLAEjwM>( z*>yZzz4(U%=+niI;v=!iI0v~7CveFvw3s2y*zO}rmj8rmkSs$Ip^oG0Y~@^~sX z2kdV#$B{5t#C)bUU#P{CkK6x^TvPNFU@)u3~b&tVHOAz^-A-nxOvKu^yZ zyke;dmpMnI*QPNB`bqwg1=KSBFKlz5kBK;2b^3 zF+e3PK-!>Nk!~1jD1+`sX+=drKuM*ghoNEUQUnAfhoQR}I);wB_H54gcl&wnKX?96 z2KHWi?X}+Z_WOB53-oEIg>R;uL0#Uo`zXA;rT!z@TdSvB>Pzb*MwU?Sp=TYVcnm&S ziz{u%G1mD}(?T5DMBos$Kg&+^oWG`%#i_Ku=X+pZWO)*i;9=*9U^RT{RiR_W8=W;c zJm4%RE2|2Ul8MvNwuH~p^gHz~>X=!Y{yqbA=c_7<6*lWG#p#QHv0IsHA@nSXAdz~^RJzd6e`gcdVYSQG~ z9LO3%JYg;oMewzm6riOoGAiWc3I&m z02EltpRDME6nTFcxz5+T*0(`uSeB2&SqJ^-Q2RPxu`r{O!MEOq<(V>Hxv}3pXAm`k z6T1jxRZI-++js9Gny>3}a_Q`E;FK*v!Ep7SV`5_BA#oYh8T$tZYejPEbK4GAj2t+} z#l=Uw7wbCBcJP49dKDx(*u5aM<0i=k3H|o=u#Fc4Frb{ zL(WtYUq_fIclZcQ09c>f%*?B{Rf_Vsu`*|3ahC3sPG#9#Omxv!EyiLcQ)B1wO4z

Np#H5IqI&WA{h6 z;IC{HR<5zJ5mjsxO8_QKKi2YSo&kDU6gdzF93W)@|Lij`tpyN=WUdV8^*n^Nm8Zr* zq(b-bKvhplK!bwmH(G5*#k{^Q({&SPy1O+_t%|Z&-DHp1E4qI7jKA67Z<6MXU{*!@ zE}Wzgz8>AOi8%s~LG(1$J?p@{eTy0@Ehw@XGy^ZjV`m@w%=NUHbq;M^miI%nFE87{ zf+$X>MD|=rsPlDJxl4|YjIN;53g1tY@NU+x!Mf^e_{CDpI#e6Q3dWfUp5yz)YVKc`IILTo zvBy#TrM2`%%G=IvrpU{YR};ezhE)c_YcKz!-2;nd=30_i_M5yp7e4-sW4S{@2olUE zM+GY`=4_@(uAMlCIzKo7@JKJW<{JIkH# zO8gvpc@LMgMkMDUIVNlVBKd=Bo(^53%bG1P<-xZol5Dk6!Jm~A7`o8r%PwUYk9Th7 zBW2;Kp>}juAx!1vY+eJr#P`8`v5rIc)sxjbu35M=$_LQLCV0hH-sZ{?heb`yWs;sx z8-Y1IV(F`^bTe-w;DH}oFD*Og1>2ki-)TLY%zoFmmIJQm6qv`TIph@a!)M63?=ed| z*k`6uwJv^gK$)^8wr8ZYDR+!+F*VlK{<|d8+J-z3VI7T85a%%u-O5tS${e_KYEEF? zeo0*MS_x0Nj#Q*K$KaP+L!nf~woEWTHZoyE_QTpn*n zawof37SV==mvZzz4-P8K=oOq~pu|ismgeuqc4WIoSp1S#2Wh1I(8)&7UV&F-xRRVE zW4P2Y>RFzh9F?7lv!M25by{lc3thZzcL8c;;}j+3)R)#D-np_-dYY;9A3pe(Pf>y0 zWVct#PCP=UevBe>+QeKYRxQiwK;Y-l;2D3CEN^~cSJ|A&X@Vb^dexg#;6&M|Jn>{1 z*G><5bJ=3Hq7k)OgPfX-;fZ}~sO_>8j{I?drMd@+~0JS?jJ&evhK!eOl6h4P!%HJaX)cs#;cpWvFqhl zn&zHq3Uyq6b)_yXvp8sw;XjxGCm>iAaY|BP8IfjhtMHLJP6Q*%OOs}Fg3Q!Dyv$}D z-~CY1-|)ykd)QN|ya+UL!8GN|M#V&?Wq-O?EXlmQeylU_9U%CcZ#wHNpy`yu&~?LPm)HDu`}1F9 z&trI1i>CcA1nAy&es8mpvL2w7MJ*M}=c%ndjd7KmPau6Jz=~JU(*CrXLxo z6yJRt6Rw``6FR%%o!x&F6#YkQvFe6|2zE16Ab)jL-yEDz!^(`-f#P{8AyK;MuQy|@ z!jh&VhcqBch`ceaLAD~d&$9}>-o9~k^cTqr&jMi(bC5q-mID?i~52a->J!WaO|aJWzi%% z#peiiuB1&`WOYo{kKr+~J4=_lSVY8ReuxP< z9TNf^djp#K^Y13ndl9Bi_U)=EOd$1i>T>4pQQC8N#@lz6f`k;n$ZsBABkX7yE?V*! z(g&REDjJA|t^H9~SWuXkmXwet4gxks3!pNcO#Jj5wq1*cfeRUMa7*LbYR! z*uj^t=mV^U`C8s{HDK<8-hNnQfBS01c;p%L=UZEpdHKEs=`C)O7(yIfB5}o-{`Wz2 z`0;If#X=M#u)fdxob7bXj&xDZXJy4kdf2RY$2rR@Fbibfm%VfjZ1RwxGlM{ar*rJF0g)Uz=>0SOe7vLf_oI-`jhJA=JQ2}*{vO7Ddfp5ON)}R(0 zyaj>(yF|lbo8rSOsEk&Io7lN%E=6X6WZSk_+?b#<_tc;O3n2TTHBLFdL|m6>X==pq zdW0Lti$_&e-;OCK3SOf*a!b5iR!AsMN38@&m?r#z_2^QZsb2p)k1w-Wec{Tn*KE~i zrHRuypM>nZ9j$n>CtD-!!YzfFI};^g-IEnj27kA&F^^~*wZ(&296)x32)~3AmP>A& zAxt`1aMCiOFE{0%C@1 zYxny@;_ggg%QJHyX=SN1m+dD(eA@e5ktGS_d25~@5CFpPna_`eF~D_}cE1|ezkVn;v^!&Jl&AfX2#tQ6 z@E{(3kN>{fqPjZKVzED;5=wGb`O8BhWt!zxzYdq7#7tXfz1VLJmrZk=j!Rmv39hR~ ze5lGK5LH)CJ>M&ur*Ka>;!aYxO^R2U*6Nn9O(qn%MKqlwQD(;90m$n>k62Av}GcP4x9#b)TJhYk+jmPk|O6G3IVsHa>a z*Sa$?A3*3l61_zSjjJ+DVq+>PgVgldOVYuF@b`ZLEdzOj(?%_r?nHk(m##gH6btr< zDkWY3>?P;rJ}b8@H|IdTN>t0=u|fJ`cML^D*V>1> zGtM7=sCN0tf>coR?mII{__f)R8u}6P;c)P4Z)NJC>qXo(3D2*X$bJaSx#ME$qxtuj z%v7=SYRF3Z@P24;L^vD`(&)6TsuHB7%gQOX0`8|8AEgH#&M%a{TBJE6Yg8B(Q3gEA zYzJd`&&#wc%b1YB_mK9yKuHEoo|AsS!oX3nM@ih?ls!$>fb5@uVsGNcBrlG5cvs$2 z3G%)w{Y&$B^}o`LUa_L_@t#i8@_ai+(kz7GKdtu{baArbtUV^UkL@Z$)gGnPo9Pvy z=owdeoh&XkRzuYOAd-CBslvlkf^~5fIyDLTa5_a(6k$2%(%9Ip)1C{C1@ZTXQk=S$ z);1>jwzzfN(l_G=!=PY>Csu=HSXNFgA}5FG)G1{DTyIynvBTU;NxVh^QC+Oty1*c` zyxcWKn6%bkNP@zL6=OV6Up5a?CQ}SVD5NtoHUDppz== zl+!{hp96mM0>m_a(p_^$9>8vY|aTs5Gx?;mwPhrxmrQunxCBF70&K@2_ z;jx%}Wzd@8WX)X=YHJuqF#e=W?YIAyl5 zGHx^?2S-j~D-UKeN{i4xXbLlP8z2HixWhpp8S0VDuV+E2QTNgiNJi*A0sQ*$qgfov z;TdzU$|w2m%jjx(JrkTyRTS_<;UC=JP?)HvbP?EeVuIPH364eklFY%;B5D) zJ2~9qL(;)roh-JECIwNgWhUfn%9 zNmTUv)FD6ggwgjT_UdE!qRRgH%ZLa9)^X-GneYj+gz>ILrkBf^-?+IjHeV0FP>J$r zFf#6>7GyWFnVb8Ix+rWB=hT;$g+x@FtfRlJj9=uS=XoeG{FRd{$H&2&78=|RNg|jU zu2U#>P_U8x(wB_Q87js{EGPtCWm%BnpgZ4+8!er{60(cKqTRncbuagageDn-w6dmD zMTdY7EInJX`CY7A+X_47(|4W{^vL5yb(fYzr*^NBWl-iR8mXs>=EcZH zXT}unnkXth7@@LOWn<&mB6sW=yz*G@A7qh=_-DnEYB8?|G2D8kE7JyX!H&YrOKW3| zzdN={tICRT)cdu~{ld>u??1SxV5;$pb*^s2OFeq1+#hZD^=-?i`3erGK~a8c`QIG|{kg zaK+Q1$|&eibMrdQ$@oe~yk}5x(clJ}nj=unu3$5q0y?ce zC^$A*a*A12eQ2-{tuMr(UC|3vXzJ_fD~tI2fSl=uqH7kd-|OFodnsBfpR3>aFrzG5Ro0s{MwZiwCw@Fs^bBhqxr^SpPwSHj1b5AM?=}fL-syl_{yC(1h*x9e%>6w{@P1Uw8vL904 zy_xl<;!t}L$=Tx>J2|Ch?^j@fipp7zznb%%K>;)}swS5wX#krfy%~}HBP{oBtX1b@ zhAe$cAe3Uwu9~aX45teAt`zQ8Z+)T~7Sm^BoXOa5uPU{TZ@OLCRk7o2_*XXG8rOcUK1{QYR^9y+9>uGq*58UwN=c`g@ zP=MMGI`PjnZ&?S&rujJE^S5#gXdx+!2}LAL6p{V?TuW4ARv|LS*a-Hyy8Il!P1Msj zTrH08P}HSYnf7^1r&!n`ouI5BuU?QOO;p)h>e;BsU+?VSoFkM9i?0qHq0@Oprrc|> zr|x505058NRLiIyyhm^+?IyYF?c{ zUA>gV0^AGOr?nU_1J$@fp8M+huDh12x#omIqfA2gdJd8#vPXmACAZuF*pJjxlV;;P z>uNe*0b_JYpLcgId@hH69poI^V@I*5hn+0TejdKDU+QR4Z5e5^*t47wAL*(mXLT6e zpSC@lX0P70H_$LSrg~Hc)iogykqsnQv0joORX{4pW47HR;-Kr=@+e4v-x?bQ*j zmP9x9Ubo)g^s}t050;hfzkCf{9WTtntlWliQ|dNgd9Yh}(@~#@+wS4s#?4GkPdm4a zkeIHWGd%VAyV;WGu%d3rw(ad-C@4PY6KmmF9euxgJw)B>mZV6R(keq+C1ED67{${u zq<_$zqqU6ja9zmLP-|2ywLog7GhQ0$TybS;uB$t6TZf1pp#^LICFfg1Qp3Z{^!GNS zs!1lI3;VP80sdNhgv`ON)j0#yW_>2cZFt6gi}fDAwz|ALqv;HrsMnE}=1Yp-k>#fE z#tn~TY7Jj1Dk*V>w~%C!9;_wV#qLT=Wh@U@x>e~s2#30$lKIeCI)sJ_7oWP5rSz(- zT2SpAvj;nd*m)F4*zZ)U>`ec>q@DN3y4<;ZoLF3`k&)}}@6>7=@8!9yOa5|SLx+8z zMC=G8nSm$t7U6fZRBti9^_xF}I$Hiw)5`O)FnzV^3FGjmtP>BGaBW*vn2?ayXBqZ3 z<3yS^S3Bm(Y2>JyjdRKm8*gI2YNuZMW*N4&V?(UoW7NrBAt@U^i||PbZ=ZfgvytYx z$6e~~8rxSr0+ec@nJF%;@IM)bwfDJSbf3ziU4PXYySMndA(@hjkTu;x{29V{)^cDo zzbBx2@uOgy9lmPzCF@}}GImc?JA4OPcb~Jz!*8IBlGi*uHo7+#L-3?Mb;Pha3;&bs zocEPFcT~rkem`8vn1Q3(TkTom;JI@|HKz^6oTnV25`++kss3*ltSr( zYotBB0y8jHmS02q%CY?4ilqZPKhy;P?rVoo;#4cPK7kq%(iNGA@B01<6Yk{@zd1ck z2>o(Z5ml-NfVNpZY|QftvlnHF@3(MG21l5PfL)Ba%AUm`l(Yq$|FEa4w+7+?nB>Qy zYir4`{g0x95q2ExN@{JC7VZofUIK1`j*Pzingr{n_PlDq&hA zu+VIBpzP&XrNt9cNe;Kv96mSO%_2b6Wk}-zuhGuNq04) zT4W(fi^`j^*vCgqn3E5mk;D;$N-^Mkc8TkTQ(uXPOd%UUI&G1(Y7Eh!R~rN5JOMe)+zIe2}=zwHYvJ> zk#AgvB^nJuS@^>pW}{L@dGd1vi}{T#>bp}Xps+zB>5Y$IA!cP(7#u7JlK13}Jnzi!ys92ZBuhf^l(xN*hmETyPRD)MYrmNqebK~E>qG|6f*dcQ;s)o<~{k{Ddc zpYZG?sAO>m`-Mr?x}JGPAE2Q|V*&fs9V&CHeFowrmz@H-w$uH1vFo4Y>s$KU&C%@T z1T^t|M5;Q8cqotOlo^ngW+UYAnCm=EYQaD;B>fsXGc^w?Rd0!`w(y;$;ZEOo;qpc| zm@rG4kfrZ|oP%?l541@nQbJ2w`Gm9kBK+EYUS4jN%Lb$}@ERpWL5Ignpoi8yZluFF zBgqczy=Bk>JzC>>SDmDCTC!PxRxztF%=p`fK|YzRSvu3fiZ8X(JkT_ug|mx=IU?)* zdp946o<1F=t#Umalw<%2ni+EFuwU{cm>!?xxeMIt(B()t>rzFMpu_Ga!Ypk_L7%A@ za0PlLX{wY|3mv26RNE2GVhDX6y52_)UW1JG%CRwj5jP}M20LHs2-$b9o?$eU@wd7j5S(Y3kBXmtgcw$S+Lu$w-? zpJ>*Pyyd#sd2X?PPERue($cjxy{ZgA0r0Kn2()vt4R|E<;f0koq;K&bC&P!+KMxNB zc-^x;)C=JUd&VqmxDgZ<02)A7=3ao8p87GjRXTIAZBG}yh|?Mb*^jVD7`k?CSF7A5 zs?e))AIgJ;Za`SQAw_}GnYbG2Gn7<68wk50^HGp){4g_wX@4_1ia{VzY{Ve|Ob>i~ z$YHG%|FfZ1A}1xq+~nx6zX&vS0+au>FX30nDu`O96}+uw3rd=x8xS-kM-U>T!?&Zu zUrDw@T~stb4z%zBMuUnGP(>&x$hC`=e0Mj2Qx&>C_ular zVxnz%kC*=s(sucrSbp<%4q5xo&9mV=Or4)1&(nuls(xlFHUrgF(BLYPBuYb^d^9vf z^svYnz9xc_ZH@pw&L=fFAZ7-nHqhz(0l6LeDPSe<~z_r-<8<)}-$9&9I-1=0g4OPYTjJbz#I5EE{j%*jvx zR2G2323iFEiJF}M*_c>j1aS0%H2VMH>RJ>&3)28f*o|QKX6^2Ov z_lD7l$z*hzvgKyYt6k$&$m5++vyjQ2MgDi!M?7Y#{~O33g>De%fu)(ndojt!cR&WW z2t8Hmx_|(95lO6l7f#T`Pl6_Pg~o?5B{Cf7)@x)By#BZ z6KFx&-{RN}JjV3+r2}DRLY$(rn#uXc&2`iQO#ysr5HLBvTP3cv7fu>^ z4q+lSZTgMCCNp}3eo3dyLd{kFd|b*0;A2R;@WdzYVG+pd0ZBjk+U)(Mj%jE}o+U`_ zs+YSEirkA27nXAp9cRG#EjeGBlH%6Xqm`tY)tPX3a7=`M-{buyx;5x%(V6@KZA$@e z?lJ?}B@Cc2)Xpw9^=J(`%ROT`z@p3a^BV?93l1*F8+!L=-A_J{U6dEWp_}@0ecF6= zye`tyN>%kUXzSGk%%*0{%4XDLwLTA)0`cU`%t;?hyzq5#Wt*W4mZ5UX-$8U|t?^Ax z7p*=Pe7Co5ZtM_COd@vkjm*ANP1-)XTB9*x1sL+1^%Ln{Mf(RPd8jPSX#GW2BO{}9 z&%Mpv)dq&CnVGcQ+`Egtc@kg+C`G;2CIQkAUhBwi?;Kafbqb2$j8^Dueq^$oig80|EMB9dspXFsgEX9cEO2);(VKhWfdTy=?=pL(KW0PG`S;^*{ zWkF|@rHMI1PMsWWTcyKQy`K--&FAp{(%d-T2ap_%O-wX*{c>1AM*+93Ay=NKKTd(% zRlw5`UH`;TAhLU2-;#FHMTS-FEeVld69ly%R__bG-}3~$P~y&?!*PvxrUljdK{CLU zA87HEV;+bMLj!|2(DlLk{;&SYTLD}|&hC+cGG`30Rc}H?g|K1_|7u3g;?k1A7z1Zy zStV1RpAy&GyWM-$)OSLLjRT)76}YjoHG-L+ z?Wn-e)j0oWg++_@D@{Tly6kVSQVY2(7&Ba=rp{ndPc;L5YrMBl2s+IslrNRZKQL`A zl!QnX6vl;^ym`mk-=~w)0&sKv-pN7D?GThNc2}O3_T=R7`TAaaP79 z)~tVU^u6crQWd_c9TFQuneo-$-Yv00TK4w#MKaK}v}z@hkp`kKR6>CoI&_XIorl5q zY!`nsFguy=s}+bIAjy|VS~a*f;azUyb$9G*Utg~6GMk~Y5U9m2%iX)Vg6iO}i1KwS zqvR@4FFgt#>kQ)8uMV4A0M=_%?Cfn3O|?Y&`R=(TD4GXdim>>H8AqCGc2IP(_sf^& zj(+EN%{p#^W9?;17^{_ACE}&~`trATf!+Y!&~;sktgpRYMJG$MuD(9%H}t!O`WABP zS?`ONc zj&S0F4gj~v(qx_cp2_}}K_nw`eEc@3xPodFz`MeXZQ)~ZT_Qzme2=o{p2cwS2$+rq zHW(WT6{;sQpR2 zEmvJpUyqx(VSeEL`)bx#p&o!Ng82b2EzP?E4S@ z>I5g@J5Ij1C#PeOwZ&LFdnU%m(EvuduNTDKpN)}pA*L{-39i!+aYX1L_tz; zc~TN_3o_t+B%;22O4!&X67y~c`1!#i$tM=p4{0Cofj@XWOFZOtE8NV4sKf4#rGvwU zms8;|=#nDowDd1ahZC_8WNUI5O^djQ)IDn6uAK_dJ=;g(SEQ4-eO{T(U^?@EsXz~o z=Wk!Ey#e@+%g>)?{iG}|zm*@W6LJ_`t@xDGrp6J-8U>%4R@j<6pZZ+fCvGTDB9!d! z_CssX`3&L0QI#OhaOw=9c$A9eMWbGRW_-KRjd=c-aY{Bd)Z{xg{is7iSvgtV;Mn3Y7<0nVJC7D{yP!^R1?pwa&C_*Bs8CJ=PO)9pOdxo!73eI*f|R z>}d$XN4#7Ii^kKRxL|egKv)k~z5S>~DhL$FLJzS+knRxYSb6sNO@CUd#b6*GVKDDG z$Xlgm!DK3I>9SLoIHb_iJ$M()O0pSyPr(lJb0u=S~iyKzm1D?TUdDtsllhNYOu~JgAg7UoBT4?ilwwXT8U&@{Ci7;IVvYkR6(|5 zFiwPs&xa5Wl2R8(a)@JNQCP>c3f;nEJI7A^c)7SY>uH>Oa;gd5g09`4A?#p;)WWZ( zPPPjd+?M6Z;FKCw}}0b6!h^ z3Y_Rz?zG?X@+y12`fNzZ0sIQu4sj0HUh8sDq6#oMeH#4}ud&4-aMMy2z^*08g~^oN zx+TG9WI~94`ZT}f-}UW+?Gi*62&2Rs8_&&T>l42#i-B#=_}L8V1>A9|QI*gADs+pE z$uXS~KEpC0?+UHZ%q~k^4}8fiXZ$I_jzpte2w}ti@7rk%z0lE8f&c2p$M#Ivo_jQ} zznnbI`rEfAA*Wy9U|qTfVw9oDUKp);E{S(C{~j!H4mfoxA;u5rRtNiG^#3G~Q7}Xh z2L&Mb&6r3hX*qwSUgp=37@Lys$D-}ng>Lt18bG2HsHbgMA06&K85SndmtL_fNcC4# z`83UmO7?+JWuY}gSll4#$q4Veg8bUbOt)vbibt|J)@OhYmEHU!l$j`1VB+??o87s3 z%K)Yp9~3OC#NQ74`>XANQbyf@B0;QWB!Cu-x;-;v850@#E?W<6DjgIS^J0hOCb{dY zl?*+Nb&|>4CX`8VVj@Y**c7v{VUCln(O}6(Ia{KlJV3(V?^MMpWHrF)fUXwjfMdy{ zA+JS*H;h$3Q*9DbimBM)gRHf&k*(iPcR6`Eh*s72Kc=9C0Q^FcJh`g3D#OB(BbTal zF*B_|aO!pU0N9G!UhS6c9aHQwNR1_tCd^(C*$epT7X19I>QHxDaF8{WGM(NIYAiNX zo+K=xiWDd){`EW{V9x_0`*lIGz|*H0?uQjpZZGHbP*DKh?+*ZL#a)pu(-KVE(Qxlx zen}Zz0)r60NMcGpn6CCd9Weke04jIfUbNBcw8aB;N+zULzDz_w=Vf;GF31Ts07d`s z`A?udzO6g;sf4H7!j~#SkMdDDXaY_v9E1(5q9MMa4w9v$UIo}iA`pS2gRYX6uwwAbS8b4Q5zI<%C)o8%_(dp4de%7+^dcZE`iekdijzH1Q2!_@XUJO1cZi8KbB-! z>0%*YT~#%4$e+8-|GpMrfvJMLJl&#MLqI`YIWRsP!UqGNhZ++PVc`u&-!n~HYn`7e zgkxJ;d1FrrZRwh$&lnq{A8JNShetGV-0y_>0-^`@HTfvM1*&S@+qZImQuJ7pQDh|N zg2LSeWEDQ+Mne!wL!VB-c?Qker6IVC5^U`8EcFHwu6xEuWlYft&VEyjHsXMkMj`cQ zSVGZBvcjGb!+;_y)t^AC3x#Ou-_$)s#^aInJDydRktUn7-y)%Y;3tKig>U@I)<;oY z__nN-sj~O&Kl?j$yjNe#1)bUpv6e)s<>6gvD2CqqA+p#8ZwhL0ti~P@Y3}_v-mCCq z4k>q#qRS^jZ02&?kI?0I#k1lB(#K4!hBNsDUAhY6y*h_T79ljVgwErqummI*mpkM1 zb&Cm0HXvO%3bd_Ik?<_Dj*j~nfO{YxN%-%XF@hCFG!PGW%-7z~X$Yb&b1$|D48S!( z0`CpAN$b)OXzidYQsz-QOu$J~)oVjf^YMihRuv9C;4Km2)f55IoNW3H zs@u2C^pIgoLBTy@ZX2KK`rrg{;CF;;AQJjZgoG>&oC^CHgi>GKyVrk#0T9BwEPf}M z;&*>ToGflp+*%W!r!>LPVU!UNN;^?Dkt<&+$lr-@}}CwF_Bvc3D3g+X(K z!#YSnKLx#?csTriPu}EUK=WHNHh?r&`RqCNdEHrX8x!XKeePT@Pv_x02{AIV=7OgZ z$EpMJ8qA^Vx$W#b{6GD})7+@K43@>Z?>@K>Km|SE>1~i6Dzd@99({s0AM8CQV+~mD z_^1-~^$LZ#k)P9)(8>)#{bf#QP+0$&@#|M=!bDOW4WEUV%zI&9-(xaXnSz()>deGK zX3Ep27GGntL}LZb$(O^N`PU2bxd$7hJ$tfn6k}s+fBtpsFcZff@7=9!ej!U8?Jt4= zqvixijyM7Cx*89PX~S}I-eu{bUtYN2VEPeeh&M@!7sBGBTWc$-H$UYJBa;Pkc{qy4 zHqHne1>BjI3yY4J0Dea~z(hL>b#xDV%=W=Tt z2PN>B|KQ1&a|2~4B0U-528Wxvp4?A-Vrcky;dEkgEUdPxOz`Wn?`lQ!x_KRWiFnS$ zx{d8EYeYl>R2D6Cav_q!sz157zqqG-eP$l3nq;)P1_J^id@gXNlEgs5O)6P+U2MqF zHwm}tq5&tPy0a}GKYTU~WlF`_T@x^Ev-tf@VmC!!$TQC&Wr-fJO_J)2kXk)Ys>tB! z$6dG(6&aNgU+%1)Q^;*h&;La5uSh#?4n_U@53nM)A2$PaX$U~8z#O`UAEpGJ;a{Kr z$r5msYW)74Fgf<^O_r`A^Vm(AOP45T2pP|qnXP~SMg~XQz{uVR@jzJ7tKoFo*y=HH zb$zLmMHs9ojo<``6n`DvbKi3z{{5F~Ko`<_ZAAt2J~?K)D$ijlmrL_~co;QOh_+Eu z#Mc}i5bL)_no-(jf|zdB&l?*-bY%tlLPJI7p_-4Snz*jlz?De|p0gyeiYOmnoKB5L z6?X$T!1)x_ByNidsVO=k6L5PYzqf&BXvl__!bg++6<-sVc_vpbF1Q2%(Zvtb$3jqO za${Z|%5FPX(|I-_+CLyX7kGy=QP0;KLoK`sVduLrX&UFQ5LQ3mGPVaULK1a}2g0(c z#)jOwTR~S|erjPlH3)D;kMDozG&d=jLV4o2Vp}afF|pIYNOG6+FAD^iBqaUIhZ^Q! zKKcOwiZt5ywUfJA$Px{&f@`)uW-x{p>WRWdDcMhKe z;MquIh3KV(>Et{kJHK{yp+$;Tk!=r1|I5&qdRLUG^IWibDN{yCb3T*Zlb$Z?TEG>{ zrwu`C6yPwEmdQpw%;;=cPOLWV_jX|AW%V=!+6&)uAn>qc)ls zZEKePBQzAtd`~r)g7yycl`A-Nh}|K28INayaTfRC<+aV`+gj-O=yh<}aVf?N1aUP1 z9vUj}ITpoZiDSavxzoNdYvx(_B2N=QBLlXtkVbM@J?ViDJ3sdokZ@5~Z?RSC=+Eyc zRqM9Z{i!87ybx4(6jDF$8LK4}x#ld*b;*jHr$;`r$)=~{S5aD8O2v^Tlk0xWY~IQk z8gi7bN*&}{M{k}!%>uBiM2>1H1Y`JV}`2 zCJjS-238eOwKvTl?`_Kc`Dgo25X^aabacJGnsjT@k& z0rasmJ6@{FyUNOdpQ(11I+jhWJUys%cRjtgOK5A3FmJ2!OkK|o(CDmxbLzmn_RL$* z7a$4DuISm@kV_Xgz9&4ipaq}>7ohQcP;mAJ;_%k*0o~<>y16ePAhNlLs{kl)&z%a( z7KXFhB01E(q~6W_WD|5=ia9Lxs_ds1PUlorMP0d?UY%u_6ZZNKMY?;BPC$(qNzyby z6DCrhfWgtJ6fN5_S#(tu0Iy`i181}6!ER%V|mKdnFAx7 zxS6FLLAa^dTs_cySkJ(;Eu&|bNHEmPJbd-a->h4~AtTOv25*67UH$nNhmt(*nX7A- zdB>wVzTtEwP;<4&DDPxxmHEf`ct#58oFVjJSUiN@+g#wHd!!d*@X2YVcx2-MSSf12 z4eIaT`BF;@aHkA)hx~E>07|Xm>}Riir!M_-U57pVa9F3bwBL0jy=Z#M+}F>K_sv@< z@p;M1i;(A8K8&hFNk~Xg0{+pJtv}^WQn3(EV3!@jF7W2T{>JP0c<{vO1)Z$nYQyTu z8B525UAI!52b5jtTe22mpTGUuaFUD>&8nYiYaVHo4b;=u=;_n3;pEJhVRdrEHN^^P zu(MPbBGcsLoqt&1?X|R0++Lb{<5G74{uT?brt{i5W#p#>Ki5UINH=0vV%x9w?~XH0!1Qyc;pvpKwKWEj;+qt~ z=eX=}ic!1eTtoi;UECu2iXd3|#30TsC55FQr=AtXt!iYJt|#b}p3Oi`dP*;B+#z~D zVM0Tn`M$nPb9uvWFEgZ->hhiHT$MUWNkRANk0!uPZtpt8XlQHu5|6$`K|ui^n36wz zA_S8>R|sA>cM5_3c@rI%mPUB#CKuvQ&HYJU=j)>=-thAB@;*{#F{omR$=IXe)GJW| zp@p@Ljj;Imc+mY_V~AwTk!FNY;m9D;<%6!~I0*`oWWM1S5}+YBNUOoeiMVGxAaOnT z!VE<$dHzgWd{3ydC>r#OoO?w^f2X<BHDeT#s?etrPOW)5lqFCaWF zF1xo^TQOc#zoVlg(!=2Y92!H6K8qno_ypL4$^zCOI|!th?x9zKHV8YlWV>90%J%78 z2fvMuKB-)96*@~!jvuhC&H_#5=0?B!t`Uh@D=$NtmAf%HRl9xzhM-gR%NH+@&ZH^@ z((HUtssD3OOO7Hxl3KyrcD_4H@Wo2PQrSGGC+K|W23o{19vm49+`X%!o~qDsD_B@< z%#qE_&k8i=y8qw-+d-{Xcw*ws%DtuXsJl;J4-O4MP8o|oTgebLbx{23%721NUH}(i zZELHz@w)C@Fgv}NS4DjgoqJ!yn|JRBzrQ{RNd`R$!$+2uma+j%K}vG6-dZX6LU}mm zfF7{C=x%ljEW`h1SSVJdIrp%;txeg>%S+2cZ*OyP3Jmh|=VRx^evJ@NS(ONye!qS5 z2FXj(5aA87hykyx)ePXagGG1KnG~avLF^7(WCj|^ha~ITR$|NU!&gH8CiEi*uCvL4 z@K+0&v@fjKb1mvN!$$wodj!o}=*p0_);L?lyrs9 z1tnNdg|Dwsh3yvjn>Z!RKjCjatgv+me?w@%7Vz=6<7|QBZ%8>ucIVD7Cz5j- z9+@mMDk`IqC44~oL4tDrzxa>YsXF$f#9s~1BUrkQ-H~F zGloK(xVE~Q*XYd3H}hYsi{OM2G4}isSs}l{FJ?RsO-e2LZXJqAM zWZH9|)=mPKqZ^Tc2GM8$LBdiUUvL6J+ZNvH7qGmyoCA1KxY#tHH)=i`&ob# zV5OEK>VaucH-P9b0G8ITPd7lha8@hBNyHP0NFkc@45FFY`sEpbQvryN9`NHvPxYY& zJw5$Y@EC~hH#n89k8KsF0XQw3vRF7kf0*q^YG!bpiFLIAjapIpMjs;BbrNHRTrCDm z?3uhSBYXn&maM)2#smExgyPly`s*)<4?)Y>5-(Q0e~}Ny+|LtaA0t(vnx>o};59v5`4`7GU0} zfZn3FWevS{QUEMX;j_B4#O0A{xhOzO^A4u9@?4e4pn1exR`D=vHHWZp#eTd14QTPA zzvNM}y}7eKg8?fxW%~HhBhpkAqj_04Ih8^-mc5U3!TV@FdzOeQG*iW{B79iwOADS( z)CZQ$#JP8Y){?TFwG?8R!D5Hn)rY&7cN7e*mShOKCy{~-At51!<~XLsp>i#-F(Jtm zV*4tfg>#gMdl9|I%EMN&nxK{QeU_lPXEI=Lci7n#o`XQu=UdX8C1RqY2H;Zvj~}}r zf%p6O@3p-m>w(mekc*)GZO(oXbORHU6b-LcdQtod#1q{}L7Jwfrb4^1N0L%f8Qw>S zfR}6O>BV>fF|jt|z>DyiDC@NJJ8Js%tNq8@bHtjH6k#Jp_7hS&+uLEmc_CeBb!PA* zILSVA<%50gSW7Jq?ObtYrI=4Z%o6Yz=atd#Yt=F{*pmqUZ24FUK%OB^-j~3jMi*=)H8N4|Dm-l{C;3)O@ZpWp}IkC~ITG$$73*62RevB)>XIMgWqp6SRQc z*c`A0;l?a5xYiCs6hM}7aCB7nJwwh}Vgni+hsDJiEQ(P8L>W$3ULz9|!a`p`l%R9Q znZK_l01`C^s5I0(7Gd3)I=4PRM-3ltAhbUWM3qL4fk+@VPsV-`c<|2N-qBbdSWA%H z@gyzViTC%HdlFeFEa{7DGcruw5ACc+o4uGiv+{ zK2d(IzYLhUxVW%3Lnu&;Ksh{8V*ebxd)NrWKmR0*k3WkQ_1t~k0J3H>RFkAMhCyp0 zw`wt({r!EYksDA6^jE&5r{4kkfXuiR!l!>+Er+ffSo}b|i)@ejUKykZ!+iYsQB04S zjV%Chb=sfHZSR0|uG}6Ea08r!+i6y1=*2`JHBdNgst;Ts{p(^59U`HqWE(31lm$>| zrZhD9|`6>HFEzx{ze0-6l*Eq6V4${x>pSbHIMm$?q zapy-s>Fm|QH=jD%pS?;NyJ*(_&xP}>H#yG!C{N}-y?Unf!>2o)qu$q*&X7Nh&Qg1G zb837gWX8sRVmLa|eYw=2GQQ2LYQJ?OX89$5jG?JSL7zfF-|xBrv8q%Il2t%dROy*3 zV!L`fY3N&Jr3eltSt1;<~#df*Hh8JIp4*aopJ@ zTGrRst7U1f1Bo>v>~wNvWUIhxc6L_A)YOzfbmP=73)|e>%*@Q3jCgo{34!>73CaZk zjP&K|xTKq#o6*S{0cSPQ+l^ymPw9nUeERzJE5LzT^qaTDqJ}G8hK7fSZxD&buC9E+ z^de1wr#-lL&z`#YRL#f+cn*QkG(By?%ggI9)f9eN@^fHd;P19JQws~$gM$MXG9O1m z^3YRHPZ4)_cd#<8-QAi}($bEAmHcjPW%}UZ^WdkL(NXfy&=8egNKj#}RsK0>Q#R z@fY|kx4s|}G?kxqXeAS}v($TdS3#Mr=9RN?TvQ<@axerJ?djUtix1piKdF z=o$^po@nh7!tO98i~XC63jh80ji4 z*zQ8y`S1uzSOTAf+h<|#7Q!dw4%9{m`p6|hpq|j@|Nn(+=kSK?_@aC@Krsk}tfbQ8 J>_<;t|2Ib!DZl^# literal 0 HcmV?d00001 diff --git a/joint_trajectory_controller/doc/userdoc.rst b/joint_trajectory_controller/doc/userdoc.rst index af495ad14d..af76798305 100644 --- a/joint_trajectory_controller/doc/userdoc.rst +++ b/joint_trajectory_controller/doc/userdoc.rst @@ -192,6 +192,7 @@ Further information :titlesonly: Trajectory Representation + Speed scaling joint_trajectory_controller Parameters rqt_joint_trajectory_controller <../../rqt_joint_trajectory_controller/doc/userdoc.rst> From 71ccb39ac264c2a14e14c75a41048d1534a4cd77 Mon Sep 17 00:00:00 2001 From: Felix Exner Date: Wed, 3 Jul 2024 16:32:16 +0200 Subject: [PATCH 10/43] Use a subscriber instead of a service --- .../joint_trajectory_controller.hpp | 11 ++++----- .../src/joint_trajectory_controller.cpp | 23 ++++++++----------- 2 files changed, 14 insertions(+), 20 deletions(-) diff --git a/joint_trajectory_controller/include/joint_trajectory_controller/joint_trajectory_controller.hpp b/joint_trajectory_controller/include/joint_trajectory_controller/joint_trajectory_controller.hpp index 6b90cb07f2..e1ac786052 100644 --- a/joint_trajectory_controller/include/joint_trajectory_controller/joint_trajectory_controller.hpp +++ b/joint_trajectory_controller/include/joint_trajectory_controller/joint_trajectory_controller.hpp @@ -24,7 +24,6 @@ #include "control_msgs/action/follow_joint_trajectory.hpp" #include "control_msgs/msg/joint_trajectory_controller_state.hpp" #include "control_msgs/srv/query_trajectory_state.hpp" -#include "control_msgs/srv/set_scaling_factor.hpp" #include "control_toolbox/pid.hpp" #include "controller_interface/controller_interface.hpp" #include "hardware_interface/types/hardware_interface_type_values.hpp" @@ -46,6 +45,8 @@ #include "trajectory_msgs/msg/joint_trajectory_point.hpp" #include "urdf/model.h" +#include "std_msgs/msg/float64.hpp" + // auto-generated by generate_parameter_library #include "joint_trajectory_controller_parameters.hpp" @@ -172,8 +173,8 @@ class JointTrajectoryController : public controller_interface::ControllerInterfa std::vector tmp_command_; // Things around speed scaling - double scaling_factor_{}; realtime_tools::RealtimeBuffer time_data_; + double scaling_factor_{1.0}; // Timeout to consider commands old double cmd_timeout_; @@ -312,14 +313,12 @@ class JointTrajectoryController : public controller_interface::ControllerInterfa void resize_joint_trajectory_point_command( trajectory_msgs::msg::JointTrajectoryPoint & point, size_t size); - bool set_scaling_factor( - control_msgs::srv::SetScalingFactor::Request::SharedPtr req, - control_msgs::srv::SetScalingFactor::Response::SharedPtr resp); + bool set_scaling_factor(const double scaling_factor); urdf::Model model_; realtime_tools::RealtimeBuffer scaling_factor_rt_buff_; - rclcpp::Service::SharedPtr set_scaling_factor_srv_; + rclcpp::Subscription::SharedPtr scaling_factor_sub_; /** * @brief Assigns the values from a trajectory point interface to a joint interface. diff --git a/joint_trajectory_controller/src/joint_trajectory_controller.cpp b/joint_trajectory_controller/src/joint_trajectory_controller.cpp index 941e25e052..5268da68c8 100644 --- a/joint_trajectory_controller/src/joint_trajectory_controller.cpp +++ b/joint_trajectory_controller/src/joint_trajectory_controller.cpp @@ -914,10 +914,9 @@ controller_interface::CallbackReturn JointTrajectoryController::on_configure( !has_velocity_command_interface_ && !has_acceleration_command_interface_ && !has_effort_command_interface_) { - set_scaling_factor_srv_ = get_node()->create_service( - "~/set_scaling_factor", std::bind( - &JointTrajectoryController::set_scaling_factor, this, - std::placeholders::_1, std::placeholders::_2)); + scaling_factor_sub_ = get_node()->create_subscription( + "~/speed_scaling_input", rclcpp::SystemDefaultsQoS(), + [&](const std_msgs::msg::Float64 & msg) { set_scaling_factor(msg.data);}); RCLCPP_INFO( logger, "Setting initial scaling factor to %2f", params_.scaling_factor_initial_default); scaling_factor_rt_buff_.writeFromNonRT(params_.scaling_factor_initial_default); @@ -1626,19 +1625,16 @@ void JointTrajectoryController::resize_joint_trajectory_point_command( } } -bool JointTrajectoryController::set_scaling_factor( - control_msgs::srv::SetScalingFactor::Request::SharedPtr req, - control_msgs::srv::SetScalingFactor::Response::SharedPtr resp) +bool JointTrajectoryController::set_scaling_factor(const double scaling_factor) { - if (req->scaling_factor < 0 && req->scaling_factor > 1) + if (scaling_factor < 0 || scaling_factor > 1) { RCLCPP_WARN( get_node()->get_logger(), "Scaling factor has to be in range [0, 1]. Ignoring input!"); - resp->success = false; - return true; + return false; } - RCLCPP_INFO(get_node()->get_logger(), "New scaling factor will be %f", req->scaling_factor); + RCLCPP_INFO(get_node()->get_logger(), "New scaling factor will be %f", scaling_factor); if (params_.speed_scaling_command_interface_name.empty()) { if (!params_.speed_scaling_state_interface_name.empty()) @@ -1649,7 +1645,7 @@ bool JointTrajectoryController::set_scaling_factor( "This will likely get overwritten by the hardware again. If available, please also setup " "the speed_scaling_command_interface_name"); } - scaling_factor_rt_buff_.writeFromNonRT(req->scaling_factor); + scaling_factor_rt_buff_.writeFromNonRT(scaling_factor); } else { @@ -1659,12 +1655,11 @@ bool JointTrajectoryController::set_scaling_factor( { if (interface.get_name() == params_.speed_scaling_command_interface_name) { - interface.set_value(static_cast(req->scaling_factor)); + interface.set_value(static_cast(scaling_factor)); } } } } - resp->success = true; return true; } From 1fb38b8c3ded349aec0e85c4c1021b460fbaa888 Mon Sep 17 00:00:00 2001 From: Felix Exner Date: Wed, 3 Jul 2024 16:33:03 +0200 Subject: [PATCH 11/43] Do not put the time_data_ into a RealtimeBuffer It is accessed from the RT thread only, anyway. --- .../joint_trajectory_controller.hpp | 2 +- .../src/joint_trajectory_controller.cpp | 16 +++++++--------- 2 files changed, 8 insertions(+), 10 deletions(-) diff --git a/joint_trajectory_controller/include/joint_trajectory_controller/joint_trajectory_controller.hpp b/joint_trajectory_controller/include/joint_trajectory_controller/joint_trajectory_controller.hpp index e1ac786052..fedad4cf7b 100644 --- a/joint_trajectory_controller/include/joint_trajectory_controller/joint_trajectory_controller.hpp +++ b/joint_trajectory_controller/include/joint_trajectory_controller/joint_trajectory_controller.hpp @@ -173,8 +173,8 @@ class JointTrajectoryController : public controller_interface::ControllerInterfa std::vector tmp_command_; // Things around speed scaling - realtime_tools::RealtimeBuffer time_data_; double scaling_factor_{1.0}; + TimeData time_data_; // Timeout to consider commands old double cmd_timeout_; diff --git a/joint_trajectory_controller/src/joint_trajectory_controller.cpp b/joint_trajectory_controller/src/joint_trajectory_controller.cpp index 5268da68c8..218c9e1c5c 100644 --- a/joint_trajectory_controller/src/joint_trajectory_controller.cpp +++ b/joint_trajectory_controller/src/joint_trajectory_controller.cpp @@ -197,13 +197,12 @@ controller_interface::return_type JointTrajectoryController::update( // Adjust time with scaling factor TimeData time_data; time_data.time = time; - rcl_duration_value_t t_period = (time_data.time - time_data_.readFromRT()->time).nanoseconds(); + rcl_duration_value_t t_period = (time_data.time - time_data_.time).nanoseconds(); time_data.period = rclcpp::Duration::from_nanoseconds(t_period) * scaling_factor_; - time_data.uptime = time_data_.readFromRT()->uptime + time_data.period; + time_data.uptime = time_data_.uptime + time_data.period; rclcpp::Time traj_time = - time_data_.readFromRT()->uptime + rclcpp::Duration::from_nanoseconds(t_period); - time_data_.reset(); - time_data_.initRT(time_data); + time_data_.uptime + rclcpp::Duration::from_nanoseconds(t_period); + time_data_ = time_data; bool first_sample = false; // if sampling the first time, set the point before you sample @@ -948,10 +947,9 @@ controller_interface::CallbackReturn JointTrajectoryController::on_activate( default_tolerances_ = get_segment_tolerances(params_); // Setup time_data buffer used for scaling TimeData time_data; - time_data.time = get_node()->now(); - time_data.period = rclcpp::Duration::from_nanoseconds(0); - time_data.uptime = get_node()->now(); - time_data_.initRT(time_data); + time_data_.time = get_node()->now(); + time_data_.period = rclcpp::Duration::from_nanoseconds(0); + time_data_.uptime = get_node()->now(); // order all joints in the storage for (const auto & interface : params_.command_interfaces) From 6890d6e48e9416f60e85eee393a892c463981348 Mon Sep 17 00:00:00 2001 From: Lennart Nachtigall Date: Wed, 3 Jul 2024 16:34:14 +0200 Subject: [PATCH 12/43] Fix goal time violated See https://github.com/UniversalRobots/Universal_Robots_ROS2_Driver/pull/882 --- joint_trajectory_controller/src/joint_trajectory_controller.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/joint_trajectory_controller/src/joint_trajectory_controller.cpp b/joint_trajectory_controller/src/joint_trajectory_controller.cpp index 218c9e1c5c..15bd053e82 100644 --- a/joint_trajectory_controller/src/joint_trajectory_controller.cpp +++ b/joint_trajectory_controller/src/joint_trajectory_controller.cpp @@ -236,7 +236,7 @@ controller_interface::return_type JointTrajectoryController::update( // time_difference is // - negative until first point is reached // - counting from zero to time_from_start of next point - double time_difference = time.seconds() - segment_time_from_start.seconds(); + const double time_difference = time_data.uptime.seconds() - segment_time_from_start.seconds(); bool tolerance_violated_while_moving = false; bool outside_goal_tolerance = false; bool within_goal_time = true; From 908b539ebe9bdaaf4388f2c402d183d01d97d9f7 Mon Sep 17 00:00:00 2001 From: Felix Exner Date: Wed, 3 Jul 2024 20:38:24 +0200 Subject: [PATCH 13/43] Use custom message to subscribe speed scaling --- .../joint_trajectory_controller.hpp | 5 +++-- .../src/joint_trajectory_controller.cpp | 4 ++-- 2 files changed, 5 insertions(+), 4 deletions(-) diff --git a/joint_trajectory_controller/include/joint_trajectory_controller/joint_trajectory_controller.hpp b/joint_trajectory_controller/include/joint_trajectory_controller/joint_trajectory_controller.hpp index 7339970ec9..5f8af7e3a5 100644 --- a/joint_trajectory_controller/include/joint_trajectory_controller/joint_trajectory_controller.hpp +++ b/joint_trajectory_controller/include/joint_trajectory_controller/joint_trajectory_controller.hpp @@ -23,6 +23,7 @@ #include "control_msgs/action/follow_joint_trajectory.hpp" #include "control_msgs/msg/joint_trajectory_controller_state.hpp" +#include "control_msgs/msg/speed_scaling_factor.hpp" #include "control_msgs/srv/query_trajectory_state.hpp" #include "control_toolbox/pid.hpp" #include "controller_interface/controller_interface.hpp" @@ -45,7 +46,6 @@ #include "trajectory_msgs/msg/joint_trajectory_point.hpp" #include "urdf/model.h" -#include "std_msgs/msg/float64.hpp" // auto-generated by generate_parameter_library #include "joint_trajectory_controller_parameters.hpp" @@ -321,7 +321,8 @@ class JointTrajectoryController : public controller_interface::ControllerInterfa urdf::Model model_; realtime_tools::RealtimeBuffer scaling_factor_rt_buff_; - rclcpp::Subscription::SharedPtr scaling_factor_sub_; + using SpeedScalingMsg=control_msgs::msg::SpeedScalingFactor; + rclcpp::Subscription::SharedPtr scaling_factor_sub_; /** * @brief Assigns the values from a trajectory point interface to a joint interface. diff --git a/joint_trajectory_controller/src/joint_trajectory_controller.cpp b/joint_trajectory_controller/src/joint_trajectory_controller.cpp index 9ca663653b..b2dd71b64a 100644 --- a/joint_trajectory_controller/src/joint_trajectory_controller.cpp +++ b/joint_trajectory_controller/src/joint_trajectory_controller.cpp @@ -916,9 +916,9 @@ controller_interface::CallbackReturn JointTrajectoryController::on_configure( !has_velocity_command_interface_ && !has_acceleration_command_interface_ && !has_effort_command_interface_) { - scaling_factor_sub_ = get_node()->create_subscription( + scaling_factor_sub_ = get_node()->create_subscription( "~/speed_scaling_input", rclcpp::SystemDefaultsQoS(), - [&](const std_msgs::msg::Float64 & msg) { set_scaling_factor(msg.data);}); + [&](const SpeedScalingMsg & msg) { set_scaling_factor(msg.factor);}); RCLCPP_INFO( logger, "Setting initial scaling factor to %2f", params_.scaling_factor_initial_default); scaling_factor_rt_buff_.writeFromNonRT(params_.scaling_factor_initial_default); From 1e66e4401a6e119f454dc88cd18c8d1fece4d688 Mon Sep 17 00:00:00 2001 From: Felix Exner Date: Wed, 3 Jul 2024 20:46:17 +0200 Subject: [PATCH 14/43] Add scaling factor to controller state --- joint_trajectory_controller/src/joint_trajectory_controller.cpp | 1 + 1 file changed, 1 insertion(+) diff --git a/joint_trajectory_controller/src/joint_trajectory_controller.cpp b/joint_trajectory_controller/src/joint_trajectory_controller.cpp index b2dd71b64a..9b1abfd544 100644 --- a/joint_trajectory_controller/src/joint_trajectory_controller.cpp +++ b/joint_trajectory_controller/src/joint_trajectory_controller.cpp @@ -1157,6 +1157,7 @@ void JointTrajectoryController::publish_state( { state_publisher_->msg_.output = command_current_; } + state_publisher_->msg_.speed_scaling_factor = *(scaling_factor_rt_buff_.readFromRT()); state_publisher_->unlockAndPublish(); } From 7daf2408a5d054e8b17cb3130337571e89c6b0ac Mon Sep 17 00:00:00 2001 From: Felix Exner Date: Wed, 3 Jul 2024 20:46:40 +0200 Subject: [PATCH 15/43] Code formatting --- .../src/joint_trajectory_controller.cpp | 5 ++--- 1 file changed, 2 insertions(+), 3 deletions(-) diff --git a/joint_trajectory_controller/src/joint_trajectory_controller.cpp b/joint_trajectory_controller/src/joint_trajectory_controller.cpp index 9b1abfd544..8dabad1218 100644 --- a/joint_trajectory_controller/src/joint_trajectory_controller.cpp +++ b/joint_trajectory_controller/src/joint_trajectory_controller.cpp @@ -201,8 +201,7 @@ controller_interface::return_type JointTrajectoryController::update( rcl_duration_value_t t_period = (time_data.time - time_data_.time).nanoseconds(); time_data.period = rclcpp::Duration::from_nanoseconds(t_period) * scaling_factor_; time_data.uptime = time_data_.uptime + time_data.period; - rclcpp::Time traj_time = - time_data_.uptime + rclcpp::Duration::from_nanoseconds(t_period); + rclcpp::Time traj_time = time_data_.uptime + rclcpp::Duration::from_nanoseconds(t_period); time_data_ = time_data; bool first_sample = false; @@ -918,7 +917,7 @@ controller_interface::CallbackReturn JointTrajectoryController::on_configure( { scaling_factor_sub_ = get_node()->create_subscription( "~/speed_scaling_input", rclcpp::SystemDefaultsQoS(), - [&](const SpeedScalingMsg & msg) { set_scaling_factor(msg.factor);}); + [&](const SpeedScalingMsg & msg) { set_scaling_factor(msg.factor); }); RCLCPP_INFO( logger, "Setting initial scaling factor to %2f", params_.scaling_factor_initial_default); scaling_factor_rt_buff_.writeFromNonRT(params_.scaling_factor_initial_default); From 66abfd9423a1a5f7bbd76e858602ada7c6b71776 Mon Sep 17 00:00:00 2001 From: Felix Exner Date: Wed, 3 Jul 2024 20:48:25 +0200 Subject: [PATCH 16/43] Allow scaling factors greater than 1 --- .../src/joint_trajectory_controller.cpp | 5 +++-- 1 file changed, 3 insertions(+), 2 deletions(-) diff --git a/joint_trajectory_controller/src/joint_trajectory_controller.cpp b/joint_trajectory_controller/src/joint_trajectory_controller.cpp index 8dabad1218..f59ccb084a 100644 --- a/joint_trajectory_controller/src/joint_trajectory_controller.cpp +++ b/joint_trajectory_controller/src/joint_trajectory_controller.cpp @@ -1634,10 +1634,11 @@ void JointTrajectoryController::resize_joint_trajectory_point_command( bool JointTrajectoryController::set_scaling_factor(const double scaling_factor) { - if (scaling_factor < 0 || scaling_factor > 1) + if (scaling_factor < 0) { RCLCPP_WARN( - get_node()->get_logger(), "Scaling factor has to be in range [0, 1]. Ignoring input!"); + get_node()->get_logger(), + "Scaling factor has to be greater or equal to 0.0 - Ignoring input!"); return false; } From 45fa03607ce119ed1a5e734ccae4d2ab7325533e Mon Sep 17 00:00:00 2001 From: Felix Exner Date: Wed, 3 Jul 2024 20:50:38 +0200 Subject: [PATCH 17/43] Add parameter validator for default scaling factor --- .../src/joint_trajectory_controller_parameters.yaml | 5 ++++- 1 file changed, 4 insertions(+), 1 deletion(-) diff --git a/joint_trajectory_controller/src/joint_trajectory_controller_parameters.yaml b/joint_trajectory_controller/src/joint_trajectory_controller_parameters.yaml index 8718d05a6b..0f758c2b9a 100644 --- a/joint_trajectory_controller/src/joint_trajectory_controller_parameters.yaml +++ b/joint_trajectory_controller/src/joint_trajectory_controller_parameters.yaml @@ -42,7 +42,10 @@ joint_trajectory_controller: scaling_factor_initial_default: { type: double, default_value: 1.0, - description: "The initial value of the scaling factor if not exchange with hardware takes place." + description: "The initial value of the scaling factor if not exchange with hardware takes place.", + validation: { + gt_eq<>: 0.0, + } } speed_scaling_state_interface_name: { type: string, From 5e9592b6bf08dd8f0eac86663ce9e174df92bed3 Mon Sep 17 00:00:00 2001 From: Felix Exner Date: Wed, 3 Jul 2024 21:05:51 +0200 Subject: [PATCH 18/43] More formatting... --- .../joint_trajectory_controller.hpp | 3 +-- 1 file changed, 1 insertion(+), 2 deletions(-) diff --git a/joint_trajectory_controller/include/joint_trajectory_controller/joint_trajectory_controller.hpp b/joint_trajectory_controller/include/joint_trajectory_controller/joint_trajectory_controller.hpp index 5f8af7e3a5..5e6d263599 100644 --- a/joint_trajectory_controller/include/joint_trajectory_controller/joint_trajectory_controller.hpp +++ b/joint_trajectory_controller/include/joint_trajectory_controller/joint_trajectory_controller.hpp @@ -46,7 +46,6 @@ #include "trajectory_msgs/msg/joint_trajectory_point.hpp" #include "urdf/model.h" - // auto-generated by generate_parameter_library #include "joint_trajectory_controller_parameters.hpp" @@ -321,7 +320,7 @@ class JointTrajectoryController : public controller_interface::ControllerInterfa urdf::Model model_; realtime_tools::RealtimeBuffer scaling_factor_rt_buff_; - using SpeedScalingMsg=control_msgs::msg::SpeedScalingFactor; + using SpeedScalingMsg = control_msgs::msg::SpeedScalingFactor; rclcpp::Subscription::SharedPtr scaling_factor_sub_; /** From 42394b9d4df0172d22b235467954ffaccb4676de Mon Sep 17 00:00:00 2001 From: Felix Exner Date: Thu, 4 Jul 2024 08:34:24 +0200 Subject: [PATCH 19/43] Remove unnecessary iostream include --- joint_trajectory_controller/src/joint_trajectory_controller.cpp | 1 - 1 file changed, 1 deletion(-) diff --git a/joint_trajectory_controller/src/joint_trajectory_controller.cpp b/joint_trajectory_controller/src/joint_trajectory_controller.cpp index f59ccb084a..5b972a2cd8 100644 --- a/joint_trajectory_controller/src/joint_trajectory_controller.cpp +++ b/joint_trajectory_controller/src/joint_trajectory_controller.cpp @@ -16,7 +16,6 @@ #include #include -#include #include #include From ba5fecb9735c50d8b1c912a19479d148f15111b4 Mon Sep 17 00:00:00 2001 From: Felix Exner Date: Thu, 4 Jul 2024 08:36:32 +0200 Subject: [PATCH 20/43] REVERT_ME: Use dev branch for control_msgs --- ros2_controllers-not-released.jazzy.repos | 5 +++++ ros2_controllers-not-released.rolling.repos | 5 +++++ 2 files changed, 10 insertions(+) diff --git a/ros2_controllers-not-released.jazzy.repos b/ros2_controllers-not-released.jazzy.repos index 66352f4960..2aa7462380 100644 --- a/ros2_controllers-not-released.jazzy.repos +++ b/ros2_controllers-not-released.jazzy.repos @@ -3,3 +3,8 @@ repositories: type: git url: https://github.com/picknikrobotics/generate_parameter_library.git version: main + + control_msgs: + type: git + url: https://github.com/fmauch/control_msgs.git + version: scaled_jtc diff --git a/ros2_controllers-not-released.rolling.repos b/ros2_controllers-not-released.rolling.repos index 66352f4960..2aa7462380 100644 --- a/ros2_controllers-not-released.rolling.repos +++ b/ros2_controllers-not-released.rolling.repos @@ -3,3 +3,8 @@ repositories: type: git url: https://github.com/picknikrobotics/generate_parameter_library.git version: main + + control_msgs: + type: git + url: https://github.com/fmauch/control_msgs.git + version: scaled_jtc From 4b2f18c8537076679a5341f7f498080150a80b12 Mon Sep 17 00:00:00 2001 From: Felix Exner Date: Thu, 4 Jul 2024 22:13:03 +0200 Subject: [PATCH 21/43] Write back scaling factor to buffer when updated from hardware --- joint_trajectory_controller/src/joint_trajectory_controller.cpp | 1 + 1 file changed, 1 insertion(+) diff --git a/joint_trajectory_controller/src/joint_trajectory_controller.cpp b/joint_trajectory_controller/src/joint_trajectory_controller.cpp index 5b972a2cd8..e15d49c944 100644 --- a/joint_trajectory_controller/src/joint_trajectory_controller.cpp +++ b/joint_trajectory_controller/src/joint_trajectory_controller.cpp @@ -143,6 +143,7 @@ controller_interface::return_type JointTrajectoryController::update( if (state_interfaces_.back().get_name() == params_.speed_scaling_state_interface_name) { scaling_factor_ = state_interfaces_.back().get_value(); + scaling_factor_rt_buff_.initRT(scaling_factor_); } else { From 76e5cab1c9b96fcbf7739bc188288974b91b73ab Mon Sep 17 00:00:00 2001 From: Felix Exner Date: Thu, 4 Jul 2024 22:13:50 +0200 Subject: [PATCH 22/43] Remove additional time_data structure in update method We can actually work with just one structure. --- .../src/joint_trajectory_controller.cpp | 22 ++++++++++++------- 1 file changed, 14 insertions(+), 8 deletions(-) diff --git a/joint_trajectory_controller/src/joint_trajectory_controller.cpp b/joint_trajectory_controller/src/joint_trajectory_controller.cpp index e15d49c944..7c7772f12e 100644 --- a/joint_trajectory_controller/src/joint_trajectory_controller.cpp +++ b/joint_trajectory_controller/src/joint_trajectory_controller.cpp @@ -195,14 +195,19 @@ controller_interface::return_type JointTrajectoryController::update( // currently carrying out a trajectory if (has_active_trajectory()) { - // Adjust time with scaling factor - TimeData time_data; - time_data.time = time; - rcl_duration_value_t t_period = (time_data.time - time_data_.time).nanoseconds(); - time_data.period = rclcpp::Duration::from_nanoseconds(t_period) * scaling_factor_; - time_data.uptime = time_data_.uptime + time_data.period; + // Time passed since the last update call + rcl_duration_value_t t_period = (time - time_data_.time).nanoseconds(); + + // scaled time period + time_data_.period = rclcpp::Duration::from_nanoseconds(t_period) * scaling_factor_; + + // scaled time spent in the trajectory + time_data_.uptime = time_data_.uptime + time_data_.period; + + // time in the trajectory with a non-scaled current step rclcpp::Time traj_time = time_data_.uptime + rclcpp::Duration::from_nanoseconds(t_period); - time_data_ = time_data; + + time_data_.time = time; bool first_sample = false; // if sampling the first time, set the point before you sample @@ -236,7 +241,8 @@ controller_interface::return_type JointTrajectoryController::update( // time_difference is // - negative until first point is reached // - counting from zero to time_from_start of next point - const double time_difference = time_data.uptime.seconds() - segment_time_from_start.seconds(); + const double time_difference = + time_data_.uptime.seconds() - segment_time_from_start.seconds(); bool tolerance_violated_while_moving = false; bool outside_goal_tolerance = false; bool within_goal_time = true; From b22ce07e4728427c73aeb8495aed588880f87bc4 Mon Sep 17 00:00:00 2001 From: Felix Exner Date: Thu, 4 Jul 2024 22:24:07 +0200 Subject: [PATCH 23/43] Use std::atomic for scaling factor buff --- .../joint_trajectory_controller.hpp | 3 +-- .../src/joint_trajectory_controller.cpp | 15 +++++---------- 2 files changed, 6 insertions(+), 12 deletions(-) diff --git a/joint_trajectory_controller/include/joint_trajectory_controller/joint_trajectory_controller.hpp b/joint_trajectory_controller/include/joint_trajectory_controller/joint_trajectory_controller.hpp index 5e6d263599..b3c674c56f 100644 --- a/joint_trajectory_controller/include/joint_trajectory_controller/joint_trajectory_controller.hpp +++ b/joint_trajectory_controller/include/joint_trajectory_controller/joint_trajectory_controller.hpp @@ -172,7 +172,7 @@ class JointTrajectoryController : public controller_interface::ControllerInterfa std::vector tmp_command_; // Things around speed scaling - double scaling_factor_{1.0}; + std::atomic scaling_factor_{1.0}; TimeData time_data_; // Timeout to consider commands old @@ -319,7 +319,6 @@ class JointTrajectoryController : public controller_interface::ControllerInterfa urdf::Model model_; - realtime_tools::RealtimeBuffer scaling_factor_rt_buff_; using SpeedScalingMsg = control_msgs::msg::SpeedScalingFactor; rclcpp::Subscription::SharedPtr scaling_factor_sub_; diff --git a/joint_trajectory_controller/src/joint_trajectory_controller.cpp b/joint_trajectory_controller/src/joint_trajectory_controller.cpp index 7c7772f12e..d328e67cec 100644 --- a/joint_trajectory_controller/src/joint_trajectory_controller.cpp +++ b/joint_trajectory_controller/src/joint_trajectory_controller.cpp @@ -134,16 +134,11 @@ JointTrajectoryController::state_interface_configuration() const controller_interface::return_type JointTrajectoryController::update( const rclcpp::Time & time, const rclcpp::Duration & period) { - if (params_.speed_scaling_state_interface_name.empty()) - { - scaling_factor_ = *(scaling_factor_rt_buff_.readFromRT()); - } - else + if (!params_.speed_scaling_state_interface_name.empty()) { if (state_interfaces_.back().get_name() == params_.speed_scaling_state_interface_name) { scaling_factor_ = state_interfaces_.back().get_value(); - scaling_factor_rt_buff_.initRT(scaling_factor_); } else { @@ -926,7 +921,7 @@ controller_interface::CallbackReturn JointTrajectoryController::on_configure( [&](const SpeedScalingMsg & msg) { set_scaling_factor(msg.factor); }); RCLCPP_INFO( logger, "Setting initial scaling factor to %2f", params_.scaling_factor_initial_default); - scaling_factor_rt_buff_.writeFromNonRT(params_.scaling_factor_initial_default); + scaling_factor_ = params_.scaling_factor_initial_default; } else { @@ -934,7 +929,7 @@ controller_interface::CallbackReturn JointTrajectoryController::on_configure( logger, "Speed scaling is currently only supported for position interfaces. If you want to make use " "of speed scaling, please only use a position interface when configuring this controller."); - scaling_factor_rt_buff_.writeFromNonRT(1.0); + scaling_factor_ = 1.0; } // set scaling factor to low value default @@ -1162,7 +1157,7 @@ void JointTrajectoryController::publish_state( { state_publisher_->msg_.output = command_current_; } - state_publisher_->msg_.speed_scaling_factor = *(scaling_factor_rt_buff_.readFromRT()); + state_publisher_->msg_.speed_scaling_factor = scaling_factor_; state_publisher_->unlockAndPublish(); } @@ -1659,7 +1654,7 @@ bool JointTrajectoryController::set_scaling_factor(const double scaling_factor) "This will likely get overwritten by the hardware again. If available, please also setup " "the speed_scaling_command_interface_name"); } - scaling_factor_rt_buff_.writeFromNonRT(scaling_factor); + scaling_factor_ = scaling_factor; } else { From 7e88744d9493f03da03a536be79a176966fb4b16 Mon Sep 17 00:00:00 2001 From: Felix Exner Date: Thu, 4 Jul 2024 22:58:21 +0200 Subject: [PATCH 24/43] Use transient_local for the speed scaling topic subscriber --- joint_trajectory_controller/doc/speed_scaling.rst | 13 +++++++++++-- .../src/joint_trajectory_controller.cpp | 4 +++- 2 files changed, 14 insertions(+), 3 deletions(-) diff --git a/joint_trajectory_controller/doc/speed_scaling.rst b/joint_trajectory_controller/doc/speed_scaling.rst index 41f2353dc3..e6f1aec331 100644 --- a/joint_trajectory_controller/doc/speed_scaling.rst +++ b/joint_trajectory_controller/doc/speed_scaling.rst @@ -61,8 +61,17 @@ generates commands to be sent to the robot that are already scaled down accordin directly executed by the robot. Since the hardware isn't aware of speed scaling, the speed-scaling related command and state -interfaces should not be specified and the scaling factor will be set by the ``setSpeedScaling`` -service directly. +interfaces should not be specified and the scaling factor will be set through the +``~/speed_scaling_input`` topic directly: + +.. code:: console + + $ ros2 topic pub --qos-durability transient_local --once \ + /joint_trajectory_controller/speed_scaling_input control_msgs/msg/SpeedScalingFactor "{factor: 0.5}" + +.. note:: + The ``~/speed_scaling_input`` topic uses the QoS durability profile ``transient_local``. This + means you can restart the controller while still having a publisher on that topic active. .. note:: The current implementation only works for position-based interfaces. diff --git a/joint_trajectory_controller/src/joint_trajectory_controller.cpp b/joint_trajectory_controller/src/joint_trajectory_controller.cpp index d328e67cec..af593226d3 100644 --- a/joint_trajectory_controller/src/joint_trajectory_controller.cpp +++ b/joint_trajectory_controller/src/joint_trajectory_controller.cpp @@ -916,8 +916,10 @@ controller_interface::CallbackReturn JointTrajectoryController::on_configure( !has_velocity_command_interface_ && !has_acceleration_command_interface_ && !has_effort_command_interface_) { + auto qos = rclcpp::SystemDefaultsQoS(); + qos.transient_local(); scaling_factor_sub_ = get_node()->create_subscription( - "~/speed_scaling_input", rclcpp::SystemDefaultsQoS(), + "~/speed_scaling_input", qos, [&](const SpeedScalingMsg & msg) { set_scaling_factor(msg.factor); }); RCLCPP_INFO( logger, "Setting initial scaling factor to %2f", params_.scaling_factor_initial_default); From d2130e0e46400f35a3fa8b66902f3e0364d51c3d Mon Sep 17 00:00:00 2001 From: Felix Exner Date: Fri, 5 Jul 2024 16:27:18 +0200 Subject: [PATCH 25/43] Added documentation on tolerance effects --- .../doc/speed_scaling.rst | 19 ++++++++++++++++--- 1 file changed, 16 insertions(+), 3 deletions(-) diff --git a/joint_trajectory_controller/doc/speed_scaling.rst b/joint_trajectory_controller/doc/speed_scaling.rst index e6f1aec331..cb2dd178b7 100644 --- a/joint_trajectory_controller/doc/speed_scaling.rst +++ b/joint_trajectory_controller/doc/speed_scaling.rst @@ -69,6 +69,7 @@ interfaces should not be specified and the scaling factor will be set through th $ ros2 topic pub --qos-durability transient_local --once \ /joint_trajectory_controller/speed_scaling_input control_msgs/msg/SpeedScalingFactor "{factor: 0.5}" + .. note:: The ``~/speed_scaling_input`` topic uses the QoS durability profile ``transient_local``. This means you can restart the controller while still having a publisher on that topic active. @@ -77,8 +78,20 @@ interfaces should not be specified and the scaling factor will be set through th The current implementation only works for position-based interfaces. -Goal time tolerances +Effect on tolerances -------------------- -.. todo:: - What happens to goal time tolerances if we scale down a trajectory? +When speed scaling is used while executing a trajectory, the tolerances configured for execution +will be scaled, as well. + +Since commands are generated from the scaled trajectory time, **path errors** will also be compared to +the scaled trajectory. However, since the next command is always using the full time step, there +will obviously always be a small error added by the robot only executing a part of the command. + +The **goal time tolerance** also uses the virtual trajectory time. This means that a trajectory +being executed with a constant scaling factor of 0.5 will take twice as long for execution than the +``time_from_start`` value of the last trajectory point specifies. As long as the robot doesn't take +longer than that the goal time tolerance is considered to be met. + +If an application relies on the actual execution time as set in the ``time_from_start`` fields, an +external monitoring has to be wrapped around the trajectory execution action. From 915bfd390e2e0f979ae214d89f64dff432ef5e2c Mon Sep 17 00:00:00 2001 From: Felix Exner Date: Fri, 5 Jul 2024 17:19:50 +0200 Subject: [PATCH 26/43] Added a short explanation of scaling This isn't the best explanation, but it's a start. --- joint_trajectory_controller/doc/speed_scaling.rst | 10 +++++++++- 1 file changed, 9 insertions(+), 1 deletion(-) diff --git a/joint_trajectory_controller/doc/speed_scaling.rst b/joint_trajectory_controller/doc/speed_scaling.rst index cb2dd178b7..4bad7c7167 100644 --- a/joint_trajectory_controller/doc/speed_scaling.rst +++ b/joint_trajectory_controller/doc/speed_scaling.rst @@ -50,7 +50,15 @@ The deviation between trajectory interpolation on the ROS side and actual robot minimal and the robot reaches the intermediate setpoint instead of returning "too early" as in the example above. -.. todo:: Describe method behind this scaling approach. +Scaling is done in such a way, that the time in the trajectory is virtually scaled. For example, if +a controller runs with a cycle time of 100 Hz, each control cycle is 10 ms long. A speed scaling of +0.5 means that in each time step the trajectory is moved forward by 5 ms instead. +So, the beginning of the 3rd timestep is 15 ms instead of 30 ms in the trajectory. + +Command sampling is performed as in the unscaled case, with the timestep's start plus the **full** +cycle time of 10 ms. The robot will scale down the motion command by 50% resulting in only half of +the distance being executed, which is why the next control cycle will be started at the current +start plus half of the step time. On-Controller speed scaling From 90c6d45f4ca85024a0f14d639c9930d2f5195d29 Mon Sep 17 00:00:00 2001 From: Felix Exner Date: Mon, 8 Jul 2024 14:48:02 +0200 Subject: [PATCH 27/43] Use a ordering-safe reference for scaling command and state interfaces --- .../joint_trajectory_controller.hpp | 5 ++ .../src/joint_trajectory_controller.cpp | 64 +++++++++++-------- 2 files changed, 43 insertions(+), 26 deletions(-) diff --git a/joint_trajectory_controller/include/joint_trajectory_controller/joint_trajectory_controller.hpp b/joint_trajectory_controller/include/joint_trajectory_controller/joint_trajectory_controller.hpp index b3c674c56f..151c8dce90 100644 --- a/joint_trajectory_controller/include/joint_trajectory_controller/joint_trajectory_controller.hpp +++ b/joint_trajectory_controller/include/joint_trajectory_controller/joint_trajectory_controller.hpp @@ -27,6 +27,7 @@ #include "control_msgs/srv/query_trajectory_state.hpp" #include "control_toolbox/pid.hpp" #include "controller_interface/controller_interface.hpp" +#include "hardware_interface/loaned_command_interface.hpp" #include "hardware_interface/types/hardware_interface_type_values.hpp" #include "joint_trajectory_controller/interpolation_methods.hpp" #include "joint_trajectory_controller/tolerances.hpp" @@ -150,6 +151,10 @@ class JointTrajectoryController : public controller_interface::ControllerInterfa InterfaceReferences joint_command_interface_; InterfaceReferences joint_state_interface_; + std::optional> + scaling_state_interface_; + std::optional> + scaling_command_interface_; bool has_position_state_interface_ = false; bool has_velocity_state_interface_ = false; diff --git a/joint_trajectory_controller/src/joint_trajectory_controller.cpp b/joint_trajectory_controller/src/joint_trajectory_controller.cpp index af593226d3..84a9a0da20 100644 --- a/joint_trajectory_controller/src/joint_trajectory_controller.cpp +++ b/joint_trajectory_controller/src/joint_trajectory_controller.cpp @@ -134,24 +134,24 @@ JointTrajectoryController::state_interface_configuration() const controller_interface::return_type JointTrajectoryController::update( const rclcpp::Time & time, const rclcpp::Duration & period) { - if (!params_.speed_scaling_state_interface_name.empty()) + if (scaling_state_interface_.has_value()) { - if (state_interfaces_.back().get_name() == params_.speed_scaling_state_interface_name) - { - scaling_factor_ = state_interfaces_.back().get_value(); - } - else - { - RCLCPP_ERROR( - get_node()->get_logger(), "Speed scaling interface (%s) not found in hardware interface.", - params_.speed_scaling_state_interface_name.c_str()); - } + scaling_factor_ = scaling_state_interface_->get().get_value(); } if (get_state().id() == lifecycle_msgs::msg::State::PRIMARY_STATE_INACTIVE) { return controller_interface::return_type::OK; } + + if (get_state().id() == lifecycle_msgs::msg::State::PRIMARY_STATE_ACTIVE) + { + if (scaling_command_interface_.has_value()) + { + scaling_command_interface_->get().set_value(scaling_factor_); + } + } + auto logger = this->get_node()->get_logger(); // update dynamic parameters if (param_listener_->is_old(params_)) @@ -934,8 +934,6 @@ controller_interface::CallbackReturn JointTrajectoryController::on_configure( scaling_factor_ = 1.0; } - // set scaling factor to low value default - return CallbackReturn::SUCCESS; } @@ -958,6 +956,33 @@ controller_interface::CallbackReturn JointTrajectoryController::on_activate( time_data_.period = rclcpp::Duration::from_nanoseconds(0); time_data_.uptime = get_node()->now(); + // Set scaling interfaces + if (!params_.speed_scaling_state_interface_name.empty()) + { + RCLCPP_WARN(logger, "I do have a speed scaling state interface configured"); + auto it = std::find_if( + state_interfaces_.begin(), state_interfaces_.end(), [&](auto & interface) + { return (interface.get_name() == params_.speed_scaling_state_interface_name); }); + if (it != state_interfaces_.end()) + { + scaling_state_interface_ = *it; + } + else + { + RCLCPP_ERROR(logger, "Did not find speed scaling interface in state interfaces."); + } + } + if (!params_.speed_scaling_command_interface_name.empty()) + { + auto it = std::find_if( + command_interfaces_.begin(), command_interfaces_.end(), [&](auto & interface) + { return (interface.get_name() == params_.speed_scaling_command_interface_name); }); + if (it != command_interfaces_.end()) + { + scaling_command_interface_ = *it; + } + } + // order all joints in the storage for (const auto & interface : params_.command_interfaces) { @@ -1658,19 +1683,6 @@ bool JointTrajectoryController::set_scaling_factor(const double scaling_factor) } scaling_factor_ = scaling_factor; } - else - { - if (get_state().id() == lifecycle_msgs::msg::State::PRIMARY_STATE_ACTIVE) - { - for (auto & interface : command_interfaces_) - { - if (interface.get_name() == params_.speed_scaling_command_interface_name) - { - interface.set_value(static_cast(scaling_factor)); - } - } - } - } return true; } From 0a3b974e880afcf5a7e6ec3477ac13a23321eea8 Mon Sep 17 00:00:00 2001 From: Felix Exner Date: Tue, 23 Jul 2024 13:14:47 +0200 Subject: [PATCH 28/43] REVERT_ME Use my version of control_msgs --- ros2_controllers.rolling.repos | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/ros2_controllers.rolling.repos b/ros2_controllers.rolling.repos index 8c20eccc96..fde72acc2c 100644 --- a/ros2_controllers.rolling.repos +++ b/ros2_controllers.rolling.repos @@ -9,8 +9,8 @@ repositories: version: master control_msgs: type: git - url: https://github.com/ros-controls/control_msgs.git - version: master + url: https://github.com/fmauch/control_msgs.git + version: scaled_jtc control_toolbox: type: git url: https://github.com/ros-controls/control_toolbox.git From 09bea48568ad0f6cbef67f37c01f485560aa5c25 Mon Sep 17 00:00:00 2001 From: Felix Exner Date: Tue, 23 Jul 2024 13:51:45 +0200 Subject: [PATCH 29/43] Use period directly instead of calculating an own period --- .../src/joint_trajectory_controller.cpp | 10 +++------- 1 file changed, 3 insertions(+), 7 deletions(-) diff --git a/joint_trajectory_controller/src/joint_trajectory_controller.cpp b/joint_trajectory_controller/src/joint_trajectory_controller.cpp index 1da82a9fbf..c66448f4e4 100644 --- a/joint_trajectory_controller/src/joint_trajectory_controller.cpp +++ b/joint_trajectory_controller/src/joint_trajectory_controller.cpp @@ -205,19 +205,16 @@ controller_interface::return_type JointTrajectoryController::update( // currently carrying out a trajectory if (has_active_trajectory()) { - // Time passed since the last update call - rcl_duration_value_t t_period = (time - time_data_.time).nanoseconds(); - // scaled time period - time_data_.period = rclcpp::Duration::from_nanoseconds(t_period) * scaling_factor_; + time_data_.period = period * scaling_factor_; // scaled time spent in the trajectory time_data_.uptime = time_data_.uptime + time_data_.period; // time in the trajectory with a non-scaled current step - rclcpp::Time traj_time = time_data_.uptime + rclcpp::Duration::from_nanoseconds(t_period); + rclcpp::Time traj_time = time_data_.uptime + period; - time_data_.time = time; + // time_data_.time = time; bool first_sample = false; // if sampling the first time, set the point before you sample @@ -948,7 +945,6 @@ controller_interface::CallbackReturn JointTrajectoryController::on_activate( // parse remaining parameters default_tolerances_ = get_segment_tolerances(logger, params_); // Setup time_data buffer used for scaling - TimeData time_data; time_data_.time = get_node()->now(); time_data_.period = rclcpp::Duration::from_nanoseconds(0); time_data_.uptime = get_node()->now(); From 0dba992c115db27394a4061940e59269969e141b Mon Sep 17 00:00:00 2001 From: Felix Exner Date: Thu, 8 Aug 2024 12:51:23 +0200 Subject: [PATCH 30/43] Set update rate in testing controller --- .../test/test_trajectory_controller_utils.hpp | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/joint_trajectory_controller/test/test_trajectory_controller_utils.hpp b/joint_trajectory_controller/test/test_trajectory_controller_utils.hpp index 796503c036..cf8a3ba2f6 100644 --- a/joint_trajectory_controller/test/test_trajectory_controller_utils.hpp +++ b/joint_trajectory_controller/test/test_trajectory_controller_utils.hpp @@ -277,7 +277,7 @@ class TrajectoryControllerTest : public ::testing::Test traj_controller_->set_node_options(node_options); return traj_controller_->init( - controller_name_, urdf, 0, "", traj_controller_->define_custom_node_options()); + controller_name_, urdf, 10, "", traj_controller_->define_custom_node_options()); } void SetPidParameters(double p_value = 0.0, double ff_value = 1.0) @@ -323,7 +323,7 @@ class TrajectoryControllerTest : public ::testing::Test // set pid parameters before configure SetPidParameters(k_p, ff); - traj_controller_->get_node()->configure(); + traj_controller_->configure(); ActivateTrajectoryController( separate_cmd_and_state_values, initial_pos_joints, initial_vel_joints, initial_acc_joints, From a96dd548ff8779f517f644165f990d9eff0f3ca4 Mon Sep 17 00:00:00 2001 From: Felix Exner Date: Wed, 28 Aug 2024 18:35:16 +0200 Subject: [PATCH 31/43] Tests: Call controller.configure() instead of controller.get_node().configure() --- .../test/test_trajectory_controller.cpp | 16 ++++++++-------- 1 file changed, 8 insertions(+), 8 deletions(-) diff --git a/joint_trajectory_controller/test/test_trajectory_controller.cpp b/joint_trajectory_controller/test/test_trajectory_controller.cpp index f188c0f04b..41443f37f6 100644 --- a/joint_trajectory_controller/test/test_trajectory_controller.cpp +++ b/joint_trajectory_controller/test/test_trajectory_controller.cpp @@ -53,7 +53,7 @@ TEST_P(TrajectoryControllerTestParameterized, configure_state_ignores_commands) traj_controller_->get_node()->set_parameter( rclcpp::Parameter("allow_nonzero_velocity_at_trajectory_end", true)); - const auto state = traj_controller_->get_node()->configure(); + const auto state = traj_controller_->configure(); ASSERT_EQ(state.id(), State::PRIMARY_STATE_INACTIVE); // send msg @@ -84,7 +84,7 @@ TEST_P(TrajectoryControllerTestParameterized, check_interface_names) rclcpp::executors::MultiThreadedExecutor executor; SetUpTrajectoryController(executor); - const auto state = traj_controller_->get_node()->configure(); + const auto state = traj_controller_->configure(); ASSERT_EQ(state.id(), State::PRIMARY_STATE_INACTIVE); compare_joints(joint_names_, joint_names_); @@ -97,7 +97,7 @@ TEST_P(TrajectoryControllerTestParameterized, check_interface_names_with_command const rclcpp::Parameter command_joint_names_param("command_joints", command_joint_names_); SetUpTrajectoryController(executor, {command_joint_names_param}); - const auto state = traj_controller_->get_node()->configure(); + const auto state = traj_controller_->configure(); ASSERT_EQ(state.id(), State::PRIMARY_STATE_INACTIVE); compare_joints(joint_names_, command_joint_names_); @@ -108,7 +108,7 @@ TEST_P(TrajectoryControllerTestParameterized, activate) rclcpp::executors::MultiThreadedExecutor executor; SetUpTrajectoryController(executor); - auto state = traj_controller_->get_node()->configure(); + auto state = traj_controller_->configure(); ASSERT_EQ(state.id(), State::PRIMARY_STATE_INACTIVE); auto cmd_if_conf = traj_controller_->command_interface_configuration(); @@ -162,7 +162,7 @@ TEST_P(TrajectoryControllerTestParameterized, cleanup_after_configure) SetUpTrajectoryController(executor); // configure controller - auto state = traj_controller_->get_node()->configure(); + auto state = traj_controller_->configure(); ASSERT_EQ(State::PRIMARY_STATE_INACTIVE, state.id()); // cleanup controller @@ -2098,7 +2098,7 @@ TEST_F(TrajectoryControllerTest, incorrect_initialization_using_interface_parame // command interfaces: empty command_interface_types_ = {}; EXPECT_EQ(SetUpTrajectoryControllerLocal(), controller_interface::return_type::OK); - auto state = traj_controller_->get_node()->configure(); + auto state = traj_controller_->configure(); EXPECT_EQ(state.id(), State::PRIMARY_STATE_UNCONFIGURED); // command interfaces: bad_name @@ -2143,7 +2143,7 @@ TEST_F(TrajectoryControllerTest, incorrect_initialization_using_interface_parame command_interface_types_ = {"velocity"}; state_interface_types_ = {"position"}; EXPECT_EQ(SetUpTrajectoryControllerLocal(), controller_interface::return_type::OK); - state = traj_controller_->get_node()->configure(); + state = traj_controller_->configure(); EXPECT_EQ(state.id(), State::PRIMARY_STATE_UNCONFIGURED); state_interface_types_ = {"velocity"}; EXPECT_EQ(SetUpTrajectoryControllerLocal(), controller_interface::return_type::ERROR); @@ -2152,7 +2152,7 @@ TEST_F(TrajectoryControllerTest, incorrect_initialization_using_interface_parame command_interface_types_ = {"effort"}; state_interface_types_ = {"position"}; EXPECT_EQ(SetUpTrajectoryControllerLocal(), controller_interface::return_type::OK); - state = traj_controller_->get_node()->configure(); + state = traj_controller_->configure(); EXPECT_EQ(state.id(), State::PRIMARY_STATE_UNCONFIGURED); state_interface_types_ = {"velocity"}; EXPECT_EQ(SetUpTrajectoryControllerLocal(), controller_interface::return_type::ERROR); From d55fea7b00629bf68a6cf6ac029d5615f56e0074 Mon Sep 17 00:00:00 2001 From: Felix Exner Date: Thu, 12 Sep 2024 13:29:02 +0200 Subject: [PATCH 32/43] Sample trajectory at point t+dT --- .../joint_trajectory_controller.hpp | 1 + .../src/joint_trajectory_controller.cpp | 22 +++++++++++++++---- 2 files changed, 19 insertions(+), 4 deletions(-) diff --git a/joint_trajectory_controller/include/joint_trajectory_controller/joint_trajectory_controller.hpp b/joint_trajectory_controller/include/joint_trajectory_controller/joint_trajectory_controller.hpp index 2f0a1f4df0..4ff06342b4 100644 --- a/joint_trajectory_controller/include/joint_trajectory_controller/joint_trajectory_controller.hpp +++ b/joint_trajectory_controller/include/joint_trajectory_controller/joint_trajectory_controller.hpp @@ -124,6 +124,7 @@ class JointTrajectoryController : public controller_interface::ControllerInterfa // Parameters from ROS for joint_trajectory_controller std::shared_ptr param_listener_; Params params_; + rclcpp::Duration update_period_{0, 0}; trajectory_msgs::msg::JointTrajectoryPoint last_commanded_state_; /// Specify interpolation method. Default to splines. diff --git a/joint_trajectory_controller/src/joint_trajectory_controller.cpp b/joint_trajectory_controller/src/joint_trajectory_controller.cpp index e4923604fd..0f338de1f9 100644 --- a/joint_trajectory_controller/src/joint_trajectory_controller.cpp +++ b/joint_trajectory_controller/src/joint_trajectory_controller.cpp @@ -18,6 +18,7 @@ #include #include +#include #include #include @@ -180,6 +181,7 @@ controller_interface::return_type JointTrajectoryController::update( if (has_active_trajectory()) { bool first_sample = false; + TrajectoryPointConstIter start_segment_itr, end_segment_itr; // if sampling the first time, set the point before you sample if (!traj_external_point_ptr_->is_sampled_already()) { @@ -194,12 +196,15 @@ controller_interface::return_type JointTrajectoryController::update( traj_external_point_ptr_->set_point_before_trajectory_msg( time, state_current_, joints_angle_wraparound_); } + traj_external_point_ptr_->sample( + // Sample once at the beginning to establish the start time if none was given + time, interpolation_method_, state_desired_, start_segment_itr, end_segment_itr); } - // find segment for current timestamp - TrajectoryPointConstIter start_segment_itr, end_segment_itr; + // Sample setpoint for next control cycle const bool valid_point = traj_external_point_ptr_->sample( - time, interpolation_method_, state_desired_, start_segment_itr, end_segment_itr); + time + update_period_, interpolation_method_, state_desired_, start_segment_itr, + end_segment_itr); if (valid_point) { @@ -279,7 +284,7 @@ controller_interface::return_type JointTrajectoryController::update( tmp_command_[i] = (state_desired_.velocities[i] * ff_velocity_scale_[i]) + pids_[i]->computeCommand( state_error_.positions[i], state_error_.velocities[i], - (uint64_t)period.nanoseconds()); + (uint64_t)update_period_.nanoseconds()); } } @@ -961,6 +966,15 @@ controller_interface::CallbackReturn JointTrajectoryController::on_activate( cmd_timeout_ = 0.0; } + { + if (get_update_rate() == 0) + { + throw std::runtime_error("Controller's update rate is set to 0. This should not happen!"); + } + update_period_ = + rclcpp::Duration(0.0, static_cast(1.0e9 / static_cast(get_update_rate()))); + } + return CallbackReturn::SUCCESS; } From 9400838f01a0e278f2414d66017b8c68f72227f3 Mon Sep 17 00:00:00 2001 From: Felix Exner Date: Mon, 7 Oct 2024 15:03:04 +0200 Subject: [PATCH 33/43] Update trajectory_controller_tests Since we changed the sampling point we need to adapt the tests. --- .../test/test_trajectory_controller.cpp | 113 ++++++++++++------ 1 file changed, 79 insertions(+), 34 deletions(-) diff --git a/joint_trajectory_controller/test/test_trajectory_controller.cpp b/joint_trajectory_controller/test/test_trajectory_controller.cpp index 41443f37f6..ad642a585d 100644 --- a/joint_trajectory_controller/test/test_trajectory_controller.cpp +++ b/joint_trajectory_controller/test/test_trajectory_controller.cpp @@ -206,8 +206,10 @@ TEST_P(TrajectoryControllerTestParameterized, correct_initialization_using_param // wait for reaching the first point // controller would process the second point when deactivated below + // Since the trajectory will be sampled at time + update_period, we need to pass the time 0.15 + // seconds to sample at t=0.25 sec traj_controller_->update( - rclcpp::Time(static_cast(0.25 * 1e9)), rclcpp::Duration::from_seconds(0.15)); + rclcpp::Time(static_cast(0.15 * 1e9)), rclcpp::Duration::from_seconds(0.15)); EXPECT_TRUE(traj_controller_->has_active_traj()); if (traj_controller_->has_position_command_interface()) { @@ -644,7 +646,7 @@ TEST_P(TrajectoryControllerTestParameterized, position_error_not_angle_wraparoun size_t n_joints = joint_names_.size(); // send msg - constexpr auto FIRST_POINT_TIME = std::chrono::milliseconds(250); + constexpr auto FIRST_POINT_TIME = std::chrono::milliseconds(300); builtin_interfaces::msg::Duration time_from_start{rclcpp::Duration(FIRST_POINT_TIME)}; // *INDENT-OFF* std::vector> points{ @@ -653,7 +655,12 @@ TEST_P(TrajectoryControllerTestParameterized, position_error_not_angle_wraparoun publish(time_from_start, points, rclcpp::Time()); traj_controller_->wait_for_trajectory(executor); - updateControllerAsync(rclcpp::Duration(FIRST_POINT_TIME)); + const rclcpp::Duration controller_period = + rclcpp::Duration::from_seconds(1.0 / traj_controller_->get_update_rate()); + + updateControllerAsync( + rclcpp::Duration(FIRST_POINT_TIME) - controller_period, rclcpp::Time(0, 0, RCL_STEADY_TIME), + controller_period); // get states from class variables auto state_feedback = traj_controller_->get_state_feedback(); @@ -745,7 +752,7 @@ TEST_P(TrajectoryControllerTestParameterized, position_error_angle_wraparound) size_t n_joints = joint_names_.size(); // send msg - constexpr auto FIRST_POINT_TIME = std::chrono::milliseconds(250); + constexpr auto FIRST_POINT_TIME = std::chrono::milliseconds(300); builtin_interfaces::msg::Duration time_from_start{rclcpp::Duration(FIRST_POINT_TIME)}; // *INDENT-OFF* std::vector> points{ @@ -756,7 +763,11 @@ TEST_P(TrajectoryControllerTestParameterized, position_error_angle_wraparound) publish(time_from_start, points, rclcpp::Time(), {}, points_velocities); traj_controller_->wait_for_trajectory(executor); - updateControllerAsync(rclcpp::Duration(FIRST_POINT_TIME)); + const rclcpp::Duration controller_period = + rclcpp::Duration::from_seconds(1.0 / traj_controller_->get_update_rate()); + updateControllerAsync( + rclcpp::Duration(FIRST_POINT_TIME) - controller_period, rclcpp::Time(0, 0, RCL_STEADY_TIME), + controller_period); // get states from class variables auto state_feedback = traj_controller_->get_state_feedback(); @@ -1548,16 +1559,27 @@ TEST_P(TrajectoryControllerTestParameterized, test_ignore_old_trajectory) trajectory_msgs::msg::JointTrajectoryPoint expected_actual, expected_desired; expected_actual.positions = {points_old[0].begin(), points_old[0].end()}; expected_desired = expected_actual; + traj_controller_->wait_for_trajectory(executor); + auto end_time = updateControllerAsync( + rclcpp::Duration(delay), rclcpp::Time(0, 0, RCL_STEADY_TIME), + rclcpp::Duration::from_seconds(1.0 / traj_controller_->get_update_rate())); + // Check that we reached end of points_old[0] trajectory - auto end_time = - waitAndCompareState(expected_actual, expected_desired, executor, rclcpp::Duration(delay), 0.1); + if (traj_controller_->has_position_command_interface()) + { + auto state_feedback = traj_controller_->get_state_feedback(); + for (size_t i = 0; i < expected_actual.positions.size(); ++i) + { + EXPECT_NEAR(expected_actual.positions[i], state_feedback.positions[i], 0.01); + } + } RCLCPP_INFO(traj_controller_->get_node()->get_logger(), "Sending new trajectory in the past"); // New trajectory will end before current time rclcpp::Time new_traj_start = rclcpp::Clock(RCL_STEADY_TIME).now() - delay - std::chrono::milliseconds(100); expected_actual.positions = {points_old[1].begin(), points_old[1].end()}; - expected_desired = expected_actual; + expected_desired = expected_actual; // robot should be standing still by now publish(time_from_start, points_new, new_traj_start); waitAndCompareState( expected_actual, expected_desired, executor, rclcpp::Duration(delay), 0.1, end_time); @@ -1578,9 +1600,20 @@ TEST_P(TrajectoryControllerTestParameterized, test_ignore_partial_old_trajectory publish(time_from_start, points_old, rclcpp::Time()); expected_actual.positions = {points_old[0].begin(), points_old[0].end()}; expected_desired = expected_actual; - // Check that we reached end of points_old[0]trajectory - auto end_time = - waitAndCompareState(expected_actual, expected_desired, executor, rclcpp::Duration(delay), 0.1); + traj_controller_->wait_for_trajectory(executor); + auto end_time = updateControllerAsync( + rclcpp::Duration(delay), rclcpp::Time(0, 0, RCL_STEADY_TIME), + rclcpp::Duration::from_seconds(1.0 / traj_controller_->get_update_rate())); + + if (traj_controller_->has_position_command_interface()) + { + // Check that we reached end of points_old[0] trajectory + auto state_feedback = traj_controller_->get_state_feedback(); + for (size_t i = 0; i < expected_actual.positions.size(); ++i) + { + EXPECT_NEAR(expected_actual.positions[i], state_feedback.positions[i], 0.01); + } + } // send points_new before the old trajectory is finished RCLCPP_INFO( @@ -1646,13 +1679,17 @@ TEST_P(TrajectoryControllerTestParameterized, test_jump_when_state_tracking_erro rclcpp::executors::SingleThreadedExecutor executor; // default if false so it will not be actually set parameter rclcpp::Parameter is_open_loop_parameters("open_loop_control", false); - SetUpAndActivateTrajectoryController(executor, {is_open_loop_parameters}, true); + rclcpp::Parameter update_rate_param("update_rate", 100); + SetUpAndActivateTrajectoryController( + executor, {is_open_loop_parameters, update_rate_param}, true); if (traj_controller_->has_position_command_interface() == false) { // only makes sense with position command interface return; } + auto controller_period = + rclcpp::Duration::from_seconds(1.0 / traj_controller_->get_update_rate()); // goal setup std::vector first_goal = {3.3, 4.4, 5.5}; @@ -1665,8 +1702,8 @@ TEST_P(TrajectoryControllerTestParameterized, test_jump_when_state_tracking_erro builtin_interfaces::msg::Duration time_from_start; time_from_start.sec = 1; time_from_start.nanosec = 0; - double trajectory_frac = rclcpp::Duration::from_seconds(0.01).seconds() / - (time_from_start.sec + time_from_start.nanosec * 1e-9); + double trajectory_frac = + controller_period.seconds() / (time_from_start.sec + time_from_start.nanosec * 1e-9); std::vector> points{{first_goal}}; publish( time_from_start, points, rclcpp::Time(0.0, 0.0, RCL_STEADY_TIME), {}, first_goal_velocities); @@ -1690,7 +1727,7 @@ TEST_P(TrajectoryControllerTestParameterized, test_jump_when_state_tracking_erro // One the first update(s) there should be a "jump" in opposite direction from command // (towards the state value) EXPECT_NEAR(first_goal[0], joint_pos_[0], COMMON_THRESHOLD); - auto end_time = updateControllerAsync(rclcpp::Duration::from_seconds(0.01)); + auto end_time = updateControllerAsync(controller_period); // Expect backward commands at first, consider advancement of the trajectory // exact value is not directly predictable, because of the spline interpolation -> increase // tolerance @@ -1699,10 +1736,10 @@ TEST_P(TrajectoryControllerTestParameterized, test_jump_when_state_tracking_erro 0.1); EXPECT_GT(joint_pos_[0], joint_state_pos_[0]); EXPECT_LT(joint_pos_[0], first_goal[0]); - end_time = updateControllerAsync(rclcpp::Duration::from_seconds(0.01), end_time); + end_time = updateControllerAsync(controller_period, end_time); EXPECT_GT(joint_pos_[0], joint_state_pos_[0]); EXPECT_LT(joint_pos_[0], first_goal[0]); - end_time = updateControllerAsync(rclcpp::Duration::from_seconds(0.01), end_time); + end_time = updateControllerAsync(controller_period, end_time); EXPECT_GT(joint_pos_[0], joint_state_pos_[0]); EXPECT_LT(joint_pos_[0], first_goal[0]); @@ -1721,17 +1758,19 @@ TEST_P(TrajectoryControllerTestParameterized, test_jump_when_state_tracking_erro // One the first update(s) there should be a "jump" in the goal direction from command // (towards the state value) EXPECT_NEAR(second_goal[0], joint_pos_[0], COMMON_THRESHOLD); - end_time = updateControllerAsync(rclcpp::Duration::from_seconds(0.01)); + end_time = updateControllerAsync(controller_period); // Expect backward commands at first, consider advancement of the trajectory + // exact value is not directly predictable, because of the spline interpolation -> increase + // tolerance EXPECT_NEAR( joint_state_pos_[0] + (first_goal[0] - joint_state_pos_[0]) * trajectory_frac, joint_pos_[0], - COMMON_THRESHOLD); + 0.1); EXPECT_LT(joint_pos_[0], joint_state_pos_[0]); EXPECT_GT(joint_pos_[0], first_goal[0]); - end_time = updateControllerAsync(rclcpp::Duration::from_seconds(0.01), end_time); + end_time = updateControllerAsync(controller_period, end_time); EXPECT_LT(joint_pos_[0], joint_state_pos_[0]); EXPECT_GT(joint_pos_[0], first_goal[0]); - end_time = updateControllerAsync(rclcpp::Duration::from_seconds(0.01), end_time); + end_time = updateControllerAsync(controller_period, end_time); EXPECT_LT(joint_pos_[0], joint_state_pos_[0]); EXPECT_GT(joint_pos_[0], first_goal[0]); @@ -1747,13 +1786,17 @@ TEST_P(TrajectoryControllerTestParameterized, test_no_jump_when_state_tracking_e rclcpp::executors::SingleThreadedExecutor executor; // set open loop to true, this should change behavior from above rclcpp::Parameter is_open_loop_parameters("open_loop_control", true); - SetUpAndActivateTrajectoryController(executor, {is_open_loop_parameters}, true); + rclcpp::Parameter update_rate_param("update_rate", 100); + SetUpAndActivateTrajectoryController( + executor, {is_open_loop_parameters, update_rate_param}, true); if (traj_controller_->has_position_command_interface() == false) { // only makes sense with position command interface return; } + auto controller_period = + rclcpp::Duration::from_seconds(1.0 / traj_controller_->get_update_rate()); // goal setup std::vector first_goal = {3.3, 4.4, 5.5}; @@ -1764,8 +1807,8 @@ TEST_P(TrajectoryControllerTestParameterized, test_no_jump_when_state_tracking_e builtin_interfaces::msg::Duration time_from_start; time_from_start.sec = 1; time_from_start.nanosec = 0; - double trajectory_frac = rclcpp::Duration::from_seconds(0.01).seconds() / - (time_from_start.sec + time_from_start.nanosec * 1e-9); + double trajectory_frac = + controller_period.seconds() / (time_from_start.sec + time_from_start.nanosec * 1e-9); std::vector> points{{first_goal}}; publish(time_from_start, points, rclcpp::Time(0.0, 0.0, RCL_STEADY_TIME)); traj_controller_->wait_for_trajectory(executor); @@ -1788,17 +1831,18 @@ TEST_P(TrajectoryControllerTestParameterized, test_no_jump_when_state_tracking_e // One the first update(s) there **should not** be a "jump" in opposite direction from // command (towards the state value) EXPECT_NEAR(first_goal[0], joint_pos_[0], COMMON_THRESHOLD); - auto end_time = updateControllerAsync(rclcpp::Duration::from_seconds(0.01)); + auto end_time = updateControllerAsync(controller_period); // There should not be backward commands + // exact value is not directly predictable, because of the spline interpolation -> increase + // tolerance EXPECT_NEAR( - first_goal[0] + (second_goal[0] - first_goal[0]) * trajectory_frac, joint_pos_[0], - COMMON_THRESHOLD); + first_goal[0] + (second_goal[0] - first_goal[0]) * trajectory_frac, joint_pos_[0], 0.1); EXPECT_GT(joint_pos_[0], first_goal[0]); EXPECT_LT(joint_pos_[0], second_goal[0]); - end_time = updateControllerAsync(rclcpp::Duration::from_seconds(0.01), end_time); + end_time = updateControllerAsync(controller_period, end_time); EXPECT_GT(joint_pos_[0], first_goal[0]); EXPECT_LT(joint_pos_[0], second_goal[0]); - end_time = updateControllerAsync(rclcpp::Duration::from_seconds(0.01), end_time); + end_time = updateControllerAsync(controller_period, end_time); EXPECT_GT(joint_pos_[0], first_goal[0]); EXPECT_LT(joint_pos_[0], second_goal[0]); @@ -1817,17 +1861,18 @@ TEST_P(TrajectoryControllerTestParameterized, test_no_jump_when_state_tracking_e // One the first update(s) there **should not** be a "jump" in the goal direction from // command (towards the state value) EXPECT_NEAR(second_goal[0], joint_pos_[0], COMMON_THRESHOLD); - end_time = updateControllerAsync(rclcpp::Duration::from_seconds(0.01), end_time); + end_time = updateControllerAsync(controller_period, end_time); // There should not be a jump toward commands + // exact value is not directly predictable, because of the spline interpolation -> increase + // tolerance EXPECT_NEAR( - second_goal[0] + (first_goal[0] - second_goal[0]) * trajectory_frac, joint_pos_[0], - COMMON_THRESHOLD); + second_goal[0] + (first_goal[0] - second_goal[0]) * trajectory_frac, joint_pos_[0], 0.1); EXPECT_LT(joint_pos_[0], second_goal[0]); EXPECT_GT(joint_pos_[0], first_goal[0]); - end_time = updateControllerAsync(rclcpp::Duration::from_seconds(0.01), end_time); + end_time = updateControllerAsync(controller_period, end_time); EXPECT_GT(joint_pos_[0], first_goal[0]); EXPECT_LT(joint_pos_[0], second_goal[0]); - end_time = updateControllerAsync(rclcpp::Duration::from_seconds(0.01), end_time); + end_time = updateControllerAsync(controller_period, end_time); EXPECT_GT(joint_pos_[0], first_goal[0]); EXPECT_LT(joint_pos_[0], second_goal[0]); From 62003f8a03785ca5ee8305be39a6d0824bf7bd3e Mon Sep 17 00:00:00 2001 From: Felix Exner Date: Sun, 13 Oct 2024 22:25:30 +0200 Subject: [PATCH 34/43] Fix period calculation in trajectory_actions test The generated period was more of an uptime --- .../test/test_trajectory_actions.cpp | 8 ++++++-- 1 file changed, 6 insertions(+), 2 deletions(-) diff --git a/joint_trajectory_controller/test/test_trajectory_actions.cpp b/joint_trajectory_controller/test/test_trajectory_actions.cpp index 164f7d0e11..8f45fb66af 100644 --- a/joint_trajectory_controller/test/test_trajectory_actions.cpp +++ b/joint_trajectory_controller/test/test_trajectory_actions.cpp @@ -83,12 +83,16 @@ class TestTrajectoryActions : public TrajectoryControllerTest { // controller hardware cycle update loop auto clock = rclcpp::Clock(RCL_STEADY_TIME); - auto start_time = clock.now(); + auto now_time = clock.now(); + auto start_time = now_time; + auto last_time = start_time; rclcpp::Duration wait = rclcpp::Duration::from_seconds(2.0); auto end_time = start_time + wait; while (clock.now() < end_time) { - traj_controller_->update(clock.now(), clock.now() - start_time); + now_time = clock.now(); + traj_controller_->update(now_time, now_time - last_time); + last_time = now_time; } }); From 1f9bfb4684718add31198bd620dbdf0115021a77 Mon Sep 17 00:00:00 2001 From: Felix Exner Date: Sun, 13 Oct 2024 22:26:25 +0200 Subject: [PATCH 35/43] Sample trajectory based on the sum of periods instead of the absolute time --- .../joint_trajectory_controller.hpp | 2 ++ .../src/joint_trajectory_controller.cpp | 9 +++++++-- 2 files changed, 9 insertions(+), 2 deletions(-) diff --git a/joint_trajectory_controller/include/joint_trajectory_controller/joint_trajectory_controller.hpp b/joint_trajectory_controller/include/joint_trajectory_controller/joint_trajectory_controller.hpp index 4ff06342b4..ca1b166aee 100644 --- a/joint_trajectory_controller/include/joint_trajectory_controller/joint_trajectory_controller.hpp +++ b/joint_trajectory_controller/include/joint_trajectory_controller/joint_trajectory_controller.hpp @@ -126,6 +126,8 @@ class JointTrajectoryController : public controller_interface::ControllerInterfa Params params_; rclcpp::Duration update_period_{0, 0}; + rclcpp::Time traj_time_; + trajectory_msgs::msg::JointTrajectoryPoint last_commanded_state_; /// Specify interpolation method. Default to splines. interpolation_methods::InterpolationMethod interpolation_method_{ diff --git a/joint_trajectory_controller/src/joint_trajectory_controller.cpp b/joint_trajectory_controller/src/joint_trajectory_controller.cpp index 0f338de1f9..ec3583ab84 100644 --- a/joint_trajectory_controller/src/joint_trajectory_controller.cpp +++ b/joint_trajectory_controller/src/joint_trajectory_controller.cpp @@ -199,11 +199,16 @@ controller_interface::return_type JointTrajectoryController::update( traj_external_point_ptr_->sample( // Sample once at the beginning to establish the start time if none was given time, interpolation_method_, state_desired_, start_segment_itr, end_segment_itr); + traj_time_ = time; + } + else + { + traj_time_ += period; } // Sample setpoint for next control cycle const bool valid_point = traj_external_point_ptr_->sample( - time + update_period_, interpolation_method_, state_desired_, start_segment_itr, + traj_time_ + update_period_, interpolation_method_, state_desired_, start_segment_itr, end_segment_itr); if (valid_point) @@ -216,7 +221,7 @@ controller_interface::return_type JointTrajectoryController::update( // time_difference is // - negative until first point is reached // - counting from zero to time_from_start of next point - double time_difference = time.seconds() - segment_time_from_start.seconds(); + double time_difference = traj_time_.seconds() - segment_time_from_start.seconds(); bool tolerance_violated_while_moving = false; bool outside_goal_tolerance = false; bool within_goal_time = true; From 0d08c38d84b0e5fdf51f236a241657ad3af161b8 Mon Sep 17 00:00:00 2001 From: Felix Exner Date: Mon, 14 Oct 2024 06:41:54 +0200 Subject: [PATCH 36/43] Cleanup some logging --- .../src/joint_trajectory_controller.cpp | 20 ++++++++++++++----- 1 file changed, 15 insertions(+), 5 deletions(-) diff --git a/joint_trajectory_controller/src/joint_trajectory_controller.cpp b/joint_trajectory_controller/src/joint_trajectory_controller.cpp index 754c8398d8..151bf77d57 100644 --- a/joint_trajectory_controller/src/joint_trajectory_controller.cpp +++ b/joint_trajectory_controller/src/joint_trajectory_controller.cpp @@ -139,9 +139,6 @@ JointTrajectoryController::state_interface_configuration() const } if (!params_.speed_scaling_state_interface_name.empty()) { - RCLCPP_INFO( - logger, "Using scaling state from the hardware from interface %s.", - params_.speed_scaling_state_interface_name.c_str()); conf.names.push_back(params_.speed_scaling_state_interface_name); } return conf; @@ -925,6 +922,18 @@ controller_interface::CallbackReturn JointTrajectoryController::on_configure( "of speed scaling, please only use a position interface when configuring this controller."); scaling_factor_ = 1.0; } + if (!params_.speed_scaling_state_interface_name.empty()) + { + RCLCPP_INFO( + logger, "Using scaling state from the hardware from interface %s.", + params_.speed_scaling_state_interface_name.c_str()); + } + else + { + RCLCPP_INFO( + get_node()->get_logger(), + "No scaling interface set. This controller will not use speed scaling."); + } return CallbackReturn::SUCCESS; } @@ -946,7 +955,6 @@ controller_interface::CallbackReturn JointTrajectoryController::on_activate( // Set scaling interfaces if (!params_.speed_scaling_state_interface_name.empty()) { - RCLCPP_WARN(logger, "I do have a speed scaling state interface configured"); auto it = std::find_if( state_interfaces_.begin(), state_interfaces_.end(), [&](auto & interface) { return (interface.get_name() == params_.speed_scaling_state_interface_name); }); @@ -956,7 +964,9 @@ controller_interface::CallbackReturn JointTrajectoryController::on_activate( } else { - RCLCPP_ERROR(logger, "Did not find speed scaling interface in state interfaces."); + RCLCPP_ERROR( + logger, "Did not find speed scaling interface '%s' in state interfaces.", + params_.speed_scaling_state_interface_name.c_str()); } } if (!params_.speed_scaling_command_interface_name.empty()) From c56ce2b618b5882b33c0a0d64fc4822d405e8823 Mon Sep 17 00:00:00 2001 From: Felix Exner Date: Sun, 1 Dec 2024 19:25:05 +0000 Subject: [PATCH 37/43] Add test for scaled trajectory execution --- .../src/joint_trajectory_controller.cpp | 13 ++- .../test/test_trajectory_actions.cpp | 80 +++++++++++++++++++ 2 files changed, 90 insertions(+), 3 deletions(-) diff --git a/joint_trajectory_controller/src/joint_trajectory_controller.cpp b/joint_trajectory_controller/src/joint_trajectory_controller.cpp index db554fa810..598fe6cee9 100644 --- a/joint_trajectory_controller/src/joint_trajectory_controller.cpp +++ b/joint_trajectory_controller/src/joint_trajectory_controller.cpp @@ -161,7 +161,12 @@ controller_interface::return_type JointTrajectoryController::update( { if (scaling_command_interface_.has_value()) { - scaling_command_interface_->get().set_value(scaling_factor_.load()); + if (!scaling_command_interface_->get().set_value(scaling_factor_.load())) + { + RCLCPP_ERROR( + get_node()->get_logger(), + "Could not set speed scaling factor through command interfaces."); + } } } @@ -229,12 +234,15 @@ controller_interface::return_type JointTrajectoryController::update( // Sample expected state from the trajectory traj_external_point_ptr_->sample( traj_time_, interpolation_method_, state_desired_, start_segment_itr, end_segment_itr); + state_desired_.time_from_start = traj_time_ - traj_external_point_ptr_->time_from_start(); // Sample setpoint for next control cycle const bool valid_point = traj_external_point_ptr_->sample( traj_time_ + update_period_, interpolation_method_, command_next_, start_segment_itr, end_segment_itr, false); + state_current_.time_from_start = time - traj_external_point_ptr_->time_from_start(); + if (valid_point) { const rclcpp::Time traj_start = traj_external_point_ptr_->time_from_start(); @@ -352,7 +360,6 @@ controller_interface::return_type JointTrajectoryController::update( auto feedback = std::make_shared(); feedback->header.stamp = time; feedback->joint_names = params_.joints; - feedback->actual = state_current_; feedback->desired = state_desired_; feedback->error = state_error_; @@ -933,7 +940,7 @@ controller_interface::CallbackReturn JointTrajectoryController::on_configure( { RCLCPP_INFO( get_node()->get_logger(), - "No scaling interface set. This controller will not use speed scaling."); + "No scaling interface set. This controller will not read speed scaling from the hardware."); } if (get_update_rate() == 0) diff --git a/joint_trajectory_controller/test/test_trajectory_actions.cpp b/joint_trajectory_controller/test/test_trajectory_actions.cpp index d4979deef8..f13d3c86ad 100644 --- a/joint_trajectory_controller/test/test_trajectory_actions.cpp +++ b/joint_trajectory_controller/test/test_trajectory_actions.cpp @@ -219,6 +219,15 @@ class TestTrajectoryActionsTestParameterized static void TearDownTestCase() { TrajectoryControllerTest::TearDownTestCase(); } }; +class TestTrajectoryActionsTestScalingFactor : public TestTrajectoryActions, + public ::testing::WithParamInterface +{ +public: + virtual void SetUp() { TestTrajectoryActions::SetUp(); } + + static void TearDownTestCase() { TrajectoryControllerTest::TearDownTestCase(); } +}; + TEST_P(TestTrajectoryActionsTestParameterized, test_success_single_point_sendgoal) { // deactivate velocity tolerance @@ -1012,3 +1021,74 @@ INSTANTIATE_TEST_SUITE_P( std::make_tuple( std::vector({"effort"}), std::vector({"position", "velocity", "acceleration"})))); + +TEST_P(TestTrajectoryActionsTestScalingFactor, test_scaling_execution_time_succeeds) +{ + double scaling_factor = GetParam(); + const double state_tol = 0.3; // Since we use a common buffer for cmd and state in these tests, + // the error will be whatever the command diff is. + std::vector params = { + rclcpp::Parameter("open_loop_control", false), + rclcpp::Parameter("constraints.stopped_velocity_tolerance", 0.0), + rclcpp::Parameter("scaling_factor_initial_default", scaling_factor), + rclcpp::Parameter("constraints.joint1.trajectory", state_tol), + rclcpp::Parameter("constraints.joint2.trajectory", state_tol), + rclcpp::Parameter("constraints.joint3.trajectory", state_tol), + }; + SetUpExecutor({params}, false, 1.0, 0.0); + SetUpControllerHardware(); + + // add feedback + goal_options_.feedback_callback = + [&]( + rclcpp_action::ClientGoalHandle::SharedPtr, + const std::shared_ptr feedback_msg) + { + auto time_diff_sec = [](const builtin_interfaces::msg::Duration & msg) + { return static_cast(msg.sec) + static_cast(msg.nanosec) * 1e-9; }; + + // Since we are summing up scaled periods, the scale of the period sum will not be the same + // due to numerical errors. + EXPECT_NEAR( + time_diff_sec(feedback_msg->desired.time_from_start), + time_diff_sec(feedback_msg->actual.time_from_start) * scaling_factor, + 1e-3 * time_diff_sec(feedback_msg->actual.time_from_start)); + }; + + std::shared_future gh_future; + // send goal + std::vector> points_positions{{{4.0, 5.0, 6.0}}, {{7.0, 8.0, 9.0}}}; + { + std::vector points; + JointTrajectoryPoint point1; + point1.time_from_start = rclcpp::Duration::from_seconds(0.1); + point1.positions.resize(joint_names_.size()); + + point1.positions = points_positions.at(0); + points.push_back(point1); + + JointTrajectoryPoint point2; + point2.time_from_start = rclcpp::Duration::from_seconds(0.2); + point2.positions.resize(joint_names_.size()); + + point2.positions = points_positions.at(1); + points.push_back(point2); + + gh_future = sendActionGoal(points, 1.0, goal_options_); + } + controller_hw_thread_.join(); + + EXPECT_TRUE(gh_future.get()); + EXPECT_EQ(rclcpp_action::ResultCode::SUCCEEDED, common_resultcode_); + + // run an update + updateControllerAsync(rclcpp::Duration::from_seconds(0.01)); + + // it should be holding the last position goal + // i.e., active but trivial trajectory (one point only) + // note: the action goal also is a trivial trajectory + expectCommandPoint(points_positions[1]); +} + +INSTANTIATE_TEST_SUITE_P( + ScaledJTCTests, TestTrajectoryActionsTestScalingFactor, ::testing::Values(0.25, 0.87, 1.0, 2.0)); From b101360d44f572326e5a5676d3dee16cdd095044 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Christoph=20Fr=C3=B6hlich?= Date: Tue, 3 Dec 2024 12:05:12 +0100 Subject: [PATCH 38/43] Use master branch of control_msgs repo Co-authored-by: Felix Exner (fexner) --- ros2_controllers-not-released.jazzy.repos | 5 ----- ros2_controllers-not-released.rolling.repos | 5 ----- ros2_controllers.rolling.repos | 4 ++-- 3 files changed, 2 insertions(+), 12 deletions(-) diff --git a/ros2_controllers-not-released.jazzy.repos b/ros2_controllers-not-released.jazzy.repos index 2aa7462380..66352f4960 100644 --- a/ros2_controllers-not-released.jazzy.repos +++ b/ros2_controllers-not-released.jazzy.repos @@ -3,8 +3,3 @@ repositories: type: git url: https://github.com/picknikrobotics/generate_parameter_library.git version: main - - control_msgs: - type: git - url: https://github.com/fmauch/control_msgs.git - version: scaled_jtc diff --git a/ros2_controllers-not-released.rolling.repos b/ros2_controllers-not-released.rolling.repos index 2aa7462380..66352f4960 100644 --- a/ros2_controllers-not-released.rolling.repos +++ b/ros2_controllers-not-released.rolling.repos @@ -3,8 +3,3 @@ repositories: type: git url: https://github.com/picknikrobotics/generate_parameter_library.git version: main - - control_msgs: - type: git - url: https://github.com/fmauch/control_msgs.git - version: scaled_jtc diff --git a/ros2_controllers.rolling.repos b/ros2_controllers.rolling.repos index fde72acc2c..8c20eccc96 100644 --- a/ros2_controllers.rolling.repos +++ b/ros2_controllers.rolling.repos @@ -9,8 +9,8 @@ repositories: version: master control_msgs: type: git - url: https://github.com/fmauch/control_msgs.git - version: scaled_jtc + url: https://github.com/ros-controls/control_msgs.git + version: master control_toolbox: type: git url: https://github.com/ros-controls/control_toolbox.git From 21c9c4d7868630fcb018236e3a34377cd19e6fdd Mon Sep 17 00:00:00 2001 From: "Felix Exner (fexner)" Date: Wed, 4 Dec 2024 21:32:54 +0100 Subject: [PATCH 39/43] Apply suggestions from code review MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit Co-authored-by: Christoph Fröhlich --- .../src/joint_trajectory_controller_parameters.yaml | 3 ++- 1 file changed, 2 insertions(+), 1 deletion(-) diff --git a/joint_trajectory_controller/src/joint_trajectory_controller_parameters.yaml b/joint_trajectory_controller/src/joint_trajectory_controller_parameters.yaml index fd3d12584c..e7120c4ec5 100644 --- a/joint_trajectory_controller/src/joint_trajectory_controller_parameters.yaml +++ b/joint_trajectory_controller/src/joint_trajectory_controller_parameters.yaml @@ -42,7 +42,8 @@ joint_trajectory_controller: scaling_factor_initial_default: { type: double, default_value: 1.0, - description: "The initial value of the scaling factor if not exchange with hardware takes place.", + read_only: true, + description: "The initial value of the scaling factor if no exchange with hardware takes place.", validation: { gt_eq<>: 0.0, } From 9d5c9813ad8613029a332fe8bbc236ad03763a0c Mon Sep 17 00:00:00 2001 From: Felix Exner Date: Wed, 4 Dec 2024 20:37:20 +0000 Subject: [PATCH 40/43] Update tolerances documentation --- joint_trajectory_controller/doc/speed_scaling.rst | 5 ++--- 1 file changed, 2 insertions(+), 3 deletions(-) diff --git a/joint_trajectory_controller/doc/speed_scaling.rst b/joint_trajectory_controller/doc/speed_scaling.rst index 4bad7c7167..e920e16a83 100644 --- a/joint_trajectory_controller/doc/speed_scaling.rst +++ b/joint_trajectory_controller/doc/speed_scaling.rst @@ -92,9 +92,8 @@ Effect on tolerances When speed scaling is used while executing a trajectory, the tolerances configured for execution will be scaled, as well. -Since commands are generated from the scaled trajectory time, **path errors** will also be compared to -the scaled trajectory. However, since the next command is always using the full time step, there -will obviously always be a small error added by the robot only executing a part of the command. +Since commands are generated from the scaled trajectory time, **path errors** will also be compared +to the scaled trajectory. The **goal time tolerance** also uses the virtual trajectory time. This means that a trajectory being executed with a constant scaling factor of 0.5 will take twice as long for execution than the From a2d319bd879d2abf6b6069b39e9fb7479cf648f7 Mon Sep 17 00:00:00 2001 From: Felix Exner Date: Wed, 4 Dec 2024 20:43:19 +0000 Subject: [PATCH 41/43] Only log set scaling factor if it is changed --- .../src/joint_trajectory_controller.cpp | 7 ++++++- 1 file changed, 6 insertions(+), 1 deletion(-) diff --git a/joint_trajectory_controller/src/joint_trajectory_controller.cpp b/joint_trajectory_controller/src/joint_trajectory_controller.cpp index 598fe6cee9..4fab04eb37 100644 --- a/joint_trajectory_controller/src/joint_trajectory_controller.cpp +++ b/joint_trajectory_controller/src/joint_trajectory_controller.cpp @@ -1693,7 +1693,12 @@ bool JointTrajectoryController::set_scaling_factor(const double scaling_factor) return false; } - RCLCPP_INFO(get_node()->get_logger(), "New scaling factor will be %f", scaling_factor); + if (scaling_factor_ != scaling_factor_) + { + RCLCPP_INFO( + get_node()->get_logger().get_child("speed_scaling"), "New scaling factor will be %f", + scaling_factor); + } if (params_.speed_scaling_command_interface_name.empty()) { if (!params_.speed_scaling_state_interface_name.empty()) From 5d2b852bcee7ed61e3cd283ab6b27331e9092636 Mon Sep 17 00:00:00 2001 From: Felix Exner Date: Wed, 4 Dec 2024 21:18:00 +0000 Subject: [PATCH 42/43] Remove duplicate reading period from parameter --- .../src/joint_trajectory_controller.cpp | 9 --------- 1 file changed, 9 deletions(-) diff --git a/joint_trajectory_controller/src/joint_trajectory_controller.cpp b/joint_trajectory_controller/src/joint_trajectory_controller.cpp index 4fab04eb37..617502714d 100644 --- a/joint_trajectory_controller/src/joint_trajectory_controller.cpp +++ b/joint_trajectory_controller/src/joint_trajectory_controller.cpp @@ -1074,15 +1074,6 @@ controller_interface::CallbackReturn JointTrajectoryController::on_activate( cmd_timeout_ = 0.0; } - { - if (get_update_rate() == 0) - { - throw std::runtime_error("Controller's update rate is set to 0. This should not happen!"); - } - update_period_ = - rclcpp::Duration(0.0, static_cast(1.0e9 / static_cast(get_update_rate()))); - } - return CallbackReturn::SUCCESS; } From 7844221d77a3cd5bfbb5b901369cc8f0512923c3 Mon Sep 17 00:00:00 2001 From: Felix Exner Date: Wed, 4 Dec 2024 21:41:37 +0000 Subject: [PATCH 43/43] Make trajectory test use tolerances Also run two trajectories --- .../test/test_trajectory_actions.cpp | 41 ++++++++++++------- 1 file changed, 26 insertions(+), 15 deletions(-) diff --git a/joint_trajectory_controller/test/test_trajectory_actions.cpp b/joint_trajectory_controller/test/test_trajectory_actions.cpp index f13d3c86ad..0eeb7f0eb6 100644 --- a/joint_trajectory_controller/test/test_trajectory_actions.cpp +++ b/joint_trajectory_controller/test/test_trajectory_actions.cpp @@ -1029,11 +1029,14 @@ TEST_P(TestTrajectoryActionsTestScalingFactor, test_scaling_execution_time_succe // the error will be whatever the command diff is. std::vector params = { rclcpp::Parameter("open_loop_control", false), - rclcpp::Parameter("constraints.stopped_velocity_tolerance", 0.0), + rclcpp::Parameter("constraints.goal_time", 1e-10), + rclcpp::Parameter("constraints.goal", 1e-10), rclcpp::Parameter("scaling_factor_initial_default", scaling_factor), rclcpp::Parameter("constraints.joint1.trajectory", state_tol), rclcpp::Parameter("constraints.joint2.trajectory", state_tol), rclcpp::Parameter("constraints.joint3.trajectory", state_tol), + // the test hw does not report velocity, so this constraint will not do anything + rclcpp::Parameter("constraints.stopped_velocity_tolerance", 0.01), }; SetUpExecutor({params}, false, 1.0, 0.0); SetUpControllerHardware(); @@ -1058,24 +1061,22 @@ TEST_P(TestTrajectoryActionsTestScalingFactor, test_scaling_execution_time_succe std::shared_future gh_future; // send goal std::vector> points_positions{{{4.0, 5.0, 6.0}}, {{7.0, 8.0, 9.0}}}; - { - std::vector points; - JointTrajectoryPoint point1; - point1.time_from_start = rclcpp::Duration::from_seconds(0.1); - point1.positions.resize(joint_names_.size()); + std::vector points; + JointTrajectoryPoint point1; + point1.time_from_start = rclcpp::Duration::from_seconds(0.1); + point1.positions.resize(joint_names_.size()); - point1.positions = points_positions.at(0); - points.push_back(point1); + point1.positions = points_positions.at(0); + points.push_back(point1); - JointTrajectoryPoint point2; - point2.time_from_start = rclcpp::Duration::from_seconds(0.2); - point2.positions.resize(joint_names_.size()); + JointTrajectoryPoint point2; + point2.time_from_start = rclcpp::Duration::from_seconds(0.2); + point2.positions.resize(joint_names_.size()); - point2.positions = points_positions.at(1); - points.push_back(point2); + point2.positions = points_positions.at(1); + points.push_back(point2); - gh_future = sendActionGoal(points, 1.0, goal_options_); - } + gh_future = sendActionGoal(points, 1.0, goal_options_); controller_hw_thread_.join(); EXPECT_TRUE(gh_future.get()); @@ -1088,6 +1089,16 @@ TEST_P(TestTrajectoryActionsTestScalingFactor, test_scaling_execution_time_succe // i.e., active but trivial trajectory (one point only) // note: the action goal also is a trivial trajectory expectCommandPoint(points_positions[1]); + + // Run a second trajectory + SetUpControllerHardware(); + gh_future = sendActionGoal(points, 1.0, goal_options_); + std::cout << "Waiting for another trajectory to finish" << std::endl; + controller_hw_thread_.join(); + std::cout << "trajectory_done" << std::endl; + + EXPECT_TRUE(gh_future.get()); + EXPECT_EQ(rclcpp_action::ResultCode::SUCCEEDED, common_resultcode_); } INSTANTIATE_TEST_SUITE_P(