From c94af39ba97c39721781161982951bad8b032679 Mon Sep 17 00:00:00 2001 From: ahcorde Date: Mon, 11 Jan 2021 16:08:33 +0100 Subject: [PATCH 01/33] Updated with ros2-control foxy API Signed-off-by: ahcorde --- README.md | 39 +- gazebo_ros2_control/CMakeLists.txt | 31 +- .../gazebo_hardware_plugins.xml | 10 + .../default_robot_hw_sim.hpp | 168 ----- .../gazebo_ros2_control_plugin.hpp | 16 +- .../gazebo_ros2_control/gazebo_system.hpp | 143 ++++ .../gazebo_system_interface.hpp | 67 ++ .../gazebo_ros2_control/robot_hw_sim.hpp | 135 ---- gazebo_ros2_control/package.xml | 3 +- gazebo_ros2_control/robot_hw_sim_plugins.xml | 11 - .../src/default_robot_hw_sim.cpp | 624 ------------------ .../src/gazebo_ros2_control_plugin.cpp | 205 +++--- gazebo_ros2_control/src/gazebo_system.cpp | 394 +++++++++++ .../urdf/test_cart_position.xacro.urdf | 4 +- .../urdf/test_cart_position_pid.xacro.urdf | 4 +- .../urdf/test_cart_velocity.xacro.urdf | 4 +- 16 files changed, 759 insertions(+), 1099 deletions(-) create mode 100644 gazebo_ros2_control/gazebo_hardware_plugins.xml delete mode 100644 gazebo_ros2_control/include/gazebo_ros2_control/default_robot_hw_sim.hpp create mode 100644 gazebo_ros2_control/include/gazebo_ros2_control/gazebo_system.hpp create mode 100644 gazebo_ros2_control/include/gazebo_ros2_control/gazebo_system_interface.hpp delete mode 100644 gazebo_ros2_control/include/gazebo_ros2_control/robot_hw_sim.hpp delete mode 100644 gazebo_ros2_control/robot_hw_sim_plugins.xml delete mode 100644 gazebo_ros2_control/src/default_robot_hw_sim.cpp create mode 100644 gazebo_ros2_control/src/gazebo_system.cpp diff --git a/README.md b/README.md index cec0ba74..6e572d57 100644 --- a/README.md +++ b/README.md @@ -63,9 +63,11 @@ ros2 run gazebo_ros2_control_demos example_position ## Add transmission elements to a URDF -To use `ros2_control` with your robot, you need to add some additional elements to your URDF. The `` element is used to link actuators to joints, see the `` spec for exact XML format. +To use `ros2_control` with your robot, you need to add some additional elements to your URDF. +The `` element is used to link actuators to joints, see the `` spec for exact XML format. -For the purposes of `gazebo_ros2_control` in its current implementation, the only important information in these transmission tags are: +For the purposes of `gazebo_ros2_control` in its current implementation, the only important information +in these transmission tags are: - `` the name must correspond to a joint else where in your URDF - `` the type of transmission. Currently only `transmission_interface/SimpleTransmission` is implemented. @@ -82,11 +84,12 @@ robot hardware interfaces between `ros2_control` and Gazebo. ```xml - gazebo_ros2_control/DefaultRobotHWSim + gazebo_ros2_control/GazeboSystem robot_description robot_state_publisher $(find gazebo_ros2_control_demos)/config/cartpole_controller.yaml False + 0.01 ``` @@ -96,8 +99,9 @@ The `gazebo_ros2_control` `` tag also has the following optional child e - ``: The period of the controller update (in seconds), defaults to Gazebo's period - ``: The location of the `robot_description` (URDF) on the parameter server, defaults to `robot_description` - ``: Name of the node where the `robot_param` is located, defauls to `robot_state_publisher` - - ``: The pluginlib name of a custom robot sim interface to be used, defaults to `gazebo_ros2_control/DefaultRobotHWSim` + - ``: The pluginlib name of a custom robot sim interface to be used, defaults to `gazebo_ros2_control/GazeboSystem` - ``: YAML file with the configuration of the controllers + - ``: Topic to publish the emergency stop #### Default gazebo_ros2_control Behavior @@ -113,14 +117,17 @@ The default behavior provides the following ros2_control interfaces: The `gazebo_ros2_control` Gazebo plugin also provides a pluginlib-based interface to implement custom interfaces between Gazebo and `ros2_control` for simulating more complex mechanisms (nonlinear springs, linkages, etc). -These plugins must inherit `gazebo_ros2_control::RobotHWSim` which implements a simulated `ros2_control` `hardware_interface::RobotHW`. RobotHWSim provides API-level access to read and command joint properties in the Gazebo simulator. +These plugins must inherit `gazebo_ros2_control::GazeboSystemInterface` which implements a simulated `ros2_control` +`hardware_interface::SystemInterface`. SystemInterface provides API-level access to read and command joint properties. -The respective RobotHWSim sub-class is specified in a URDF model and is loaded when the robot model is loaded. For example, the following XML will load the default plugin (same behavior as when using no `` tag): +The respective GazeboSystemInterface sub-class is specified in a URDF model and is loaded when the +robot model is loaded. For example, the following XML will load the default plugin +(same behavior as when using no `` tag): ```xml - gazebo_ros2_control/DefaultRobotHWSim + gazebo_ros2_control/GazeboSystem ``` @@ -138,13 +145,13 @@ Use the tag `` inside `` to set the YAML file with the contr ``` This controller publishes the state of all resources registered to a -`hardware_interface::JointStateInterface` to a topic of type `sensor_msgs/msg/JointState`. The following is a basic configuration of the controller. +`hardware_interface::StateInterface` to a topic of type `sensor_msgs/msg/JointState`. +The following is a basic configuration of the controller. ```yaml joint_state_controller: ros__parameters: type: joint_state_controller/JointStateController - publish_rate: 50 ``` This controller creates an action called `/cart_pole_controller/follow_joint_trajectory` of type `control_msgs::action::FollowJointTrajectory`. @@ -166,7 +173,9 @@ cart_pole_controller: #### Setting PID gains -To set the PID gains for a specific joint you need to define them inside ``. Using the generic way of defining parameters with `gazebo_ros`. The name of the parameter correspond the name of the joint followed by a dot and the name of the parameter: `p`, `i`, `d`, `i_clamp_max`, `i_clamp_min` and `antiwindup`. +To set the PID gains for a specific joint you need to define them inside ``. +Using the generic way of defining parameters with `gazebo_ros`. The name of the parameter correspond to +the name of the joint followed by a dot and the name of the parameter: `p`, `i`, `d`, `i_clamp_max`, `i_clamp_min` and `antiwindup`. ```xml @@ -181,7 +190,7 @@ To set the PID gains for a specific joint you need to define them inside `false e_stop_topic:=emergency_stop - gazebo_ros2_control/DefaultRobotHWSim + gazebo_ros2_control/GazeboSystem $(find gazebo_ros2_control_demos)/config/cartpole_controller.yaml ... @@ -228,11 +237,3 @@ ros2 param set /gazebo_ros2_control slider_to_cart.d 15.0 ros2 param set /gazebo_ros2_control slider_to_cart.i_clamp_max 3.0 ros2 param set /gazebo_ros2_control slider_to_cart.i_clamp_min -3.0 ``` - -# NOTES - -`ros2_control` and `ros2_controllers` are in a redesign phase. Some of the packages are unofficial. -In the following links you can track some of the missing features. - - - https://github.com/ros-controls/ros2_control/issues/26 - - https://github.com/ros-controls/ros2_control/issues/32 diff --git a/gazebo_ros2_control/CMakeLists.txt b/gazebo_ros2_control/CMakeLists.txt index 1d689ffa..f9536612 100644 --- a/gazebo_ros2_control/CMakeLists.txt +++ b/gazebo_ros2_control/CMakeLists.txt @@ -8,7 +8,6 @@ find_package(controller_manager REQUIRED) find_package(gazebo_dev REQUIRED) find_package(gazebo_ros REQUIRED) find_package(hardware_interface REQUIRED) -find_package(joint_limits_interface REQUIRED) find_package(pluginlib REQUIRED) find_package(rclcpp REQUIRED) find_package(transmission_interface REQUIRED) @@ -23,7 +22,9 @@ endif() include_directories(include) # Libraries -add_library(${PROJECT_NAME} SHARED src/gazebo_ros2_control_plugin.cpp) +add_library(${PROJECT_NAME} SHARED + src/gazebo_ros2_control_plugin.cpp +) ament_target_dependencies(${PROJECT_NAME} controller_manager gazebo_dev @@ -36,19 +37,20 @@ ament_target_dependencies(${PROJECT_NAME} yaml_cpp_vendor ) -add_library(default_robot_hw_sim SHARED src/default_robot_hw_sim.cpp) -ament_target_dependencies(default_robot_hw_sim - angles - control_toolbox - gazebo_dev +add_library(gazebo_hardware_plugins SHARED + src/gazebo_system.cpp +) +ament_target_dependencies(gazebo_hardware_plugins hardware_interface - joint_limits_interface - rclcpp - transmission_interface + gazebo_dev + control_toolbox + angles ) ## Install -install(TARGETS default_robot_hw_sim ${PROJECT_NAME} +install(TARGETS + ${PROJECT_NAME} + gazebo_hardware_plugins ARCHIVE DESTINATION lib LIBRARY DESTINATION lib RUNTIME DESTINATION bin @@ -56,7 +58,10 @@ install(TARGETS default_robot_hw_sim ${PROJECT_NAME} ament_export_dependencies(ament_cmake) ament_export_dependencies(rclcpp) -ament_export_libraries(${PROJECT_NAME} default_robot_hw_sim) +ament_export_libraries( + ${PROJECT_NAME} + gazebo_hardware_plugins +) if(BUILD_TESTING) find_package(ament_cmake_gtest REQUIRED) @@ -68,6 +73,6 @@ install(DIRECTORY include/${PROJECT_NAME}/ DESTINATION include/${PROJECT_NAME} ) -pluginlib_export_plugin_description_file(gazebo_ros2_control robot_hw_sim_plugins.xml) +pluginlib_export_plugin_description_file(gazebo_ros2_control gazebo_hardware_plugins.xml) ament_package() diff --git a/gazebo_ros2_control/gazebo_hardware_plugins.xml b/gazebo_ros2_control/gazebo_hardware_plugins.xml new file mode 100644 index 00000000..5dc0497f --- /dev/null +++ b/gazebo_ros2_control/gazebo_hardware_plugins.xml @@ -0,0 +1,10 @@ + + + + GazeboPositionJoint + + + diff --git a/gazebo_ros2_control/include/gazebo_ros2_control/default_robot_hw_sim.hpp b/gazebo_ros2_control/include/gazebo_ros2_control/default_robot_hw_sim.hpp deleted file mode 100644 index a1023cac..00000000 --- a/gazebo_ros2_control/include/gazebo_ros2_control/default_robot_hw_sim.hpp +++ /dev/null @@ -1,168 +0,0 @@ -// Copyright (c) 2013, Open Source Robotics Foundation. All rights reserved. -// Copyright (c) 2013, The Johns Hopkins University. All rights reserved. -// -// Redistribution and use in source and binary forms, with or without -// modification, are permitted provided that the following conditions are met: -// -// * Redistributions of source code must retain the above copyright -// notice, this list of conditions and the following disclaimer. -// -// * Redistributions in binary form must reproduce the above copyright -// notice, this list of conditions and the following disclaimer in the -// documentation and/or other materials provided with the distribution. -// -// * Neither the name of the Open Source Robotics Foundation nor the names of its -// contributors may be used to endorse or promote products derived from -// this software without specific prior written permission. -// -// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" -// AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE -// IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE -// ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE -// LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR -// CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF -// SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS -// INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN -// CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) -// ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE -// POSSIBILITY OF SUCH DAMAGE. - -/* Author: Dave Coleman, Jonathan Bohren - Desc: Hardware Interface for any simulated robot in Gazebo -*/ - -#ifndef GAZEBO_ROS2_CONTROL__DEFAULT_ROBOT_HW_SIM_HPP_ -#define GAZEBO_ROS2_CONTROL__DEFAULT_ROBOT_HW_SIM_HPP_ - -#include -#include -#include -#include - -// ros_control -#include "control_toolbox/pid_ros.hpp" - -#include "joint_limits_interface/joint_limits.hpp" -#include "joint_limits_interface/joint_limits_interface.hpp" -#include "joint_limits_interface/joint_limits_rosparam.hpp" -#include "joint_limits_interface/joint_limits_urdf.hpp" - -// Gazebo -#include "gazebo/physics/Joint.hh" -#include "gazebo/physics/Model.hh" - -// ROS -#include "angles/angles.h" -#include "pluginlib/class_list_macros.hpp" -#include "rclcpp/rclcpp.hpp" - -// URDF -#include "urdf/model.h" - -// gazebo_ros_control -#include "gazebo_ros2_control/robot_hw_sim.hpp" - -namespace gazebo_ros2_control -{ - -class DefaultRobotHWSim : public gazebo_ros2_control::RobotHWSim -{ -public: - virtual bool initSim( - const std::string & robot_namespace, - rclcpp::Node::SharedPtr & model_nh, - gazebo::physics::ModelPtr parent_model, - const urdf::Model * const urdf_model, - std::vector transmissions); - - virtual void readSim(rclcpp::Time time, rclcpp::Duration period); - - virtual void writeSim(rclcpp::Time time, rclcpp::Duration period); - - virtual void eStopActive(const bool active); - - // Methods used to control a joint. - enum ControlMethod {EFFORT, POSITION, POSITION_PID, VELOCITY, VELOCITY_PID}; - -private: - rclcpp::Node::SharedPtr nh_; - -protected: - /// \brief Register the limits of the joint specified by joint_name and joint_handle. - /// The limits are retrieved from joint_limit_nh. If urdf_model is not NULL, limits - /// are retrieved from it also. Return the joint's type, lower position limit, upper - /// position limit, and effort limit. - void registerJointLimits( - size_t joint_nr, - const urdf::Model * const urdf_model, - int * const joint_type, double * const lower_limit, - double * const upper_limit, double * const effort_limit, - double * const vel_limit); - - /// \brief Refreshes all valid handle references in a collection. - /// Requests from the RobotHardware updated handle references. This is required after - /// any call to RobotHardware::register_joint() and before a handle is used or bound - /// to a controller since the internal implementation of register_joint binds to doubles - /// inside a std::vector and thus growth of that vector invalidates all existing - /// iterators (i.e. handles). - /// See https://github.com/ros-controls/ros2_control/issues/212 - /// If a handle in the collection is unset (no joint name or interface name) then it is skipped. - void bindJointHandles(std::vector & joint_iface_handles); - - unsigned int n_dof_; - std::vector joint_names_; - std::vector joint_types_; - std::vector joint_lower_limits_; - std::vector joint_upper_limits_; - std::vector joint_effort_limits_; - std::vector joint_vel_limits_; - std::vector joint_control_methods_; - std::vector pid_controllers_; - std::vector joint_position_; - - /// \brief stores the joint positions on ESTOP activation - /// During ESTOP these positions will override the output position command value. - std::vector last_joint_position_command_; - - /// \brief handles to the joints from within Gazebo - std::vector sim_joints_; - - /// \brief The current positions of the joints - std::vector joint_pos_stateh_; - /// \brief The current velocities of the joints - std::vector joint_vel_stateh_; - /// \brief The current effort forces applied to the joints - std::vector joint_eff_stateh_; - - /// \brief The current position command value (if control mode is POSITION) of the joints - std::vector joint_pos_cmdh_; - /// \brief The current effort command value (if control mode is EFFORT) of the joints - std::vector joint_eff_cmdh_; - /// \brief The current velocity command value (if control mode is VELOCITY) of the joints - std::vector joint_vel_cmdh_; - - /// \brief The operational mode (active/inactive) state of the joints - std::vector joint_opmodes_; - - /// \brief operational mode handles of the joints pointing to values in the joint_opmodes_ - /// collection - std::vector joint_opmodehandles_; - - /// \brief Limits for the joints if defined in the URDF or Node parameters - /// The implementation of the joint limit will be chosen based on the URDF parameters and could be - /// one of the hard (saturation) or soft limits based on the control mode (effort, position or - /// velocity) - std::vector> joint_limit_handles_; - - std::string physics_type_; - bool usingODE; - - // e_stop_active_ is true if the emergency stop is active. - bool e_stop_active_, last_e_stop_active_; -}; - -typedef boost::shared_ptr DefaultRobotHWSimPtr; - -} // namespace gazebo_ros2_control - -#endif // GAZEBO_ROS2_CONTROL__DEFAULT_ROBOT_HW_SIM_HPP_ diff --git a/gazebo_ros2_control/include/gazebo_ros2_control/gazebo_ros2_control_plugin.hpp b/gazebo_ros2_control/include/gazebo_ros2_control/gazebo_ros2_control_plugin.hpp index e2d75a90..dc93ba59 100644 --- a/gazebo_ros2_control/include/gazebo_ros2_control/gazebo_ros2_control_plugin.hpp +++ b/gazebo_ros2_control/include/gazebo_ros2_control/gazebo_ros2_control_plugin.hpp @@ -39,18 +39,16 @@ #include #include -// ROS -#include "pluginlib/class_loader.hpp" -#include "rclcpp/rclcpp.hpp" -#include "std_msgs/msg/bool.hpp" +#include "controller_manager/controller_manager.hpp" -// Gazebo #include "gazebo/common/common.hh" -#include "gazebo/physics/physics.hh" +#include "gazebo/physics/Model.hh" + +#include "pluginlib/class_loader.hpp" + +#include "rclcpp/rclcpp.hpp" +#include "rclcpp_lifecycle/lifecycle_node.hpp" -// ros_control -#include "controller_manager/controller_manager.hpp" -#include "gazebo_ros2_control/robot_hw_sim.hpp" #include "transmission_interface/transmission_parser.hpp" namespace gazebo_ros2_control diff --git a/gazebo_ros2_control/include/gazebo_ros2_control/gazebo_system.hpp b/gazebo_ros2_control/include/gazebo_ros2_control/gazebo_system.hpp new file mode 100644 index 00000000..963268ae --- /dev/null +++ b/gazebo_ros2_control/include/gazebo_ros2_control/gazebo_system.hpp @@ -0,0 +1,143 @@ +// Copyright 2021 Open Source Robotics Foundation, Inc. +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + + +#ifndef GAZEBO_ROS2_CONTROL__GAZEBO_SYSTEM_HPP_ +#define GAZEBO_ROS2_CONTROL__GAZEBO_SYSTEM_HPP_ + +#include +#include +#include + +#include "angles/angles.h" + +#include "control_toolbox/pid_ros.hpp" + +#include "gazebo_ros2_control/gazebo_system_interface.hpp" + +#include "std_msgs/msg/bool.hpp" + +namespace gazebo_ros2_control +{ + +class GazeboSystem : public GazeboSystemInterface +{ +public: + // Documentation Inherited + hardware_interface::return_type configure(const hardware_interface::HardwareInfo & system_info) + override; + + // Documentation Inherited + std::vector export_state_interfaces() override; + + // Documentation Inherited + std::vector export_command_interfaces() override; + + // Documentation Inherited + hardware_interface::return_type start() override; + + // Documentation Inherited + hardware_interface::return_type stop() override; + + // Documentation Inherited + hardware_interface::return_type read() override; + + // Documentation Inherited + hardware_interface::return_type write() override; + + // Documentation Inherited + bool initSim( + rclcpp::Node::SharedPtr & model_nh, + gazebo::physics::ModelPtr parent_model, + const urdf::Model * const urdf_model, + std::vector transmissions, + sdf::ElementPtr sdf) override; + + /// \brief callback to get the e_stop signal from the ROS 2 topic + void eStopCB(const std::shared_ptr e_stop_active); + +private: + /// \brief Degrees od freedom. + unsigned int n_dof_; + + /// \brief e_stop_active_ is true if the emergency stop is active. + bool e_stop_active_; + + /// \brief Emergency stop subscriber. + rclcpp::Subscription::SharedPtr e_stop_sub_; + + /// \brief Gazebo Model Ptr. + gazebo::physics::ModelPtr parent_model_; + + /// \brief last time the write method was called. + rclcpp::Time last_update_sim_time_ros_; + + /// \brief it is ODE physics engine? + bool usingODE; + + /// \brief vector with the joint's names. + std::vector joint_names_; + + /// \brief vector with the control method defined in the URDF for each joint. + std::vector joint_control_methods_; + + /// \brief handles to the joints from within Gazebo + std::vector sim_joints_; + + /// \brief vector with the current joint position + std::vector joint_position_; + + /// \brief vector with the current joint velocity + std::vector joint_velocity_; + + /// \brief vector with the current joint effort + std::vector joint_effort_; + + /// \brief vector with the current cmd joint position + std::vector joint_position_cmd_; + + /// \brief vector with the last cmd joint position + std::vector last_joint_position_cmd_; + + /// \brief vector with the current cmd joint velocity + std::vector joint_velocity_cmd_; + + /// \brief vector with the current cmd joint effort + std::vector joint_effort_cmd_; + + /// \brief The current positions of the joints + std::vector> joint_pos_state_; + + /// \brief The current velocities of the joints + std::vector> joint_vel_state_; + + /// \brief The current effort forces applied to the joints + std::vector> joint_eff_state_; + + /// \brief The position command interfaces of the joints + std::vector> joint_pos_cmd_; + + /// \brief The velocity command interfaces of the joints + std::vector> joint_vel_cmd_; + + /// \brief The effort command interfaces of the joints + std::vector> joint_eff_cmd_; + + /// \brief vector with the PID of each joint. + std::vector pid_controllers_; +}; + +} // namespace gazebo_ros2_control + +#endif // GAZEBO_ROS2_CONTROL__GAZEBO_SYSTEM_HPP_ diff --git a/gazebo_ros2_control/include/gazebo_ros2_control/gazebo_system_interface.hpp b/gazebo_ros2_control/include/gazebo_ros2_control/gazebo_system_interface.hpp new file mode 100644 index 00000000..dd70de2d --- /dev/null +++ b/gazebo_ros2_control/include/gazebo_ros2_control/gazebo_system_interface.hpp @@ -0,0 +1,67 @@ +// Copyright 2021 Open Source Robotics Foundation, Inc. +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + + +#ifndef GAZEBO_ROS2_CONTROL__GAZEBO_SYSTEM_INTERFACE_HPP_ +#define GAZEBO_ROS2_CONTROL__GAZEBO_SYSTEM_INTERFACE_HPP_ + +#include +#include +#include + +#include "gazebo/physics/Joint.hh" +#include "gazebo/physics/Model.hh" +#include "gazebo/physics/physics.hh" + +#include "hardware_interface/base_interface.hpp" +#include "hardware_interface/system_interface.hpp" +#include "hardware_interface/types/hardware_interface_type_values.hpp" + +#include "rclcpp/rclcpp.hpp" + +#include "transmission_interface/transmission_info.hpp" + +// URDF +#include "urdf/model.h" + +namespace gazebo_ros2_control +{ + +class GazeboSystemInterface + : public hardware_interface::BaseInterface +{ +public: + /// \brief Initilize the system interface + /// param[in] model_nh pointer to the ros2 node + /// param[in] parent_model pointer to the model + /// param[in] urdf_model pointer to the URDF + /// param[in] transmissions availables in the model + /// param[in] sdf pointer to the SDF + virtual bool initSim( + rclcpp::Node::SharedPtr & model_nh, + gazebo::physics::ModelPtr parent_model, + const urdf::Model * const urdf_model, + std::vector transmissions, + sdf::ElementPtr sdf) = 0; + + // Methods used to control a joint. + enum ControlMethod {EFFORT, POSITION, POSITION_PID, VELOCITY, VELOCITY_PID}; + +protected: + rclcpp::Node::SharedPtr nh_; +}; + +} // namespace gazebo_ros2_control + +#endif // GAZEBO_ROS2_CONTROL__GAZEBO_SYSTEM_INTERFACE_HPP_ diff --git a/gazebo_ros2_control/include/gazebo_ros2_control/robot_hw_sim.hpp b/gazebo_ros2_control/include/gazebo_ros2_control/robot_hw_sim.hpp deleted file mode 100644 index 93d37eb2..00000000 --- a/gazebo_ros2_control/include/gazebo_ros2_control/robot_hw_sim.hpp +++ /dev/null @@ -1,135 +0,0 @@ -// Copyright (c) 2013, Open Source Robotics Foundation. All rights reserved. -// Copyright (c) 2013, The Johns Hopkins University. All rights reserved. -// -// Redistribution and use in source and binary forms, with or without -// modification, are permitted provided that the following conditions are met: -// -// * Redistributions of source code must retain the above copyright -// notice, this list of conditions and the following disclaimer. -// -// * Redistributions in binary form must reproduce the above copyright -// notice, this list of conditions and the following disclaimer in the -// documentation and/or other materials provided with the distribution. -// -// * Neither the name of the Open Source Robotics Foundation nor the names of its -// contributors may be used to endorse or promote products derived from -// this software without specific prior written permission. -// -// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" -// AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE -// IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE -// ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE -// LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR -// CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF -// SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS -// INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN -// CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) -// ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE -// POSSIBILITY OF SUCH DAMAGE. - -/// \brief Plugin template for hardware interfaces for ros_control and Gazebo - -/// \author Jonathan Bohren -/// \author Dave Coleman - -#ifndef GAZEBO_ROS2_CONTROL__ROBOT_HW_SIM_HPP_ -#define GAZEBO_ROS2_CONTROL__ROBOT_HW_SIM_HPP_ - -#include -#include - -#include "gazebo/physics/physics.hh" -#include "hardware_interface/robot_hardware.hpp" -#include "rclcpp/rclcpp.hpp" -#include "transmission_interface/transmission_info.hpp" -#include "urdf/model.h" - -namespace gazebo_ros2_control -{ - -// Struct for passing loaded joint data -struct JointData -{ - std::string name_; - std::string hardware_interface_; - - JointData(const std::string & name, const std::string & hardware_interface) - : name_(name), - hardware_interface_(hardware_interface) - { - } -}; - -/// \brief Gazebo plugin version of RobotHW -/// -/// An object of class RobotHWSim represents a robot's simulated hardware. -class RobotHWSim : public hardware_interface::RobotHardware -{ -public: - virtual ~RobotHWSim() - { - } - - /// \brief Initialize the simulated robot hardware - /// - /// Initialize the simulated robot hardware. - /// - /// \param robot_namespace Robot namespace. - /// \param model_nh Model node handle. - /// \param parent_model Parent model. - /// \param urdf_model URDF model. - /// \param transmissions Transmissions. - /// - /// \return \c true if the simulated robot hardware is initialized successfully, \c false if not. - virtual bool initSim( - const std::string & robot_namespace, - rclcpp::Node::SharedPtr & model_nh, - gazebo::physics::ModelPtr parent_model, - const urdf::Model * const urdf_model, - std::vector transmissions) = 0; - - /// \brief Read state data from the simulated robot hardware - /// - /// Read state data, such as joint positions and velocities, from the simulated robot hardware. - /// - /// \param time Simulation time. - /// \param period Time since the last simulation step. - virtual void readSim(rclcpp::Time time, rclcpp::Duration period) = 0; - - /// \brief Write commands to the simulated robot hardware - /// - /// Write commands, such as joint position and velocity commands, to the simulated robot hardware. - /// - /// \param time Simulation time. - /// \param period Time since the last simulation step. - virtual void writeSim(rclcpp::Time time, rclcpp::Duration period) = 0; - - /// \brief Set the emergency stop state - /// - /// Set the simulated robot's emergency stop state. The default implementation of this function - /// does nothing. - /// - /// \param active \c true if the emergency stop is active, \c false if not. - virtual void eStopActive(const bool active) {} - - // @note: Avoid using these functions! ros2_control was not built with gazebo_ros_control - // in mind, keep to using readSim and writeSim so we don't have to update the documents for now - virtual hardware_interface::hardware_interface_ret_t init() - { - return hardware_interface::return_type::ERROR; - } - - virtual hardware_interface::hardware_interface_ret_t read() - { - return hardware_interface::return_type::ERROR; - } - - virtual hardware_interface::hardware_interface_ret_t write() - { - return hardware_interface::return_type::ERROR; - } -}; - -} // namespace gazebo_ros2_control - -#endif // GAZEBO_ROS2_CONTROL__ROBOT_HW_SIM_HPP_ diff --git a/gazebo_ros2_control/package.xml b/gazebo_ros2_control/package.xml index 706ddc5b..e674eb37 100644 --- a/gazebo_ros2_control/package.xml +++ b/gazebo_ros2_control/package.xml @@ -23,7 +23,6 @@ gazebo_ros controller_manager hardware_interface - joint_limits_interface pluginlib rclcpp std_msgs @@ -37,6 +36,6 @@ ament_cmake - + diff --git a/gazebo_ros2_control/robot_hw_sim_plugins.xml b/gazebo_ros2_control/robot_hw_sim_plugins.xml deleted file mode 100644 index 1787efad..00000000 --- a/gazebo_ros2_control/robot_hw_sim_plugins.xml +++ /dev/null @@ -1,11 +0,0 @@ - - - - - A default robot simulation interface which constructs joint handles from an SDF/URDF. - - - diff --git a/gazebo_ros2_control/src/default_robot_hw_sim.cpp b/gazebo_ros2_control/src/default_robot_hw_sim.cpp deleted file mode 100644 index 32c76367..00000000 --- a/gazebo_ros2_control/src/default_robot_hw_sim.cpp +++ /dev/null @@ -1,624 +0,0 @@ -// Copyright (c) 2013, Open Source Robotics Foundation. All rights reserved. -// Copyright (c) 2013, The Johns Hopkins University. All rights reserved. -// -// Redistribution and use in source and binary forms, with or without -// modification, are permitted provided that the following conditions are met: -// -// * Redistributions of source code must retain the above copyright -// notice, this list of conditions and the following disclaimer. -// -// * Redistributions in binary form must reproduce the above copyright -// notice, this list of conditions and the following disclaimer in the -// documentation and/or other materials provided with the distribution. -// -// * Neither the name of the Open Source Robotics Foundation nor the names of its -// contributors may be used to endorse or promote products derived from -// this software without specific prior written permission. -// -// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" -// AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE -// IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE -// ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE -// LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR -// CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF -// SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS -// INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN -// CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) -// ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE -// POSSIBILITY OF SUCH DAMAGE. - -/* Author: Dave Coleman, Jonathan Bohren - Desc: Hardware Interface for any simulated robot in Gazebo -*/ - -#include -#include -#include -#include - -#include "gazebo_ros2_control/default_robot_hw_sim.hpp" -#include "urdf/model.h" - -namespace gazebo_ros2_control -{ -bool DefaultRobotHWSim::initSim( - const std::string & robot_namespace, - rclcpp::Node::SharedPtr & model_nh, - gazebo::physics::ModelPtr parent_model, - const urdf::Model * const urdf_model, - std::vector transmissions) -{ - // getJointLimits() searches joint_limit_nh for joint limit parameters. The format of each - // parameter's name is "joint_limits/". An example is "joint_limits/axle_joint". - nh_ = model_nh; - - // Resize vectors to our DOF - n_dof_ = transmissions.size(); - joint_names_.resize(n_dof_); - joint_types_.resize(n_dof_); - joint_lower_limits_.resize(n_dof_); - joint_upper_limits_.resize(n_dof_); - joint_effort_limits_.resize(n_dof_); - joint_vel_limits_.resize(n_dof_); - joint_control_methods_.resize(n_dof_); - joint_opmodes_.resize(n_dof_); - joint_opmodehandles_.resize(n_dof_); - - joint_pos_stateh_.resize(n_dof_, hardware_interface::JointHandle("position")); - joint_vel_stateh_.resize(n_dof_, hardware_interface::JointHandle("velocity")); - joint_eff_stateh_.resize(n_dof_, hardware_interface::JointHandle("effort")); - joint_pos_cmdh_.resize(n_dof_, hardware_interface::JointHandle("position_command")); - joint_eff_cmdh_.resize(n_dof_, hardware_interface::JointHandle("effort_command")); - joint_vel_cmdh_.resize(n_dof_, hardware_interface::JointHandle("velocity_command")); - - joint_limit_handles_.resize(n_dof_); - - // get physics engine type -#if GAZEBO_MAJOR_VERSION >= 8 - gazebo::physics::PhysicsEnginePtr physics = gazebo::physics::get_world()->Physics(); -#else - gazebo::physics::PhysicsEnginePtr physics = gazebo::physics::get_world()->GetPhysicsEngine(); -#endif - physics_type_ = physics->GetType(); - if (physics_type_.empty()) { - RCLCPP_ERROR(nh_->get_logger(), "No physics engine configured in Gazebo."); - return false; - } - - // special handing since ODE uses a different set/get interface then the other engines - usingODE = (physics_type_.compare("ode") == 0); - - // Initialize values - for (unsigned int j = 0; j < n_dof_; j++) { - // - // Perform some validation on the URDF joint and actuator spec - // - - // Check that this transmission has one joint - if (transmissions[j].joints.empty()) { - RCLCPP_WARN_STREAM( - nh_->get_logger(), "Transmission " << transmissions[j].name << - " has no associated joints."); - continue; - } else if (transmissions[j].joints.size() > 1) { - RCLCPP_WARN_STREAM( - nh_->get_logger(), "Transmission " << transmissions[j].name << - " has more than one joint. Currently the default robot hardware simulation " << - " interface only supports one."); - continue; - } - - std::string joint_name = joint_names_[j] = transmissions[j].joints[0].name; - - std::vector joint_interfaces = transmissions[j].joints[0].interfaces; - if (joint_interfaces.empty() && - !(transmissions[j].actuators.empty()) && - !(transmissions[j].actuators[0].interfaces.empty())) - { - // TODO(anyone): Deprecate HW interface specification in actuators in ROS J - joint_interfaces = transmissions[j].actuators[0].interfaces; - RCLCPP_WARN_STREAM( - nh_->get_logger(), "The element of transmission " << - transmissions[j].name << " should be nested inside the element," << - " not . The transmission will be properly loaded, but please update " << - "your robot model to remain compatible with future versions of the plugin."); - } - if (joint_interfaces.empty()) { - RCLCPP_WARN_STREAM( - nh_->get_logger(), "Joint " << transmissions[j].name << - " of transmission " << transmissions[j].name << - " does not specify any hardware interface. " << - "Not adding it to the robot hardware simulation."); - continue; - } else if (joint_interfaces.size() > 1) { - RCLCPP_WARN_STREAM( - nh_->get_logger(), "Joint " << transmissions[j].name << - " of transmission " << transmissions[j].name << - " specifies multiple hardware interfaces. " << - "Currently the default robot hardware simulation interface only supports one." << - "Using the first entry"); - // only a warning, allow joint to continue - } - - std::string hardware_interface = joint_interfaces.front(); - // Decide what kind of command interface this actuator/joint has - if (hardware_interface == "hardware_interface/EffortJointInterface") { - joint_control_methods_[j] = EFFORT; - } else if (hardware_interface == "hardware_interface/PositionJointInterface") { - joint_control_methods_[j] = POSITION; - } else if (hardware_interface == "hardware_interface/VelocityJointInterface") { - joint_control_methods_[j] = VELOCITY; - } else { - RCLCPP_WARN_STREAM( - nh_->get_logger(), "No matching joint interface '" << - hardware_interface << "' for joint " << joint_name); - RCLCPP_INFO( - nh_->get_logger(), - " Expecting one of 'hardware_interface/{EffortJointInterface |" - " PositionJointInterface | VelocityJointInterface}'"); - return false; - } - - // - // Accept this URDF joint as valid and link with the gazebo joint of the same name - // - - // I think it's safe to only skip this joint and not abort if there is no match found - gazebo::physics::JointPtr simjoint = parent_model->GetJoint(joint_name); - if (!simjoint) { - RCLCPP_WARN_STREAM( - nh_->get_logger(), "Skipping joint in the URDF named '" << joint_name << - "' which is not in the gazebo model."); - continue; - } - sim_joints_.push_back(simjoint); - - // Accept this joint and continue configuration - RCLCPP_INFO_STREAM( - nh_->get_logger(), "Loading joint '" << joint_name << "' of type '" << - hardware_interface << "'"); - - /// - /// \brief a helper function for registering joint state or command handles - /// - auto register_joint_interface = [this, &joint_name, &j]( - const char * interface_name, - std::vector & joint_iface_handles) - { - // set joint name and interface on our stored handle - joint_iface_handles[j] = hardware_interface::JointHandle(joint_name, interface_name); - - // register the joint with the underlying RobotHardware implementation - if (register_joint( - joint_name, interface_name, - 0.0) != hardware_interface::return_type::OK) - { - RCLCPP_ERROR_STREAM( - nh_->get_logger(), "cant register " << interface_name << - " state handle for joint " << joint_name); - return false; - } - - // now retrieve the handle with the bound value reference (bound directly to the - // DynamicJointState msg in RobotHardware) - if (get_joint_handle(joint_iface_handles[j]) != hardware_interface::return_type::OK) { - RCLCPP_ERROR_STREAM( - nh_->get_logger(), "state handle " << interface_name << " failure for joint " << - joint_name); - return false; - } - - // verify handle references a target value - if (!joint_iface_handles[j]) { - RCLCPP_ERROR_STREAM( - nh_->get_logger(), interface_name << " handle for joint " << joint_name << - " is null"); - return false; - } - return true; - }; - - // register the state handles - if ( - !register_joint_interface("position", joint_pos_stateh_) || - !register_joint_interface("velocity", joint_vel_stateh_) || - !register_joint_interface("effort", joint_eff_stateh_)) - { - RCLCPP_ERROR_STREAM( - nh_->get_logger(), - "plugin aborting due to previous " << joint_name << " joint registration errors"); - return false; - } - - // Register the command handle - switch (joint_control_methods_[j]) { - case EFFORT: register_joint_interface("effort_command", joint_eff_cmdh_); break; - case POSITION: register_joint_interface("position_command", joint_pos_cmdh_); break; - case VELOCITY: register_joint_interface("velocity_command", joint_vel_cmdh_); break; - } - - // set joints operation mode to ACTIVE and register handle for controlling opmode - joint_opmodes_[j] = hardware_interface::OperationMode::ACTIVE; - joint_opmodehandles_[j] = hardware_interface::OperationModeHandle( - joint_name, &joint_opmodes_[j]); - if (register_operation_mode_handle(&joint_opmodehandles_[j]) != - hardware_interface::return_type::OK) - { - RCLCPP_WARN_STREAM(nh_->get_logger(), "cant register opmode handle for joint" << joint_name); - } - } - - // since handles references may have changed due to underlying DynamicJointState msg - // vectors resizing and reallocating we need to get these handles again - // any handles not registered are skipped, such as the command handles if they arent - // involved in the control method - bindJointHandles(joint_pos_stateh_); - bindJointHandles(joint_vel_stateh_); - bindJointHandles(joint_eff_stateh_); - bindJointHandles(joint_pos_cmdh_); - bindJointHandles(joint_vel_cmdh_); - bindJointHandles(joint_eff_cmdh_); - - - // - // Complete initialization of limits, PID controllers, etc now that registered handles are bound - // - for (size_t j = 0; j < joint_names_.size(); j++) { - auto simjoint = sim_joints_[j]; - assert(simjoint); - - // setup joint limits - registerJointLimits( - j, - urdf_model, - &joint_types_[j], &joint_lower_limits_[j], &joint_upper_limits_[j], - &joint_effort_limits_[j], &joint_vel_limits_[j]); - if (joint_control_methods_[j] != EFFORT) { - try { - nh_->declare_parameter(transmissions[j].joints[0].name + ".p"); - nh_->declare_parameter(transmissions[j].joints[0].name + ".i"); - nh_->declare_parameter(transmissions[j].joints[0].name + ".d"); - nh_->declare_parameter(transmissions[j].joints[0].name + ".i_clamp_max"); - nh_->declare_parameter(transmissions[j].joints[0].name + ".i_clamp_min"); - nh_->declare_parameter(transmissions[j].joints[0].name + ".antiwindup", false); - - if (nh_->get_parameter(transmissions[j].joints[0].name + ".p").get_type() == - rclcpp::PARAMETER_DOUBLE && - nh_->get_parameter(transmissions[j].joints[0].name + ".i").get_type() == - rclcpp::PARAMETER_DOUBLE && - nh_->get_parameter(transmissions[j].joints[0].name + ".d").get_type() == - rclcpp::PARAMETER_DOUBLE) - { - pid_controllers_.push_back( - control_toolbox::PidROS(nh_, transmissions[j].joints[0].name)); - if (pid_controllers_[j].initPid()) { - switch (joint_control_methods_[j]) { - case POSITION: joint_control_methods_[j] = POSITION_PID; - RCLCPP_INFO( - nh_->get_logger(), "joint %s is configured in POSITION_PID mode", - transmissions[j].joints[0].name.c_str()); - break; - case VELOCITY: joint_control_methods_[j] = VELOCITY_PID; - RCLCPP_INFO( - nh_->get_logger(), "joint %s is configured in VELOCITY_PID mode", - transmissions[j].joints[0].name.c_str()); - break; - } - } - } - } catch (const std::exception & e) { - RCLCPP_ERROR(rclcpp::get_logger("gazebo_ros2_control"), "%s", e.what()); - } - simjoint->SetParam("fmax", 0, joint_effort_limits_[j]); - } - } - - // get the current state of the sim joint to initialize our ROS control joints - // @note(guru-florida): perhaps we dont need this if readSim() is called after init anyway - readSim(rclcpp::Time(), rclcpp::Duration(0, 0)); - - // Initialize the emergency stop code. - e_stop_active_ = false; - last_e_stop_active_ = false; - - return true; -} - -void DefaultRobotHWSim::readSim(rclcpp::Time, rclcpp::Duration) -{ - for (unsigned int j = 0; j < joint_names_.size(); j++) { - auto joint_handle = std::make_shared( - joint_names_[j], "position"); - if (get_joint_handle(*joint_handle) == hardware_interface::return_type::OK) { - double position = sim_joints_[j]->Position(0); - if (joint_types_[j] == urdf::Joint::PRISMATIC) { - joint_handle->set_value(position); - } else { - double prev_position = joint_handle->get_value(); - joint_handle->set_value( - prev_position + - angles::shortest_angular_distance(prev_position, position)); - } - } - joint_handle = std::make_shared( - joint_names_[j], "velocity"); - if (get_joint_handle(*joint_handle) == hardware_interface::return_type::OK) { - joint_handle->set_value(sim_joints_[j]->GetVelocity(0)); - } - - joint_handle = std::make_shared( - joint_names_[j], "effort"); - if (get_joint_handle(*joint_handle) == hardware_interface::return_type::OK) { - joint_handle->set_value(sim_joints_[j]->GetForce((unsigned int)(0))); - } - } -} - -void DefaultRobotHWSim::writeSim(rclcpp::Time time, rclcpp::Duration period) -{ - // If the E-stop is active, joints controlled by position commands will maintain their positions. - if (e_stop_active_) { - if (!last_e_stop_active_) { - last_joint_position_command_.clear(); - std::transform( - joint_pos_stateh_.begin(), joint_pos_stateh_.end(), - std::back_inserter(last_joint_position_command_), - [](const hardware_interface::JointHandle & ph) {return ph.get_value();}); - last_e_stop_active_ = true; - } - for (int i = 0; i < n_dof_; i++) { - joint_pos_cmdh_[i].set_value(last_joint_position_command_[i]); - } - } else { - last_e_stop_active_ = false; - } - for (auto & limit_handle : joint_limit_handles_) { - if (limit_handle) { - limit_handle->enforce_limits(period); - } - } - for (unsigned int j = 0; j < n_dof_; j++) { - switch (joint_control_methods_[j]) { - case EFFORT: - { - const double effort = e_stop_active_ ? 0 : joint_eff_cmdh_[j].get_value(); - sim_joints_[j]->SetForce(0, effort); - } - break; - - case POSITION: - sim_joints_[j]->SetPosition(0, joint_pos_cmdh_[j].get_value(), true); - break; - - case POSITION_PID: - { - double error; - switch (joint_types_[j]) { - case urdf::Joint::REVOLUTE: - angles::shortest_angular_distance_with_limits( - joint_pos_stateh_[j].get_value(), - joint_pos_cmdh_[j].get_value(), - joint_lower_limits_[j], - joint_upper_limits_[j], - error); - break; - case urdf::Joint::CONTINUOUS: - error = angles::shortest_angular_distance( - joint_pos_stateh_[j].get_value(), - joint_pos_cmdh_[j].get_value()); - break; - default: - error = joint_pos_cmdh_[j].get_value() - joint_pos_stateh_[j].get_value(); - } - - const double effort_limit = joint_effort_limits_[j]; - - const double effort = ignition::math::clamp( - pid_controllers_[j].computeCommand(error, period), - -effort_limit, effort_limit); - - sim_joints_[j]->SetForce(0, effort); - sim_joints_[j]->SetParam("friction", 0, 0.0); - } - break; - - case VELOCITY: - if (usingODE) { - sim_joints_[j]->SetParam("vel", 0, e_stop_active_ ? 0 : joint_vel_cmdh_[j].get_value()); - } else { - sim_joints_[j]->SetVelocity(0, e_stop_active_ ? 0 : joint_vel_cmdh_[j].get_value()); - } - break; - - case VELOCITY_PID: - double error; - if (e_stop_active_) { - error = -joint_vel_stateh_[j].get_value(); - } else { - error = joint_vel_cmdh_[j].get_value() - joint_vel_stateh_[j].get_value(); - } - const double effort_limit = joint_effort_limits_[j]; - const double effort = ignition::math::clamp( - pid_controllers_[j].computeCommand(error, period), - -effort_limit, effort_limit); - sim_joints_[j]->SetForce(0, effort); - break; - } - } -} - -void DefaultRobotHWSim::eStopActive(const bool active) -{ - e_stop_active_ = active; -} - -// Register the limits of the joint specified by joint_name and joint_handle. The limits are -// retrieved from joint_limit_nh. If urdf_model is not NULL, limits are retrieved from it also. -// Return the joint's type, lower position limit, upper position limit, and effort limit. -void DefaultRobotHWSim::registerJointLimits( - size_t joint_nr, - const urdf::Model * const urdf_model, - int * const joint_type, double * const lower_limit, - double * const upper_limit, double * const effort_limit, - double * const vel_limit) -{ - const std::string & joint_name = joint_names_[joint_nr]; - const ControlMethod ctrl_method = joint_control_methods_[joint_nr]; - - *joint_type = urdf::Joint::UNKNOWN; - *lower_limit = -std::numeric_limits::max(); - *upper_limit = std::numeric_limits::max(); - *effort_limit = std::numeric_limits::max(); - - joint_limits_interface::JointLimits limits; - bool has_limits = false; - - joint_limits_interface::SoftJointLimits soft_limits; - bool has_soft_limits = false; - - if (urdf_model != NULL) { - const urdf::JointConstSharedPtr urdf_joint = urdf_model->getJoint(joint_name); - if (urdf_joint != NULL) { - *joint_type = urdf_joint->type; - // Get limits from the URDF file. - if (joint_limits_interface::getJointLimits(urdf_joint->name, nh_, limits)) { - has_limits = true; - } - if (joint_limits_interface::getSoftJointLimits(urdf_joint->name, nh_, soft_limits)) { - has_soft_limits = true; - } - - // @note (ddeng): these joint limits arent input into the node, so fetch them from the urdf - // TODO(guru-florida): These are now a part of the node as of 2020-09-03, - // so what one do we take? - limits.min_position = urdf_joint->limits->lower; - limits.max_position = urdf_joint->limits->upper; - limits.has_position_limits = true; - - limits.max_velocity = urdf_joint->limits->velocity; - limits.has_velocity_limits = limits.max_velocity == 0.0 ? false : true; - - limits.max_effort = urdf_joint->limits->effort; - limits.has_effort_limits = limits.max_effort == 0.0 ? false : true; - - *lower_limit = limits.min_position; - *upper_limit = limits.max_position; - *effort_limit = limits.max_effort; - *vel_limit = limits.max_velocity; - - has_limits = true; - } - } - - if (joint_limits_interface::getJointLimits(joint_name, nh_, limits)) { - has_limits = true; - } - - if (!has_limits) { - return; - } - - if (*joint_type == urdf::Joint::UNKNOWN) { - // Infer the joint type. - - if (limits.has_position_limits) { - *joint_type = urdf::Joint::REVOLUTE; - } else { - if (limits.angle_wraparound) { - *joint_type = urdf::Joint::CONTINUOUS; - } else { - *joint_type = urdf::Joint::PRISMATIC; - } - } - } - - if (limits.has_position_limits) { - *lower_limit = limits.min_position; - *upper_limit = limits.max_position; - } - if (limits.has_effort_limits) { - *effort_limit = limits.max_effort; - } - - if (has_soft_limits) { - switch (ctrl_method) { - case EFFORT: - { - joint_limit_handles_[joint_nr] = - std::make_unique( - joint_pos_cmdh_[joint_nr], joint_vel_cmdh_[joint_nr], joint_eff_cmdh_[joint_nr], - limits); - } - break; - case POSITION: - { - joint_limit_handles_[joint_nr] = - std::make_unique( - joint_pos_stateh_[joint_nr], joint_pos_cmdh_[joint_nr], limits, soft_limits); - } - break; - case VELOCITY: - { - joint_limit_handles_[joint_nr] = - std::make_unique( - joint_vel_stateh_[joint_nr], joint_vel_cmdh_[joint_nr], limits); - } - break; - } - } else { - switch (ctrl_method) { - case EFFORT: - { - joint_limit_handles_[joint_nr] = - std::make_unique( - joint_pos_cmdh_[joint_nr], joint_vel_cmdh_[joint_nr], joint_eff_cmdh_[joint_nr], - limits); - } - break; - case POSITION: - { - joint_limit_handles_[joint_nr] = - std::make_unique( - joint_pos_stateh_[joint_nr], joint_pos_cmdh_[joint_nr], limits); - } - break; - case VELOCITY: - { - joint_limit_handles_[joint_nr] = - std::make_unique( - joint_vel_stateh_[joint_nr], joint_vel_cmdh_[joint_nr], limits); - } - break; - } - } -} - -void DefaultRobotHWSim::bindJointHandles( - std::vector & joint_iface_handles) -{ - for (auto & jh : joint_iface_handles) { - // some handles, especially command handles, may not be registered so skip these - if (jh.get_name().empty() || jh.get_interface_name().empty()) { - continue; - } - - // now retrieve the handle with the bound value reference (bound directly to the - // DynamicJointState msg in RobotHardware) - if (get_joint_handle(jh) != hardware_interface::return_type::OK) { - RCLCPP_ERROR_STREAM( - nh_->get_logger(), "state handle " << jh.get_interface_name() << " failure for joint " << - jh.get_name()); - continue; - } - - // verify handle references a target value - if (!jh) { - RCLCPP_ERROR_STREAM( - nh_->get_logger(), jh.get_interface_name() << " handle for joint " << jh.get_name() << - " is null"); - } - } -} -} // namespace gazebo_ros2_control - -PLUGINLIB_EXPORT_CLASS(gazebo_ros2_control::DefaultRobotHWSim, gazebo_ros2_control::RobotHWSim) diff --git a/gazebo_ros2_control/src/gazebo_ros2_control_plugin.cpp b/gazebo_ros2_control/src/gazebo_ros2_control_plugin.cpp index 1c27e8b9..b464f902 100644 --- a/gazebo_ros2_control/src/gazebo_ros2_control_plugin.cpp +++ b/gazebo_ros2_control/src/gazebo_ros2_control_plugin.cpp @@ -34,11 +34,16 @@ #include #include +#include #include #include "gazebo_ros/node.hpp" #include "gazebo_ros2_control/gazebo_ros2_control_plugin.hpp" +#include "gazebo_ros2_control/gazebo_system.hpp" + +#include "hardware_interface/resource_manager.hpp" +#include "hardware_interface/types/hardware_interface_type_values.hpp" #include "urdf/model.h" #include "yaml-cpp/yaml.h" @@ -60,30 +65,26 @@ class GazeboRosControlPrivate // Get the URDF XML from the parameter server std::string getURDF(std::string param_name) const; - void eStopCB(const std::shared_ptr e_stop_active); - // Node Handles - gazebo_ros::Node::SharedPtr model_nh_; // namespaces to robot name + gazebo_ros::Node::SharedPtr model_nh_; // Pointer to the model gazebo::physics::ModelPtr parent_model_; - sdf::ElementPtr sdf_; - - // deferred load in case ros is blocking - boost::thread deferred_load_thread_; // Pointer to the update event connection gazebo::event::ConnectionPtr update_connection_; // Interface loader boost::shared_ptr> robot_hw_sim_loader_; - void load_robot_hw_sim_srv(); + gazebo_ros2_control::GazeboSystemInterface>> robot_hw_sim_loader_; - // Strings - std::string robot_namespace_; + // String with the robot description std::string robot_description_; + + // String with the name of the node that contains the robot_description std::string robot_description_node_; + + // Name of the file with the controllers configuration std::string param_file_; // Transmissions in this plugin's scope @@ -91,24 +92,24 @@ class GazeboRosControlPrivate // Robot simulator interface std::string robot_hw_sim_type_str_; - std::shared_ptr robot_hw_sim_; + + // Executor to spin the controller rclcpp::executors::MultiThreadedExecutor::SharedPtr executor_; - // executor_->spin causes lockups, us ethis alternative for now + + // Thread where the executor will sping std::thread thread_executor_spin_; // Controller manager std::shared_ptr controller_manager_; + + // Available controllers std::vector> controllers_; // Timing - rclcpp::Duration control_period_ = rclcpp::Duration(0); - rclcpp::Time last_update_sim_time_ros_; - rclcpp::Time last_write_sim_time_ros_; + rclcpp::Duration control_period_ = rclcpp::Duration(1, 0); - // e_stop_active_ is true if the emergency stop is active. - bool e_stop_active_, last_e_stop_active_; - // Emergency stop subscriber - rclcpp::Subscription::SharedPtr e_stop_sub_; + // Last time the update method was called + rclcpp::Time last_update_sim_time_ros_; }; GazeboRosControlPlugin::GazeboRosControlPlugin() @@ -131,7 +132,6 @@ void GazeboRosControlPlugin::Load(gazebo::physics::ModelPtr parent, sdf::Element // Save pointers to the model impl_->parent_model_ = parent; - impl_->sdf_ = sdf; // Get parameters/settings for controllers from ROS param server // Initialize ROS node @@ -161,33 +161,33 @@ void GazeboRosControlPlugin::Load(gazebo::physics::ModelPtr parent, sdf::Element } // Get robot_description ROS param name - if (impl_->sdf_->HasElement("robot_param")) { - impl_->robot_description_ = impl_->sdf_->GetElement("robot_param")->Get(); + if (sdf->HasElement("robot_param")) { + impl_->robot_description_ = sdf->GetElement("robot_param")->Get(); } else { impl_->robot_description_ = "robot_description"; // default } // Get robot_description ROS param name - if (impl_->sdf_->HasElement("robot_param_node")) { + if (sdf->HasElement("robot_param_node")) { impl_->robot_description_node_ = - impl_->sdf_->GetElement("robot_param_node")->Get(); + sdf->GetElement("robot_param_node")->Get(); } else { impl_->robot_description_node_ = "robot_state_publisher"; // default } // Get the robot simulation interface type - if (impl_->sdf_->HasElement("robot_sim_type")) { - impl_->robot_hw_sim_type_str_ = impl_->sdf_->Get("robot_sim_type"); + if (sdf->HasElement("robot_sim_type")) { + impl_->robot_hw_sim_type_str_ = sdf->Get("robot_sim_type"); } else { - impl_->robot_hw_sim_type_str_ = "gazebo_ros2_control/DefaultRobotHWSim"; + impl_->robot_hw_sim_type_str_ = "gazebo_ros2_control/GazeboSystem"; RCLCPP_DEBUG_STREAM( impl_->model_nh_->get_logger(), "Using default plugin for RobotHWSim (none specified in URDF/SDF)\"" << impl_->robot_hw_sim_type_str_ << "\""); } - if (impl_->sdf_->HasElement("parameters")) { - impl_->param_file_ = impl_->sdf_->GetElement("parameters")->Get(); + if (sdf->HasElement("parameters")) { + impl_->param_file_ = sdf->GetElement("parameters")->Get(); } else { RCLCPP_ERROR( impl_->model_nh_->get_logger(), "No parameter file provided. Configuration might be wrong"); @@ -197,8 +197,10 @@ void GazeboRosControlPlugin::Load(gazebo::physics::ModelPtr parent, sdf::Element rclcpp::Duration gazebo_period(impl_->parent_model_->GetWorld()->Physics()->GetMaxStepSize()); // Decide the plugin control period - if (impl_->sdf_->HasElement("control_period")) { - impl_->control_period_ = rclcpp::Duration(impl_->sdf_->Get("control_period")); + if (sdf->HasElement("control_period")) { + impl_->control_period_ = rclcpp::Duration( + std::chrono::duration_cast( + std::chrono::duration(sdf->Get("control_period")))); // Check the period against the simulation period if (impl_->control_period_ < gazebo_period) { @@ -220,16 +222,6 @@ void GazeboRosControlPlugin::Load(gazebo::physics::ModelPtr parent, sdf::Element impl_->control_period_.seconds()); } - // Initialize the emergency stop code. - impl_->e_stop_active_ = false; - impl_->last_e_stop_active_ = false; - if (impl_->sdf_->HasElement("e_stop_topic")) { - const std::string e_stop_topic = impl_->sdf_->GetElement("e_stop_topic")->Get(); - impl_->e_stop_sub_ = impl_->model_nh_->create_subscription( - e_stop_topic, 1, - std::bind(&GazeboRosControlPrivate::eStopCB, impl_.get(), std::placeholders::_1)); - } - // Read urdf from ros parameter server then // setup actuators and mechanism control node. // This call will block if ROS is not properly initialized. @@ -244,49 +236,73 @@ void GazeboRosControlPlugin::Load(gazebo::physics::ModelPtr parent, sdf::Element return; } - // Load the RobotHWSim abstraction to interface the controllers with the gazebo model + std::unique_ptr resourceManager_ = + std::make_unique(); + try { + // We cannot use (for now) the tag in the URDF, we need to call it manually. impl_->robot_hw_sim_loader_.reset( - new pluginlib::ClassLoader( + new pluginlib::ClassLoader( "gazebo_ros2_control", - "gazebo_ros2_control::RobotHWSim")); + "gazebo_ros2_control::GazeboSystemInterface")); - impl_->robot_hw_sim_ = impl_->robot_hw_sim_loader_->createSharedInstance( - impl_->robot_hw_sim_type_str_); + auto gazeboSystem = std::unique_ptr( + impl_->robot_hw_sim_loader_->createUnmanagedInstance(impl_->robot_hw_sim_type_str_)); urdf::Model urdf_model; const urdf::Model * const urdf_model_ptr = urdf_model.initString(urdf_string) ? &urdf_model : NULL; rclcpp::Node::SharedPtr node_ros2 = std::dynamic_pointer_cast(impl_->model_nh_); - if (!impl_->robot_hw_sim_->initSim( - impl_->model_nh_->get_namespace(), node_ros2, impl_->parent_model_, urdf_model_ptr, - impl_->transmissions_)) + if (!gazeboSystem->initSim( + node_ros2, + impl_->parent_model_, + urdf_model_ptr, + impl_->transmissions_, + sdf)) { RCLCPP_FATAL( impl_->model_nh_->get_logger(), "Could not initialize robot simulation interface"); return; } + std::vector loaned_state_ifs; + std::vector state_ifs; + state_ifs = gazeboSystem->export_state_interfaces(); + for (auto state : state_ifs) { + loaned_state_ifs.emplace_back(hardware_interface::LoanedStateInterface(state)); + } + + resourceManager_->import_component(std::move(gazeboSystem)); + impl_->executor_ = std::make_shared(); + auto spin = [this]() + { + while (rclcpp::ok()) { + impl_->executor_->spin_once(); + } + }; + impl_->thread_executor_spin_ = std::thread(spin); + // Create the controller manager RCLCPP_ERROR(impl_->model_nh_->get_logger(), "Loading controller_manager"); impl_->controller_manager_.reset( new controller_manager::ControllerManager( - impl_->robot_hw_sim_, impl_->executor_, + std::move(resourceManager_), + impl_->executor_, "gazebo_controller_manager")); // TODO(anyone): Coded example here. should disable when spawn functionality of // controller manager is up - auto load_params_from_yaml_node = [](rclcpp_lifecycle::LifecycleNode::SharedPtr lc_node, + auto load_params_from_yaml_node = [](rclcpp::Node::SharedPtr lc_node, YAML::Node & yaml_node, const std::string & prefix) { std::function, const std::string &)> + std::shared_ptr, const std::string &)> feed_yaml_to_node_rec = [&](YAML::Node yaml_node, const std::string & key, - std::shared_ptr node, const std::string & prefix) + std::shared_ptr node, const std::string & prefix) { if (node->get_name() != prefix) { return; @@ -363,7 +379,7 @@ void GazeboRosControlPlugin::Load(gazebo::physics::ModelPtr parent, sdf::Element } feed_yaml_to_node_rec(yaml_node, prefix, lc_node, prefix); }; - auto load_params_from_yaml = [&](rclcpp_lifecycle::LifecycleNode::SharedPtr lc_node, + auto load_params_from_yaml = [&](rclcpp::Node::SharedPtr lc_node, const std::string & yaml_config_file, const std::string & prefix) { if (yaml_config_file.empty()) { @@ -386,7 +402,7 @@ void GazeboRosControlPlugin::Load(gazebo::physics::ModelPtr parent, sdf::Element YAML::Node root_node = YAML::LoadFile(impl_->param_file_); for (auto yaml : root_node) { auto controller_name = yaml.first.as(); - for (auto yaml_node_it : yaml.second) { // ros__parameters + for (auto yaml_node_it : yaml.second) { // ros__parameters for (auto yaml_node_it2 : yaml_node_it.second) { auto param_name = yaml_node_it2.first.as(); if (param_name == "type") { @@ -396,17 +412,19 @@ void GazeboRosControlPlugin::Load(gazebo::physics::ModelPtr parent, sdf::Element controller_type); impl_->controllers_.push_back(controller); load_params_from_yaml( - controller->get_lifecycle_node(), + controller->get_node(), impl_->param_file_, controller_name); - if (controller_name != "joint_state_controller") { - controller->get_lifecycle_node()->configure(); + if (controller_name == "joint_state_controller") { + controller->assign_interfaces({}, std::move(loaned_state_ifs)); } + controller->configure(); start_controllers.push_back(controller_name); } } } } + auto switch_future = std::async( std::launch::async, &controller_manager::ControllerManager::switch_controller, impl_->controller_manager_, @@ -415,35 +433,24 @@ void GazeboRosControlPlugin::Load(gazebo::physics::ModelPtr parent, sdf::Element while (std::future_status::timeout == switch_future.wait_for(std::chrono::milliseconds(100))) { impl_->controller_manager_->update(); } - switch_future.get(); - - auto spin = [this]() - { - while (rclcpp::ok()) { - impl_->executor_->spin_once(); - } - }; - impl_->thread_executor_spin_ = std::thread(spin); - - // Listen to the update event. This event is broadcast every simulation iteration. - impl_->update_connection_ = - gazebo::event::Events::ConnectWorldUpdateBegin( - boost::bind( - &GazeboRosControlPrivate::Update, - impl_.get())); + controller_interface::return_type result = switch_future.get(); + if (result != controller_interface::return_type::SUCCESS) { + RCLCPP_ERROR(impl_->model_nh_->get_logger(), "Error initializing the joint_state_controller"); + } } catch (pluginlib::LibraryLoadException & ex) { RCLCPP_ERROR( impl_->model_nh_->get_logger(), "Failed to create robot simulation interface loader: %s ", ex.what()); } - RCLCPP_ERROR(impl_->model_nh_->get_logger(), "Loaded gazebo_ros2_control."); -} + // Listen to the update event. This event is broadcast every simulation iteration. + impl_->update_connection_ = + gazebo::event::Events::ConnectWorldUpdateBegin( + boost::bind( + &GazeboRosControlPrivate::Update, + impl_.get())); -void -spin(std::shared_ptr exe) -{ - exe->spin(); + RCLCPP_ERROR(impl_->model_nh_->get_logger(), "Loaded gazebo_ros2_control."); } // Called by the world update start event @@ -454,37 +461,12 @@ void GazeboRosControlPrivate::Update() rclcpp::Time sim_time_ros(gz_time_now.sec, gz_time_now.nsec); rclcpp::Duration sim_period = sim_time_ros - last_update_sim_time_ros_; - robot_hw_sim_->eStopActive(e_stop_active_); - - // Check if we should update the controllers if (sim_period >= control_period_) { - // Store this simulation time last_update_sim_time_ros_ = sim_time_ros; - - // Update the robot simulation with the state of the gazebo model - robot_hw_sim_->readSim(sim_time_ros, sim_period); - - // Compute the controller commands - bool reset_ctrlrs; - if (e_stop_active_) { - reset_ctrlrs = false; - last_e_stop_active_ = true; - } else { - if (last_e_stop_active_) { - reset_ctrlrs = true; - last_e_stop_active_ = false; - } else { - reset_ctrlrs = false; - } - } - + controller_manager_->read(); controller_manager_->update(); + controller_manager_->write(); } - - // Update the gazebo model with the result of the controller - // computation - robot_hw_sim_->writeSim(sim_time_ros, sim_time_ros - last_write_sim_time_ros_); - last_write_sim_time_ros_ = sim_time_ros; } // Called on world reset @@ -492,7 +474,6 @@ void GazeboRosControlPrivate::Reset() { // Reset timing variables to not pass negative update periods to controllers on world reset last_update_sim_time_ros_ = rclcpp::Time(); - last_write_sim_time_ros_ = rclcpp::Time(); } // Get the URDF XML from the parameter server @@ -547,12 +528,6 @@ std::string GazeboRosControlPrivate::getURDF(std::string param_name) const return urdf_string; } -// Emergency stop callback -void GazeboRosControlPrivate::eStopCB(const std::shared_ptr e_stop_active) -{ - e_stop_active_ = e_stop_active->data; -} - // Register this plugin with the simulator GZ_REGISTER_MODEL_PLUGIN(GazeboRosControlPlugin); } // namespace gazebo_ros2_control diff --git a/gazebo_ros2_control/src/gazebo_system.cpp b/gazebo_ros2_control/src/gazebo_system.cpp new file mode 100644 index 00000000..b348ee83 --- /dev/null +++ b/gazebo_ros2_control/src/gazebo_system.cpp @@ -0,0 +1,394 @@ +// Copyright 2021 Open Source Robotics Foundation, Inc. +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#include +#include +#include + +#include "gazebo_ros2_control/gazebo_system.hpp" + +namespace gazebo_ros2_control +{ + +bool GazeboSystem::initSim( + rclcpp::Node::SharedPtr & model_nh, + gazebo::physics::ModelPtr parent_model, + const urdf::Model * const urdf_model, + std::vector transmissions, + sdf::ElementPtr sdf) +{ + last_update_sim_time_ros_ = rclcpp::Time(); + + this->nh_ = model_nh; + this->parent_model_ = parent_model; + n_dof_ = transmissions.size(); + + joint_names_.resize(n_dof_); + joint_control_methods_.resize(n_dof_); + joint_position_.resize(n_dof_); + joint_velocity_.resize(n_dof_); + joint_effort_.resize(n_dof_); + joint_pos_state_.resize(n_dof_); + joint_vel_state_.resize(n_dof_); + joint_eff_state_.resize(n_dof_); + joint_position_cmd_.resize(n_dof_); + last_joint_position_cmd_.resize(n_dof_); + joint_velocity_cmd_.resize(n_dof_); + joint_effort_cmd_.resize(n_dof_); + joint_pos_cmd_.resize(n_dof_); + joint_vel_cmd_.resize(n_dof_); + joint_eff_cmd_.resize(n_dof_); + + gazebo::physics::PhysicsEnginePtr physics = gazebo::physics::get_world()->Physics(); + + std::string physics_type_ = physics->GetType(); + if (physics_type_.empty()) { + RCLCPP_ERROR(nh_->get_logger(), "No physics engine configured in Gazebo."); + return false; + } + + // special handing since ODE uses a different set/get interface then the other engines + usingODE = (physics_type_.compare("ode") == 0); + + for (unsigned int j = 0; j < this->n_dof_; j++) { + // + // Perform some validation on the URDF joint and actuator spec + // + // Check that this transmission has one joint + if (transmissions[j].joints.empty()) { + RCLCPP_WARN_STREAM( + nh_->get_logger(), "Transmission " << transmissions[j].name << + " has no associated joints."); + continue; + } else if (transmissions[j].joints.size() > 1) { + RCLCPP_WARN_STREAM( + nh_->get_logger(), "Transmission " << transmissions[j].name << + " has more than one joint. Currently the default robot hardware simulation " << + " interface only supports one."); + continue; + } + std::string joint_name = joint_names_[j] = transmissions[j].joints[0].name; + + std::vector joint_interfaces = transmissions[j].joints[0].interfaces; + if (joint_interfaces.empty() && + !(transmissions[j].actuators.empty()) && + !(transmissions[j].actuators[0].interfaces.empty())) + { + // TODO(anyone): Deprecate HW interface specification in actuators in ROS 2 + joint_interfaces = transmissions[j].actuators[0].interfaces; + RCLCPP_WARN_STREAM( + nh_->get_logger(), "The element of transmission " << + transmissions[j].name << " should be nested inside the element," << + " not . The transmission will be properly loaded, but please update " << + "your robot model to remain compatible with future versions of the plugin."); + } + if (joint_interfaces.empty()) { + RCLCPP_WARN_STREAM( + nh_->get_logger(), "Joint " << transmissions[j].name << + " of transmission " << transmissions[j].name << + " does not specify any hardware interface. " << + "Not adding it to the robot hardware simulation."); + continue; + } else if (joint_interfaces.size() > 1) { + // only a warning, allow joint to continue + RCLCPP_WARN_STREAM( + nh_->get_logger(), "Joint " << transmissions[j].name << + " of transmission " << transmissions[j].name << + " specifies multiple hardware interfaces. " << + "Currently the default robot hardware simulation interface only supports one." << + "Using the first entry"); + } + std::string hardware_interface = joint_interfaces.front(); + // Decide what kind of command interface this actuator/joint has + if (hardware_interface == "hardware_interface/EffortJointInterface") { + joint_control_methods_[j] = EFFORT; + } else if (hardware_interface == "hardware_interface/PositionJointInterface") { + joint_control_methods_[j] = POSITION; + } else if (hardware_interface == "hardware_interface/VelocityJointInterface") { + joint_control_methods_[j] = VELOCITY; + } else { + RCLCPP_WARN_STREAM( + nh_->get_logger(), "No matching joint interface '" << + hardware_interface << "' for joint " << joint_name); + RCLCPP_INFO( + nh_->get_logger(), + " Expecting one of 'hardware_interface/{EffortJointInterface |" + " PositionJointInterface | VelocityJointInterface}'"); + return false; + } + + // + // Accept this URDF joint as valid and link with the gazebo joint of the same name + // + + // I think it's safe to only skip this joint and not abort if there is no match found + gazebo::physics::JointPtr simjoint = parent_model->GetJoint(joint_name); + if (!simjoint) { + RCLCPP_WARN_STREAM( + nh_->get_logger(), "Skipping joint in the URDF named '" << joint_name << + "' which is not in the gazebo model."); + continue; + } + sim_joints_.push_back(simjoint); + + // Accept this joint and continue configuration + RCLCPP_INFO_STREAM( + nh_->get_logger(), "Loading joint '" << joint_name << "' of type '" << + hardware_interface << "'"); + + // register the state handles + joint_pos_state_[j] = std::make_shared( + joint_name, hardware_interface::HW_IF_POSITION, &joint_position_[j]); + joint_vel_state_[j] = std::make_shared( + joint_name, hardware_interface::HW_IF_VELOCITY, &joint_velocity_[j]); + joint_eff_state_[j] = std::make_shared( + joint_name, hardware_interface::HW_IF_EFFORT, &joint_effort_[j]); + + // register the state handles + joint_pos_cmd_[j] = std::make_shared( + joint_name, hardware_interface::HW_IF_POSITION, &joint_position_cmd_[j]); + joint_vel_cmd_[j] = std::make_shared( + joint_name, hardware_interface::HW_IF_VELOCITY, &joint_velocity_cmd_[j]); + joint_eff_cmd_[j] = std::make_shared( + joint_name, hardware_interface::HW_IF_EFFORT, &joint_effort_cmd_[j]); + + try { + nh_->declare_parameter(transmissions[j].joints[0].name + ".p"); + nh_->declare_parameter(transmissions[j].joints[0].name + ".i"); + nh_->declare_parameter(transmissions[j].joints[0].name + ".d"); + nh_->declare_parameter(transmissions[j].joints[0].name + ".i_clamp_max"); + nh_->declare_parameter(transmissions[j].joints[0].name + ".i_clamp_min"); + nh_->declare_parameter(transmissions[j].joints[0].name + ".antiwindup", false); + + if (nh_->get_parameter(transmissions[j].joints[0].name + ".p").get_type() == + rclcpp::PARAMETER_DOUBLE && + nh_->get_parameter(transmissions[j].joints[0].name + ".i").get_type() == + rclcpp::PARAMETER_DOUBLE && + nh_->get_parameter(transmissions[j].joints[0].name + ".d").get_type() == + rclcpp::PARAMETER_DOUBLE) + { + pid_controllers_.push_back( + control_toolbox::PidROS(nh_, transmissions[j].joints[0].name)); + if (pid_controllers_[j].initPid()) { + switch (joint_control_methods_[j]) { + case POSITION: joint_control_methods_[j] = POSITION_PID; + RCLCPP_INFO( + nh_->get_logger(), "joint %s is configured in POSITION_PID mode", + transmissions[j].joints[0].name.c_str()); + break; + case VELOCITY: joint_control_methods_[j] = VELOCITY_PID; + RCLCPP_INFO( + nh_->get_logger(), "joint %s is configured in VELOCITY_PID mode", + transmissions[j].joints[0].name.c_str()); + break; + } + } + } + } catch (const std::exception & e) { + RCLCPP_ERROR(nh_->get_logger(), "%s", e.what()); + } + } + + // Initialize the emergency stop code. + this->e_stop_active_ = false; + if (sdf->HasElement("e_stop_topic")) { + const std::string e_stop_topic = sdf->GetElement("e_stop_topic")->Get(); + rclcpp::QoS qos = rclcpp::SensorDataQoS().reliable(); + this->e_stop_sub_ = this->nh_->create_subscription( + e_stop_topic, + qos, + std::bind(&GazeboSystem::eStopCB, this, std::placeholders::_1)); + } + + return true; +} + +hardware_interface::return_type +GazeboSystem::configure(const hardware_interface::HardwareInfo & actuator_info) +{ + if (configure_default(actuator_info) != hardware_interface::return_type::OK) { + return hardware_interface::return_type::ERROR; + } + return hardware_interface::return_type::OK; +} + +std::vector +GazeboSystem::export_state_interfaces() +{ + std::vector state_interfaces; + + for (unsigned int i = 0; i < this->joint_names_.size(); i++) { + state_interfaces.emplace_back( + hardware_interface::StateInterface( + this->joint_names_[i], hardware_interface::HW_IF_POSITION, &joint_position_[i])); + } + for (unsigned int i = 0; i < this->joint_names_.size(); i++) { + state_interfaces.emplace_back( + hardware_interface::StateInterface( + this->joint_names_[i], hardware_interface::HW_IF_VELOCITY, &joint_velocity_[i])); + } + for (unsigned int i = 0; i < this->joint_names_.size(); i++) { + state_interfaces.emplace_back( + hardware_interface::StateInterface( + this->joint_names_[i], hardware_interface::HW_IF_EFFORT, &joint_effort_[i])); + } + return state_interfaces; +} + +std::vector +GazeboSystem::export_command_interfaces() +{ + std::vector command_interfaces; + + for (unsigned int i = 0; i < this->joint_names_.size(); i++) { + command_interfaces.emplace_back( + hardware_interface::CommandInterface( + this->joint_names_[i], hardware_interface::HW_IF_POSITION, &joint_position_cmd_[i])); + } + for (unsigned int i = 0; i < this->joint_names_.size(); i++) { + command_interfaces.emplace_back( + hardware_interface::CommandInterface( + this->joint_names_[i], hardware_interface::HW_IF_VELOCITY, &joint_velocity_cmd_[i])); + } + for (unsigned int i = 0; i < this->joint_names_.size(); i++) { + command_interfaces.emplace_back( + hardware_interface::CommandInterface( + this->joint_names_[i], hardware_interface::HW_IF_EFFORT, &joint_effort_cmd_[i])); + } + return command_interfaces; +} + +hardware_interface::return_type GazeboSystem::start() +{ + status_ = hardware_interface::status::STARTED; + return hardware_interface::return_type::OK; +} + +hardware_interface::return_type GazeboSystem::stop() +{ + status_ = hardware_interface::status::STOPPED; + return hardware_interface::return_type::OK; +} + +hardware_interface::return_type GazeboSystem::read() +{ + for (unsigned int j = 0; j < this->joint_names_.size(); j++) { + joint_position_[j] = this->sim_joints_[j]->Position(0); + joint_velocity_[j] = this->sim_joints_[j]->GetVelocity(0); + joint_effort_[j] = this->sim_joints_[j]->GetForce(0u); + } + return hardware_interface::return_type::OK; +} + +hardware_interface::return_type GazeboSystem::write() +{ + // Get the simulation time and period + gazebo::common::Time gz_time_now = this->parent_model_->GetWorld()->SimTime(); + rclcpp::Time sim_time_ros(gz_time_now.sec, gz_time_now.nsec); + rclcpp::Duration sim_period = sim_time_ros - last_update_sim_time_ros_; + + for (unsigned int j = 0; j < this->joint_names_.size(); j++) { + switch (joint_control_methods_[j]) { + case EFFORT: + { + const double effort = e_stop_active_ ? 0 : joint_effort_cmd_[j]; + sim_joints_[j]->SetForce(0, effort); + } + break; + case POSITION: + if (e_stop_active_) { + // If the E-stop is active, joints controlled by position commands will maintain + // their positions. + this->sim_joints_[j]->SetPosition(0, last_joint_position_cmd_[j], true); + } else { + this->sim_joints_[j]->SetPosition(0, joint_position_cmd_[j], true); + last_joint_position_cmd_[j] = joint_position_cmd_[j]; + } + break; + case POSITION_PID: + { + double error; + // TODO(ahcorde): Restore this part + // switch (joint_types_[j]) { + // case urdf::Joint::REVOLUTE: + // // angles::shortest_angular_distance_with_limits( + // // joint_pos_state_[j].get_value(), + // // joint_pos_cmdh_[j].get_value(), + // // joint_lower_limits_[j], + // // joint_upper_limits_[j], + // // error); + // break; + // case urdf::Joint::CONTINUOUS: + // error = angles::shortest_angular_distance( + // joint_position_[j], + // joint_position_cmd_[j]); + // break; + // default: + // error = joint_position_cmd_[j] - joint_position_[j]; + // } + error = joint_position_cmd_[j] - joint_position_[j]; + + // TODO(ahcorde): Restore this when Jonit_limit interface is available + // const double effort_limit = joint_effort_limits_[j]; + // const double effort = ignition::math::clamp( + // pid_controllers_[j].computeCommand(error, period), + // -effort_limit, effort_limit); + + const double effort = pid_controllers_[j].computeCommand(error, sim_period); + + sim_joints_[j]->SetForce(0, effort); + sim_joints_[j]->SetParam("friction", 0, 0.0); + } + break; + case VELOCITY: + if (usingODE) { + sim_joints_[j]->SetParam("vel", 0, e_stop_active_ ? 0 : joint_velocity_cmd_[j]); + } else { + sim_joints_[j]->SetVelocity(0, e_stop_active_ ? 0 : joint_velocity_cmd_[j]); + } + break; + case VELOCITY_PID: + double error; + if (e_stop_active_) { + error = -joint_velocity_[j]; + } else { + error = joint_velocity_cmd_[j] - joint_velocity_[j]; + } + // TODO(ahcorde): Restore this when Jonit_limit interface is available + // const double effort_limit = joint_effort_limits_[j]; + // const double effort = ignition::math::clamp( + // pid_controllers_[j].computeCommand(error, period), + // -effort_limit, effort_limit); + const double effort = pid_controllers_[j].computeCommand(error, sim_period); + sim_joints_[j]->SetForce(0, effort); + break; + } + } + + last_update_sim_time_ros_ = sim_time_ros; + + return hardware_interface::return_type::OK; +} + +// Emergency stop callback +void GazeboSystem::eStopCB(const std::shared_ptr e_stop_active) +{ + this->e_stop_active_ = e_stop_active->data; +} + +} // namespace gazebo_ros2_control + +#include "pluginlib/class_list_macros.hpp" // NOLINT +PLUGINLIB_EXPORT_CLASS( + gazebo_ros2_control::GazeboSystem, gazebo_ros2_control::GazeboSystemInterface) diff --git a/gazebo_ros2_control_demos/urdf/test_cart_position.xacro.urdf b/gazebo_ros2_control_demos/urdf/test_cart_position.xacro.urdf index 2f0d8f82..23d2bc04 100644 --- a/gazebo_ros2_control_demos/urdf/test_cart_position.xacro.urdf +++ b/gazebo_ros2_control_demos/urdf/test_cart_position.xacro.urdf @@ -60,8 +60,10 @@ - gazebo_ros2_control/DefaultRobotHWSim + gazebo_ros2_control/GazeboSystem $(find gazebo_ros2_control_demos)/config/cartpole_controller.yaml + 0.01 + /cart_pole/estop diff --git a/gazebo_ros2_control_demos/urdf/test_cart_position_pid.xacro.urdf b/gazebo_ros2_control_demos/urdf/test_cart_position_pid.xacro.urdf index 2fed7bf0..9de83e42 100644 --- a/gazebo_ros2_control_demos/urdf/test_cart_position_pid.xacro.urdf +++ b/gazebo_ros2_control_demos/urdf/test_cart_position_pid.xacro.urdf @@ -69,8 +69,10 @@ -3.0 false - gazebo_ros2_control/DefaultRobotHWSim + gazebo_ros2_control/GazeboSystem $(find gazebo_ros2_control_demos)/config/cartpole_controller.yaml + 0.01 + /cart_pole/estop diff --git a/gazebo_ros2_control_demos/urdf/test_cart_velocity.xacro.urdf b/gazebo_ros2_control_demos/urdf/test_cart_velocity.xacro.urdf index 854cf6ba..87ba5819 100644 --- a/gazebo_ros2_control_demos/urdf/test_cart_velocity.xacro.urdf +++ b/gazebo_ros2_control_demos/urdf/test_cart_velocity.xacro.urdf @@ -60,8 +60,10 @@ - gazebo_ros2_control/DefaultRobotHWSim + gazebo_ros2_control/GazeboSystem $(find gazebo_ros2_control_demos)/config/cartpole_controller_velocity.yaml + 0.01 + /cart_pole/estop From b61b137dd32829a3b006413636612a2a33a8a3f6 Mon Sep 17 00:00:00 2001 From: ahcorde Date: Mon, 11 Jan 2021 16:24:51 +0100 Subject: [PATCH 02/33] Fixed dependency Signed-off-by: ahcorde --- gazebo_ros2_control/CMakeLists.txt | 1 + 1 file changed, 1 insertion(+) diff --git a/gazebo_ros2_control/CMakeLists.txt b/gazebo_ros2_control/CMakeLists.txt index f9536612..6ce32bc2 100644 --- a/gazebo_ros2_control/CMakeLists.txt +++ b/gazebo_ros2_control/CMakeLists.txt @@ -43,6 +43,7 @@ add_library(gazebo_hardware_plugins SHARED ament_target_dependencies(gazebo_hardware_plugins hardware_interface gazebo_dev + transmission_interface control_toolbox angles ) From a0ef367de590faef5d4133c508886326daed838e Mon Sep 17 00:00:00 2001 From: Karsten Knese Date: Tue, 12 Jan 2021 21:44:17 -1000 Subject: [PATCH 03/33] make compile on osx (#46) Signed-off-by: Karsten Knese --- gazebo_ros2_control/CMakeLists.txt | 5 +++++ gazebo_ros2_control/src/gazebo_system.cpp | 6 ++++++ 2 files changed, 11 insertions(+) diff --git a/gazebo_ros2_control/CMakeLists.txt b/gazebo_ros2_control/CMakeLists.txt index 6ce32bc2..30d8edce 100644 --- a/gazebo_ros2_control/CMakeLists.txt +++ b/gazebo_ros2_control/CMakeLists.txt @@ -20,13 +20,18 @@ if(NOT CMAKE_CXX_STANDARD) endif() include_directories(include) +link_directories( + ${gazebo_dev_LIBRARY_DIRS} +) # Libraries add_library(${PROJECT_NAME} SHARED src/gazebo_ros2_control_plugin.cpp ) ament_target_dependencies(${PROJECT_NAME} + angles controller_manager + control_toolbox gazebo_dev gazebo_ros hardware_interface diff --git a/gazebo_ros2_control/src/gazebo_system.cpp b/gazebo_ros2_control/src/gazebo_system.cpp index b348ee83..fbbc544f 100644 --- a/gazebo_ros2_control/src/gazebo_system.cpp +++ b/gazebo_ros2_control/src/gazebo_system.cpp @@ -192,6 +192,12 @@ bool GazeboSystem::initSim( nh_->get_logger(), "joint %s is configured in VELOCITY_PID mode", transmissions[j].joints[0].name.c_str()); break; + case EFFORT: + {} // fallthrough + case POSITION_PID: + {} // fallthrough + case VELOCITY_PID: + {} // fallthrough } } } From a69ff7c25d4adc843fd5239c3310f181e5032ba2 Mon Sep 17 00:00:00 2001 From: ahcorde Date: Wed, 13 Jan 2021 09:47:54 +0100 Subject: [PATCH 04/33] Fixed velocity example Signed-off-by: ahcorde --- .../include/gazebo_ros2_control/gazebo_system.hpp | 3 --- gazebo_ros2_control/src/gazebo_system.cpp | 9 +-------- gazebo_ros2_control_demos/examples/example_velocity.cpp | 2 +- 3 files changed, 2 insertions(+), 12 deletions(-) diff --git a/gazebo_ros2_control/include/gazebo_ros2_control/gazebo_system.hpp b/gazebo_ros2_control/include/gazebo_ros2_control/gazebo_system.hpp index 963268ae..eaa256ff 100644 --- a/gazebo_ros2_control/include/gazebo_ros2_control/gazebo_system.hpp +++ b/gazebo_ros2_control/include/gazebo_ros2_control/gazebo_system.hpp @@ -83,9 +83,6 @@ class GazeboSystem : public GazeboSystemInterface /// \brief last time the write method was called. rclcpp::Time last_update_sim_time_ros_; - /// \brief it is ODE physics engine? - bool usingODE; - /// \brief vector with the joint's names. std::vector joint_names_; diff --git a/gazebo_ros2_control/src/gazebo_system.cpp b/gazebo_ros2_control/src/gazebo_system.cpp index b348ee83..42936332 100644 --- a/gazebo_ros2_control/src/gazebo_system.cpp +++ b/gazebo_ros2_control/src/gazebo_system.cpp @@ -58,9 +58,6 @@ bool GazeboSystem::initSim( return false; } - // special handing since ODE uses a different set/get interface then the other engines - usingODE = (physics_type_.compare("ode") == 0); - for (unsigned int j = 0; j < this->n_dof_; j++) { // // Perform some validation on the URDF joint and actuator spec @@ -352,11 +349,7 @@ hardware_interface::return_type GazeboSystem::write() } break; case VELOCITY: - if (usingODE) { - sim_joints_[j]->SetParam("vel", 0, e_stop_active_ ? 0 : joint_velocity_cmd_[j]); - } else { - sim_joints_[j]->SetVelocity(0, e_stop_active_ ? 0 : joint_velocity_cmd_[j]); - } + sim_joints_[j]->SetVelocity(0, e_stop_active_ ? 0 : joint_velocity_cmd_[j]); break; case VELOCITY_PID: double error; diff --git a/gazebo_ros2_control_demos/examples/example_velocity.cpp b/gazebo_ros2_control_demos/examples/example_velocity.cpp index 42f3e9f5..a22060c8 100644 --- a/gazebo_ros2_control_demos/examples/example_velocity.cpp +++ b/gazebo_ros2_control_demos/examples/example_velocity.cpp @@ -28,7 +28,7 @@ int main(int argc, char * argv[]) node = std::make_shared("velocity_test_node"); - auto publisher = node->create_publisher("/commands", 10); + auto publisher = node->create_publisher("/cart_pole_controller/commands", 10); RCLCPP_INFO(node->get_logger(), "node created"); From 02ac826eeed76700d64aef9a5616709c31d54c57 Mon Sep 17 00:00:00 2001 From: ahcorde Date: Wed, 13 Jan 2021 09:58:34 +0100 Subject: [PATCH 05/33] make linters happy Signed-off-by: ahcorde --- gazebo_ros2_control_demos/examples/example_velocity.cpp | 3 ++- 1 file changed, 2 insertions(+), 1 deletion(-) diff --git a/gazebo_ros2_control_demos/examples/example_velocity.cpp b/gazebo_ros2_control_demos/examples/example_velocity.cpp index a22060c8..e59e8c9f 100644 --- a/gazebo_ros2_control_demos/examples/example_velocity.cpp +++ b/gazebo_ros2_control_demos/examples/example_velocity.cpp @@ -28,7 +28,8 @@ int main(int argc, char * argv[]) node = std::make_shared("velocity_test_node"); - auto publisher = node->create_publisher("/cart_pole_controller/commands", 10); + auto publisher = node->create_publisher( + "/cart_pole_controller/commands", 10); RCLCPP_INFO(node->get_logger(), "node created"); From 90a0b6f3fa39c8996c8173a9a3cacdaf916cd354 Mon Sep 17 00:00:00 2001 From: ahcorde Date: Fri, 15 Jan 2021 10:26:54 +0100 Subject: [PATCH 06/33] updated Dockerfile Signed-off-by: ahcorde --- Docker/Dockerfile | 18 ++++++++++++++---- 1 file changed, 14 insertions(+), 4 deletions(-) diff --git a/Docker/Dockerfile b/Docker/Dockerfile index 2b079289..33261f3b 100644 --- a/Docker/Dockerfile +++ b/Docker/Dockerfile @@ -9,24 +9,34 @@ RUN apt-get update && apt-get install -q -y --no-install-recommends \ dirmngr \ gnupg2 \ lsb-release \ + wget \ python3-colcon-ros \ && apt-get clean RUN mkdir -p /home/ros2_ws/src \ && cd /home/ros2_ws/src/ \ - && git clone https://github.com/ros-simulation/gazebo_ros2_control \ + # && wget https://raw.githubusercontent.com/ros-planning/moveit2/main/moveit2.repos \ + # && vcs import < moveit2.repos \ + && git clone https://github.com/ros-planning/moveit2 \ + && git clone https://github.com/ros-planning/moveit_msgs -b ros2 \ + && git clone https://github.com/ros-planning/moveit_resources -b ros2 \ + && git clone https://github.com/ros-planning/geometric_shapes -b ros2 \ + && git clone https://github.com/ros-planning/srdfdom -b ros2 \ + && git clone https://github.com/ros-planning/warehouse_ros -b ros2 \ + && git clone https://github.com/ros-planning/warehouse_ros_mongo -b ros2 \ + && git clone https://github.com/ros-simulation/gazebo_ros2_control -b ahcorde/update/foxy \ && git clone https://github.com/ros-controls/ros2_control \ && git clone https://github.com/ros-controls/ros2_controllers \ + && git clone https://github.com/ros-simulation/gazebo_ros_demos -b ahcorde/port/ros2 \ && rosdep update \ && rosdep install --from-paths ./ -i -y --rosdistro foxy \ --ignore-src RUN cd /home/ros2_ws/ \ && . /opt/ros/foxy/setup.sh \ - && export CMAKE_PREFIX_PATH=$AMENT_PREFIX_PATH:$CMAKE_PREFIX_PATH \ - && colcon build + && colcon build --merge-install COPY entrypoint.sh /entrypoint.sh ENTRYPOINT ["/entrypoint.sh"] -CMD ros2 launch gazebo_ros2_control_demos cart_example_position.launch.py +CMD ros2 launch rrbot_moveit_demo_nodes rrbot_demo.launch.py From 2933f8dcc157ab9e44826039abe6a3ea7466b229 Mon Sep 17 00:00:00 2001 From: ahcorde Date: Fri, 15 Jan 2021 10:44:12 +0100 Subject: [PATCH 07/33] Added effort example Signed-off-by: ahcorde --- README.md | 2 + gazebo_ros2_control_demos/CMakeLists.txt | 8 ++- .../config/cartpole_controller_effort.yaml | 17 +++++ .../examples/example_effort.cpp | 58 ++++++++++++++++ .../launch/cart_example_effort.launch.py | 62 +++++++++++++++++ .../urdf/test_cart_effort.xacro.urdf | 69 +++++++++++++++++++ 6 files changed, 215 insertions(+), 1 deletion(-) create mode 100644 gazebo_ros2_control_demos/config/cartpole_controller_effort.yaml create mode 100644 gazebo_ros2_control_demos/examples/example_effort.cpp create mode 100644 gazebo_ros2_control_demos/launch/cart_example_effort.launch.py create mode 100644 gazebo_ros2_control_demos/urdf/test_cart_effort.xacro.urdf diff --git a/README.md b/README.md index 6e572d57..c6c51bd0 100644 --- a/README.md +++ b/README.md @@ -209,6 +209,7 @@ You can run some of the configuration running the following commands: ros2 launch gazebo_ros2_control_demos cart_example_position_pid.launch.py ros2 launch gazebo_ros2_control_demos cart_example_position.launch.py ros2 launch gazebo_ros2_control_demos cart_example_velocity.launch.py +ros2 launch gazebo_ros2_control_demos cart_example_effort.launch.py ``` Send example commands: @@ -218,6 +219,7 @@ When the Gazebo world is launched you can run some of the following commads to m ```bash ros2 run gazebo_ros2_control_demos example_position ros2 run gazebo_ros2_control_demos example_velocity +ros2 run gazebo_ros2_control_demos example_effort ``` To get or modify the values of the PID controller you can run the following commands: diff --git a/gazebo_ros2_control_demos/CMakeLists.txt b/gazebo_ros2_control_demos/CMakeLists.txt index 27a49626..67b47332 100644 --- a/gazebo_ros2_control_demos/CMakeLists.txt +++ b/gazebo_ros2_control_demos/CMakeLists.txt @@ -40,6 +40,12 @@ ament_target_dependencies(example_velocity std_msgs ) +add_executable(example_effort examples/example_effort.cpp) +ament_target_dependencies(example_effort + rclcpp + std_msgs +) + if(BUILD_TESTING) find_package(ament_cmake_gtest REQUIRED) find_package(ament_lint_auto REQUIRED) @@ -48,7 +54,7 @@ if(BUILD_TESTING) endif() ## Install -install(TARGETS example_position example_velocity +install(TARGETS example_position example_velocity example_effort DESTINATION lib/${PROJECT_NAME} ) diff --git a/gazebo_ros2_control_demos/config/cartpole_controller_effort.yaml b/gazebo_ros2_control_demos/config/cartpole_controller_effort.yaml new file mode 100644 index 00000000..9b4fb4c2 --- /dev/null +++ b/gazebo_ros2_control_demos/config/cartpole_controller_effort.yaml @@ -0,0 +1,17 @@ +cart_pole_controller: + ros__parameters: + type: effort_controllers/JointGroupEffortController + joints: + - slider_to_cart + write_op_modes: + - slider_to_cart + state_publish_rate: 25 + action_monitor_rate: 20 + constraints: + stopped_velocity_tolerance: 0.05 + goal_time: 5 + +joint_state_controller: + ros__parameters: + type: joint_state_controller/JointStateController + publish_rate: 50 diff --git a/gazebo_ros2_control_demos/examples/example_effort.cpp b/gazebo_ros2_control_demos/examples/example_effort.cpp new file mode 100644 index 00000000..6d139d1e --- /dev/null +++ b/gazebo_ros2_control_demos/examples/example_effort.cpp @@ -0,0 +1,58 @@ +// Copyright 2020 Open Source Robotics Foundation, Inc. +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#include +#include +#include + +#include "rclcpp/rclcpp.hpp" + +#include "std_msgs/msg/float64_multi_array.hpp" + +std::shared_ptr node; + +int main(int argc, char * argv[]) +{ + rclcpp::init(argc, argv); + + node = std::make_shared("effort_test_node"); + + auto publisher = node->create_publisher( + "/cart_pole_controller/commands", 10); + + RCLCPP_INFO(node->get_logger(), "node created"); + + std_msgs::msg::Float64MultiArray commands; + + using namespace std::chrono_literals; + + commands.data.push_back(0); + publisher->publish(commands); + std::this_thread::sleep_for(1s); + + commands.data[0] = 100; + publisher->publish(commands); + std::this_thread::sleep_for(1s); + + commands.data[0] = -200; + publisher->publish(commands); + std::this_thread::sleep_for(1s); + + commands.data[0] = 0; + publisher->publish(commands); + std::this_thread::sleep_for(1s); + rclcpp::shutdown(); + + return 0; +} diff --git a/gazebo_ros2_control_demos/launch/cart_example_effort.launch.py b/gazebo_ros2_control_demos/launch/cart_example_effort.launch.py new file mode 100644 index 00000000..89df1466 --- /dev/null +++ b/gazebo_ros2_control_demos/launch/cart_example_effort.launch.py @@ -0,0 +1,62 @@ +# Copyright 2020 Open Source Robotics Foundation, Inc. +# +# Licensed under the Apache License, Version 2.0 (the "License"); +# you may not use this file except in compliance with the License. +# You may obtain a copy of the License at +# +# http://www.apache.org/licenses/LICENSE-2.0 +# +# Unless required by applicable law or agreed to in writing, software +# distributed under the License is distributed on an "AS IS" BASIS, +# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +# See the License for the specific language governing permissions and +# limitations under the License. + +import os + +from ament_index_python.packages import get_package_share_directory + + +from launch import LaunchDescription +from launch.actions import IncludeLaunchDescription +from launch.launch_description_sources import PythonLaunchDescriptionSource + +from launch_ros.actions import Node + +import xacro + + +def generate_launch_description(): + gazebo = IncludeLaunchDescription( + PythonLaunchDescriptionSource([os.path.join( + get_package_share_directory('gazebo_ros'), 'launch'), '/gazebo.launch.py']), + ) + + gazebo_ros2_control_demos_path = os.path.join( + get_package_share_directory('gazebo_ros2_control_demos')) + + xacro_file = os.path.join(gazebo_ros2_control_demos_path, + 'urdf', + 'test_cart_effort.xacro.urdf') + + doc = xacro.parse(open(xacro_file)) + xacro.process_doc(doc) + params = {'robot_description': doc.toxml()} + + node_robot_state_publisher = Node( + package='robot_state_publisher', + executable='robot_state_publisher', + output='screen', + parameters=[params] + ) + + spawn_entity = Node(package='gazebo_ros', executable='spawn_entity.py', + arguments=['-topic', 'robot_description', + '-entity', 'cartpole'], + output='screen') + + return LaunchDescription([ + gazebo, + node_robot_state_publisher, + spawn_entity, + ]) diff --git a/gazebo_ros2_control_demos/urdf/test_cart_effort.xacro.urdf b/gazebo_ros2_control_demos/urdf/test_cart_effort.xacro.urdf new file mode 100644 index 00000000..853d2626 --- /dev/null +++ b/gazebo_ros2_control_demos/urdf/test_cart_effort.xacro.urdf @@ -0,0 +1,69 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + transmission_interface/SimpleTransmission + + hardware_interface/EffortJointInterface + + + hardware_interface/EffortJointInterface + 1 + + + + + gazebo_ros2_control/GazeboSystem + $(find gazebo_ros2_control_demos)/config/cartpole_controller_effort.yaml + 0.01 + /cart_pole/estop + + + From 7334f06cb849cc49b222f9ce674c8bbd87a7ab28 Mon Sep 17 00:00:00 2001 From: ahcorde Date: Fri, 15 Jan 2021 10:44:42 +0100 Subject: [PATCH 08/33] Instructions to run with moveit2 Signed-off-by: ahcorde --- README.md | 13 +++++++++++++ img/moveit2.gif | Bin 0 -> 302263 bytes 2 files changed, 13 insertions(+) create mode 100644 img/moveit2.gif diff --git a/README.md b/README.md index c6c51bd0..3db8cfe5 100644 --- a/README.md +++ b/README.md @@ -239,3 +239,16 @@ ros2 param set /gazebo_ros2_control slider_to_cart.d 15.0 ros2 param set /gazebo_ros2_control slider_to_cart.i_clamp_max 3.0 ros2 param set /gazebo_ros2_control slider_to_cart.i_clamp_min -3.0 ``` + +#### Gazebo + Moveit2 + ROS 2 + +This example works with [ROS 2 Foxy](https://index.ros.org/doc/ros2/Installation/Foxy/). +You should install Moveit2 from sources, the instructions are available in this [link](https://moveit.ros.org/install-moveit2/source/). + +The repository with all the required packages are in the [gazebo_ros_demos](https://github.com/ros-simulation/gazebo_ros_demos/tree/ahcorde/port/ros2). + +```bash +ros2 launch rrbot_moveit_demo_nodes rrbot_demo.launch.py +``` + +![](img/moveit2.gif) diff --git a/img/moveit2.gif b/img/moveit2.gif new file mode 100644 index 0000000000000000000000000000000000000000..00ad27af4a7de2c4bea39472bab69a8e97703754 GIT binary patch literal 302263 zcmeF2Wmgp5+qPkf8cONz25FFvp}V_l=uQEL7`g-r>28n)DQOUflSolU* z>;YI}3D{WjxQ~K(By3ReK&Vm{fk71^IT;ZV(Q}LUBoGNw8YxnTZgNIb3cEH+=WZHo z2(3R89fX;V;u)QwA%nCnBbbEIu8~Q}pZP!Bd)NZU*%_$0!e+QB@VNhjhlkrBnU9Z; zpPyfVUr-=wLC_&jBy3ES3{RAnSqwrX#;+SD*Sx!z)UQS+K!&*@hrXsAUq86mGrJ)+prk*~nfs3U@L#y>tREG>t*Zr+t)w#aD zfqw0+fdI7;F~G>bGHBzn@68)Rm7Wfp8@cJFO&ZebqXYC#6Jwzjo#3AW3ea&T~P zOmTEr<+p#e zDL%C|mGxd8_5H&Q4Gm3AP0g=$-WwaYwY9ZNg4(@!JI$YW+LLv4b#|x5clY#sXsqb1 zPVD=S^I!cK7y~-c0bQ(t*3#kOz7b#MkvP4PWS5bT&7&iuV>b`ulc@38r70)usi~tcK4@-_M8*RR*(h;P;U-@bjj`H%14zyJ90<81kMIqmlL z;%>*Hsea;|F5?rvu|}5EzI7z~K3x8~@WJ{(p!6ljQ#-`TtcCY&6Cz zY#P;;(%~5F=UkRkEoGzeM9k`is;%YY$rM6v+f%I-lj#hKNi=G0m7lUW4C*aEwN=gJ z@;giysuC{vo zzwXZVb${C%iov7T?(g}2G?m3|GuQv&_N@H=ho|O1@6TbG{s(y=i}SCm9cf&2nIc^6 zpd;H+(o6RP=m5hDe#? zAeO`!et@KKu04pO2|7QBXNcoCOkl}@A0~2C*B&PEbe$h2^G|Rbr3kOWk5a`?Ymd^T zew`ns%RxAgGhk${EO9(6?<#S*Qsnltbd^86C3GB$(IW1fy8RT&tmk_24Du!8B!`|B zQ(FejdCV$m`$HH;eyYS$onsj^7DKl*#5~7D)nqot@k;s5xe$Byw;E9#L|`G`lfV&P zL@7|eP(gr?Tc<98(K|(ulNR7oyjkiyDUrQk!dgHPfvZznk<*(|33WpEo<&mVZR*yL zeCqw8(YwTT@_q=?phtv7h8I_kO_!`{&C zoCG%E!6@xhHD@~y&8zL}O^sDGNojqTGSfvh8EpkjUl%`}QO zR2xQJTWY7cie1+HXUd#O;`C$j)>fa&@NFcAVsA1ui?E~OO>fTi;I%p->}CNX0DpQ6 zIWDoNjJaF3NFVrxMXFV?`14ZVh~fwt zYN|@KE@?A02sxLIdms|JyrrsO4kqzoLqirGM>}Q4F@0=jxoSLI!9r{m)sbiUH?bU= zWw<6&BV@fdNd89Z!@2Bctj(J^T`G(D1O~S9Iz^gVc-BvJ}d5C}0dWxU;lD2qU>CU1OeDTvg2Wj?7x*jQgufemMj~5o8NJyuZi-@E)L0ug1$Dlw zPQ6>H6Nfh1z5(FIkOVO)CTKD)mnDpIF$q#%$wS#SHm1#gwdKt=I*ZM0%!U1GXDTc^ zglKFoF;!3%WD}cN`LRl>B^@IXKuu6mH0<72)#MpWY*{3IKycGjEpgqtO@(37193MeG_Nx+ zvTA+Zw&Ha$=!}o5djDpcdy2o#-Rkm3SC`dxle>XCG}$*s%akeqRg^}@1|TE?A`hT# z7?P$yRM1)TLm~uRUI1Ny_%0z>i~ssSjF)A!yLk%YITpwifFB_y6ySzWY8%qC3c0mX ziC{O`_om6ib~K$78#y?HZPaJK-1U8BAvr)-i1`6#?e*$WN#O2T@W6e(V9u#;TDfm< z=V#K>Kx!Tv{72I~S~e^%%si{TksLItQwbn-_x-S^IJk#?EAJhl<)o^5?#GrD-b8n) zeYy)%YMmR9gp9G1JIXhEd|)l|lirS;%l$BJ*Y`W9Cq9fjfAJn3UvY-%$}{Oc4XYiI zI=76G4uM*iFjR{4e*fr4G;F;i&6PW_y~B?d?IN&NVBYgRmBFj5Y`Ds;H@kAnPgPs( zD2{I$SV;6qP$cy;z_uJHQ@+U|@5yYJe_njRzc-$ov3))vS(z&Nx%Y90=OvH)F>fu9 zG&(0eHDw73*o=I9+`}O38N$-OiKc$q$9|CscgOw~C;7xHS=u6#Gc@|@JH|wvu(EgJ z4bsOJx*AM6F@7LVNWULUERU`Q2!N@+`)F?4$cHFAPiak4;OZ2V z&mv41Y7MCh8=tHA%^qI*!yZz05>RbPM72R^;-2NV(3JXv4J0r30s?9VFXTmEj-(O@$Y0<=HK6U^nXplC;yZU zK31)9|4ByJl;{dV0;~=Z5SS6s+fj7|6W^g4zmeRKz5AfectHhnP>P8^Kovm~Xq71h zTKkDN-(rd1Dtoc-(DsvHlz}MUL~e*wci@Z*D*!=g5+kB2FAkTdl=lV<#}K|TO+tEO zwRwYE84rzdL>ZWs5Lg;R0Gt{oDO)U!j97WUSi^@{(>$bk57KfSY5jn-g)`&1#5kJ9 zSuE-rFNc-fST~SJk^NK^s}a3W0Y!Ei=EcOVRA3#*Nr)yjg~M z?Jxf78>6!fDAAvF37x~FOYQS+=az~o0MZiNrQ7k=pAF>cX1LH;?gNAab!4-oq<2|1Yt=!y& z&qbzN9YEOG2^0=`VFC(ij7=PzQu3}*4x5T6aB%z@6TdfVk*}Isjcw5o!2aq%_8=rd z-6=j@RrJj{mrfQ3AO!S9Hxaq6`misPX74+D>iCB|;pstjG0&d63&hoB$lm!XyEJKQ z)UJsmAtxl_V*S;m!|RdK^vqG;C1t~q^EW$+NpaZWwY6`OM&7XCWRAbpzU#5dT=%@+ zPr>6%;XKS=)WNuPL7{dX>t56lwzog(-lAnQD29E|tl7*|_FH1(XoJ6r$n zbIZX_dh&R6(>8cRLh#ECEobo@M^0jy^O)>%(-b4@FB#sB^06RaM!pvCLJLR)1ABBo zR=^Lm(E{R?%hlKiC?FtVzr})ILPd4+Ui#%Fx-xR_Lwy)n_Va<9e_1hMcI>DEkVVMiA9^CZaX~%1HTK_x{CpN`9!@XHEaRrYGs3=g`*Ye^PvT~ z83k)~FS)n^*w>2J$wl5&#gX6Vw{m(y5+PD|1)8}8o3^;OazP+a5qthyDz0J@oYK?8 zVx4x`a|XP(c>?Dfz}~vTW7ia>uzbF% z)AD0T4T;~B$WZETOP z=>3c3xw9&U!2Gno+&F zp7LutBs@8A>qG>d;BahgL5T-4=7zpbCgOQ)QKN46=ScAhj66QYt*(4+tKY43-}!>O zm6f@j>bKClnYN;aw!p2{hI0{%Ghp1aR1ZLpds5*~E~`v~50MQVO13!iAa}IBeo!}d zTVIf(6S2?u`##|;`*LGR$NUcJpzr1bt6N0gK(Wj>bp(E(l@@Gs^bP2+k3rMk`cR$8 zLI`^B2r}Q##Xqc%Fw3(5TG0vS&Sl^^VL$@*u{HJ^VF2Lx4Nll60KaY%pYA)Ja$pfd z6E9Ky^&{qZFC)JkboCF@MsHJ?S|fml@$^;G<)2{&nh_?c5f;mll9T4Of)Oqc_E-Fb zPj2}H=9=Q4ZKrGBkl$Ab&=>@l8u~63oW9YUmzIx?{u~UZ~IW@@Qhg%{Qt*5a*(s4Ss zip6z;JzYW#1nakrsN%QL#sQ;Z&O`~(i9B7#^c7*Naue2Q*B7s(1R^d)j6v?aQ|xIp znPN{PU)5fo*M&KR6C|(d23Zms_z-;49aHJYmeTELu9+_6?uj8GC`ut{F8w4bF;?X< zrn>E^-f3=rnQzIH!o4}ciQOV}Il1DmUe*u7fk!n5s{>+-vprBnSe67QFREeF(*3S~ z)I~q_qpVLfMxG{g3pM@2Tc%u9O4zdR5qe#selNnuy~34zpr2~E3&@k^lB?$~Ev1{c zCBiLdzrF*%RHK_%nP7de5_eH zLQIoRR#34|7XVZ5R@cA7FM=y~iLMCWt8+w9I)4mZKHx}PK{x_Xk%PML1F$Y*5tPlH z7XVpXoM}0zs(3TyAtv!9Lw7Ikq#QJdp-~%PS+cv>GapvTp z3*g2y{Ef^3#-ZLO=u*?{CcsyEP2O?iP$Ji3XDzvOnN4bY%xZfgVtcA+8x=hww6i_8 zLqv0%o*nbXg^1v*7_5p0Ho1ioc`2}pj(|N|AvnAVnP=FcaZ+>riGT1m4T`s`r9t4q z1j>24b1JW{SV?d`?DBLvZDU%wmpg)%rw3)Fk3|HBJ6ef;r>y}*_-XiryN4fO zJK(yPnz$cUh1RAJsan=AL(zk0#JguCGVMnXuA=e{M2gIeP@U{smbeHrfV6GQI*#u!m|Fz{?PPJzL=Wusj`p&~*Xh5Lcr% zFUaZ!jeymc_~()+0YwKK(*W!e&32E|VNI43USgIjper&3qr6v%fx; zk7r+oRim}skb!58mg8Sg`p#?no#OrX5l=>P8WP1;K*K^K(*n*z^S2C*cVR_%RtsRy zeQ0*+wl4ioec7LeHb0H`7*JPV&G)`4J9!L7OO{SWcIZd7lK*1#st~BR0sGQPPU>MT zdV$LL&6o?O0KXuMp@6c8)?5)UF#R8=Um(l}w@k_RnM4p!FkYE7!X_#Tol^4fpV$Ea zMp^Kpmkhsd{5PVPjW%)%w0`f217v?=z4?_KP3)QZyGoY$2k;)};6CcbgPkzZ+i$;s z-$ADWeljt|Q-^<&0goLoensgJb?xai=RC@5fDY__-?$PLMc(_)|9KNDm5r7`z2I-9 zCw>72wSWA%jkbv!N@Ku#^SR)n?laMLI3<`)u0CsHBQbQC#;?B4JhxD5i}$A9-z>L% zlQ9bid%firV{rtTOvWn{;Fk@E6BXx?!g%IfF^+4SY)bQqOo?fNm0mN#UQd?=FUf}` z3HDB~3Xhmx%vmw3eBxaKcfz}X?=kC4=_Tev96_Ha$UQ(tbXqtS`Jb5A1DbumgEya% zyTnmGQRs8hkW)BlZ<~>BePR|141c0rX3?uqO(&2V<=Nc+@LA4&c|H0_(~kFH(?{U> zR%V75KD~0G>392yR9e|M8nYjc)7iW>6NP5C&T~c5uOYPNckrbutrF!T^Pg_3O;#V{ zXf1wuY`#I8Z9A7SDJ2n0hod2MmJdFM; z%2s7+@3Gci_Fjw%75a#9z{_mDB?vxmafp2)Syx^?M9#8x7-&#vSFP?`npoa6X1R}< zVV4nZk4;^8slkxe>-OVQ7LC7O9-U!ZS)x%ArZT08DdK>wrv>K=PsU)vgt~Lik{xLY zZhaX#^<|Xr1k)ry(xFAv2tEvX@iQ}-(kajPG^;+2(v3n+=6h+DI-S2ASh4RZc7@Lh z=Te`p&8=)f$s@tAQtCi_iuBFX({dcI2j$PQSgII2D*h69d7cF(X#l67!$5s0b4OIY zsAu;{mxcF7u$ZOqBx|>&|GbizRp6Raw^i_7Ahi3xG?iE7)wgjmn~3|9ZkyK;x0n-% zd)hpOf0xqYy|H!N;uCSy;Sb|T_rixhkVC)eKoa_-$01!7^3w5*%4tXf?d!|K#FS*} zALjMu*mVsaIq)nb-$&ul1jY`-MiXjW_c9GT?96vuY_7)7;S=@wp{x{zdMAlY#vlCA zYf z!5w1aG7z|C6E7XK;ZidYwB+WZ`j z+m~i0BaRe2+<1-zD9ATCL9>8~m6$BUm8mFtLzU<(!Da{(vH%}74XMtnb!0{pl``Q7 z{JHrkYImZW@ECg{+TB3QvtX`aHw=2+8i(gh#6LB%V!E2kWm`$)g+YSzpl(|C$I~ZR z1!n&&y9dT5x|paFYfn-ouEZr+9eh`BP1f0?#22)fYy)zj7#CL-%vnrvfjLl-29V@- zDmm-rsjWpGrdYz|@jP_(9ZY>P?AE`l>evnwYU-)*p4)Np+3M#E>ZS?@VB+5zXyOm@ z<69ug@T`5tp4sx_D@e)XVY_1P?H{s{k$9z7Bb2E+_QAr1KXe^5MxXaDaHyAEV9(jo zls7(;u_sc%ljg#1F7zc$7gvltHh@CY-psrc2U7Dt&S1#L%Q0dwWt*edNA&&L{<~Ls z?b7;X$~aeGI{#5#x}Tl=QzanXGAkSK5~wLv8gK1ZhCk70FZ1(*PUNr8C1?;_4lJP? z-Fuq!(ZE50v{yGybh(TW35T&t=p`91m)m-niI&=vz_gXXvir{Rk+wLN#tR8?0wp5n z&r(}EO0ijtAOgDb6loN(m2-$Chr?xDM{&h!jrCzN#4u;ufm(rm)VmS|rdT);!L3gjjOCwhayOn2INwJmqt!&#)y zY%XZEJ@F-cfKS4FDQC5#M#Rd*Ucx5yOv5>jGxz`TG@VworDEN2N zl1D+oHsHRyaD&%J4tdEdS_{53y+YwlpvT|G1xyaGjFQnx0?FxQR)W|v{_D>#PR7DXn zN;y!itxt$e_@)JFD&YjLPs&34GLTY^OynC=D#r6^2k2x?Rej+|xg zH|AeM0!qQs=d|%bSn*xMy72%P)6p`%F2wcV)mUsC#SY zTU>DeiL`gv+ScydcMh2l8T3sH-aewo3Y}7t@ypEJK4w=5oi-Zu%jw=ec@h76l2^t*e{K6zY%+8X zC*^zI{q~tGR@eekCZL>r=Uhc4Y$CT2Hk|@53m7Jk9i~_&drTI6!b8G=L$>Qu z;iW_V3|Jls0GwI`?}MyYyPT^kmY;1r3kRkj2No*_29PL9PdvU)2os+Jfh!&ZcSs=M z$DqiFFmP@VLi}>1ccZeP zF*%Ykd6qE+;j!qfVVL2VlH-_i0Ia)I9^MB5QGhWn6={$A>Bb;L8P81?5H#naqNu@u zg?N@JL;w+%aSsv_j^UaSFYkk4tO^!~Bc#Q#f^4HnTVgFUqKFvcF<8IUL@bt%qGP{|Q)8SeKZfACvR@AbAdWmLK={DpS;sH~ zP2)fm$RK!pB@|5eBo(}mkuMeR0Gi&%8w4PtgYu^9`_%zc>hsK4iv0y#uuV+;;Md_V%02wXw)eD04WhH~DZ4U0PMd8`liILH!d zQ95V0FZZ=!{oxOllwSapy@l|3DMH5Y|`YHGlV+hJdy)a4O zG)b6^ny0{|z5&j408yv~a^xaK_9A7~B30)i_4p#q$|CK_BHhnLdhikh=@R3~qF@Hb z84P;fF$~vGxOCLGf?~ReL$neh=rJixAH+)>Mfg`KECx<9U5)DFB>@i1uLeVKpExZX zEVQj=d;lB^J~Tm;5f|LEglC8~a3qrt(iLvX6p@zhPU-UO(Yb10P!L&GR9c1^Eh~9` zj84Fi@X@1AjUo6ig>G5a7+=<0S=KsP*8aJy9T>yc5;f%!MQj@-_^@nfv|{A6qD#B- z{3L~dBAV1mQz9gqwzR-es-nCs#wFkoh8_RnEgSZ7`NrcqH*70l~y3Fc& zxYM`AF!&WdNC$v$pm8k-XDBMcX?r4YdlI=lmAanTWcsGla)vhs`y9h?V0#X{fkGPXC1K1u zYBPjve3rJN&RZ#S+F1?USwrruXYXuO?QC}LYz=7P@NaGn3FdVeqiM#*f`;NKeRK}+ zM*ue%_y?k*PipiiY#t8`V*bG>)_5Pd3H<8_k5mjAsDRB8PkBBk{iJibwRYY2`Eo_! zIu(FTF@(!M%Gja*DSPjC)!v`Zy~m%5(<^#7H{1Wl*8}eMFr1BccvFc@cg8h=D@r@y zATv@T&28j9cFsP|e_46gKHkJWbaj7x8` zRt*7csU+voHqx4s>zFxC`+Rf&OVT-oyx862xYsTFg1_|8vhY|91kwT{&b}6Gs)|%8 zT|vPd3I-ggXOF0Mj_`jS$wH3h$d2W$HF+`gRHZhFheTURG+Z0({2Y#z|8=Y89D7*k zvP>Lnt{!Wh9&5|I{5z}nFWa6o?of};iHk0kH~~1Z98G(3XwntM{(v&{nbok3(-=A& z4{yzG1Ii+h_86zO+9;VcTYG1eLP)HJEz%s0RKV7fwLP-0efD4WY@8P>ajGe+3U=C$ z^SX}n+K=}Ru~PMMP=(_@uqPej z>iJyS=I%I4`O915FWJtnfk3CNOQ0zOl8hH6YYSExa-JY@GVnUoKXqkSc3Mop2;xIA z?jM>s@6)YgmMd#Ysv_ZV@aMZ26;-5p>D&dBMAz1BGzFp?68j$VwIvdiY#eKk(P}q$ zhB5>xwJfUixa_33$jUkEnmV_qLH_F28BTpcfxynXoV^PqPNmPa*4;*VKwboA-o}^X z5Eplfqw(#tQ4kUy5<8-OW|-mZT#KCa(o({RgD-%?jZq2=S4(_X1G}iYL69y6Sk}jL zjW5=)C)WKGH5H^K36C{|Bmc&L(Z)To3N4qz9aqXdNcYIAqsS|TjH5W`>(ij?GrCRl z{kXnruk5yK__?z=#Q48@$_?P4UGgA@?Av#?Z$Cu8F-3mad|UsHPgB;^ds!P*^v_kR zDn?-_CiUl+-vs-m1gWg2wnb5fymD^KT2XU_pbzJ6OZ}ieQ32G`~1sQrld@ z*WI?*G-Y+;;62C%9uTAk&)9aBAQ#Wd_Uk6W_YoeD8Ob?^4%p1nZ@%zK0RyQZ=LIbR zDe3yo!p;xU+XN{7xg;=PfWY0nHhnQJQZyxJ!b8o$MR$|;3 zV%4u~#Na^fk#9O!D;nv*zt$@XXee4+Q&M-IFXPl)H&&41CWjU?e-1TT?d81gGan1? z<%qL@gN@-}P)V}J0t$OgQ=kSfyX|J2Cw67^hU&^^wfbtC#o0L_{WM(f>ZO-?<31#nwnsrU0*SFO{E_2%lVk~L9i&jCj8$`z$zFQOF&n5R-p&^ zA;gDG2es~eg-&qsjBfUuYrK`}iRD}iF>?gF{JWZk-ja9w&-KSz=-y_j+*(jPxapv_ z=VHW5{CUq}rE7lYcmFPUJ!`x#`)~B;;-$Z{X-KwyocY6dxcILR`w&5TeN*~G7~OqM z{GZy~KXo;K>bw6mO#W$H`_pvxr}_TRd#uM6^2b*8$2PIYc9q8tlgCb%$FAVV?)b-^ z+{X_!kG$e)Hw2vto`GIDX2rAA@-u99-$<7)vfw%1cwBSF-&eO=LIk-$X1ez9VV5 zjTQ@Ws(nB&^94CCfF*(!m200_sUo{qog%w`%@4YNXn_Rny1Yn#u!~>xbh%2Oob@)j zue0HFvemTGy}v}e2NOD*E}$%G@2Srq&f+fNgbyDO!6U-=Qa3Ti557k#C=JuPk7Qww zxvv*M2^y$!Oan)D!jV{9a<=1N>5L-^b#i*3>?DKwlsZ#sw__|ORb2*hYc65GGQ|vJ zxspTB4U1-6uGetA>ut4`Rl038XoG`vL`{;B%>L)1PJOOGuAt||9p`ebevN*U+fT05 zM)PjJtBar9>n-+^nY`}5c+6uXaq%5LJ$qZy<99X@JKjV=n=^jNQC^XpU8KO>w4-ie ztdNWzOCs;KJ;*~Qk#H(+H+cLOJVoV;`CniD7CK)jSIOe@{3Cp^TyN6ub@fN&a=p#v zbF=58==FAQ@a^^0qu9;mk#6eB@B!fE0lTT5`3@()fzc#KlbDz>RSzEq*Lw|hjb*_ic=mjdr6GUldX}tD5 zFM|pVl^#N<{Tu!MD8UR|pZeeOT3%h()AQlzuG?4;$%7AV9LovO6_ zovIQ^wxOz}I%UvONHpmZhf-=~6fE!%j$R5eoI>P7$9z@TTH=%* zpLy9*$6hGNva*oCB0JhV=~TZ+a86LV_X|wYzIqavVoa72{KOj5n84@T#?l~y9^3uX z*3|p(GSez#AdsCq@|ik^o%Q!Re$6B)LE%NEU}4g1QyIuRM`qNm@UotUw8)B)MTE$z znfrjqn$@enBI|a^(xMwq1ref~t_=gCTb_M?MYnxtq{Vguw<5%LL%$A)?L|EP72A)( zlMz2aQb&p(CUQ6b3eXPJPh}3eJ3w)*pOj4s-+mc}@}-+*mK|3=F-P&BImST<`0J!hR%8Yi}_=flCxm)D>mT@&RJLe_Wad;HqrLFSx>+Ag54)J z@lnn>-^}*H(+=mOydOnR=Lh69{xG_svjkboGls}>kO0kMynW>vLw}#8$Z5N_zPM6Q z`*YpIJKaI%-`Hib2{F_hmAVQrHNr85F`6`ivIM^Q@Ef4+-ToOwPL5fbqm3vAVpy8i z#R$`Li;0~JUi{ZlM)CX){OP>LplH*Z<-x#!+0d-Xri}@qh+SF$BCQ3s#ioRE&>GMQ zWT;28ST-U)fmHOdZAsLT#A=2t%zg?aas1H~24kk5HfuFl&~4nj;RiKuW4WlNGn$2I zKCv`@=cdc7h~FW~wu}kkc3}Ey)S5|3WVbq&hfvT)_PQBpe^AOfabrx?)#vT4HBvdO zYtk^QfUP2VNz!uCQk+!j)ZB?9eEA#yKKsm&n5bGKZ2v|q6h>Km1LAEtcqUGHG-BC+ zjW#1D$*nce%|M# zreBsUPNJBrYv(46O3H9a{gPyU(hTNZSE_^DvZ(bv6DkOr!+hQ|1d-v7e%`nb7U~%$ zh~$rD<~hJI2pRt3IDK>e4iEqHbE;76Si#<-BFs1Cgy_lh8v2mn`S3pmGT^^(721GB z<~JmStM8P#aE0~darNcvZ+6qR7a)Ku?3%wgb$6B^W=h&~ig7t*KEzvQOeY{=lxjv@ zxjGABWi4}_1#?ihXDfik|}RE_*oWs%}q``ZaZ2NDMX(vFFzZ;T;3hszUgWNdZk z%`U{xs=r6GG%);b&&$)>7@yYo? z+u9jTX{%k1H=5~YTr)^op>l|&a1yLJt?I0KeeCQmu4q>0!$n<(`-UH7HZ(T^|Z{F`r! zZu`%~TtbjBe0OEf2hNpcC6=<9@2Z3bzG%OeSmEn`OHh(ly6+APk%9Job8MFRB0nW7 z`3C>*lTZ+oQ5}LTKS;Eak>F=&da`LFouuIu$!G!xwZw%~A=B?rKKrHD=9@C_+lOZ~ zFJS6IV!@JQwMBGS>BzjYvh=}iRE{@hKAN%I`9)P3Z$DkV2p!`YBMT`L#hXyV6+@D0}72HB{qz;ECIA?>dfm=-aD{1 zUJyrr0ahdf_TfA8+O47NQk-H2-0D)?=KVm@!p;B_u5jH~uu zCc(%Uz)V-*9Oo11==z=5CgD7=U%Hwy@X)RG1S}|M{W=Ryw@++nY zC^lUsCN0JM8=m>&aC@zt<<}f<)qKlg#FS64gOe-6Q-QJ5P_?Out+URNe2SGqtCXt` zNI?uB|9X-INsM4URAX7ef;b7gc#Ow01H@Tk-ZFwIqafT!4ZFd?)>7~_GB@1T5D^5w zD9a$N%C5k$xY^K*SQEmLD_&odexNb44oY_o0bC>QPiX3BBppgG4_ zh}3!a3CfL<8}o4f2>`i!=s&R*3a?sM>)L8|0E#LVSVa_GLG?edFi^{H!Rw5;pbUMa zr4_WL3O*JZQX@<|EFmkfo;oDo{uu7bqSm$o{dWzl=u*8wYMivv+g1hx(JBKORzu|~ z!!%e>*)x7i^+Cf7uD=YuzN2`D~kd^vhu*|Qv6$o%WWaEUr<)QmTGj&RD z8qKRdZ+Uw7ba|+7cc?eKhexJJg{_zv68ECH43UKo>;MH zX1z+Ik|rhQ%4|(Rw)%E8I2Mb4v$nBY)mZ{8|-eBA_p5Sj~c^eL{fmW=wStk#mRJ5 zvArZ;lzLdO^wHFV$Cgkp28Q8P{rU>f$OtX(n70{~!VMlf&57P>&7c-*UR+&X8t1#5 zFYF)oyR}BzTRcc>FEGqKH5f!l{wFRx0C#Ez?wxLHpZICxUnW+~76*+KX@ zsXab-IM7zKzCwnp^7KTkWyHa_zRH@b+PS{ki>oH6zJ|)#aRf%67cFXgdID4As|AOK zV~5qoU)&kcdALLhk05(g9$>BtQ1+y;^*~%zwW#=4Bx-L#YSF5y-fs38lvDA?25)tX zo4ZumOZE8{qUbu}qtB<_c%<=a+Q;WP@tK}6E9?gGD?Z%NhD6tdaDhSz1=yO z!X5^ywbdIdmPUIYNj7W8rsXqB;zwW!bZ_bg@|zZpiVevu5Of;woWBC&K&v-QhDR&` z)H%hV=?++`Xo?xc^&?T8@)$8T4sRwGEL+B?v$Y~C&9Yk>5OTn>9G&a3ajZph)w2QP zU7*wRtJ4c}jmYO*k84^_f8HGliZ zcLRBUL-67|+57KwFMhDS|H0%{n+9qQo0R9-Jro$*miK1Nx60H@NECKIIM`tUB>W0{ z0n<9%^?mOXeRzMplh`q=WXF^g;ti{NaZ=>YSM9FQ_?3v^zYTRoE;wev!aII7V{V4@ zg(>wf4Dco)AZKnHXNe$JO&iyHLGJE0?vH{z zlWjcng1l=#c*NctolpPt8*eXv{{rpD0T4=FkiTdI#9+67SbBf5@j_w$Jy{322G2Hq z?r=T^KkSJTr>)As&cBpVr)Pyn2+qu~NQKX~G$cd+%)T{kI#b*qT!FEtz>kKjjkQ|X znOisW%Xss^8eK=gt8#;=HNLT_3H7q6n@@a|5xwm6-Tn*fCVDhVhWnlx{mD+mNo5Qj z8MvNH|E$SoW_rVg7pT^jiZ!~eMxG7UJs*L2+VN5eRZ?}|k+&C6zh>aU1}|zV$nCXi ze-qZZ@6btxZVoy@$udbJShuG+xr{UzkFJI~#+$yV>xz&{x1XG`Qq3fcOl$oJ)@EcA z;$nX-Vw#-Kz9ndu+i6xJVqVi}{$9kQyVK&Mh~;Fb<-Ca1THxiOAp1{2!Ec?x7b1VU zqM~VpY+ls}zVO%F|3(DOdR3YzXP7MXfT=$`hE>D?V2vg9RGL)6e)bEEH*c9SvXN9FM=Km!`ya5UNlP~GF$v;g=!6v%%j zGF6IVv1P%wqpx|9QYCsCLbcCE9pLHP8GZ^F(YhKz!gQViF===1olxL)zJ*j76H#&~ z_g-1veN*dq%~!V0($Tt_0H43Y5o_HMdt#9e;QY2LR*n%C>{R-hCezH^LgUVDzMqT* z!UfTw7aLvbJx&E5T%X35fS3kl&NwFAeEi!$DG%|ZFp=8-7WrdE5*06w?VI!ZW2_29 zED<9~AH`E9L%ucxMJyGC7DmNtds4oMr{DLaqs23@K4cL7K0W+@0H8o$zyI|n`SoBY zIrJd8k~jI06}Fi%a~>e}5Ws>-S^bE%YZkOypqO3x2)gxJUdzz$F=-ch3=875xAQc=% z^L9iGsYPt@x)g0f9Bm#gDb6)1o3qg`A)GTDl6xG|Ks=#hyG0|<7b*>8Md`%xRv&89EN*4ML$o7q zCVxr_CNh9lro%L0+F+| zG&n;zw8K1%d%b7wz32PBlY3i>LoD5g$Ac72@*Av9=xOiwM0WJWOqc@!ZM0cT+B-$<@7?t z$tA!acrWESBVblE0!)KNBRDw6$T^);pIp73ouP_A{xi(9Gj10&4g-3_M98DtS9wRn zfJa4t%O<$ch!+EroD}Gd76em7ak>bgb|XY;#iVyDV9NxI-G^I%!#uL&R}RmlYqjyK zCqyb-psg3a;U7NYk13kIrFhTn*GC*uLwL6p!!3ZjVsirxtN#Qj6n#|`f=w3<=?o3h zk3_Q@?z3xdwR3|DxQY#IyX)^|w^Q!7-@`tHJHOlYE#w0~=mYQfzVGWpJ`BM^e3+Mv+g^HgEZVe@uI`Q7ko4H!ojb@ z!h^r&zQZ?!gW?)L@>^~@e1kfu|MG4D4BWsLr2q5xKS00}IFMjLg9i~NRJf2~Lx&F` zMwB>_VnvG=F=o`bkz+@XA3=r`Ig(^alO0>6l#qvIOP4QU#*{geW=)t9*yPl?lV?w# zKY<1ns#5~ap+}J>Rmw&}N~ceuMwL2M>dKlnhGf;cmH+G3Cy$&(!=p8Y9h-SBMN_+0 zS)sEsTdj>&tQa%4m);hW8;#kdvyY<5jdEpX%#>Zu zoEdXxWyNZOQZ{;YvCni-rv`Oa*SBxoxLLEN7IW#;H6zO`ddo+t(8sq9nQ+WP zYL)4}w4eVa?lQBBW;R`BvP-~dU}^6q?^*(7oChI{Fv3(=Vg<203h9r(|Bma>!w*3W zQN$5REYZXhQA|8wo7I`RC56@;QG%yb)oSR~On8S5#GH)m4+^83c+#VO6M{ zX2xk|opqXNrWb1V!So@0lwhP)fhzT69Y}JRr&D?oFovRcf(ap8;n^d-2Uz-+lS**WZ5u4p`ukod2@wNe_)$O5uf%DvIHUAqL9ID=DtHDx0wC zDyt_n-YSkswi=2 zH#IA|v&)bMjV3=}G0o}Jpe}}$w`y?>HrZ$+Ewx*4!x`piYI$kr#BNdR5yu+QS;0Kw zn(OSuf^Nx=Mjoj^wUvKUG>#jZ{79RVJE#1R%)r;_SW zxakH>%DT}7$uhtIr5MCb2c7ZJW&fIZDlNC{@=Jp5xd)!?2RbuN7QP`z1w6G;;tV*m zslgO!@NA!(Z5)v1PWRo^lOP~iqQitVw4h6iG&(>BmHAugbSFN}yhTrmR^9^qUAQ-}c(s6Ym$aA4=?6$7L}taq%V z5-2dh3XJiNa>xJx2Jk=|!Z9mt}LFkutIXvBrMLjyttKmvAAK!LEM2A&XzHUg1A zA11_rGL)l7thg#HYLSax1plKL$!JD2s!@d4h(ZAjpo37vi;%&B0;b-vjRKVM1ArLh zq257_UNl1+=n!MGn&A(Eu+fbbfa45RI0I{8YK5a9hb>x|sds?O7~UdCJ4#W20yIDe zqcBLTprMBlb_ySBAj2s&0)t(=D}>l|;y1w=PH~QtoaHpcMOmd!(;p1_TF+=4E*fCo38un)qtsvVdxfEijP4@ekb53aoIbD>+=c*wy4 zop44jOi`%lZkM~=^=@>5u_zAWBZK9I)DZlk4tH?i4A%I?DAaLTb@0&>oa$~2QeP{w8JVLsS&BZ2$vZaZjk0X;b57nV4egE5@p=lTH*9ro~t zKkNtM8W*|mP%d+wt6>$d__=RTBmd*+AdtpZC72A~ z(8d_dwc;I{0yf{6Rb}bxs{HO3zbwwMixnB;8Q1v6Io@%Pe;ni~Z=(TQK*lsC5y$R& z(z4f3fHcJ63JUDO%5`>DGpOM$YTP-!l_j!~k=$U*CU_6poi7VpHRZ|@Q@fQdZVb9H zjZfeax&?f0HOZjpI$IVV?Lx*4QoLzVkDAn_Hub4dooZFDn$@j#^{ZhWYgx~l*0r|v zt#O@eUH|X;xdtWduYvs%JCxxGJFvkBTu@Mh&EyF{=nBUas<9s6uP}bl1%lq1m`f6?;{yEW^o8~pQ`OR^jbDi&;=PF_vFj4`Gf|Ks!ih*oYBx}9P0>fKO zuWV*h0Dv`pqYRlT!)30{3;+bLwAxsM1SSXwZj^%tLc{?#h9Lt9tiTlF_(TT^@BnK> z0{@dRkY6iYQ6$zm`6TXhz@b&z53o_#~KR2V_FE2 z(xX-cJPKirOBCZ0)+hu#6oFtRm_du0=X?S+-vB3=Ljh^LMv%X+01jXe@~a#;;0`S9 z9j*cHY(*Wm!337c3%;%b5U?GvK?&B*7}UWVln9R&umEgj)4)I+9-$r@fdowu1^-X5 z9=bsCC@+D^;qo$%`>anMh|l=KVT2^eTxg*L-T|3#03JB70Pu(%qCf&pPt!zA3^qWK z-XK~kE55Xg7BE1)Mi2Sefd#Su#Rw(91MXmpT(1F;z{FgE_n4@%c5D}< z@Ernh0NEi4+$aZ#DIV590}9{+(m?HC;29K<0pW1`?r0aN&-zY{37rrM6AhH8&41wSQALPIZcF*{vVID59032W!EKmj_;E_hH9q#N| znqd}JNfzYK3*P|@oxz&kAs&=q59%QaQa}SP01(0f`?O^coZuZ+u@%jM1OGZ;?ci|4 zUZ7RjVFvbq`o16sgCPSP5CVHI9K=Bmga`tZaK*L&25tZbw8<3Q5gxao(NL`&-*F!G zu^xG?AN}zk0Wu&3av%w^APw>$5i%haav@L6*Lv z7^k8xp(eZIsaldHI*ug@;V_u8DVeem7H%;P3l!dlB_pat>>w&zB5sBwC%w`uS%DQO z0T(tQ=3c@qk1{RQaxK}iE#2}h)sku4>YdQCCMNPJl8&-0YaYCXFaMtoO#lEh5RV+v zz%|^!FkM3exXye^ix?sSwz6Rc?f^}&VFtc{7{=fRoS_ah^BA~+7?=SYXut`?Arc&5 z6^H>Dguwxj!5RQB@CL6{=s*j);2Yk-54vD9y1)<8f$_9}4q8PI+n`$7VHR#65u5;- z9sn6ClMKqC0zyFnA%KlyVD1nozKV+kE{wRWp&PP63xfp-xIq>U;0~&x4o<)UFTlny zFFd(H8q}dXvq1*7F!{u*yqNF2_J{_w$(58-H80>4=!+amVFi$37%m_b^w92#K^kPC z1jr%OSgfmt!y4!SFQUN@E`biLAr%zi5kJH1umn#KOG!{0!~qQAOE`(sIFa)|g&{!O!5Y5dJIP=h?|>YlK^^c52+8G1tw9{d z;0UZ!&`3>H0)PSD;2zd77)wzSk*~N)0Que_!H`QF65#>t^ai4#OhdsO9AFgIK^j77 zJtOm)TICH9RUKqOM#VuI_$U-)g;I@yTJAs`>VP$~K?yQ#RPFQyAglz=0UeZ68YI;o zMU7AW6i}mUx}1Pee-IN6wNokJQY?#&AXQS&)H}hm4*x!>vaSJvED!|DK=lAY8+Mcw zk$@bmAsmoYNtv|Nav>7XH40v$3vjp<1xNtxn)8bZIh&JQ#L-8&0UGEN(`1FzvpwnZwYB4ff1 zGG=2kQe(;@u(DD_k}_x&<7rt!D+fzzbyP>oq^A3PiQ~%Y6GGyTaqJbOSY%`HSwqoNDaG$PGl@Mwz_EbFt#Ar3%+8~_DS$N?1MfE++;$c9lCNT8QWAqS|1{vZqkND&H@3lCS% z9D5+NI*Yjr(I9YpU|{%;))AqUa{2tV-|Eo*goRmH*!gYt8OJ}AB5K^x!z1Xf@d zsD;k(K@H5nU-zJN=Rpt2;9%iUgnE$F{D3atVISzi8uno>iXmF)Lc|i43*spR6xDk% z0DD7-{{->>!XX%1v140h8KUU21Y#K`phq(x9pWJhw(t#?q4Kr?fr6n5F-0BJL4X6* z!MZ>kw4olVL4!GXgT+A~ssRfMMHu%W82?Iuk49m1qxT)A*9`J&b*beW-vLg2P);8> zz7F;j=D~HZan#5`kv4z|glu*{0fExNQ-5$426)K0K$$==6u4I%NYM$rfdUI9SaRST zfH1%4D4uel9rU+**?|JOmzbg#9vV0t$bnlXMS=x59jdH!+o6R^?T1$-h==&OX3vO` zxHy-1m;yApaA6d%bSGZLBs z5+FfcBS9PxtcjIL1V#bV>~#&yARlyT6iX3>1J)D=!IFn5Tomwsi>m-60079abk*T> z(;*y(xqy-B1qL?LNUhUMp%Xgc4*&Q7nxR=9VfNIR*_rR)nWLExOyOjE_M5>uoW*&Z z$+?`(`JB<2)qb{Y*|{)wfMSR?Cd!}(k~X1QpbOeLpY?g4`MIC{`JVwgpapuM3EJo= zCT%ZE7raHG|B@Tp_8Sg!AIM=J?%^EnL8AAeZWr?m%I6NoPPMS120WS@lF5l3U^8fv9_!HtxOh(?SAB)GEH;q8hd2ZH4pQCJK% z<@w@}RUhCxq1phPz+Xp!?El0X3SKLYYITz_j6zA~Lh~RnHZ&SM6huAu39VEC#)8YTlK^!We^3}^V6@{4 zu)E7jJy;v!;kG$g99mEvqF1PiIvips3+vhm&N{0tFbWRf3=BwNZCD&PP^_hzw)IOI zRwV$CVHL7ywlC}VY=yGj0RgU2xu|-v!;+dxM-DxPVXF{daSE@flNU*z5yQG zjc%ee9!s3&;9(*0X@+7 zYn=)z(&o(6xdN2DD zX4y7;;P!G=9Z)p-ZW&WDxgjz~A#c&-Z(nm7>Y#81Hvvq+84&kXO^Y(NAput0aVaA< zp{o|?q86Y_9sihdTMU2AOP$aml$$b~h9nV*ct&dkfzg@=Y0Rf1C8!HPQ=!+eO(Xyg=hIiv#Fvw(UVOFT22rd0>Zy zhl61PIyRVzdA=m`9PszsRZJZ?3=6sd3p&i_fgb38Uc?SfTb9cVYBhRid*02xP})KD zM&W^bw-kc#hSh4IY>cLXZA-!|Z>XGyg(&3F0-nR=r3PtVf!+z}LOZChiiP8Ssfk>@` zaSfoL?WcIyM0ek{s+rJ37jD2wY;iDEx+b&4b~tM)&LHE+Ld~| z3&(w{4Y&&l4VLe^kA4?Z#)u41^}qcZ6LKukF8*}Sf$E9bz+K+n>rBSr0UbgB8P*(T zCH&N^{~gdF#ik6-1-<;u|NPNE{ndZ{+26Ye{nOua2oU{Z&LS(F4bpqy*zg(t`M>`G zB9Fj<1PdBGh%lkTg$x@ydDDMq~e2{b5BR^PZu__mMSzJE-cHvJ}nTQ_Y=&QQI>EgOYV zRJQA+bXT*>>tAnH)w`&PjIfH~lTqFmpfSJNpK~Gt3eEa(S>-QTgp+I%jDpagk zp<23xs$)lCS2%1af!wSI$ik9&CvVV*9PjF>xe?78GI;OQsjJ6DL?>szOl?ar zY8|8;p`ARg;R)Tg2jQ+==)_G~xOIb|q@md zfHC?gvBx{+C?L%{rQiTrl-FGPUx44(=N^2420Cb=hbD^UJB&ICsidP&YX2#wfL=pE z8^~zG1R3Id8fu#4>?ThlF@#g$HN!C-R-q&LB>ZQ%pDKI^m52(!k@50^zvU z4kj;9sg7oxd6s7e=jf?UI<%A^449e+EUfnd3;zOT9hDek1CH5> z7|4$tpa73@$PXRZ7-I!K12l}uu>m)L7uC`RKlxou9aEBv1PTyD5I&ND>`+4Urm&n( zSdW2A+S5A*Sil2hXz(@fIFPA0BJmjFi>CsB(%&J^6Aw!WY&&h$>W&-AmnS3xQlwgfq6mH zTGvQv%8NP1m8)#!D`Pp!0kvZoQ7C``JkTq4#Bi6^T0{W~Fak21gHAPcjl8_&8euj7 z2G5Ac8jh#Kcl1$&pCMay(qWBr#07mK*RcJ%0HED~A?oWz6zgdm<_+Y$_ru?rYbY-(z&&QjBPNW4jPs#LA2 zRj-QGtZH?uTkeTEE&l|-DOUv#+*U}P7Q&i3f=gTr**3cD zg|0FRk&1V)q7V^Ut!}f{j^N_SrVfJ{jE-9-*SW>r@N$z| z+jp=AxIqcpE!BtIZ%O;*e2w*UU*2I|4 ze2($N(o5(>D|*q4ZnUEx4e3ZrdeW4xwEv|qjpQIY%)TCZ3U{CEg zI=Eo4ghREfUk&S6%X-$duC=Xijq6U}ma@Nj_=uczJLKwqX|H|!c_HNshcE+?KilK<;raRr4 zK6HfTE$VHro74_AcZo$!Z$=ZB$M^QMzXL95K~MV7ohAny&_E8_?)%I8ruTpO4Q3rj z4dIbiIL1E?@{o&sB*%RC~3ZGi-Cj`N)BeCIsxxzB$N z^q>oU=tM8N(T|Swq$_>tOmDi=pZ^Z^s7rn7RIj?#ua5PsYklin@4DB&4)(B%ee7f} zyV=i<_Oz>g?QCy*)@x2!oCF)Ov{Ogj9a|K>008LDp0?lr?swHzJGM$bFTW=aYK|8< z+@iijF)s1)lrui^lm|27D^F_0Te=p+2(adJd*%m!UgYB)G{fs1dd#bS^{j8b>t7H1 z*vo$Qw6A>3H}VHg9OD?w00u4`k%vw|;|~J~gfmEy2R&4S6q1{{S!*rd3b>F5e_#s3SA56k2YN6K%-4L*mpahbfL-W?UkHX_D28K5 zhGl4mXNZOh$bV_bhHdDEZwQBRD2H=MhuZgmf)jx~F=Knkhv{&E8wiMjcv^zdhlOZ} zhlq%YsECFbG!?dpj|hp8D2bCuiIr%HmuQK+#ao!jiJj<)pSXt|28yHDiNHl?n@EbO zsEVt|iZf6kKNRH)bj^~Ju>8OtD$d2pB zfBx5w@hFe;NRRbskM~%8cW4uNI0B3Khk^)@07;0>NRS0-kOzs73F(YMrjQNkkPiuw z-H--apap5r4G@Wu8L5#Q$&nrDksk??At{m&35^yp2T@3T1%ZUn0FHKGe5Bw9mM{&# z7mnh{YWRqgIjNI7$&)?llVG@pKPi+$Nt8utlsu`Au2WdC6d>Am}dBnfk~K!X_$wJnCX|4G{KKe36+nzfl`T6xDinxQG0qxq3)NfB(B3j`4ez(5L6_zRBEeB79P)$om3h?k@@j)|$8yUClq z>67CyR zp5ZB;<4K<7X`bhap6RKc>&c$&>7MTipYbW5^GToeX`lCrpZTeu`^lgE>7V}zpaCkN z14^I;YX6`Iil7OqpbKi9ra2KO$&v%XjegJx*(eY$d3?!tg|>N{qm!G)38En?q9aP8 z_s0iUa0?}>qASXxEh>M=8F#SL6Wpl`z|alKhNC&EqdUr@J?f)Bs-xWi49f6Z3~HoD zilj-Zq)W=AP3oji3Z+phrBh0!RcfVIilteqrCZ9SSn8k=;Ri7}jgo_*Fe#I@iG;K{ zn^@SPrSqXK3a4=@r*nFkwJ?};il=$1ry>fY%DJ8CpbWae3WG|hg=(mWil~XIsEf*| zjmiqTK%`wNsgp{nm1?P%im92Zshi5Fo$9Hd3aX(hs-rreUn&uO;1;+r36mg`$j6q% z0RIY?unNkMnt5OetjVEm3OaAPr@iW{zY45#c&EWiti@`qJK3j8IisY?tj+4I&kC*4 zDy`E>t<`F+*NUy#s;%4Vou&#A*JugFzzoq)46o@{sLBkzSF3eNn{TPBp~I`kDzEcO zuk{Ll!)mYjs;~P>hRG^-v2zXqE3gAgumx+d2aB)?tFQ~punp_54-2soE3p$xu@!5v z7mKkOtFar)u^sEN9}BV}E3zX?vL$P>CyTNvtFkN0vMuYfFAK9VE3-38vo&k8H;c15 ztFt@HvmEQK5@DO}`mS&lul#DXM~k$^imyq_v`y=@@aL~GIs&&qwN-1iSBte-tN*oI z%e7tWwOl!aVxiTOSg4vw|9%Td8@a3%eQ^& zw|@(`fh)L!OSpw=xQC0liL1Da%eal}xR3j`KRdLwR9&yw3~0(JQ^vOTE==z1NGq*{i+V%e~#}y}m2ClRImb`?=+7 zzUPaN{FkEW%f9VPub~?|${@es;6HLJsY{3_d!5OT<8_dBS?7<%l!XYfM5lq4*Y{Dmu!YMq! z;VZteM!xO~!!azwXt=pEY{NIqqVU@jD$K(@?883{#6c{?Lrla)oWdfE#7V5gOU%Sg z?8HwD#ZfH9Q*5zDY{gfM#aV2>EZoAc_QE&}#$hbR__wrUY{qA7m^wTHTFl06?8a{l z$8jvjDclOFpa_j{$9as$dz=cbFuzm`$bl@#gG|VUY{-X<$ce18bIiz%%*J)B$C1p( zek{LS+{LK&#b~U_o6O1ESH_(T%AuT-YV63RY|5vM%Bif%2;2&~u>TLQ49l?`%eO$u zifqfbjLW&K%e&0Wz3j^|yUM{V%nIDfvTV$-Ov{x#6Rmd1yq3wL49(Ge!=Eh8)ojh= zNXqle0;|N$-8>#HFwEgB&f`qZPk9fsK~zX0$G6|D+{AO;yN2yM^@ zeBjXlV8XwE24CO|`E1fBjnXMSzz%W``_R%a?b0xP5BJar?QG9Cjng@;(>u-6Jw4AV z4b-R1(k@NZFD=tFt;{yp5vV#1pdbpGkO~ED&^D=7(Ff62jsMk5+t69f)m{C660Hmr ztqQN83Sl4!VsO@hzy}@82Otf=t}rkq?Z1751jP{4ca7J1J01JIR z(>1LOK8@Ikt=Nmr*p2PjHfzFtbOU-#*#peig#FinJ=lb8*Z_SHF3AkJppDx22bREl ztoekd%?!kFmw_Oz(clbjDG;U2d#s(SQ+*Q8?A5!?+i<$oy$#&KjecM))~cWis2~P! zAP8@u)_kDW1z^9<5DDYaJVMY0%pkwRPy>Kq*Zs>3&_Dx6fZdf%-sNrHS632-~G+l3JeJZ0RISbtqjm010j$LORxpweclaD zzv(>>>)qb(9pCd^-<`e8OMMKl374JF)S_?+j*zCJFbS)mrZP$5mJr%@FybXno41YI zB%#~FP2)A*o4;-2Ij-aR2zUHQzW^}S#*GTft=ycT2OixC&|Sa4PzM*#2$MhvF$4q0 zpbP~5zu15RF<|8m&gEV11d_ z29PShw~z+g#pl&k2Df0p!XN?SJ-@PG0B5k}UvA!EF6Lxz=4h_wVvgZT-4TIc7Px?X zb2*KwnW26V2+9DH-uQ&V=jomP=`b1NDly|b&j0GIUX(cQ>apJ2#BJQvpbC_*+{45iEFHtn-;XYcop@A!zyuG_-NaA_ZIKP(P35_;1~Q}rrts}3U*O@5-LkL%fB+3}PyiBeFX*ny>Q1`s z?(Xm|?~~5V8{r2fjtsA9msuzyj@$<{)t6yDx-sewHzsDfm2f*FT zp!ql83kw5^ZaO^@g?T|nhk#GQQKnaMj3ZOswb6onRd-|!r z`mLYTOV9Lk8QR|XmR2YViU1Ib6#o@+WXDpqf_XYYE2L+dD1ieL=Al^8;zf)ZHE!hC z(c?#uAw`ZPnX$!5lqn^^V%gH=OPDcb&ZJq>=1rVAb?)TZ)8|j1L4^(_TGZ%Kq)C-7 zW!lu~Q>am;PPNI04^^yLwQl9w)$3QVVa1LmTh^z9lxa`0V9P>9iWDQ1%~b|~nytIJ z-Uxc*3{WRNojMtyOV`;T2dkLPB~~ZFDq#)IWJ?0$7+qpx9yoK>IDsi_D3BCWcKMjI zLk^BbIsk}SWI)0qAaPdM_HEp`b?@fg+xKta!G#YeUflR`)idTEUYJuhHCd;l+<9U;o~`c(v)(uV>%h{d@TF<PSqP#hw##NFs|=F1qQeyDq!!y8BKUlq4t#BtQB< zCYL~%vBjc5oY}G>JMz#2Av^5ogcwJ<{F0(Dr*!j8IOCLaPLkML$t*nc)N@Zh`}Ffq zKm!$YP_e8c^iV_-Rdi8C8+G(in$TjeEw|v3i!K0E!ONCk1aT${Vpb6hFc5BY#z)2G z>hZD2&T!_F0z8<*6#r+c(X2KW7XTy|6)!_23JD^RATew@Kw=t5602s70zL@jG9#mv zc3Ntywf0(Uvy~P}>7pqE3}uQbql{?YQAfHbDOC472-|h{U3lY_cV2qywfA0p^VN4> ze*5)Ty>$bwkgg3o>~O;igDlLmRfw@-Gi6d7v5o>NE&zZA0FgK|EGPhEm=0du+1HHrptxYB_stw%d05ZMfrxNz(NweJifQ z3b+d|V&3T6FaJ~cKxQyg5lc1VBsPmo56*HyLxT$dsYVWnS!^w|(LxkKlTF5Oz!X~_ za5w~JIJ1S>6%JQxG+<=4KUe}tUXq#wOZST~9i$+B z=)^Ay5x|W~sse z058yh#{Vz+(w9*PMsS3&&8ZTz7-vLcHqL03GmcTZVTh(N515NHAVC1oXy6FPsG=7W z;|y0cAPh5bRTrHh3tf@se{-Z`9qo8WIyRzq>EL4@{n*C?f=7Dmf?gpFc}PSiQjv>f zWFsB<$OH{?T^4%6CFW8Fgn4KPX~>N>xF7;ll}=*0Y9q9$*Z??ut`rWiLI_C2jKx5M z2@t>)9&On=J*wl6yX0dap>z@{*{n@$!bq7i(k5f(AxtF12s2aoOlU^aO)K1CHLZC~ zY-UrNfU4m(z4=XWhEtqE>0x?)h&Q^}pkf-Rm;@wXu>yd=00nSC;Rry9Mi2s6FenBY zCI6!hJOpABl_&rbY;^!HPy!7S7*UEuu!<~-AQPML(b2NOgbq9=Vsp?L99nZrkcL#G zBPA(t^oS0Wrc|XWRR{1SIUz{KRHiefX-#cfoO`rk=mMLjjx22AirZuH4r5P}# z`Bu2bRjyZ~<~Z$oSG?v`uQKfBUj6!4zy_9VcF0Kg3vGmOs`paN}xmRW6kTmRhV zR$HJzsk+c{4p0b^r|i;cagBRiZ{UjPSKzypR# zUkQ9*1SeR*Ng-@n44a!v3}FP29l;Ya@tegowu{n*C1b`w%hJHIHnjv2ZiG<*K)A8Q z?qzX{UHszTv;r0ZgGDQZ`&{xgSI0Z%agTlcV;~2)KR7mzb82%8Q?hq1r0K9>oa_uJ zmacRphH;f~BV!udxW4!0ZqaEF7NP|Ml${=!ignVgCXIj&n z=5(i(S84JfTGV({^rKB3=}9LL%&TT~t4AW{Hpg1lv!->U(p+m?=UUe+d^1YoT$p0m zUiXItCb=61Key&h|ehuY&NsjA=l z2Tq70nI(*1E{6HcK)Bo0U553p?R{^2=Q}C4)_1@C{ck??dM$0a+hK8&Y}fgj+zV%T z!&MgU@O)e16Q_8^Eq-xELi`*K=lC4WEzLe0BNuciNtZ|wlAl3Cn*S;HgVCVjOpq{o z-gI5hodAAwoaa2>{MLETeg5;K2)qTq?s(CSespPT9OFx8defc$bf_ap<4C8v%04cq zJ}Bmb6TwK<PtxNZ?USjpXV|H!)Kz7ULL zi5RJvgeG7ycH)=B?Mowx(MDMJIo%!b+vk4wU)Xo=hhO};7XLiKEp>~3q+k8(XMg+M z|9<$#U;gu_fBo%$fBffP|NG~E|LNZi{|i6?96$mrKm$BL1nj?CFg@05KnHw42#mnw zsyzy@?(pF zL%#&`0INNZ0GcHwgqCT)PsK zw>|*I8-&F?FgcbBlMb>)=xfPa1$i?$5^9q%DH>pG6R-0FJD8PR2)XNv$2P1vek@C~Jji^ zwu~Ep+(Q98h8Q>kWQc*fJcfbXKYwtAFNi;X$OSzx$oXRjFW3daj7Y>x%=lwS#cWK+ ze9QuzNNdwb%B)PwyiCjlNzL3$&g@L{5Xm?3gLH&KM-V<^>V&BAIw91OS+NEfgh3g+ z#Wr!ttQ;n^1CpUkxr;zbj5w2m*g|M96ErE4xx30Tc@|p;lb>P2DKyQNREFfty16)p z+{{X4BFSigK`&G}ODHc<_&u@AgL!OA^8YN)dsIvFOi%T6l(#%T0i?@2n1V0pgfEx^ zK&VUo>xV%gfx~RSenmN$b3-#V@wF0PztS3^^;6c z!%Pj`P!8=-)$>dc4N(!jM9>V)mSl!pn1d@JIfd{b(+oajAcaN%#)wdaH8i=|yv3{w z&WbP^Vt@z@>PdxW^8f&wsr3fKa0 z(9aCOQ}z4L0Hr?y^#lRcQ$96-5B~rJLR~*|K!8(FKX(uU1GP|1eLo4^R8RfXhQv_Y z^H5SPRZ~4xPa9DRA;a})RabpgSdCR#omE<`Ra?DPT+P*6t+V(d4_4JxU=3DbZB<^4 zIJeT8D!G!B96pz;5~&nI?V5vzSwk+7%@nLj-_%N2w1caB$%^ecW- zTBU{1ragxeB?+9-8J_VH93+NI$l8;8(K8%5R)oe+roRuuqAf`FTs>y@y z#0A6MgrdoWM+j32>R0jn*MkjR(akl29bMBs-JeLqrg8y_seozAlnBF`E*?qVM@2Z7QkN_tT*+kHvTc`vL$bt0JhE*trPvC&@ z)!y`bWC)mt!>k7`z<_c22bl!~YmkP0fM5Bo2Q_d2OUMN)P=IH+ zhh-purl|x?=4A@_0{hv810F;IzGiLSW{G6L2mWSo4rg(Omk2fwR!CuVPG@yq=M-jz z@;GO9j%RgtXR19`I(fG$R?!dC$%}|P>SL4WQznWaA!aHQWU6A|J7~J|=YbBwi}(Y8 zE+&Jn2$)Nzpq%KObS8!t%QwDbkN#+DqGOOA>4VKBzOTl71Vu*2QDaqd-&c`Q0D&})bE{z1bBv|U1c@MfqPKpf52&-UcdiT z0C1pXC@@H39@I&t+3bzqf4BxpHAs7)fvjGJq}~Vpgn)avh6C_wZvMk;j%&Ks<^+DO zan5VK-fO=0k8*zJpbqSP5NyI8Y{M>W#6E1rPHe_rY{zbF$bM|ej%>=_2YMb4R;X;v zo@~zE?8v6)s>M1}*k{j`6XPrGtm$ZyUTxNvn=7z{){bpCHtCZF=0xq=yUe1pVaCvJT*X*oK)M+4N)XQ$Su|i2x1IX{gQz8pwhEtm>;yf~@|B zd;b_}aOi6F6Xx)?YJ+@aphjz@-iKLu0C1>>F*txGFwDA6z`4F}{pQ)b9u93*Yj?(kJpZP^ZS5&xRk z9&r;lSlZTOm6pGKID$K<(^0w8_u~gHn1G;8KXZs*p0)=NP;TgU?&YRbb1;A{Kn5ML z?gBkbRvzAefaL(i>h$x6Sx{z~^=e`Ehf;v=^j3os@ZF>aZ(2a_zZ?StaDu4a@B7Pd zG+*;g?QfnMa5#^1IcMMk$LxE!b3D&;J>TJ(w)QSvs00u&^Z!f?Vps%CUT*I)axTzm zcK`t-2#58sz zEdYj9IP}`TedD+Nd-(Wsp#0-EepqgN0MK>bZ+_~p{?AYT73Q)M@&io}g^mAKdGJpm zmY;d@FMpzNkN|+FaAw~=f39W} zDB$7Fy?^~&p-3ojU%yWj814I~(c!Qe8Vq~@bT6a6Bpzfaypz$Nu!t8t(YvUz9vlq~ ze(ch?EWxvX`)EA?w=JRp9icWNO{#P$)22?JLX9eQ>c(zVuVT%rbt~7dUcZ73yY$w% zvS!bsO{>;yi?(jx!i_6;F5S9z@8Zp?cQ4<*e*XdvEO;>C!iEncPONw_yZ)oIX#Q!Y3LZh-%r$J+J0oyKE5N^W0iLGcklPwP199OS1u+F zj5#kae?ITKog*Wc?9ANDF-sxpo0%W7@>p{QdnVtbx8o4 zh8uF&p@$!W7@~+Hl31dNC!(05iYv0%qKhxW7^93c(paO7H{zJ1jyv+$qmMrVN#Yfj z1X-k!MmI(yh#;0lTuo# zrI%uwsivE9+NoTMf@&5z?OcPvDCx9AO9H!)gU&V!FjCGE8WeC7tLTt}O%xJTuthlJ zxB~(bYO%uGJIgFU25a!Nvy1^|%)<^Ev|bQOFb&vXQxnF_qg?{V3T zXh}5DFyjm^3;xjwG=5AN2r;DC!L!p(Lmjo$Q|pJ}lvn>_owe3mbKSMqUxOXC*ia5R zw%KQ+ownL*v)#7aAy!!zmRWAurJ;9!RT30<^W8U~fBGG`;DZwmD59aF=BeU~Gv2u4 zk3$~0NJyKxs4m}2Jp$jbGTq`>&DE$6TFy9Ur0yE4=b5HQ>&_KpK$Bsr! zC;7;L#J(}@G4DI;Tn`Ns4`d&F@auF^_#a zT;?`&xjzCjkb)c}Aq#29Ln1PflIbI;N)?KBoTDT!I7d9>KmyQFU=QtRhdVUjgmpmT zcjS-?_fs~Uf@7@yyG46ID~Ry!U%P|LmksI#wNFs$!2}4k|l6pw;X7^ zOu}-P4x~;{&Or<1KdJ!b#tR0t7_G&f(39`-6~hR z$`n2_GA)W6D_P5G*0Z8Dt!iCsTEm)}%@N>{QQ2D*193XJ5EUOb+S_QTM8PH{DVTp|;pdbPoFl9W((7@Nq51y<*Zt&_^ z7Q;TYgW^w4?+oS~Wy52_urC568$w z(^@LhAzs1}EL9MKj`532OhOb$6yhU9!P5gHIKc+;sZ$&5;0HrE!V>lxQYUQT3u8FL z8g>y>#xkBUjbprG)Hw1qn7qR_I@gZJ z?lm4<@GBQWz)@x>qkyV`Wi0=N96iwvub}8-vNB^^SQE#q>{T#kmIMGFt-p2LEL zUi6|xwkkD$7840D1)U4X!h*)qk=3nhI3UgFPais>6OCFYw1EgeG{O?jIH}Q)hS6N) z;k^2_1Th?;hiZ^iKP{~&BJ!}rKV%eX3LZAG5zOEXBRkp3UN*CdTH$6xJKEBob{0Dv zmk-+w#oFGs;7ZKxZ-cu}D!y@z%Wdv+qdVQ|UN^f9b7RiH^^s+%Bne6}fzNs4m*k*q z4rci+MJ+d$>Y!h11>XNG1GqNdjA+NecRBEDzzWOwkV6L49Ozt9*0oqx2QJh3fJm6K z%+fpuD3ycDi*tE+BnXEr50Sr;to-7CRfaN?NI+w{SQS%b;XVai>(TO@vA%qMb|s$Q}pmz(BVa)RIh@S82*e5v!UWJFF2%#lNWcf&fj_h( zI6j~^%HY(L+TAgc4(5R$=wQ>F7p#p zTswSDSy<&c=vb?8BJq9SS)N=wpo3VV11)}5E}jF!wc}}=B|5AnSf)c;o@F{@-1pgK zT|$yxmc{txl3$A7`R(Od$|b7kB`(#a_~j*J4jlcVidfCKrDl3&VwQzo zejj4iUpp9PVj|{gEaqpj=2>#)&gdh0^#=|Hp(*47BG^HK90L*t!VtZeMYR-yFvI^Z zxYs58K_)yxs;$~WMr3nBUB;NQ#DU2ftw8JM< z!AWX`J8-}rAO$~gK`<7;-XJCCwd6mzgAmXpRmh|#Qx zhd%M#X}r$;lMJ0z4?95{^=am4=GysFG@_nrek|=vs)wAb`XjsHIriT&pmWi6&{S z#%NiH!yK5#Y1k?{n1j6pBf<@7uM(?`E~&>1Yq2WpvZm;l2zOoRVv~n(MN$>A9-wx|XY)(y5``gF2z7M*QbJaLyi1Tu}N$ z!7K!ru)`WiKm#m61F+{t-~$)LfSBw9CI$t=)JhZdgh3!g0enCsz=8iLK8!}-!^{|f z2pol{4$hz412!l@tsucY93>|93VQBq6v*O2psb_*!^YB#$2NsNtU(79zy+KF!?wdA zRDjD?z!#vWJaFs>j6z1FpSV2BQv75F5X4SAgT&H`2b_UM93|D=13#=m69@wWoPwl+ zthh<&shaKCqHWr$?Tn>rRh|avyn|Vc<%+RFS+=br-q<=2Dxn^OG^oSfB2GF0o!tWN z-3l&~Dp(;j!mfpD<2tTH(nW@_>*P{yA3HULJHgacSB9Ar{^a={63$Cz*qAP|Eo{Dc2E+=4Q!&I>riAvi!W z{K6P0;4KUT3cLVCKtcjof;PwjPmFEg{7L%Vz}^9`EwL^E_^$Lh0YO|t^R`Fy?x*xp zuk~WDf>OX10K+PPL+}1>KO6%8+=BGwfJ0oL9@NkQFv6tLz!yY=HOwng{A5tFE>GaE z3;lvCF=vSV_=b$hP zcg9+(Fj}Z^49hT8(lFvCn9oduDD>Uq3h@wEP2_Iw5hHODTM_0eaT7c7;dSnnd~W3# zN_Yk%*hcC<*aHn<0SB1DKZsNR?t_rwz(17AgYH90ZUq0J2BQMh@B6|@cv?rKrm>&; z111E8dhP*1*u#2?EeD6ipCA-c9HrD!#2`Sx7!Mgi0IK>rsvh&PAH(ke`-IfeYa&2x zLCgYAs3#c^#Be|@r8dRWMy&&5GC{=4Kg5I}C;@IHg*kxj9|JO2fGQ)A@GawVF6;6x zKSmDUEi)8@FAMW9qeU?=Ls|ecF-xd1^Dq%R^D`gVxIXbTQ*$*N2@_j$HfytlMKRrg z7~h1a3q^x6AOkpLvAqHS1KR^`1r`a!s~c;CdSZmZ7MU|#&z@ScPh>;RHo$P1v+3?b zAMf!`G}bocRzk?Vzz>)LK@>9f?!*5q1jQB)=sz@a8at{%A9O+|1*Yb6 z7XQPmoPtSfgg?weV+p8JEO045108QPJ%B&~xG|e(uq-QdSJZMJ@$ydtbx;fSP%E>9 zDuXU$Oj0ZLQZsc^JM~jTbyQ3BR8#fE=)y6p#Zg!FR&#Y%Up0%38Z?XbSUZt4Z}VBB zby}MUHmh}8yLB0L^Az_@cm{<6n{Me!K<8+&oNkBrbz66-7Ik)O_jYr4cYj`aku`w$fhLH;w}$t5Ux*RE^?I}Sdb4$V!*_hM zOL~m<5@&HpfREYHZX7L?!@@#3W8sKF5fwWQ#x723wao2Gu zYy<462`q=Lg%3(}BhGaT`H&NNkprT4BYBc5`I39yv*y$vJVJWyRNJ9T zLn-|;fC@B0Bu7j`0{`d&E&zf~`}kG-Nj+!+GE74xbWUmi!)d$mP$Ca7pn?XJvG9e1 zO&asrC<8OlSJV7pF3GS$)ybPw zxS}%!qryGWt0A07#TklI`2q@>w23UwJ>3^dv4hIe6Mo?v{^3gs)GPktGk)qx{j?JZ zLF(EuAcIZW!W^tZM-3+{)RZ%bX%ME=mEzqhAcN=!!j?uunC74H{dJ(-6$$lKtoFT56LY5^pAxH zBmVVcfA(vCVKjdCd;j+*4tP&ZAWQ>7DuXR7(W@zfBKU!P{Q?moLouYnBUnO1PH87h z11P-LN(B*q0feJGmYj*2WQiFxKYuz^Gq}nbsXPoFPFhvX5kq1I6;XVM(M}$bBT1Gt zc@kwxl`C1cbougS3z;)%N`Q3}XHK0vdG_@A6KGJOLx~nOdK76=rAwJMb@~))RH;*` zR<(K+YgVmWxpws$bil2zW672^dlqe4wQJe7b^8`>QVBHa%4Bhug^Cm@M%?=M7jR&~ zg9#Tld>CDPZ){<5k8FCw-2$tBmhX4&Hs)T#yLtEat-Ee;;lqg+H+~#>a^=gJH+TLVdUWa2saLmt9eZ}|+qrl5 z{vCXH@#D#tH-CQnZ}schw|D;@eth}!>DRY^AAf%Ryk|;)>5?IZ{OIHtKl11!A_EUR zCKo&Gu!Io@Is0F2t=6^DIBTA zJYI}Z!T)sJk;fi=go!wt;u@03B8@x}$t0CrlF25WY-@lgrJRz=Dy_T{%Ph47YA)jN z%4@H_Y#aZR%reb96U{R%lMJA86w^$FGnCU#J^d8aP(>XTzy5wa2|-c}48+7d+DI@( zQyR2G4~!O~kX92z8Zg2@jsYeWfgX%dBwuX_(7-ul^+OLj>8vxCJUUTGq-N`623iMC z-Im*Ky(KBgEyW#|+;Yu57u|H#jcR~e)_oV=c;%g!-g)i={rwl|irN%X8p{9j2|&PBopF;)*T47~_mJ-k9T#J^r}SPj4BSh4_X8VjL7eD%7W>!1;C}!4L9l5narAO*S8wda3pz8mi%qs*J{zWx3i z@VoI9PTw&5eHih?6Ah4j)*KOObd zRbQR;)?I%c_SI8~o%Y&oza977RlkMjZZ~YC5k(qVCBi0s8@KUVoAj|(%L zh(bTs?qd}Wl@6)I6U(N)Lg`7e1KDCR9RKa~)lWa}z}~zaRhn_22*h zslkIQoL`X>-~b7jnt~M&feBP#U?yiM&^-`>5tQHrDOf=ZUa*3qgN*Jt*g+5CZgw9O z;Rs2{LEg#4Ki+DQf-J-gTPUj-VFY{=>BKZdaS4d1Dif1XgeF$x2ZG?@ z5mYNs`6d)JhD;+BkGO;=a;TvlMsbSk)8ZDn)js}x5sYCJ;~4R_H!_|PjcHV)y8Krc z0E%gW*!TfB7zQwQ^x+wkVTTuXQO5=T>wy1g%^+LzM?)S`Pz~G<1{v8%M?Mmgk(A^l zC8@#3ln|4d%pE9xal2ojq704D-7g4{2@#@V4w^J!@3y6p5p@k3g$P73nBo77To^BD z)gT4=W<)-OFoPJXngc?jp$uFIgdn;o<}W1ly$yxr50+3yG;Fz$?`cSy)C?LIx!Fx1 z4M#|86z4d}Sx$3y#eU~h=Q`Qh&a1SME^j;>0{5|u1mv+{^-O>gb<@3tz9mXP=F(xE*E2H zz!o~03sI_076rHfCtx=W8B`z;ojjc|G;n~NV)S+=Y(WaSrLB_qfrTOg5r~u;5~jjr zdq*9Kfz~#XU5O+|C&{Wex!P55fzzE~73)~Z8b&jg6|HGiD>>mw6M6ss>mIVuKmiKS z03D2C9*walJ{xw8eGY~lXwXape$dCl_|p@9OsJU#TF}C{Lk1QAjX#DFg#uLI3x7fk zWF`BTazsG_4QK*i4Z~T~d^WVBUF>RQqe%Tw6t=OI?QCgVTia^PqK!f6B4$9>1_;5F zK*dE$3$Oyz@e}|sFkK`HaDX-(qPaf}sZNKx2oub;0$$(*bxlW705sur!_WW#R`82R z0KfqvEgeY<00Zu_E~W-xDe7_|2LOnm6~e8ZP>I^jr<$ayE-@mpyjoxbzs-wlRq%ot z++Z!G)4>sz@PzHw)|tH3U;ZeC16BcyTts03j8N=g^hw%)>68DTf$;_iJP-(2kfIC# zJ?uY6%-Y&CmN*6-OgUztfed`c94n26D>~qW8uQr4pUDReV1Nv0$RGp>+i{P7ypJU} z`N>hPv5mQ07}w_KwqX|Yn8{pbGoN`lxn)dutuRREzBiM<7z26fJLj3Ubj}X=BpT+x z3OJV#q`7GGAU#0S)BS?ICoSDCeo+Z6nDV^og|jRGK!EMSE*FdN!X{Gp3s-2M0d4rR zes{;p1N-P|jtKCnS>5XYB$&dnmi4S@ZI!du8rQkj^^z=X7rg8Xj)T(h12k(78W@=$ zaG0wH?f@9nHsA*H*sDLTaezJiLmsXe><0jf4bT>V*#G}PZ3VVKM}ElR1fanO7jp0q zb}V7AKS=RCynWdy?6Xbv-~zFwTn}XvmY@4TENJ`85O=}j~)D$(P*HUSk;=s*D^VBB0N z`?5{wq$_5y^#XVxl_@Qad^_36Pb9q!q~obce?e(WBO2@#5Iau|5O?OfH>L}a?(0JM z3#1$12bB2wcvp~$T&%(D9-xF201yEQNWcT8ocjNHOQYQN&bhpgH~R-Z&2~X2_tT;N zbZZ2k3nsL8)TBloe_ib(qt+hxxlakKcins6|DM7S2LAAgU;K9#2g8H9M=AKd4p|&P z#Qwm=F^CZf0+`$#AXvdFaM6hpdxHaH_(wlV;ap(2f&;Kw1_1y;3{(6g``br_3`hWu zbEo?s`e64z=)r+65M%x@;4|m}1Ylql1P$K+V;dS^4;ZE%)W88OLC_T783c~T9xwtY zumabw{oZfp9OL1HBjWy|A0mMS+M(s@i2y=jAM}9lehU?@F%?grNg=ku?bM3}G?$WY2VHPxp$^ z7>`j$c+dEjkr|uujBd>tqfr{C5f*x_1(HutG%O8W0|(w@VeEke_CUiFfQ|seo>0LA zaPS}O0R*7nFP2RG?&&Z50Tak^AMXEQ8z_Jg?hiEhVgKksAKk>BjG-SOf!OW=#ZY4( zg5l)^;~Gj1G>i=g2ks$HAtI0MA7ai3K~OLVD#rw48yw&n=<(wCArcy(3zVS#+=MVf zawJpGAC`dwgkTLEz!((EB}wu#Vsa*H@+LPDC;u2}zy4gnwmBvBYyhZv7B5Q1gZkkK`bQ5mUGHfNJIJ9H zgJT5sK?%f9C-4zxe1qA^CX7lm0r_Ni!nBJQ&0z$P@e=E z3l&ilb)9(g*9_-hhV4)GLBsBe77n0UumJ?jAU*SB84e&q#qS@^vpS6}9`Okum=iTf zRUYJ^Iq~x!1M(k8?iBJtY1Wfv%Pn z02DwPN&y1E;U4565yEXSlyzBIg95kVJ!A4cuQgk>^%=O;yi*@EYv_43bUE9@N z-xXdnhAIDo9J2qgFu<@9Uz9XQ@w;$=E9p`Y&yEx5^1K@02@X~ZydV`Q4H2!N5or;1 z5N*yr01YM05a*P+4EA83zzbM`3>zQ{8UPInU$KERsAqHqRTu<&kcTB`1&99B zYI8486;*4umTSG@HoF#V!&ZM7^)7(zL;(d-=dm88;Seqk9_jHuYtaG9`Kdw|bXx+!g`mk2m?N6P3;2MO{uFB({K(c(@n*)@^=3b zr+!v2IhfQu_*7IRS`GvmoVI)N6npB#8JLMij)56~p%@5^g&VrST-b&qTA~&8YbV;G zFPdC%*lZtFuF~+g&fqiRVG+hF0z4qG_95X6UQAJT(*}@ukoV!UF6#(1 zs~@y&GnkG4VAUL`)3erqt||Zq$`LT`Asf(Ot{UJ2Sg_y-YZplH6KvPtLaVU;Vvs|* zaRS35A+9iV65A?auvBZw+)xFTCexoC|CI~ zPznyrt^s)9OnYlHR3PrqFne*KeRb;V%&r3FAQg7>^xW&~>{qnjYnWY>eM$e*f*(5# zBbzQ4@t4udG$#?At*fZLAh>XGF$3GTiogr|vH-xV(KMs$Uesi}`3o8CypEJbHDCb* zAxS-2OF>Oal{R(s`A4?KK=gnZ4$wwAAwuS0Md;u{aG?=60U4ktdYIuCEl!fzijW9NGWI*M6vMwk1HylI!WG=EJ%z6~oWncZ!^6z44Wo5>yDb%1bpSSE!H{(5 z@`7D<(Nrh)+O8^R+{IP=nqj;uTRdVJjmKa7&sLVRxl6N4$Hc3$Vo(2Dxlf0=ePlpz zs1tHQM4X3fuqRqfIMq5N4?+Ya&YR1*D81tw%)>m^Dq76T+|12lzIFJZ{2>=s;TV22 zZZX`(0;x>);Ti%rGVVNbp!i{=>#DGRm(Lf7&J~6-eEruO&d=k6(34%+mz~)^#?V*v(xbh0)T`4pDHp(? z5m0=TDj`m#UCB-DRE%at^dM@Qs79!K)T>38u%|+7L_}5{-rfJ^%WIw9>phGt;R?jU z-uIo~i{jSL){vyE*tsm&2j1WV=Gft**%zMS8{Xj^<=GG3SOrGlj}Y8XWkP;Ix^IYh zR87=t#6qTFX&T}~sJ2hz9pz7D-us>9Ti$Q*-Q{Cm=Ko#dYkpt~-sW@OOcMS*9^U7F z9_WMKIwD@@2LtDe9x;~O_ADV9L_T?l#z4^BgllD&d}SjnBGpq~>v?45W!~$*K3?$M zUBI5~X`SYg9_<+`?bqHmc-}pP9`55_?&p3ci2k7Vh^_?fb{u>|HTAM?Zf?D_wm^C@HRJ0J87!|mIH?n~eF zPhZ*XKA;fmAH1OgaurQJzw`aRM^^3jvV5tmsx?&@@_Qd{T0QfFU-+{`?1$g@Eqe1q zU-|iS`I|p6MxQ-UU;3w?`te%zV`EaMngkPJ0xCW-`~e!)K;g*k8ORgoJq6hMN3y~>fFh*r_Y~2g9;r= zw5ZXeAtfwanvjK47AjJt7;)>L)vH*uYTe4UtJnXpV8e?2cdy#6dt=k8UCXwu+qYc1 z!JSLDuHCzM^Xh$j>zv=efCCF2{FkZW!-x|rUd*_$}deXu`gIbp6SaAc7MtR87LsTj1&6 zZ{W1C%C)+!!Iocj5*W)`{d)H8`?SF+u;5hm^XP9WlyI=U`}gqU%b!obzWw|7^XuPl zKXF5(00t=FfCLt3;DHDxsNjM_@o~j13`Qv7gcMe2;e{AxXpvHhJq49iRH3((Z2**5 zA_>r)$B!HZ0AN4`TWrS_KWdyH;*B`wc-8-O{tOd^1P%PK%T?tlQGf?`q^RSPOg8Bx zUVX(TY6wp8u#wbbGbSq*o z&pzzX-~?8oj#}!e{H)Q0FbJID>65f-rCvhp@u%yqy!PtrufPUdkbfE$YwWSeCadhS z%r|?r2qyZRqmu1ajI#0}QZ4a=`x{`6jIJ!XiegW}0V4Eb+t?S8Vac7-y{U#vFI7 z<-=-*o1<+HWFrF-`}A{&Z~Z`$fF;_VFjtA zl>S2x2Vb}gue^3mmk$k40JmZWDNbGWKUX_yPI(ODdut213TyV+Xs50A+5!=)?b~q2 zE%)4X*BxNAcIU14-hB5>H@Am*3!=z4wy85#`mE7G0T-O&C!it->W?ck6i~nijldy+ z0Wiqh;|vlYsieB~I%f_CW?1@Xp!=+7Vxpgio@Cgx(>5Je`_MA8Ke`j$wY{|mFZ}Qh zgB+X3$S1G-^2|5y{PWO9FTMY1#!pH3jUMn+4BZ z)z2V@XLaX!WO!)B!DxF;K0Qs+b94W_qfMz zCbb1%tO6W0yIIb5b_fR);}>Hvz!7dS3>3WJH_NC%8=PUVN?nCUrBj*#QWr#=>1;(I zh=w)7v5#vsV2V{#pc>tBJFDD-9agAUKjgqZ=k#ukc+6wIidQ|tOz)3?45T0jNytJP z@{on>V{EP`qU`Z50n-1dgKxHBxk?rQ3je4F8c+~{4iMlJ>+{r#ARs6CF$Zb&OB&bI zP=W-qWjgi%LH~F|%B#e3mj5f|KfWd_JvMAT_4&sG)z*h&WKe?y`9mk5;lXA)^O+!g zp){vS&1zbcZYjK`Hn+*mZZa!|OqpSbmP8^G#fpAeIbZrhiONA?LTB~hLJpjxE*xM5 zA6&3eJG8Ne3k=CB>NEzufU}Qy&Xa3gu%|B<8W*E!05?R72N#~`oMmXol?=_OM){&h z*dX$wAPuQVM@rI?nzW=HeGMbglf8f7V+<>h3gNX_tg61felb$@qK&?{Q%VPAZ!fRtYrjZLP#7kWi-N!Q0 zcUsii_O@B!V@eBi(%$;^x4;dqaED9W%PtfdG?;OTyL;2ujD!${Z3v znUa>1%I=cZRJ9!osN{fw-%RaPS0t}_O@$Teh8MSB$tr!WGR*eqff?0s#6Xl8jkC(f z4t+qzSPlQ8%(c4pzzF6QT>Hx420Qq{EW`>r1*tq;g-;t> zNAjg^AHi_IGX#c&o8pv=SHWi(p&^41$SK4l7Ofnz7|So@^u_OmZ@$`i75-6mvQQJU zl9#O8;}-YHP>!;cr%dH4W9+zsNiJ;+SIT=VqW~;}!~y#C3q7o|r$1Gnb+yuuNEqM; zmZ(K8yzq=gAwfAwqlX0G+}ev?4(QnKF0w>&K+tZEJ95MS3eQ==!qe3^P)ktL0%JLp}3{?R4P4KHW zdAC+hxWX6C@P<45;fTR@`IDE{O>2#sj3+>THvAP%1hyB(klJu6l%_*&#UpRClkAeJD8 zCGy*9wJtN*_r=8{KAk~jPD2!zu*6pZe2ia+LKABBLxJt85h5|1FZ+~+r=OGCU2DSJ^0}%H5-Y@jvDTTQ3 zhfn9^M9MsBoXUL!K04R5M7kC6%fClJneRqHgxPT1U z5`)(Q)rNT3b`^>BaUnNy-&Q`kqhdQZ43!fBE0APZ1RW9uFczpOBbP~Va47$c(jziZ z03euT+BalYfe(wI0h%HtXt592@Fy2AJ2M!B#G`z?g?vVMguN97YOn@Mpax6e0!SEz zQW!Br=ob`6aEYZC*e8Uv!F}<86;DSH?FS8h5Os>M3cpZ>?-zdpVF&g{3VJXNqyRzt z2W*|d4AH<0cqoT!r%cXZb^#cO2sVHXScryrh}D#Uh`5N1*oY4pfeZ6|U15FHcNGaF ziI!+S>BNNzGaUohe3i(FqNp&y*HKe=il_)kN@xhI*ov*F1Wf1xP?(CeSc|7oh39aE z`<8`yv4x{}7hVV-oYo!%<_CRH47cD6q>u+umwwDZ3c<#9a%g{!5N!VemO-6R4T`Xh z+gNqX1VMqY3e13O-zSLXs5XSyi0ZhG>TaYF>2t71lfvepailQkP5kwmVt}9$d78Fj}X}w!T26l5rze!YXV^j$Uug9K#jT< zY|4~hY?udSbyk)jhZ%WwcF>X^DTn2Fjxs4M=_rpjd6PI9A@7)zJlT_bMUPHlcn>*| zM42NJS(HeLBc-TF4B3=U*(Gbh3sNbShQJH1$OTx5khA!dT-lWh;gCuBDOSM@x=@y8 zd6s3#3}ML?73m&Z^&Yy`l6}Am%lMJi0F9R53|g0$UDpZIkP82gpa}v7V5U$FqA&@X zu#6)~3VpB%kMIbqKy@=YnQw&{|KXFEnVFh76g#<@p81(A1e6~_Lu*-@OLCN^nVNO6 zlzrrtuKAjy;R01Tm9%M^*li>nUS(~((1YDp7T!4@U8lk87 zo2cav#6VQaB?~hn7QzV@$*G*oi6872jqed`(%FUu5uN`nSwYgdq9^K}Fd8iInV&RT zqnT-+HkzY4YApL{j{*9lZ-JUXI;6QZpb~ndNV*WRsi0G72o2hxO27iUnWR+ua1=T+ ziI*2sV+NjrPbN|#3&49=;SaMAre85rE61T$@u6P9rm7jDF&d|GnjbT|qjq|yh=`+j zx~F_vAU#T&wDAtW0Aoaok3w3gM9P}gQ>Bb*pf)g@Ov(#V(4bPFm5q9-3wNbBVndo& z7hCEn{xA*ZQVh_*1RR(ZrP2WyaBh>B79IK(Zkn2KI;XT+tM5^#eVVJfig$d#2M>`7 zz{(BLa0|q`tHye)J@Kc9rx(#c1!ABMYB4!qP#gcbpa-?Z4qkvRYcx4kaB13isE7)r zifTNVTCQG+ppj~oPpX?NV6N^OWtw^;TsAp|awKQ4OWb1>oo3 zP%0&|MO)EkjRUH|@BrIz09M2sx$zJ7Fau5?TQhSH*kB|Lpj}$=s%_ezvudj(Te7%{ ztSFnZ4A!d-kqUJ1vUH#fGFuEPTeCKc63RN1YC#MeAO>im7VkrE3A<)s0V!Zn7C_S# zNc*$V5mZG9uHhP>;|enGTD1Y`0*{)mlKP~UYPDYbTk+aR*G5D=^9xm!4@q!P^b=1j zU{+F4UOeM7yC5)MAV!@^7S|A_v!V}5KnDN#pav9WDQPPYg8(oX`wUZa1I|DUrqEFT z5UX1OxurR>C0n_3da^g0xtd!|EDH-R3$wPS3^cpBq+7Zbk+XZT3O$Qa{oo^j0wX&! z2vEfpPAh$KP5+$P#d-WIkgY-wbF}< zOB$(8>Y%zgrPI5;h!nOgm3X{?HT$q_Ip7bFKuUlXFV{d@Wkh1n@u^%v5ADXZSaA(A zQ$`8!PcuaUXwWznH8YDs28p(&9xAe$HXqKpD}JB}qCldS`@p_}xu!e86wEihDlIN+ z2QM4Cqg%lqoVlo*7d-2;zzYeM#|i(bfE=+av}{JSwi_u|AyFO>2(>^8TL2ED)fG7m z7s4R{E5He?Pzf3^v9&vq&Fj1%YNXt|#Kh+UHDCz6zzea!q?4)!2WbQC%EVesNZvbG zW6Mr7@vhfo0Mb+~QzW~pZ{Alns^ zyOxwI5N~N8^jD7iXJGsF2>J!Vj(i^y{K1ku$=1@jpR2(#E4q}t$;TSPVAu+<&EAd&I{)P zkq`^Lpw8u4wOPz$nay*Fb_`4#wIrl`O6jV z@K9eGKjbC>we$}br5pYr9un}zA4|ZnYQVUnRS7H*?e~5fR94_=L04B00antFywdRz z$(;PsFpVLW46}5=!7+W)cIwGjK@M)v1wP#cZa@xW;S8w!4H!iu5sei=`x|Do1-T~y zr@|X!b_+s$P})!~pMW|_bGuf7wxndtau7yiv=8EN3(D{=FW^*S9S-=gW58i=IRJ1M z00_Ut0wh)*j45Nkl@a}&j{s?TmsrVmgGwUoD31W*OtR9WE-T0J7yh78g0+QN`DEdv22Gf#(W ziFxZ;S@FkQ5y)XV$aye~?a>L@K%y?`z$@vI1kne-Mh7hY+_!3(I6d9eeJqv?28)me zct8xW01ebIVbvYp@u|~0-P1rV)LucQcV%q<8_OB=6&46(w)IAqxip z!w?zHgFU(AoZ0^-{#)qm&Qk2ykc|nHUD=m?;xaxln_Y3>yJn-c&;}sD<0}Oppa-iq z3isf&A%+W~K!Rh?GsOT5z)%cCqpwVGP*7ek+fV_Xa1Yn;;SxPF^&ptj5D7Y$(T`ie zAbP;vC)@_%evUBGvj$+}d25c4Rx-;B!0>;(=Gy*uLA|Do$PL{O?9$>L=z{JOoeK(e zaOjZW3sp%CgWl+vN#5lh)L(HAVt~qmaLQpozg;2UizjGH4Q|je#!frNCno_BpaD-b z;CT%Vngatk47lc#4T{qML;T=bG+GA5TvGJpY$gXuZ57KPZ-=lsuFSk6j>LrxF*CmG zCY9m_$%_Av4GAx9+00(;5>w-P(b+hz;P11cR?)A!8`UmcB$^_?Rg6%&v0@I4h78)k1gXx|>EsRVmcvs61F&`oU!>qpRXP*y9P5Az zOmHx){muK**DQAkA7BLuz$Zq0?9Q9)Q)2CC|4}TE&a7yahL8l0?c$V8?P*{4V1n)V z0*e14qW25V;9xNwWQmr7ua^BzHd+PnAdP+l0bsx8hA?TDq_B1X!9YI05T8NCRMK&X z@fpw38=vx=-}xH>@`&yW?o17!?D?kOfGfWiL~ZF~L1=nw6<@;$Ie*{4;otjRM|?dq z;-(ubQuL**72Ea#ggd)8&j`Ok3pz7zu$)WvCQp_a4{E@|6sQ4lJ^hKIG8PaINiHLT zP4?kx_EKW^;vYzBKgF&H_r8z_(;nmF-~OtB_W&y5rU~3&SdIcu5N>`}0*?p~1d;&J z37Vfgb4=y((+62DIt2Tya)!$h!8{c$Uc{JD<3^4hJ$?ikQshXIB{jA{nNp<$SS?+? zgc(!+=1iJ3ZQjJ0Q|C^eJ$?QJ8dT^|qD74!MVeIUQl?FvK7|@p>Qt&W`S588s?JtS z$uMCOR#og+vSrPlMVnUbTDEQ7zO5-i~jYKNw~l4yaWRF z3yuLZ{$?G}^UD-F8ZeGIgY*ELKU%(rv;Re@aOpJn^tu;$IKi z04Fi`p7rLlEho+rONuYXIAe`BMvy@$KbDY5kw+%EWRp)uIc1fTjB!R9ZN$-+M0)fQ z$dzx#IcJ@B=DFt;K?XWXj)x}NFN=#t`rZoBWsJ8!-BhH6t-wBjlm!ENEYaKjHr zJaNSrhw0S|W6f(XDGS_Zo@WEp_42=T^^0@QH&={v{X`dCFwFrg{h!nS?|XLjq+ieP zXxL|`y>{FG@i=IpedfJ)-+u=_c;V-2*+v=-Q6tA4d;D>D=bwi@dg*c2J?P1A$6i3$ zv*%vFrCVq^q<^4}nix?gd1Mkt)TBcp^Cwwl8ae3%`yf9IGXD}s0ud$sRi=hp00lTe z0&YZZj6+}o6}UhKHqe2V@*Cjl(3QcF>VX%;UDlwcFka zRk%VH1}1magVOY5I71rN(1tr}SubL-Lqp_9W;C1LsI%;5HxEZC{?*iR<@EvnuL-PFXo8puQiZC+|Wz*U-lNn7qR@0i-G@u<7xlL|%)0^MSqu(6SDGDZI zRNzEsI@P((yD^e3j--_^8jps#Y~A z?j+t_A{WnmcGas_`f6Ckx}b<|@}Xx%Ygz-^GJ_rzl{QmrT;)1fk(E_K6V=i^#Gwmd zNCptVD8@5xDWHAOLILy%3_sKm0>Bod7~vS~f$X`B1^m^q$Y@<;?-QS30*11dEe2*a zt3sU0@gdBJMlmFkOro~dwLvwiRb@L{+Sc});(TfaZM$3E_I90ERS7)tI#%M|)1Jje zt|j+rSGqRWxz8P*DBEgEATAWT*TrsjJ7m`g4cAKlnY#u8PT`mFbf5qg_yT?Ou?F*A z;1v5PN5al~gl8pd1`?RoJqml#j`{^3T!=yD_A#&ao`M}wD1ZS(u#3^!CxyHs19Ze2 z7%|+ivM88 z60qf%N~E9w`BfdlG*E#m&?g^r7)65(R9ZP6vm(@dZIq=v$JqMT%2&p6mXp#7E^|2* zUrq%m#0&~Bf4R$CPKr|lM@TKV+0Ae6V1|TyyLSKsvdP6WfsUJJKCf`OWz}w=1wCjZ zNw=*CJ7};1$kahO&}l#$ zoDqowFybDxZ~!u*Aq~KM^aS_N@3ZK^fh`mR)a!tSGN56F{%Q|(+9+{;Df?di`lZ4h z_67&`kPjtTryg7&buQ!+nn3`k7U@y3UzWX(X6qvfFepYX1cr-a5F-)<81JsX01Q`X z-~;EW1HAtcn1E86g1jq#sB@2kjQ$~2g6>gF$!`a~vhqyY=+=?=fdCZrV1f#5;8cz76fahgD>3muZMj_ z8t!u1*WUJYn|Q@74hoO=-uJ%;e(*cK`&3+o6RZd%$_aOS<~QH@O@Vn`v>L+N5n}^l zsMdb?F^CKxHb52bCD2*ubMcoSc0%VT)YZR!?HbykOII}ew_))I@!JB%nu zAOaeA4XwL6HOMfp<0x>j2O9YQl?5b$!aB9U_^%LfhBlIheGoto3zrD!0DT(}EU^a- zxB!;|ugYp8W`HaKjE`1BmQoO@1zdnrST?`7Fq!&`&te8;Fu}?D3w)@A`|5y<0=!Zn zyno1tB!GgnTfhQPDb10GNGO1Co08Uxy(y$Z*P6ZO!@?}oLZrw&Fxx%h1H&*B!!Zm) zKDYu(xCBDTtz;O6O8~i$JF_j6!#T9Q=xYI)gPm2lzQG!pkOBY_XopWIvH@AV@bin0 z3aODYzu7sOe&D|ZBNtt<2N2k__K1WKT*OS=67+*5`t!t3Y$*3DrKM{+P&CC;yczpz z5d8Zt{rd-VkPg;hf&lFQ7XRXc6Yz_#Q;tbQ0&cK|UkrzPI6$;hgA>Rc&FiqMlLOL- z23g=hV`~roYk(gZg&LeNzz{%skN^oNyTC&RU*ra9fQN0kMt+cjaI3n%&_Sf9Dm%o(q_IBivyZ^LG{>qyxf=|3*gO|o ztj2mQnAAinu^4=S1jk^7RDc5s2(Zhe0W%1VOAG~^%*my^4^Gr1RD{Z?45g$yw6~JV ztHeqpQN?p$MJv(&zkLXX1Yi$-kONvwM$zb~jS4$1$gsp{9mBFI!1ym*#Kv0uhsjF} zbGSxm%tdXeu@9gYSNsdDyEYuy1`6nMIoL$bNb4 zJNTA0kbnkQf(9_efB3He>zsYCI|(QNwNMTO9*eVju5@#@sZ_uoPIV@ar znCsmC2eO2Ka0tt|TZRf~gT872Z!tFqI1e~L%v!reSWOJ=1O#F*g?|u-TTlj6;Ewh< z1P3UFUl;=eID%Uk1{8P=E=>SS&;~gWOA3Y3LsSC@u$;fRwqu#ZGq^-g5L9v{SEodx z5VhBPJ(&&lA^3wUeD&9V9nqq3MSQ`Q^KzC8Ocn&I02vrU`_h*cV2^&$011HD9lS*f zYf*MsgLheh@NiOR6w zeTWAxz=41GO7N>SHBh@{7+2647{YrP7WJ0OP>z-Lygi6lp2LzNd=0=5jl)X72v|&c z6-{BkE zQ~*`#Ro_Kb+f(J3dk_P|5CrH9gY3JHfni2vKn8Hg+wA_G$q2;9ps-+-HHyZ4h8Z9NoXjTpF+r&P@c*1%W5ffCcN|6vmIz ztsdBQ;TIkeeRV75=~o!G;ZKxZ6{?3o5F^ic%n~9$6~-N=ecmEA;yj4n^;P0Uwcgnj zv+{-FD3)S~v{X#}%~F7>O`YN`2E+43-?CleFs8lsr9O_?hr%$74IqaG>r4@T59^cw zeM`Vzv<6=chj}Ok1BQ*vqsbtxJO}m*%`^^YI0WU$Tg=-uuyg=$xQ5E&25_Ve6~+?9 zf`HSxw)b#Qc3=Vr*f}Bgg1jv zR$=Bn;#^M6Bo^adroAS{UfSg1VJ7Bc4!*Aa+O5E1!5Lp;cIJrmRFMN?U#4cNB4f5~ z+cc(I{czRleB5ie08^-g2>^#*YD>#gOnBY5VYOJg{0l&S#m#fT3V!1ROysa!DG>PK zPsWn$TmbPTujpt{O7yTXIJ{3r=ui%tRc2@yUfuVz%7&KcMr&n+E?JAN4_wyejiy3g zuI7)fDo1@(VSeV4HtCb*xbIEoI#}jp&|;K^>D=_1h`1%H|uKMpXr|6S;#-c#`y zH)i*41roP$shDs2=5XS=?j0Z91CJpH7jpS~ZU-OoBmXA}-;!5Dsq@M^U12Gg@~C25 zBH5{jF*t6&Xu`7-jB@Bd$FM1X5C$0#(7^DHw!<-WX@DbGJ$d455QlT20_+>7bEhzI z7?<%p*K-+P?B8_k!P)abPiz{m^Fp_Y9QSb_@9{*RR|`e*M>o16?-59+^r%zC%svp7 z6jQRk9Ns2Nr`~Wa@5cf-?z%%TE(Z)jMh0k*fe_IDu+8{|Iw+XGV2%iAyTDxmQ@{o$ zn2&jS^Ee0gYMOIHCw7^*b3sS;WJmV%zG4^81Z9VI6esjz7i>gl^a5Y>YbQ`3f09b~ z_CaHC4mI*`C-)mtaxLjh1qH%dJTRk$ShBpRvYStUvCm#nm@`mUIQT&kV2=+AvAER9 z8U#~0IBt8Wfi1{m(*z8?9IxyYOR~fO%W2tMyaorrhFUa-wmZ=m^mPvp_K%ly5vO)y zKlW%h`IA?67H@XJQE!xYc|o7{k)K*?*LJ+l_L|R0Zg-M$=lSQ7bROyXpr4*|&yoW6 zzW=)2XCup8pN3ADRXGTOXs`yzYSw3s)_$1()>ZfgR`Zs6Py+|xgj(>?Ys3V>HvByKnNc#s!-VHbIsr{`NUWJ zlV9vg=#)PC+dkLn;?1W;$yF+9Y(hG(1-+35#@Cmq95cv@cu4iJJh0FTQf zXzQ$Gd{6_>kjV~9z!+GLXsbkF`t`vF|F#)+%cn!cpZxPj|Cc{+Fc<`7cJ}m#|M;(b z@^>@L=X_7b5@yha{pbJw2MArdnEfmNXz(DygbEijZ0PVI#E23nQmkn4BF2ih&T;JM z@gvBP9b1qrY4Rk>lqy%UZ0YhP%$PD~(yVFoCeEBXck=A%^C!@tLRYeg6w4RVq)5jw zWjgdJ)TmOYQmtzBD%Px1MRM)x@m5BR{z@qTXV4#}vh*l0@^?+b2R&x_$vLsF;J$2Y zIyBJm09?OB7WVDqr{={yvStg81yJB|fd!}ThE>=NA>9&`@zN^0xnRFYA{4=C;AEdW z5N1Fpf&lK?U(^&l{qr|WhGPi^_Ehfe+u*H|67mo)Zu~g%VLOZ~i?0`t<78vv2SIJ^c9c=hLrm|33Ft`uC^mp9&O!0A4a6 zfdv|PAc6@hxFCZKI`|-j5lT2Ag%w(OA%+=hxFLrfIylJ{feg4v9VM2M42q(7xFU-! zy7(fDG0F&IfS~y2-+ry&wcc7daS%&^lF|a0<9N>%22XU!JLuH1ibnGtWgEeKgVvz4@r4j5_@^ z)KN=4HPt7%@MoY&4LU~EU3>jC*kL2e^rKKlI#yYXEn~oHnI2>h4N&|_0%hi~MHnrs z3U-&M`&=X0X4f45py{UH@`@R-pAGAou*4FUDP0&4R_bZ%SaZ2I6x@$=6GI7v z8$`|&FW?+H|NVP8v_kfAgd3obX#P7O0uy+VrIF1mVtXJ2BPhWMChBT{%9<~>M!^ko zu!9~1TLa_NJvJpK0jnT}DBxg#7(9+G{Sd`5l;H{vn86>kIDj60VG4Gb3RRHMTdVq} z4<^I~7_4~zhCZa=0X+aC7o$Mm{|@r2U>Rg_#e!Q7_F)bK903{77=r?yv5##SU<Y+86YqN61l*a@2vR+%?_tpA>wkRyaZ z9RP$ZW;44cZMO3x>-;QeLn~UTj1z+z94%^7t6B+mmMdwEl;Nrv%)7)kfQlnbZGWTx z(T7mxwwr>Yuy|WI%{C;bI|V9oldIf53U#c`eXdxM+8?EIwYt{5E_N9yJmNJBdD;Cg zc*AQkP<|Dx&^<4DdsJ4GoRxbE>B3rH*$_WG0g8%{r6LM4k0IDWA?@G;37~-6gII%p zFNlE|@Tb3h=z@MYF!26}D`9XwGaO&&L_wkn2!m8}!XEzcL^#`8j;yxCCO+|KOPjUR zqPWE_esP^f9Fo_9*l4@0G182?+#U0{$LnftdV?(FcuDs^`w}mbldR+=2Mm&zkR&Co ziXu!hxyn|)@{GKSqx}rI%U)jZN!rWGguu58g?NZH-U^H~3?UV<)PgO+Am3yEPT>TM zAk06=Aq_PaI0xXkhhJ@Wigws+5Br$k3zCK7MN8?K_qYKJ%tG0BaG24SzO;x(4C766 zy3epy7jb*xvreW~N(f>VXry;8X#%pv-CTg)|z7)0tzxc-g8t*w0 z`etII35#h+KUBe+Hq~ACmBIVov#)(U_WknSe^1~A6#4O!zx>tz9RPtyR3e8R+x+f- zKjCNY=E{FRy_s*p<`dF+E$!nSd?*0``qI+vL(|=bf=xy-7+Cu_mi5(J*8PJX9D&z; zT?1Ain~YsM9iIknU}_0pIW+|bhM)+JP4X?@GVMb!gwaDJ5wuXB1>W5qZJ!LzAnJ5q z{aIf4EfxIjAP@E+Qz71fR6_BrTr&8e5guXu%^bemAXy=a_MjEdWJ@P}K@7ML67Yt) z`59rf1Jx16`cxqfI6<+zprt+FLf{@5rlII0-#Lt+8@{19VU1}uMHIlH9p0f;u%QV` zNn-$j9|8c~WCRMT;6boMMe$P;AW;&uAe;1xO38o$xKu*_JYpoiR6#6*JozE$=pOdb zpeKGJcGw^jj+N~klK3GZDyE_;E)x0;2pCiq5w4;v&f?(7pLva@g${1v*?{2% zo&lp8GTN6ggFqZ3G9Du>4I?wIVe;W2G)Cjpc;KK!feT0@HfAGE=wZ%`g$We{I4T-O zpkM-w;Xhc42LwVbkir&#gFY-Gs~N;LG=Le^K^h^%Jl5kq4k9x|Lo|d#ZdF_-f+9f{ zq;rTOF3wIVCRNDMqC-9;MEVX8UV{470sBQHMrI_;P2T*`UqZ@5@fCt>c zrlerI6+~)~K`{QqJC49met;z!z<3)T)K^5$ePiyjbzD`)`S z1Y|;d$+Pf{9Av;|WG6#$Ct8GnG+3wA$z@&to+l{YC1bKj4(cFcz9)Rf=f41kkX-Pb2gvzO%x?P2`$yhkRDnx@aAOkpT zgJdwqEQFC_90Wd8!VE~jP_9O|{3c`nKm!~|K%~8BLBP#wBOb6QyJ0GM9>kZ} zgK8A%^O5S02I=$3gD_|S4uq<`nJ1La>fT8yu2Jci=Blpls)o>~eR3(U2CJ|x8-L!S z?3gJOW<&%mE3-Ch1OOMC=3aqD>w&r{+1x3%iYA?AE4P+ip2E|lFsY#KPg^QLI2>w0 z+`|p&K{Q|k4c$YE29P&^fD>3MaMFP5(Ejs>r(UXRz$(^}O5AJ|cN)aA80=@D z4W!zgtkNpPVw|mhT#lHcdk!ncW~|0O2>KO5A%H<0jDgAl>&BL>$tIg(>Ic0bYk*qB zK14tO#H`H9>;{|zwd!6mCZo>(4#dq)rnNFnw+5|CZmZB1ZK-{$nxGAnK4n3C=sXAx zZGgrg48}f`ilgG_LcHS(*sIm{!_-a=zIH0sZbKVU=0?3G=|rsD zX5Yk$Ob(tb-sY{|D#!r*q2Ctf-UhDV23xT%=6kU0n7J&>&g{%S>qVf0DeQsJ^sI#W zOqpCRI-nutlHt!jiqU>9G!iZ7j;@O#ZJNM}Ife!f?dIUzgFbM916YDCu!1qn!T|sR zGq~$&{0$&HA3JzKAOJ&avJKbb>pj>m?&@x*(jzROf((R!S7_HVx^1 za0rSn2#+vonJ$_rtxkRd3KYNx>;V)#R92osJS@UKMSus~89-s}KN#W)`{XnguNmya z4A<}t-@`IAfDLE>i_+0PRPXglFBwp;^&*5L3IhtX)JyH@%&62AOX5G2Llk7CKUE<6 zy001k6#TA-{Q55&x3T@=uO9-g8_zKvqild6Ze)_^JIup9yaPP+@gJXNwyi=HmH-Z1 zAz}1c!(xOkl)wxBs8L051N+3l`zOF9dCE%BK7)EB97F7HDn7@+;R{8K1E)^U=hvaUBmcF~2b!%W*L$voa$Y z9&<@CIK(|Do%@FNzp6LpO9(H8VmK zgN~?dD?D>V0DuJeZ3O&bLPYZb-oq-Kfc_}*KeU4$fFT)NiAh&M`{aP3{lhn$fz6zN z6Ih}muXIcQzw|$xgC#uJ3m^e)m|N0)w5We8Y$27Sf4d(mEa5RLq2E3vaMIzW^|8#yZrQ`@Fz2)V38~vo4hY zC0Ah(@53=vAz_`{E{9!(U08mYcvsp{Gb$87@8|YhKW?av;ccV*P z3$}RwkN2+XwI3EhA&|FvueZbyc3~fOVk(77>U;?t+Jp{rFtOh##pCjLaQw#N#>_arS-aNcRRkuYToPeP< zvY)Zuoz0KT9QV~Z8l*{D2vAycJ9qAZbyr+Bj+amYGh$)QyrKr-8?|{J?zqIC<`*20fbpLiJ!%3_mXdyfD8Yhp>acDBiLt{_R;;9p&P`1k$@9)!X3c-F8D(m zkocjYdAyMUyu&*-4`bGCUDxs3rCXqla|Ng$JUH$6XCgeq{Slzg8!AkY7jN&sJj!q!-$I^VZ3>^Z#Y2axuNfa zqT@E}N%cNVU{-$}?Nz#^4?NfvJU2Bw+fz`dFMQj_{Z%}Clw7DE2I4rzt3eo|MJ1xW zHez${Lkc)G3<2Sy^!EvrTzT`Xk%1=bg6Z@9Oe7ZvRW*k}-;t9KeCsC#>2_QfK04rO@jQJAfJxe8^?AvE@ z-@Rj1a)4`R3CD>OILLq_H|52tf5lEfnP;s;(0hDhnE7XoM9`%tPVIvV1>8S!oxYr@ zQo_tWYhQ50IDv$b&VAj^#E6l@(?7g&k%GHgV$VKqF6yC~JmS9R;YVvW&0CW;H_-@%6$Kc0Mf^XJj07eAYQ``08@W4>4F zLD`e?Dxom&VHD(ga5^wRglG7HLxTc5xZ|IFf>Gd^liUG;44q8UCy5aP{2-K)3Oq2u zlCX(Ff&wbo!oJWp`{%Qh_DP`tayW}m#u;h6B_j#)$Wg}~dF;{0AAt-~$RUX=(#Ru` zOj5}unM^V_2`Y+G$|rOx$M%*FTo5`%rVI<)66r`Of!%H0BF-q0Md+8 z&N=C<)6P5b%u~-j`RsEcLEZ@TqTD?CD5Q~0W633$WSS}erJn3UDbfWcU64XZb-E`~ z$n5I0BuxLgC!BlCs^WyYK4tM!PI+3@QoA(e39?sdtku@hQe;M#U3u+wS7vSvR@h;Q zEp|rM+)GwA^_Xqe*=M1RR@!N)Jx@C7uB)z;?YQ%<+Hb)PSKM*QEw?#k(S6TYll&<~ z0l{MJr<4Qq_yvvw82P6jH5}li7E8eK2bW`riG+Z#f=S>(lk!Od0&r%v5QbH98AIWJ z1SZ(vu$Cb}4`N)=fCLIbOR+O@o+zZGQ~-#>q!rhVxmFu7!m-Jlan4!ioq6ur=OUl< zQ|O_IF52j$kxp9arI~KJp*7!h)9Io^4gG|;XG8WgueK@tf*(%xJt z>a=g2m9%xLcmatRs)AVNyYWsf#k~3M+wZ?kLpEJ>%`M#U!x2wh@x?c~Hrwj5+past zDX-k}%P|jk@N~~Mw%s=oIK>?fCfo-fH8R-e8U#FX`%`;3D6GMSKgC9d2Ab&a9}9E( zhaL*{U=jAhmbqB<1@c8P#&;r+fSeXzd>QcRF{8N!n}5z;`|Y{!-g_W}-dg0i3*K#k}cl!L^+jqF1^N4=Pl11>Q@iZNU#Kn3D$Zwqwb z10guG%@Hnh6|~?5F_=MdIqq@WlAO0R7(x;Mj*x_uo1n4+NUU}_U=`6&1~S00jRiOb zW3zCOyH4~Ed{klv5(to15=J|AK?4pFfB`soR}y>BKr1`!;Sc{&yoD{XEy`0-Nk9RB zGO)~L(u<%2t%tqujggFHG~*d{6u$bck&SJ1;~U`^$2qkxYI3yW9r2h)JvyyxMtDR1 z1hKzO><=ORv(5j^_C;cCDuIf0UBtB;;VWBB!0nb&`~& zH03Fcb4mB4a9HiC&q-uR!+qE=95^(|J!nC%Xkdc_X1K@fBC`)~fWQe!{6{{Rh)a*{ z5(HY2q7s|gNXnS(Q!Z#z^t?z(zl9P1jotL-H^HeSHSUp|Lt`(AOb?aN>gV2rACZlz=>s=ihQR{@VTX^;BUjh59xymN3w{oT3 zR2m6-6%1eZ&<7VBURD0A{FZGA)Z)%|@{S zTYv>BWDtU~(1Ua(@x}-y^bc>;_9WCaNf}b`ypzBTuC_{QQ<0lo<@W5UU3Knrp&MQ4 zdg-cdn(lS6n_cPN?`xnSBv~n9R*j%lf$soDIHXxz_1vivYPa@aB2A00{wJ+oJ zsx5Af^1l7`?|*$W*w_@-Rv*pbKjiTV6cpeCdmxp*41}Ol#A6W$ihu{|Qjayn^dIa% z!-Dq%h<%*4EflsehVQYA2G~FYxOau z$VE2tk>y!kI3bzIO?Gns{k-IpbBpupzMDNam_lr57|i@$-V7nP*B_sxrCq)uD9(EHd->MnQJ; zqaQuwCr_Hvm9{k2lzeGTZ<^D6iZa;3L}iRv8F0kdfEXTp8GjH1fso7kPKv$}3gnP-}&*2$Jpk0BjxX)9IIowoM1v7K!$ zWm?U<2>qbA(FAFdDR}v`Oy( ziM~)4WK!M?I{nA!g2#?1Xutp~ct$+rAlsAB0|Yqm^FHXI0UYcu2~g127*yZ((^y^i zy&sm=FKKrF;SaxrV29kBiJyGsmj~_VP`mG^3H{SRTkh4jev|0lckOSV`*GBJ_rV|j zH+~gtpb$Ks2;Y%(Ki@K4Kzz2(5=)!FF&*ca9D+_(2VFAg7oJGCXg1_(2LzAXXw{ zrCy2uCzc^}ECdN4!9hOo25nFe`S96HFa`lJ5Tj)UTkwMf@emPFBWADf^BL{gf z5+yN5vJVL@@e(m{j@ZO~GO-gqF;B!zfA(kQ`lJch@9^G_GVVbP7_VzKAPiEiGW4y8 zj))zYh+T$3L?S=~Ucd~sq9hJ5cJARCB;W(|;J{3xALQU+P+|^GK_8?*0tg_b95MQ; z@fvaP4-;`4x$!v&(FMCP98Yi&*To-bfpz?Y3rGMNk7{rHK^SB}KsF>Y+(8CfYC%E- z^X%gt<52|Wu^txT@;u-SAcGy?pa2@+2owWja#0^~?d>KpA|R>2Sq8w&G1H3Xqj({12p#z+NRLF7*%yKB}Ar35|U>cw>d~N};feA36 zEX<*`qQMp9G7lFB5+$-RHBln=av;@W&-L_y380`HVv8M@QUsmy8iDWsgtGED zky9hS(GZifIg4#8jb$HtDtPjN338yrqM!f-WEbRN5GFt;jA8~0eKcAmhNE|Ua21v;U2Y#F&*;LkEras%2yF+oeTNXrZokcDtz6t;l_Xi^)vpchAU6>uRG z+T{S+pcsS!c=|yUjzJk*p_d>~0x?Dw3g8DU;TN7R>S!+~hRF#OQxAo6I32M#C&)Ra zG%A;qqNemp=L|ZHg&zjt0cy!X{$U+pK^dUI3hE<>U{3=|peFznI29=WMe;K>?(a17d@Pg(<6|F)feO-LNj(h2K0w6&p&XO|A<3X0Tmi&JU_D#)RU2SJ zObj7)AQbRn4dgBJP|rs(1{;>ZL;h_ilIWN4#Ysz|Nu8Asp>%Vwv|10bD!Ii5taV!f zOiPW$9zb9SDxffAWg7^<7=A}~B;Z}f@C6{_d!6llMF~@iDDpNcB_dZp#i!;3D)r;Yi3d@R^%#`Q!zIGV>PY1o&gG!#?NCZ+y7C0dyhW?^<(2Zvj276q$R*lu=b{mNU5#UGZT0M@i5 z>fys8paTx39=IR}lranpH8#mJQB^8nPedP-fX4DwC;H(NGynh$Km#f;UZ<8B_hB7~ zp%M&WLi}MEWB>pPKmrUPcaYvA5(}ia(*X(lE23X*7ITxdRwpd2z7h5zMWZ_`i1p?Ti21daU zoZuQb?2F)(H92HXXT=-};C62p0KoJDyI~#b;9*L0cInjr&oIyfFYp`4Az^mmbOl2m z5+M#LX>a>>dco;$4flGncd7_Cd%5?>lu)ePsBtCNNh5cBp^tJYsB_hK;jooC*Y|x* z>2rxiY>#v&%wat5w-V}O86KbxP9Sgjraa{U16+y*Y;{n%!5XY#8V&&hq+wR>;Y4Z7 zJPY`MO9BJmWmbIie-m(M8RT^(NqVVwgwM!&yZ3}qc#rsC6W^p`Q}~6sYC^p$apOpQ z&9^Db_l9*3eU$}%eYn>$cXNMuh%-rkhXr;-mtR__bP>qs3P4Hip~ZsdT}@&eX7U#{ z%ov0cDA`3%F=iUh26x31v!z^=_3hZao5O(b@&={IFhlBhm(bfF*(h0cI+~_ zlQYMNg~c6iu_V}G4Q{sqRsbk}>0tID0ijos+))@%Kmz=60)LVyy|`g2;0H`$R^D-z zYgw4q5<$K|YvrH;gn%F+13wnb#U%E6`Z$`a*9R53nytBwK!Fbwpa7xUsBpDBY?Qf1KCYLBJ4 zpqY!B!8xH7x_l<#3JkeTym_G|+I%t-s>(V4otYG)pA;(TxuY*?li|#xMVegfxf;<~ z`Uu*fRT^jhc%ohUrR#(b62Jhu8K!NTYC@K(E?T2W@T7VA*4DW_MtZ1ADFu#p1duw2 ziF&Cu2kk`l27TK1QhKGSTAUF2rm;G!^Q5648UP|%tHBx+y+-B&&ymSlH*D^wYcQ(S zn#_V4lbAZLMJNK+2A*|RuJO8AO4gJiH7ySIINASPk|h1ce*f4jInQV{%T-0o?HrAxAd#T)>j0wH6i z3c&Sbq&g2^4q9OoDnXfpWg7|rr9Ne}gY&d&FtwLuw$=M^T>G^F0HoJDzQ3ck1*jen zVHZeyT}*rJa9g+in@4!txCI=n3Aw9@d%zJ~A!K+IiOjieMRgjWjUmGvIG_WDc5PpE zAkFYm1#|-DftlqICHespSeaJ3%mffpEB>R!et?Vbmxf$di(Nqm`t1&4u}>)=3T}Dh z4W-Smt4`_KJ5 z&=dXTtC_2Z8|DXGoGJ9u9-T)1^8w<)3d+zNDj*bSp+0=B1T^KNo&hXlasfPHC--4^ zYPYmhLe~6rCzfbEU%Vt-cNYZIE9Hg5ROevWK?ab3#}(uC%+(kK6sPk10x_XJl=eDX znG0|LAEY1#+_3AlmI8%n49gH)b4w?-enGC`U<9h(LD0-$Bj6byJ@!3nV!QDr|2765 zHH2~%fT3dW77fo(G9VsytGF!Bl8Y-u3HC1z9IXi?y34`%Ik z0_p)`A1wvX?9l*FAYlO#_pV9!paZv6MUfCe!;5_yPhtG$uM|Rs z3r<};2{We5nKWzKgxT$;&Ye7a`uqtrsL-KAiy9Sr>zvZ1Oq)7=y0nGVsZ^_4y^1xf z)~#H-di@GEtk|(+%bGolHm%yVY}>kh3pWLTxpe9Jx&Vqmb-#-jFQhSi$3$@fH?ZKr zgbN!!j5x94#f+;$|9uRZ>8+zcQ$CRRPhXM}6fNdE2*7}ufA!#WFd*U?JrE-#7=U4n zvh0{S|M8Q9VctG=G@Qg_H-pj3nES2~aQP3oaF{RmeTK5n+yX}bNVdE;>+-~k!)JT1 zd26bKJmkxpKaW1W`t|JFyMGTqzWn+0>)XFiU#o;m{QLX=4`6@-4oF~u1|EoDf(kCk zV1o`m2w{X0PDo*e7G8*9h8k|jVTT@m2x5pLjyT{XR}4_sTu+e5Vv8=m2xE*g&PZd8 zHeMo#AaCrL15bBM5>?x;!VXJpvBn+?R8o;G`&47jJ_~KM(oRclwblkESBiG! zl@}&`jbQ@|*N#hWx#pgWZn|$V%dTX|!gObz7}diCXHPmu!xzz515Q0^IKW9QmViUg ztGb}V1O}tN>r-vdU36Op-MK@-9rMhj4;MJRM6ty)$s@}Jp8RvoMi|+XbjC0O9@62=0KEtOUkU|elbkRm1jdapVFU@q*HS&>w0V%HNbk$a0 zjdj*q-q*g^5iKLP;+a^b!`z%wy1mF}$z%%jGdyzl0T$#}Yt|YL_ zKJI`}Crw@gZs(%U&}ryK7a0UIJsj*Ys+GG~syE*!l~i3kV-zrF643o)&PJ9Rq^X>X zGf~1l&8!+42Oj80x{WmCRlul(1bjmpCKSMJ{eZ*) z+MtVH=z%!pkU<6DNQ^p!u5hH`LZotG1qHnF(Tn8io8)5rpiG~jAN4O&_e@` z+Eb(^MSxUULiisYy?Y(v+&y zYLl2k5bHvAVCVl|VrO8gPVt&TA1Jpr8t}%D9u1MgtA_K?5bG58(t!uey%@kqtF52YFYj2C&-0F5+sf7$tjg^u} zSwmE#S|B{UAD%>cXiy{=h_X6ZH*p$Y~cT(dRwn zkqGUWb|xAPse9iG-}u&Nq&}^$eea9k{OVV0w&24L3LwP&3V6T-)*4RVkfT)ar>6x* z8c?qyR4lITqT9U*g=I1-r0T?11C-#Cbkh?JS9m7;OR9z?$ejU_|ClB!Hmzva3*#8e zIHSFV%x-Ut;~eW4Ti2V*Y<*GNG3_!(R-ObZ*>d3|0^rpZ-eiQ=RE6q&--0O zDUy*4YK#NWba4Zp4~^(VTc~S10!0)VtY{!T*eVfLo12s8B#T^lZG+nMrD^l&P>Wib zs6}#AjEw43t9rMwt;>&tyy{rXde+x6^;48gEO%;kP>@;$E=EDGLh6DQs#$JyOh(UO zZR1tHSc9W(Wek7V!Vg+a$%L)*0e6U$xmLr9%FB|+Kd9qUk>w_qs7)vvAD39+#O4m zLkU;ioo6p_ig+>?+0V6=Fi;=?5rhIIr9f3bK4H}c=wRs>$=FCv^7N=ry*l17U;#Yv zh2qMg0YbPeMlu`qCOjk5^v1W_-wt>8=sV(cue;sv?r(zE0no|tMZ)n8_`vhf;RqIl z;3YkzB3;qaA#c3nzvJ=8OMdb^8M&!tj`_@MUNEhu|H~K#aR^LsYkM}>yy;IbbDB5B z=ERgYaXekT$e(05N%cwaURPn*&$#Vz@4fHeKKH{5fB3{NJ`wfKcZAQy(8h1R^L@nV z!av_e6Q@eWDUbc^^F;RA@BZX1k7U$~fBfXPO6RrJfi*-T5|CI!_W)D=_{;yss&|+7 zV}JkR@&5Px@4tM5KYalxfCET?E`odq_jd)TfC~sAjMhYu#(*qReN%CL`DcOH$9)&5 zfu9C`H8y`A2!bbfekl?GE}#M~fP(NBf-A^^)Kq^0f0TG`MCS`~*I2#5262xrA4@lc7n7m4}TfxVT6p9qT6G=_9h zf}v=Nr&uj(*oK?f6O+h_J8^?{D2uabA9#p}w}^|mm|uPfh`Q*D{6>g6^@}8;h%LZ~ zq@_P=w-f$A42U8;`Je=jR1@-`3v+`J-cSM9^@=s&ibBT|;$RB8cU`mL53-;+Gr^3` z_z%!1joWBKotRpvD39}~E~7XXrAUwY|EQ0Gp^6`e4NU-vCgh6l2p)4tiwB92^I?m_ z$dC=`kUGSR4=IuR6@6e6HV`@F-6E$dpal81@JN z_~?{VNtIvGj~5pw1VI$osEsml57n>>BiV{bIWq>CkY|aO>9LR*$(C*DmOv7bZz-1~ zMR*YB9~e286|#|vH&knLE2~g#2LMJSd5$+xl#jFkfRIazpaJUU9T!$*%%O>H*p17z z69Vy0J3%qaAsZKVnAJg+$fK0a|5TNwX_{*Rl~Q?{t67>?Ng3q86XsMG@kSI`sf>vO zl58~!HsKC6Src0n6v5&T!XN{vL3K1y4{P95bX60>S)59@fw7pD(@BeKnU~jzo!Mz2 zajBi%xiy5>Bi{KTdpU)DDKj{SFB|g@*$@R9Pyt)eWXsS1Hb7QthY=mYa~_aR>j)a6 z0TZ<{D(;{GTr^lSAORk52N%H(?P&n&))A0}PV*oP24ny@z&Px%1ZjsT(E(rpa2(!P z4j=KJbK?)L;C1>*nfE!N8c?B_RaFM?0SfdFlCuLE5CI|(I2aM4P6eOlMhkSIUNVtZ z63_rk&;Zy~8XeF8FtB$0|3F!h6+cOe8qbiNT?KT>SfWk!b$9S4pD`Dr5msYWRLKKbHWDT?@q!teF%s@T12C`(r~q#gA)i|S3%)8h#UV?z@Cj$cpZdZt zvsW^alqi_6KiALzZQu-%;5)am0;VtxolrRja0Io03!&g7kwOf+KqvbkIbT2wz6wgx z0SMM04eGjFgR=s?|N5)tx(dI5t(<9vwV|))Di5W=ZodErzB8i|00XR$3sJB?g98J@ z`m2G34ACGBG@%)VWUv$fQS@@JxgZ4!;|&zh2FUOW4dgEXBQONR0b5WEs{jtkND-0p z3yWX?zVR8%3J#2uvX%fyTDh+6Dg#=krl-ZGbc(cZ8mCFiw5DjMM$rX$suReiRcHsJ zGD;ezF{S*VSX;_wT4^h#pkA8MCsrFlGrC;Z@DY&(pKL=H>bZT=g&VrT8%_XiFkucH zn<$DC4{8tsC6r}!+Z&*2mZNI8c37&gs(GO)J1u zxwHdpz+d>ZMbQOOo2Si*C!y;)6G5$N{(uX|a7f1isJHnKwmL8MGQR~2 z2h%~kZ$kipFm5n&8zHbSqB55JIXV#&Txlv0eB&pKV5xt55)Z>R5_5r}dbma0dx=ZA zNvy<5|LC|&?8FV|a1ZE&c=^N;V!7stJ}N;M7m%QPvSybOT_p*|W`H_`atg3p9pnoq z%g_>Rq7Vte5Dozm5^+y3k#UUUjb40g&J|AqbuzKjX?t>YR|v4GVjYpBHw2N#d}66z zTwR#ilT7zcKgkGp^2P@DlsK9n9PAGl=Dd-oIdN*K4vh? zqhidgEXvQIPJKfo(MlgV*JY{c)3Z%ACl^Gwf? z|Mm!vPzZ%!2X+t#Y!C^u2m+!AO@0bOyh$X1Z2K?^c{0ZqvWk;z39IES{MOQ^^o4QRp*65$WIum(4)YcS!B zrt4NP%_@gUCtGbBtL%-)`^rQS%glqzZ5@iX?ACFudAd9l3oNxZ5nPg@49EZuwSp2w z{R|Hb6I5lOr!g9BHmK*6PJW%p#YP<^Nz|9o(?DTQ;G9qLM$VXVT`^O~;XK5J{|nEd z4R`YF(4}qKGj-4Syw7p)&j5YT{c+C$&CjfD2Lb&Ej$qKIt;E5oV7jd#S4^u}Y-ah8 zFsB3w;>#tEtvS~)9jlu+wDTMorp7Zmpq*7O5e%9-9Xs^$#oM86cx;)F<0m#ryvr-n zjKI^4>eG)0)Eol>F=?q5;f;eMJI8H}$&HyHEECNAJ3k3gz4JTW(YjaCJLFBgCjq~k zlsWawN9mfsU>rG?S<`6^%K6|+xuMGuiYT{oX>WE2SV5kn=s{&>#B~n&|{7vz%9|`l(`q-4TO_B zAi%2(MM5gf!mgkJ@is z>U1s<+t9MaFfcQr$rtcTu3*0U&`ZA*O!uG-mcR_eFb0>AF~UY{T@AmB1WSJ&3Owsa ztMIe2!M|ut;U{F_9WL%uF$7Prc^W?M={{>89u#-|%PCGk?~M`0|2z)`j&)x$DyEFs zO!r+5B=6WO-#MY>?#}QqTm)cd}3hWsnE8ozDZ^@p)O1|IyGf-ymwfin5_=*hZ*`5~7in zRTrVQi`BM+)l^TVqdeCD*UNP(c~v3+2qW1Mg>_howOGu_R78pccP!HeP@^{*IEiv} z1t2o~`|}l$Rjkf7s$PTbeG+I_05SR|7>WV_u%u+V4`(0r6Y&Ww>X;mZsH~S^q`s%X;6XwkkU_r2EG`t zA2~8eD#Hys^zKC%;krd93G%SZ+^s;R1?pvvs$r8FQ*pNqXzG z_g;MS)puVZnUwTjfCCnIV1f%a_+W%H|B90ihS>o0Of*qaXiYoVV1tf08fL>xK^;=$ zPCWJGbEApHw3uOpB2IW^mRojNqeWLTVo^|Dw)y5PDgDgSpoZ%1U7%b2G-#q%6<5@L z21yoz@m58(-J+wG`Yl+mwU%0}v(|cRt~q<6x6^>tt&Cxx@U?5_kX80LX3=*0ZMfr> zd+wdAzV_#-^N#W8r0P*(52)R_z!<3YW;Nax=H+*B#v6D1amai07iY>VxBPO|5m<)P2N>=KJrNktTcc%Wt)6ySJlzefHaT zzXjTCYfWrnb9;X^wbw4L?fd)p|9=1mFnzMBp7{)@lY zWZ?&W_`^dj$_Q^jp7NLnL?pf}dYze`&l>ndC`J(}36x?Lttd704Nx-y8Q5{T2POBHrDaRe}!oeCIv&xzBkjgdl841H*oovQn;7qQr~YDnU`RS58!;SDGbH zYMIS$hE$|%;pRw9I#OU>lQPw0X-nTW1hQQxSiB(?07sC<6xyIZmV|RjK+a|K~=X`c$Y!HDT=>CBz`&Cm!-sVN_kARB^Kx-8SiR<^Uf z)lV@KRM3tpx7j-CQhobd-~y?sekE>kjeFdXxOJ|U6srrtiqMBBw~|^_mn;>MM&4SI(M$vMQ(d(!l*{MSH3U-tWE?wwWN`Nfmrc}EEsgy zd?+CYMLn87|7ane{Wd1R1D1y_0%R(4ARw}E8QM|y5eyLh!y6UgtWxwL1t>g5A4v$Y zcNUCG(O#3bD`xR)P}?lkmQ9Rsb1hDz*+`aE*NA-wt=a zOJ;JD%}LdP-t%=eabX-7T2F&ob)E>ZvO(?XFfB90pWa19a{bh0Fk}p#`ebfQ9BE}X zl;NN~baI^^0$)ejS|Dsi+xW|^+aj}i9lVf6yj5I|ijb97fV@F%sI39LoemrCt2^rgvDKe71{cS%g zdC%h}cexL#UPxkfy>)G*c>#40Nm9%pVJ(RY9~SRFndwYprX6^jn{T)_!Vha2FT20Q zRnR3;-jF1(x%*ntB05~+73p(Ne$q2rx(YlASOqY0F@^&$LeZ)A3S`_t0})sP7pOP` z$=@OmU=#xyNeBTjbb$;;yIhJ#qjjjJVvYs8x>UcOwOO7Lj06M-F&-wdh@1W*of|I2 z!JKy0W&2{S(T162v>(@MoW>hlUF>6@X0<7E?QKU!+i7o1x552(xJOXj6Q_IK?Or8O z|7O+T*{$-t>D)p^E|U-3V;>OV~zaS8GZ6>prU0Zr%+VQ26j51hd$>{x>Ae_#xwEa(}w z$Gz^^L!SaP0MbagM$ni3kM?xH03zs5^cw(!+PmWR@G(C0;n0EWM>;B|e!*4zF$^Ve zA1eG<#CfKV=zkDB`qLLbF2%Ka_IIEF23P?qqL6$f$TaWM0ObQdbD)3@(+4IPFzds< z_#?4a8#DkQ0HITg^ZUOFI0M@&015DbJD7)mU_bX00r=yJZ9sriAS@ZMG!I;l|9qeU zGcXEw-~i5|2M*W)4Tt~{*afMuwSV{&c8CHE;6HE}u@R8I5AYDC5W)Q;L8JJ!{?fk+ zFp+=YJ>LVqf1or=tAH&Sk6*LG%M(>#gFG;uRD`Qo zOcTo^C3^#*1Bu8^JNQ6|#3gHJX_(ra{h6dPzTKEJBaDoTCfm_Ih zH3+!}46%O<$bm$|ToM-rbb@^tu^aF>890D80ESO6fEYYUOUMN)0Fe<37=06@?N zIp7b-luTlvOqWE>1h53w1WcyjLoI4V-dv+( zGD?4t%Mh$c96bf7um>7&0@P%hd$6@@AOOPg(Ni!=S96MZPy;2s3Lx!=@OTEJgi>sL zK~}5NQs57>Gzxp5!Jx#CeGpS8IMWQHODQ-30W3)bK|rR+(|?rGr@IP%Py+1g{LG}l2PvSCtBBJ%l|e#1R2sa8PfZ$8O-rd5)X##KM_f)| zeV^atn%X!-(1&#Ydm7MH^P;dR#_WH#E zy@XaI#($%v5sDaLB*kC^IP_wOyc@>(oQPRWhF7o=77{PRBMI%&#q5%+%QIJw$i;l^ zyaWYTNy#gk!6<}{(9lRdRsoOW$UsmX(QH@)@Y4VQd76F5)bbme69iLtGz_WmSZEXv zqd37EMGJXAg*D*EeTYW?C_s?ToL6!MSYH%hg<_L&4KHB~ z*y?rOno!ui(%)r#*k*L1Yyl5(w1#l7ijjLk7&r!JIE0NQ*$|Y26F5i5b+r^t+qyh~ z)q{$V^@=TB07j5m4Ea-J;09~p25A5X{|uJkjVs|3mIinji)j>EvpouzG~p8thkx+n0|N)61q4Xu21$OE*9BfrhOuIm-B1RO zWiun|*j?o4-A`U+R&EX9Ene@aR#;Yw<4s;$w$A1CUtQj1%~6O%8l~uc2~k=vPkJlt zHM3C^h=J1`#dF`SN@mviWn)%||9bVewt`=T@T7M;<}ZO?H_>LwgNd(NFaP9ak$^9~ zGUrc}&`S|ujVpx*x#DZ2U_*5f6^7spre~u7x>p-nbIIq(6grhv40O+%!v{4u45MtmpAD%C+1e+3x`9R!{YujbL)3jRum>mw zS!+J71Y!upQm2^461ZXr)?ti(I*nemK|RZ~)oD6LHM*@q$8`q~U>7c>H8F*PH-^E& zEwP>+)eB>gy4>S^9^2F12YasE3dY$)c#wP0+(tu78h`?u-U=IJwXWD|d!~n^mXS_w zWxBSGVcnX$W{y(sI_N-U|23*>zz*!wc;#6Rm%{!f8o6b~w&h$_XUBeQfDzX?STlN? z39e$OcgiQsv+Ntf?2NIPIdf)@;Hrko?91zz`m_^(g1k`5oyl&f$+nn-9Z&M?GK`@E z+1}pqEQESun9-3}(biu)a|y@>MRul8cQN7>!Gr`D1u?{PBUn(_%H;&?|b+) z1-=DVz`~@k)!ADG|6(wO!k|fASmOa3u>c?N0|1=UO|(Q{aTov4QlQCV5C%y_M~`Cy zy=_XQ1cwCa2T?c%WpD+>d}`4}3K$n~0?!XFSOH_$1`fDmZKz1=?qde|V<|3Fu6R>( z0D->bNmWG(Bv*1KHv?OJ%3Jsa6^8^C#|1!W$1ksB)MW8r(1SgkYrzim;Fw)y8)fPk z&fHxNzs@N^Z*)h`3Bo>X#*k%6|A$&$Y)t>Q#x8D7?{q5(p>6iw_XXe0Zmw4hU&hO- zk%-rDj;_L+ZBbSNsj`VpLe- z_H^S0;0blc{{e>Q2SbW-Py!5?2W*f5n{9v_xM%8~;GyB?3&!W_{)ci{f*Q2}@SZd@ zc#j6q0VQk?+>5MGdyfk6$oYo8cQ3Rj1zP?7&|z3XihV#2;C2su@Ta5q0=R&W=A{ea z({v$e1ejVBxoPhsksqimv>gP%WcYlCR2FIYgr3o1n1STOfx@T&45Y#lJ9zlG1FFS% z8)x}Kqr!if4|tdND(pP~xIQe@5B^9Hd{_f~HxVZni5VmiCBS2)N(9HpQ zbiKb_|3k;?GBDQam?;?pjz!;}y+8cAj`T{03rd&tOV4!353WsjcFM1Oe(l%xz2-+^ zSHP2XV`oM1m8Z@x_Rr_V&@XkqOT5hY2=4MOSNH?$CD{C3-&fadI63vwe`a?*=K0;c z(e~zE*G|z(9?LJr3<9Hk7^Iy3$ajs>&J`mSD=2t1P3oUfY>MSAHje7 z3L-3cFyX?44j=xzb#5ZXiWVfoDRZXD z|1Na8456vhl}FW<;s>XW6rF3Gw05pKZ6b}dNk?Mrca|zt$H=<)~;W}jxBpOZPbr$7qX)}j&3`J zZa<>^s1R{Gad;Q<<0rRq-oAkgC!YJb9XiRGQ-6M2`0(k}uhYqs{r7g(gzBKjlx#gJ zM}_h<_q{y4aoyyD&&G`%Ie78Cq374#Zq6m=M|jx*D4TxX@kd^54?-BBX@Ur1|HKMGo0dA{H!35RgJD6ifoo6yzk7JTke~lwGP-PawrO;|d5=f;pE& zVzG&lS8u`@r<`-rxz!V83`LYtL)BRmPJNOjl%7XDk(5eHJ(VZ`Q32YhqmM!wsic!q z>QS4Qj+LgSo7M#vr=NnF7G4|a^_Z!rqME9ztFqeaVUd*>tE{uqTC1(M;+m_jyH|6U#Htv5^~ zlMFX)x6VFW9n3jP=E(#>{Ij2Ik&tfrk7UQwbx&R4QEe( zb|h#Scoquj5O{{o(b{yJO(;r;D(V!YZR4G{-h1=i_exu13ggU!gXt;ZhZ8w!3#Gc+ zxZ{sQ9=YU#!FsXfmt&r}=9_a)v9$4Ncd&r*`McWZ&S{sKfa7JG|C+R{yW6XDq?fMR z>jcIwdvOJ~UfOx-t(S}{*QS1%egl4MI=r|ad`WiNSWJl?=)m2kQcu=|C~JhZd}1bg=yBsiquY91;Q2HEc$xCALLGKGm{5p2S z9)dEIqFl=k54XTk+U0)uJ0;>ISi_9WFqX2MB}(q}gq4^LZ6ef)E%nyRkaX~DNb!gY zSJ*;YA~TuFTqdMmDV9&7Qk12PW+)ZMxFTXRo7&uFVvd-}Z-O(N;vDCQ9?=NqL=lg! zSsj1;aLzyqGCzvsk0Q{Cx_ByRp3idUeh?|o-LbKrfqX<9$(4*@wB~qS6li_+7#oGM zj-d!rCu^>^NNh>epZP3K7b!~4%?Kir4YN!oKWfsG|B`c)AnD}%sOi#|hH{!PoheOI z=1ON;gqb?sY2ViNlb8hagI5Wm-ZWUtK_R7>bvq_co9fi3LKP)A1q(E5sz0mt(3;%b zDp$LzO>d$!tYRH2S(kV^-q0Zp{A%O7urn_@#6hjaV(Y!&C9t>>Yp#ui4H)A(FTBo` zt^xASU%i#RIF=%KqIhV!{0djOwrj7i!Od|B>nvkQcAbw1*k9FptwMU}Hu-w%_XHcx zkdlu=WnC?6FR9Xxu+(E%oh@xOCDYpCHn(!Q=~O2Y)!zbFPDI^FE|0RyncV5PUR&EO zTOz2Vtk7=3oi25&OUvG3q^i12*=@J`F|B$v|GeTIZ>zxC+Vi3}z3QziM`8CbcD75i z?PcD30UFtaVv%{q(`)CuufNhOaP=%&#>{pOlBpHMdRy$`%)QnlvDL13Yiwhe-8jcOMhI_v zYuz6MIVQukN>GO>WS{JfD9T-lQWeG2AVWFIQg#$}FGAxT7Y@rH121{I?By>T#=I{c zGnvcGT8OgIqnm-Ri2tZZgN?DhcLdGpdNW}<3mC<9&hTgK*k(5u_`{w-Z17029Mk4; zdHUs}KJV)pK&CU!8@8|^C9LK@&XbXS|F$%W^XNVIhEK&95(I?JZ0b{&D8?O`v6fRN z4pXSI)idg@tZVJk9#3`3y599he#w>M@`)uz%^L}6(&R*?fY-`iHnXQvWs6+d);*%N zv}eR+Fk?I0Uluc}yY207YYxqK?DQ1vo4q{?x}te@-kT4cP;-|K-FJRByrI=@a%(1z zvnX_<<9*0q zbA;71BF9?Tfd&nftO+PfQ#>j$g91cgYMk1~EFJ*CYEK*II=}U^E7I(r19!-A5=v2Y zX%b)KEx9{6_EWTAbf7~$>Qd)O|IaBB?VZzw+E`c954G*}uX~l-9v?f|%U;*zr2!0b zwRnI6#s;H6mhB4K?6A^M^tF;`IQf!S(Fv6ILW~v+f=>f-3_fUaH8>d$whVDb>yt7N z{y8L?4&Tp4yi3c|IBBrEB`s`?M5# zpPsv?=6ZztBOJC)nC_Hh2lMILUqAb)d;N181g(EW0BagaMAZ*UTUbG!~EY4^5AC7UJKM-jC8^6p@lnu z02xHdKgfeCpn%jc!am?bC7^%-h(IV11U5uL)R+teMd1`yq0T@80i41DElC$rp%wmv zKMaEsNDbAbp)0&x0enCsz<~r901Tjv8GhkC&_Yw#92Q2+19-y%JmEj&0}Y@_{rv;| zDPkis39jK(`$-}OA)Tb;(lAwG*ks~Nm|s&Qn@1EG3QgiDlAd1&LukhsqV%lE<<^jH=q$#H8{1-4X8U>bEy5s>E90G#{k1fz!I5wlg zg;8HR<1~KezcuD$dS+>Q<3vr?3W}rbeBcP0BRgUSJ+fG3Y+PRICb;RNipY;_$%s#M zK_Q%l)5t&rG{GnwggqP~8M*@p?14eR%pTmsGDIYjK)^mc=N<^ebT))J;LJm8XLmxU z?v=nj?1Mj)f&x6l&QuKrJfS~eg3XQRK1}C5%);|6gmt3KLJH(Q1cQD$$kLC{hY@Sp`@EfLN9USq7VeYUqZ_$yydDDShZ#xFTJWXo(hvUG8Rz zs;I>z%f8%`Xwuu>RSUmlV{`x>x40-F@_dL`6!K^=0okykp2fjAzq=` zDCNBO}cwGhV}P(fxAkU<{3a@FJ;r02Fwn87#y$ zFr|BXXY;Y=q7Et)G@s4wCr1*5ot^?e$U)GgqFaXOsV2mM))0rXYF9Am*YpJVbwnsi z|B8}b1%+B@N<4uZ6rE7D>aPOpOn4}&sv@!8MO>O_vMQ?)iG*aF>9a!Xtps30?Nf6| z$A`$wqpcd$F^cCV`^&|g_gKJX1Vs0b&M;4a9}cU=3rr%x>6uFy3X{-D-3=n zyw=CPb`-a6(P~!5x7wh;9$dPF0TqOS7!*PnB*$^U$Dc)O#JX6Ta!gCj$Pm71TI_>2 zfPfQR!=2{o0ssOxSc5fiLjwINA1bQIlB~%lP(j#(1~|bz5Cni;iKLEf$#MfYFejvb z>ZCr&avmyxIsiCa1Iv=^$yzD|6^*CMsk^%}^Zerpqy{;KK z?xKCYX1&6o$t<_@f{Mz69#qIs3ZP>QW*OEjil5JHeT~?s2O4uqe>52N`|8D|w=&;f+ zLf9=U;;r6FFf8)z?^^KRPOISVsN-(h0YWKf@Z#(yTI6=A?tp6t2O5MaI;$RFZ=CT>F9$Z^dy!bv_lI-KYW4)7{CfVgC(aSCM-a7ZZay))mpfx%(THt{}84OFYxHV}|9_Pt5UCYW{vo+qqM!UZ27lEGO<+X3fN@Ind z+7(``c;M#soq;j7H}c(Cr-A3?9b#ia7hnMvAgmY!$0U>!yrf+jXqs1>Hm>|LaE21o zEFVKGNfOdUYa0YYz&4`V98_9$PuJg1V~SKOuu*r7DF+3u(!?s?YIJ$xNd&M=V5qG6 z_H#!WRX1>MDud{SD*HFkC`w_ATyGl9u*G(?sE&0@C2SPdl}|;hj4jc*f%E@O9*dzp57c#@-(cSqxA6f=MLE0d44r?K#et+x_$ zaJ?Sx4LYEee5^uDC)x~xV{>qr zn>%>I+A}3&!eng13WwN*SK4$?&uDt9p(}Z#`yh(=W)`EkSpaB4)9i^)dIPI?oA@}e zx_G73_?$Giu9g8&PsNRYM5t$lj2l^}yE-!g|M~n1x%^qTk=r^qA-SXLIul7bhm*I( z?WJIPX?>J;us8XzABTWzGkq;?l^^c z`I~zwIHM!E+m1V5ng?#PwWlVq8*FFWbF&vZ+cnl=)4QI3i+u0;--39iS2e)X@20cK zt8*xDca3oimkG^y*}SriBX?Migi?D&`n9^jV>}GSI@Zp5_0{^VgM1O?dcTuA=4|_h z^ZV&qYawjA2S>YF|K-VVd64eTzRx_((@x7n`;_xly`B6FlOAb8nsH#JW_oiS0YC=~ z0k|ioV*dPp(>yqDduXQoe9!CC!*12z|G7GwlM{D#6i)_d-wW@O$M(FuyE8Gm3sF=!R2NCbZlN6bUt#-3T1768FW5mfBtBRzFez*i2%pm z5uRd8USyXw=MzsM;I|q905?Ry5M);A)t%^HzMT(dyu6(ooK0Y9Jvs&+gP3WiiqC5-9^dcCmm*QIt*=I? z!doK4cfs44`h)@m0D%Ju4ouMk|6xLeUAicA_z+@5i4!FbdGe%7nJyQHQ1ti_WJr-C zNtQHu5@kx2D_OR5`4VQzb2Dkyw0RRJ&0GI?_VoD^Xi%X;i54|_6lqeV-IO+U`V?wZ zssC;zl#mB&R;^pPcJ=xdY*?{l$(A*H7HwL!Ytc@Wa0zZ)xpV2(wR;zDUcGzy_VxQ0 zaA3iM2^The7;$37ixoe5RH%?0J8|MjhU{4G<3g0}TxML?@ngxHJBOAFd2?mYpXY{- zJh^gd%y2cs?p){*Yr2kKlg6DpZf(x1bq5!1TXts1wuu+N#Cvq?-^P~@$L*Z@Xv?!{ zqXsjmPMulF$lD_P2*5vU{}P@w0)1RM_vfgYH`fh)@^;|ed#kp8zqjo&tF6B4uzT(i z$-T7W5y&8g9FoW)0INV$zolZz$Rw3qlF25WeCn2*q@1#*n5?`K z%Ph6rlFKd~8iJvY9(L@cUlF^)cd=k<~jY3k=N-gcFDuk|Li_=a${S?$tMIDtaw`4pO)l^ko zmDN^V<;%6`BumaO&8)jnu>V+*qqQ&LZo@U#<4EKcRuoY?OjqCJ+ed?Y# z11xb}dZknGyw?_N@WFXe1kqkt@r_O2y!f@SVP-v)EMjUa^zFY_J^mQvkVXEB#))pk zQAZvxT^T8Va?xWSmSvv#C`xI*8RwjJ<|)cXeWpp#poJcq=tI{8=^``dL=?;}#4H-5 zFcbPy&ZoPy6VHP5Oz3E+Df*L+K)oKD?6S>1d+49lest%yp|aWSxRc7Xg-uDl8}GdJ z-ka~QOdT2Uzy%+i@c+VFi#9f55wlfYiLuSLVufMrcsKYUUyNG=sf~74f)_{8TF3j7 zw=vK!YnXG4GaiiJTbad|M9=%Ggj{pURPjZhe&AOyiA zsEAllPEXiiOt6+UgD6CU5md+!&IH01j!=a$l;I3%s3->d%zg7Bjn%E%^ zKpp~78D+&q5t$A$Y(!2J|MH#i*e)4%Y26w{Lk9r7qh0?fh6J>5#o>+aGIGq;i%tX^ zXDJeVj8xvQEF+MO7-@qOL%1DZFj|?+p6It0xSN0`-5t(1g zawrvYB!wMl&_Dqy(1d3&i63$(000b7fh`z=DEZqTQp|yXQ}hs;J>g+AsaefSE%1g@ zs^K=d+0BYbO(hn&;6>8JLJ!8UOfZB9nZ|j}mz2N^#5;=qP9fT0X&sLU!c zB$|$XG^DC&6?E9(QILwXGb_zdOHrBz%eZQ$7j;8OXGPNDveW$ zX;3lhM|ALxC%TY87kv7;rS7y0szIZRAahlWhHh0;WCIq+iUmt5f~YZiOh?P`(u|&t zRrqpgN`F<=&&V|mB2AxNDcV=RdMuU@nPvTi& zgy&p&tXzOOg;ltO#Fe!*lPH2*Fa ztVV{RQbXM7B*(T|Iugk^mE5awcX`}n-30a_gH>6Ox?otNxB~=a*av6j;R+NKzyplf z2RtyA_`!t}#B3kt;D8za;g4Y`0m^5HS^g>z1^-@t z0kZ#)N0klmfl(~k9K!?v0YDpFf*KmpiB<|~ms_ReJ{rg8to`W&kVY+ZqjtGTWee2T2$Hf@veE@>tJCEygSx# zekcbm`*OH7=)Fy2&= zcl%-hyBG0j9PRns7{CkDvBiDe@$CZHAwq8MQy5}oqU0k95CC9L`caAlwEsaDsW3)A zAdvt|XhRMOc*Z`KK>$k-qY@Hu!aitjbDZnkC;U*unR!AF1DIhS*J!{NYVir7|091d zzeOc9kOQo{To1p1!vUo1SwL7r8l08&%3{5Cw}+O|tv<)9>0bAb(6&vLb|*>jE<kvr}_=hh^K|h~f5y$!!{lpZkjTUA@F+zpwq4yH~yM_Z)Y>E#;y65=N~< zf)`n<2SYfJJOPCS%HW3$Hyq!kZ=8js z`xM{ny|klng~1;Apx6IjL9P&y3yC4Rpb&~;AFx3N8lVaO>>unQ$N&&O-Cj*wuA7(-4 zAW+GsObuqRnF_7)E`{=bPzVnw?pm$!j*#y9j!*)xxF7=4RA|z+MDId^@a_Z%Y6v4{ zEAcQ03A@k>W$5v2BJze%NP>_Ir{eN9PYu^F^Ez+;-VhGgNAy&$_>yOGGzY$p;y9_< z>gv31tPl~7+C|8#3P1!rfdXj&>Ud%sK5Mh^@w4&~v}zEuJj(~q@JY;& zAP@4O!qCyakRe&?37IDGWNS?5iG~c1PMB~as!(fah)=Qvp9HTVLsBFYMIm(pAt&!7 zlOzqPO4SLf4CUG-_lB^np4sda$ssk^naxdQtH7LU?dvZf?szY}2 zrKqwosaKJ!OR zPAT*u30?rnl&mM{p#gv594C+#))7t1Q7Dw|%+jnh@1Y*dEM{s@=l0PbFyRK149wJE ze>{sG?bAr=(@+z2NUC$W+|yCdMmx&}xBrMs(<-tI)^kw)m7M-Y`&F~utOQ&wknZ~9Y9Z#7Hv@N#%BHJsGg%t#OU&?oPM5G}?* ziIqY30z|tlS$Wk)$qV+jYQBh7M5T3EnYE3OCoGrmTpq4h0H7Empan+24)!4rQa}+7 zM^=z+L#Gs4^96OMDm>k`2MR)H86;p+M!5)MEQh~a1@Fdt|D25uo0 zcJ5VMb!w~DNfjvS2Ql^lB{PECSemK*TsY}S6J+EXUtnmmv^CuU+s_;GZ$is zH(`Z$T?N)~!?!Lf_D1Mu$p0cGm!7Q8Q1&0fjF-rueXFbh8sG*}7U}k(O##S#8{i1? zj3?xjf8t>bRL;$0Kmsa2&f3fsWEt0JsB0?CYr}I?y=D#A_7GmUZQm9ER7li{hHAKQgmbtH^VWltf`eK0Zv|I~ zhZrmfSA37SuMn5ox(L0BEe|R8jS}=h-y=c~#B%j0b&7HkITRIZ4@29Fiz88V(};8r zM?;x-c)cfE`AYc`>^+1JJ$Aqi3PBN4AP@Fo2X-JSzgXW~2aAt~j{%Mrv3TGxi4ta1 z#FBK7-=lhe>Uy^=8UJ@tk-?WXVoVkt?qJo`VFP(%<`0R(mwau+eD(Hb)NTTiLhVdB zC;~{8m#l|>tJ#{3_>;5weWcgF_}CERpx&&{i@ljwDWl%tvN^>vN4KJs7(z`&;LpbUP8 zklcep&#j;xF;xT^p9k&@3PCV00g(gIq8quQzxSfGs-BH+l25ucR;5WVIu?yo<1$m5 zH#3w`hOlH=r~lt(r+a$QRJECdIwf)$f=YNydKrf$XoXqW7kmK|VgVCexR^mTsmCS@ z(W#fmcA15mtG$VbeL5(l*-)w3n#)>nvAL$x+Pi|04u;AxEr$-`+N~Y4KjONr4Kt-P zH1*F$x}}Cyrh3D!2isTQ>o`2>unAkHt}+c8dq)q$b;t7cCL^*HQ#JhH zQoFzpLYhZ0Te2y6Ny7jOsKBh)APh1&qZ4E&C3~`Sax)@3t{KyLDf6{!yGU`H4H{dO zaO$M=*^?eutt0BDM;WY>yC}q3xu+SZyBfMb!l)m}Y)dU7x0-~JnQUBO4SJ!ezuT$h zK!$Pah5vrJA+S(R+9`#jo4twVtDBoAn0r3S+N|qaR?)h+^P5K<7g$WHKoxs(-?i_ruCqlCy7LV;9C)H^VhtFxuF%-x$M_tq|JU zrWRSTN4&x<{Eck!5d?F2FM&c*Q5i`Zc87byp>)9#F0cK&D)}Q|3A}S*=f`jSLpCl% zH@U;FG_UphRgRmM;9JV2Y09OXmT#!NvwVd#Vw=44BvAMwJJM{p+q=QLsSiPhyA!F& ziEHK7gfDf4N>$6}ylCDVzU6y5>D#{dye0A5$^V>Llk~QOuUG&2d<31r{{q1i*`2jG zF8_}ea}3-sA~(_@yuKuy(T4>pl@-$~UBwBV#kJRyv5m(g-Nsoj$ccME>Mz!Vk+g$lR*D?hzxQ`H2jh6Xd1)HZ zAqvWKy2_gy&#xUJubhGCoV|&fx|fQxNxRpV(qVE^*v zt|l4cp*N9xUB8n3<)w}1`E5j0K65)6$=5~bcOKE3J>XrX+RxWW0>J76K-(oR+q3=* zxm|7SovXXHhQNK(u6w;hqPow$yVKnl*4>z;d(GV(OQKMQYWVJyS?Y=$QuKwz|-tCZt8FYdByWjh{pBb=UQUAUEXZHS< zr~84>-%ZSZ+{Jy&*FN3d9#r{`{mcFAy@rMEKhDdfyv-jVS_m9Su%N+%2oow?$grWq zhY%x5RCunU#fum-YP5LkpU00NLy8oJsTFt$`Bq=-kP( zr_Y~2g9;r=w5ZXeNRujE%CxCcg%U1Fol3Q;)vH*uYTe4UtJkk!!-^eCwyfE+XsJG0 zTZj&wIC1RAEwnbRU8;rb#7X1!ZCpEa>)y5ds8Ad>eBJ&9EO;>5!iL%Og*&&g^72rdurJ zysSyf{aoBD+q}K$lnE0?%o|FAayS2~T5oGQrR^}^zV*1?IJM!9C!h7X+~{fI&}9$S zJlyZ4*VDIZ{(O4z`*rmkba2t(M`rp3sNjMOk|n`HEJVnH3Mr&8LPs@?6u^cY29V*0 zAciR7h$NOsl1u;Sg3gL8wz#4$CdMe^j5OA0BS^Pwq~nekP2}T`Kn5w~kVF<~ZnFR)!?b9rmE_yRjpOndy8fE7Gtcsn%8-A9XRWJtJ(@{u7$)$Yp-nm z3fO^gA;{__#p)%O9l9pVE3vnlcHnu+*7~Zm$3h3#w5qQ4tAU01L0PuMj++@8hX6Or zaN52HEUpM@7w#i+g+WDiVJL#@fe8jEuCsKMn+Lt8rK?xL*TNN7z40zwE`f6;e6L(| zKsy^{-v+#&xaetYEX3)emsz!@S-kAZEMNAZLK03`;e{i1xM7UkRN(|TFYOafIF|-3 zG>s_2IFdB;cx3d@OgHT`(>XROwMB|nZS~byV;!ZSS^xi7C)ZaG;b)u=?fFF4KZZG` znPj5L=Gy=iDR!M$$~mN!V51$;o_Q1bX5Dt{E%@Ms7vA;Mh(G%D;viDW_~SHX+QO!! zR&M#_m}jneP^Px*`RAZ}?yJ0>+1skO;BMC}x45;3dLbWg%eu-{ZTxNQ+j2}hUId~` zUbDLEx3PSwHwV0F>+$w5?DQQE+f~YU9DB9T^EbTo&F5a3Rh0l&$8gCkU%YO>FK7Dc z6rX&)@%Y-IZy0YBBFI#mTv9)?vmv~GaRdLQUw7x)9sj%~p8ZJ$fZ{V?Y+mI*1G)!c z<0Buw8iP~>t|-xOk{G=`B+gPI$h%xK3x`tgs0 zyQ0)yNX0^e#Bqj9q)l+Lxkftjk&uj}PdbOfN?P)gk6B%;Tt$|R`7SLaEL~_`cNyn( zOo8RejI>ZWmeFmJm9BdoEW=_-40dIBp9H1$S~p6=EN_8z8La+kJDW%^7Q z8e|3x41;hNyrQQ*5Hj##AB5h?^jFGTz5nkGikP2qsF};uFwlIv$zK4o$(;}mtCiaf zATvWlI$&z^dZ)A|x7dk3lznTSt&|r()zZO#+S54`d?zjKBhP_i@}YxKAwpO$El^{sG?D^e&4(Yo3dg`=AtCqbi1;*C?7&q}6QMB~?m0+yG2 zCFMeIrPqVjr?0nL?8qGY6seao#4}~3?Vm!0 z+d&~p>GTx_Bylm<19Ko_`8ToL!K=uL}64?S~Kpjexv5t3~A)S&{BVrA*kPo#r zf&6W#X*AnU<5&hd%(0IyK>q_9+Za^g~s} z>uYpivWpf-W43+V((HFFjal0!IyIJMUTQr}X;3dS(!2chCAufgWWbgy!!>lOOFdY1 zDtFZRqJkKFE6$JE8hfXc*KzOSo(t~poYU3wb3KS^>=Js}=iO~W3;1k&T36cpB=m5@ z%b#p32)x(Mv$(6WUW2rkW+5Sm8}HlK zF&tm$ghyfuh>z5?u9M|_Ot9+~;(IR8;nSeg5Q}d;RNEs=1?N?zA?Oy;5+dv)b3r_EFh++;ES3 zJKHi@RmTQ7Y2b``C*88lu!b{!5hcr1`JGJfb!CJ%P-o0X>$@XoGm7Ce%T$vb*GPV4 zypasxFTX7FXnygU{)+eN@UCRILKMb{Cw?4FE$Dnc4f@jcZ#%C%#e?Uwt@qEuZew@Q zkWlf$>iscoUH`DXh_La#AMRx0Abe{s8~Dse{_uyFKoExcf*|3H2@UerHETN^}o500TT@WAET{514^FMss3!4q*3zAUF_pVsvywH%NvyBN$dG zs3$$QWnCvYW+Nt3#&ly)gEo)?CNKgK0E0c}2Ga3@V3c)Q^fxXTf<}0RKhl92p=KIb zBWBlxHIjC1H-%JKg+=jp*O!Ikwr3Rs9)N~~%JB%_6(lYIoSeI%i7?si`s5)=C{Z}s*M{?G;r2ShnTL-_W7)<6RObqpAX zZ}{e4mau>zac?W7fDXtFD)tQVM{@AzU?~NFQ20166;pb^avo|{7#DQXmg!njQ zK}RJf_;XxURA2>=JU2G}I5>FYR7+QbH5dgdFobnebU+0te?)Z!nU5A}gi44JOh}I< z^8bV!St3$sg(5kURfvVWc#@UGg}7lrs+4TMBWQ@`K&aD-bN4KRb``TllL+NcD|t`n zqLTuWS;@0#KnZKRR6xhZX#zu96*ODJMi@+qlaPgpci}IMAZ-*wZTG}YWr2vo@oGj% zIv7MwMLAlKSRL0P2v>OtnQ%bMMwQ>?PFg8jV)>N1By0{8J%*S)0wt5DWtW-cY@Oy$ zsQ8k_zlv@3#*kheOjCn*YFmx!DO0_WzNK zLt{1;0x$qH7>JzE`8f7ia~D~iKqZhs(t;;gC|?s+Lbwn|MS@+kBw!+gYy=4kIR-Ys z0$J3Z10iPHnML1ubZ@e5@oAm-Ib<1m5gQquAL5bz`5_@mk_1|yab}X1nV_hml6;qX zdQpbcS9i^IPJlUDLP=Q^T8GY8cb%kI$;XqSXBAEfl(mGRN;!ODX`;OYp&M#=6M9-S z*$7&&12nn=Kp-~qp`u*r6<+CTv87EZN=%NpnC>G6@FNDj_M_T$Y9uO`7)nkRno5F+ zT)9=0$flxMxr_QVOjNpeA-YiBmU`58i>0JN*~L(h>3e3Xh}&gQWvQT4f&ZBTp_vy| zjGsAj$`}aE_z&wa1t)L{>PQF*r`Eba1*N5Tv1q$t zO1Nhio&=bU_N}1gp=`>b-Q-J^*=aV(dW7MWgLRaL=ZY&zX(g(YFxsu8=6fSrYotR5 zPp|_vFt9eT16t5{WT_QB3YNvfF|xQ@`P!|ycBH)q3h!!L;(Dbz8UJfvnp$|tuYXx; z?i8gQG^W~mUHw2wQA*U@sr!rxupNW8^ zsbBZ@0%w3>Pyi0`7Y^{i2OISQ8&yQ-fMNO8ar-bs8HNMKfDTr>Q7|^B|K$<;(5F2F zsLom`H1-dAa0JfzoM{`kGGeMfhOBmrg2VbHtqO!bf}KnSt3pDne9NkMRGvzwtLeF( zh4ZUW(t=qsxOtSfU&XlZ>9|#Qx0t&{%32ZqDYq@*xdO^a(+XF9&x>9ar^6GAI~$Y^hRihld>4SL{FIj{%!5S;(z4-&RfNZ<*>c@BDjVG6bnwK-rp za0(zMVg%;G=a`ISyARvwU!Z#bmE6Ld>fncKuf=C^sWw?;CbOIEn7N|53? zC1^wtxmqUZsgP07tAlfO6A_+}`>K*FbXGi&T6UjK{Qt&>vbpEbxk-E?bu1Im>bj0J zUwOdCer&pbtjCW8yRuuzqqe|^r>=oPyb0W)t8}55w`ht0$(^@ojc}B@+Z>j4$@^N# zufxgM8_Ay>m9^rOplo^^-5Tpp+q-#d-2=SXLP}&I8 zW5Lw*m%u!wy)wUrP|RF<%)~rxwOm{)d&vZRFTZv&(tLcPyt0qb2#g7aH5;?Ci@_4o zLg-efG$ES$^~32$wjlAS1jaKakR{sQmk`Oe4VoTC0plJuS&+aYX6=IsgQ~*I2fHImYcCoCglx!g`g>)d9?#rNxx*J=5Ff&ft&AnqJ?+4v z(=15+FelWoX%HV^@ERK0GEgnmy!X@-gcxx!)ytvPks;N>Qq_NW7-H>RV=)PN5U}A( zutQ)6)MeHStE5(qFKmDXSU?4NT^)!(*P^o;Tx}b~^V8|X8dyEpgxyJI-PNU0n25I; zSnWY4^muVl25G=-p<~xUEFSB(pK}(53#C~i`*2g+<}YST}&ps zItF2^H&jd{TbI&!^3hD?-DP9O#y#Fb($c|w62INs&uFlq@uYd=8 znTfAb9lDGiYoQ2;fXl^{;&I7bSb1v4Y|MIzk+@5)FPzapxT(>AmNEKHOJC z-hv)R5siZV_+$=qhdA zem)X?{?h9W;HtjrtlsLb{_3zE>+CJy2tnWlo`naV;m)<;dUmh&#H}x>i|j<9&z!sL zl#{*g;m)PV#ZJlEg)L)#y)J56AkIFWyrf6o?4C93Exr|W5Cq{H1aweb^uio-ov?;k zq`HQrg7Bj^4zb-XK}x>t0-WwrZj@B6It|S2`OZGm?7!9Q=C!ruOKQN4tQO<7lURQ6 zyS1jvj>x~W=0W+*S)M`=GXKsMl}PDF&osjErJf!K9BrXp~o}TF;ZSq3j0;DeT9})5eo$9i_^i1FMPXF{x zPwNL^>$jd>xxT)g#OuW7trZ_^gFVdciuDe9@0r9{4*sr34))k9eaE}?*IsGWUiK@l zXmM{&Z(nP5-{Es_YS3=sRWS)=z{&&r1bG0YsJs<(O_$pnm_i}^{;6Q=}4IV^z=}{p&aqJW-ln~(~iVPdt!B~i*M2;N^E-Vx$4#Y5GUG;* zEf0dc2+^fLiWo0GWI0nOOot?AR!q6Fq|TiX8}^L&^HEToLy5ZNiPR~=Mp|rKwXx%g zO^0@JnyeGHPBOB>CUu0!5UEC`7{iDO^G1xIfuNpxjQWr*RFqx6-oHk>qM59Ob?rqr@qvXj3L8@KLIpN{WodXN*N>cPowO&`7{+u%O&WnFd zdxmMb@#})5ZQnkb_GoC{z@JKJkzD!m7A%~zP>~|Vh+F@xU&o$Z`*!Z#y?+NEUi^6S z<;|Z*pI&|VZtLB@haX@5eERj(-#V9H|9<}c{p)8gKmi9Nus{P3L@+@G7i6$O2Ooqm z!UUfv;|U2b#E`iswz8v(Cx*x{L1RM5jAmrQVoGLU4Fzzw@#aYHDh#4<}Qx8yRy|Gorszv}EG zv&=HvGygM9HQ&2MISKNBGfp7pq_a*t@5D1tJ@@3ZPe1 z&NvH{z&J@KrLZ0}|Z($AYCT#OHwzAazt?4FWi>(N> z%MvTtp@R_?SSp5F^9o?ryxq;SpdPL@;av%P$zY2;6HcVrK&@@$SY;j9HcTs4Iop!2 zo&PpwgODrmIq0OLZq4%E0VbS%d?vbRqmQ-@O{AA*x@o7$#4k*#{p+%7tFOkIOA@=d zGHVf?v~a~Ey}pn_3(1yn$}&7uk?RCyr18cYG1+kp8(1JaNVE}D+rzU7RC4bVVcc8o zu?0swamAUOx^Xd|hTKf0Bd1)xHj{hP(L5OC9M2)N7$S(yM<<<6AI^won9^5g9Z=2l zfYfH$XCJL1Ix-!VTZ=6o?V=Sj9h zdOE0g{(6IqVuOz9yZ2sShQc48*YeHJUi|IJU;h$o(SJXVCw9O}t40)Km#k#WQvXa; z+((Bn)awm}piBG|f|>!MN`VRypzqkQ8RX?FHX?B!8yr?aYUKul5_H%DA&8ndWN;)L zgqXMJz`HnbOm-J^$O_|-h8Bv@W0sMj22t3n*ocZ>0K*x9bQYcIjEQp5pn@3GQ91JP zV-aQ;8WW}Xp2L#x2f^Uj$=_w$`;UHmO8p6q}XG$eb~*aX~7&o!??K zBe~73Zawl^;M}O3B2~#n%hBT=6BJ0q6^TlIBcmV{xyUVX(Q!u1VkEs&MM+i?JC|!g z<{ZTXJsg7>(J00*2(g6L@ks}!m_{YaRZ3RU=?u)s1{x3rgi|s@7(=+z5dY5L4Ar&L zm!*7N>_j-s0ETK+h48}!)wMoj&dLvkpy4vhcRZG1CR`uQ=8Xo7(LU8s~vU>GWz76UhFUg{9R=SV0hO| z`sc1zaTJXQ*;ct2ON^>of#Cq%O6$?OZSk6e(i%)>bd8-ti7{s(7l5 zn!BRa_d;^Q*)`K9C=FOcifi0(2Cp}#(o1uJt3KsQ*QFg4)^mR&nCxm7xzMG_sT^pt zd0Ll!@_Hd;wskR?N^@l4UFUEil82s@AqZHp0TANgl7;>+p_xI+TasvmM+jmP2hIyQ z@B2^J&^MzRos4EGOtO7_7h(U@rpIW8;Q&%hG9Hvzb8WKW>;HDx!#q?ei_Ire)u`Ae zj=AB8Neq}6;~0h+k+8*j{1O-r^)^Kn&{2yhA9Ac`6-=G#cG!Ui4HTdPO?XB=XaGg; zXqn6J@dq^4Ab|pSpbg*{8dkMxSxZ)y&2NVDn#Ky*|2WppcXp7IgkXI4I7{V5G5e;Sh;{UX#i^eTWd)h60dkI4rLK9XI z4Pu~T3D?GUYIQpx-ul+J&19DDh-+U;IhVVcQOk4-&dq@9M7;{1)NzfcyIYlaqwUR| z!+*77i7@=&COKA+BVJwf`syemmlVcv`reUp3coMDSVmzi(v=5HEo{&N5Xg0vA^4#q z1qR@6-4anT7(oz}IIyiyGt-MRrRM2X7}HCYPndJKzE8hPP3HTPnPseFCf-R@;M=i{ zQM~Id=hTWRj$)tkur_8VVcW?bLZzHt>QldQQ6dK9s^82&O72;F+|Xq7EVZfLi3b-v z5QtikVhiB#a+I|bc`(aD0xRGID=MLZ2R!2+YX2rR7DpX=(wE*mbM`cUIK6t-C#TPL zCUn}2bm*-8b<;trv~mRdghb12(K_mD)gFE4!0kTwWz<_?GY!|)H(zn7{}QN8&$Q7` zzi6h`+-8~4OV}>r2+?4MGLGR2A=Ebf(U^v;e}D{T6yq4tK(-G!iGE(U76|PI<@lBD z3}EOY7ige1Yty#YLalr=oh`5iR-+|TK(_mH23>eRVn733vaQlmrSF4=cWVRqgTU=G zz}wn40qHk?+a};@IN%sK-~c$G;J6gLjU0oY&d`j$`z?~gy2aQy6~r(1>J0LNxTk0@ z*J#0CAvhp>xf|>_AEd#@XeS=bFeM~0mH*?oXF)ll$R{T(v5B4CDAQuam(Z z!^1q3!;sk^L7W+nlEIYe!?=4x9)rXeEV6}J4I~Q?z>_}o=z_sJ4?);~4R{C1%MNz{ z0W#Q!snRk40009p1AmZ(4zRK>0Ed5Q#aA=~FS8DJ;D9~&2X=@84KRQec!qe8gAlmI z>!1e^z=5GzMS9Qx9QeGf`iFWL17);6r>VYe^u}#OJ?P61=Oahu6SOy5|lg!Cq3c&ywK@yxW zRSB*{)VOcr3z93jO2Mur^tg{Jm4_?Bi3q~3EVvxxi=INuh$F(fJ1?x{y5;)AXz>@h zgqP*AIFLI+j>ADBsGNy8lF(K>RQl3rw&}O+;)9zW}ejo5YUWnAohQ*{q#P^e4M( zOGSj4nUh4*)R)reAmO0HoX|w(;6(W-5l|!#XBfqAFvaZ1ha`XiG`kKhqc&@}MQvDx zV)z6OFaunqf$fC6E$hW!4*nh}103Vm4+oN(_9rAo$3P6iJR;ziL1O zAShA*WQI@L(G0}McmF#|R64CW(E&hct#-qP(0NKep{;5|HPzvPHh?uACAQich8~DX zA6=~-{UjqTz%5;!sAP_*q)L~w$`hO&7t|Hp>C7keu1jG{;i8?dWSH#|OO<&Qg0Vrr zBu%=sFDZN;B_y)AWK1IIL7FRLxMmv0c@>s6#K#yj8{svVR)YMs2A=Ma|~oO-0pB z_F_9iG?ur!)kc)NkBHWsGES99&gEFn_$ZMsCqa-f0@5QOm92W*gm255p& z7#hm6jws>>HUG$geXv(v{0DnbPboNodzen^=!ZcNQ0&-;Wk7&az$zqw1O<48g0<25 zsL_hW*ep^|=yTDIRh-vztP91G3H^}=y|WLEklwqI4Q(_nNxnhb#{)?$O-q~*Wh@ir zBjfYfoox^p89CWB|$`U4)OU21O_Y zttEtTd&vb%rBxb&0IV%ygHt^Tf*^n`L@))81cKE922_ZHPKX9#LmhQPB~^OT)p7<> zPz0@Y1T>JXvn?GtT@E^})7xOn-V~nmDV~V~Rus&h$L$I%oF?MA9e-imL5&{fnK)ts z3GE3e%m3Y`^I@LR6;u%dp9VVA%RL{~C0%?v75Y&p8Dpj{AeV9}Fjt5u%N(W%dY}CI zT?UdM3Ig4k$spq$UWG~C(FB+uOWtI4%Y7-K35r}xl+6;NI~(fOp3q+DO*w20iD&}d zZ&i+Pg^%VWyzaOMF&IV5+<-7}D)9(2IFJAs00(wJPx>5&D3E{%(0~`<*Zn2W@%#s0 z+=F|#1_}58Jy=HV=m$Bt&g@`Vhm`^eAOKGw+B6y34fbHC+1S+M*%7`PkZmjz_R!g5 zQ3;7qJ1Y?kQCSNMtarvHi(bLk2hfNLD+7W2lBh34#x4+KdDOAz(mP*a6Y{fn)F_ zR>L>Ky%QneEMsZ_2fr0A`D!YI%z zC(xK>;fyajc!D*6gRn>jT8M-+(Ar9VDOu?#S}sA5dL~*0CyYQJVZGiLeBEUpu}E$o zYIa1Lx@JU-=0{v9p~}{e`sU#XXNwwVlflIDG2i4s-}m^$_4ST@2!l}^MRK56?*G^a zZvX)&@YjDZ2Lspws$~KJ?q|wF;QSPa&2s=_*pB+VPwd#w{=_OFKmlW1V){_xi`M8g z31Lqo;*X9JlRZ%&t{RffGn_qPn{AL7wj&x=VJ1=Ox$@x*>Bk->>9u;b z#Acl_W;QR_4k8LX z_;AkffX??t53G6tEnBmF2!{UrhxH_A8d$Sx+}D5oMeMK#{^ky8%z^p+2WfmpeP9A8 zC4lEZR zkq}>!oW8RXk8vYmn+-R}pU#h%@%wO-Q{${&suQLLHZf%eV*envon$Rri(7a* z<5~+pbHn3kFyk}U17&cAlMJ2i+QS* z%s>}SxMOa@3~pWj^{-QI&vZ=-D!aLa?&syhyj)gh-(G|Z&QM1%@$R@mEN@`{O=;Ke z%{7hlZfEy^=kS>44QPjZ#twGyfp<2=t(vwYrXbPw{b%J_}vXdXWY9S8Y5 z`|!rf$1sv{Hi~JS9`Ou0@fp^U0TC<~rz?~uc^DTFAx4pZKL z4hpyMCiauE4(mBtKRBL~I5wADx|1LXogr|^EZ1{88C)sP6WNktD6SLP%JZym6u;gr zKi{a3xOFQ`Y;SiJNoQ@PaBLKW`-Ova;~>ANE2VeHl#kh;uqd zT=wwodpPV>*I&fOZ+$^DL=`N}&=c4?BP4IPhl=3m)!|Q8a8GZfTAFNkK9a02Vt{_a=BcvyrgYXBVx1$D%Xz?P(j2bs` z?C9|$NQJk~kt}KQB+8T}Td-{D@+HieGH24PY4aw|oH}>%?CJAo%OPFpbQuElC{mh2 zyCiM8^U0GkWuO{;8MUg@tVfq>ZQ)`~FJEHE`v1Z-=Ij`oL!NXg(*^3&GFZFPefp#> z&b3k9KADSjD&D|2*$Qp}we8!!g%>k!yjUgV$R=-vtZe!6#EO_VbLM=jrGz}9M*}Hs z`ZVg)r+*-;hDJ5)*rkO4QWmY+q9L+(^X~2YH}K%XhZC1QdNfT5mzFbc?)*9Q=+dWC zuWtSN^FoEW|Nrx1AW>a%Y@zn(dG?c~d!PyhbC_Bh-h-Mr=Woc258@d*BK~bg7+=hAch%M7v6RV4!GWj^o1zm zbR_CmAB7RBcp{4}%Euv%-hDXUiZwz zsik>#{OKc~3iV+GrC!J)LIp~@eLds&HhWe?Xq>O%7CxC8F`lB5Z)Wia*EU1t| z3L{X~8AJQbv(G-9#R?Iu2f;e)tgYV4DzCj-rkSt73Og*Z#YQxeWXY!F7_-ef`|MFs z^~KgycR{OF7e!s`6jV}C#nrZW4FOnJUxh`MSZ1N6lV08`M$=W{;zgLeEFH$zyFR^D zZ(U_Ds~2Ka@jEcVO(}cuWX38?EdQ_zJIv~5EQNMl9>tvo12Wp6p_|2}6|o940FOX$ zzr<9+amOW_d@{-@7e{d($!YpB%+f`O=yz2&{IAcBCjZ6RNGnQXRN9NQ_`+T(7jRr}xbKrIT zblc5siC~9CcYQU?lQ74mDo<9D1|n&Xt*F>_FL(EydgqDsoQz+pciD1>yf4|Dov%D zimIv#=lU@7%{w1a!_P}UJ@v#Qi}3%!1#7=O_cJZ!SGU!6U(>kOj?WWRbo?=uU*``d zS6$|!D;6YZrR7uj0$Zi6`#sUCJ;3l~m;UL?e9j7BVhE@}eqj$`tEwIZEfT#5Qm`Qr zYr({hbFv+%jDtWRnaV;a!V!{iI4pD7?NW#z{RoI`hfVsprJ z#l1Q4WlVAsl%zDqG=b4=nY+@F+PEn$cJXm?++3f4W~9z(u~3;4kddeuJ3l@OO+31z z-DXE6K&GyYFe79kGlfXp0nh(Ws9V$|{i8@vp($^~n~CvGm8u6;u#~1eB}68O%2l$m zg4b)HWELpPS<>ZuHR;w{+Q&Ux($Xf`YFD*%Im>JX#sw~zU%Kpw6)Cw$>Maou|QkCR{-~}^Cni8_Jo$h=mJcDz>nJ6cdnG8=F z*uVz5*;963VnZ6hkWYU0Q*;4q} zL7z9BlHp7$9-|7>L__~wTv2V>)TDwGbyB@3RSSwHsX}yeEj{Q_@ix;W8YrL-UF2Aw zSXMBcHF#Ae5kPgioKMOml*k+BIrFMlhnaJ)e*J4_UKvi6e6z5Ig-Kh4DU)gPMX~ad z)?r^#KA7Y$Uken92$L{pXs6m3hKIofe`519HJEo^5pSjpfO zu+HnNZ5@_QmhrZ?zWpt5gDc$O61TX4w!=$EjgKlc;>|EbN9=mhOdE3QB;lJyC4$bo_uVcX z#XDXm{=p84n8g1XpA;pex;KS!;@#!)C}2V{5yJi{U4Om1#}i48pbWjFPCu8`KEf`- z00LTmFUesHdv&^!8W1GWdQbDfSdo^@uOyvA*O=IKl)3#ekSl}RAQQRB3=!;XPZHZD zFA%anxfg2X#Y@<-#j%Fj%WKc)bx zZ+GjqqazKcC;6%$lnpK?!m3jnx!)Bxe8mD zIik=6PcQ!gIBKMk4z#ZIhT$Z}VeiunkTmY}x2^p$6)W3OGOl8Prn6(1^f-BUzBj%PGUR;o`>#lrGfChq@Lm3rTUgF) zv*Hz7%-Y3WYKB&o8?#w;okc5?wFB)_Aq~7LzE30ax!N;%LDHvz*9o!es^Zy zEVoRa1ugTL)4b+3zqx1#U1&MBN7s>iw0XcyZJw$1OHK>ogJg(km(nnc1X6m@J0k`e9D-n-qVO`r|~o~Tu~lC}#E)ffBy?@0_~hQ2*^4`JIwcf*n5v+Kkdw^(Rj zDkC8e)%K?gRo4~^3~hc<*a|bD^re=lha0FaGh9U;H}XxpybM zbt_qV@*3*-fSX?3xTl)JhO8l?xf}l@=AUz8rLOzEU)fPurv#v~G03(NNvtiM5+xvZ zY?=X5TZzEk;PF}nW}DXi--BIXa|GM46`KP-AmWUkjyPV8=obl!poEQ=;Bj5GY2g3i zjh7fv;NZm|p~y$BaiHOqo(ncz=dB%$#a+6k6}$Z$hPjo96k&DD+e_4&_Bl^B^Z__{ z9~Blv_Z37vAi^$eMm%WY@>C%h{=>fkob{Dq!jVg1FqX;H#qGfs?=2JbT?_I_95Q)X z#WjWR-Nc!VPxFafW+@-S5fB<47Qhh2@|j`1U|+(7;jb_v%z;MvMWQ55A|)c%`Jvw( zMc0`a9i&a23ld#{T%8WChYy{JdPUk0_1yZYjr@6{n6wwh$^yQ0V*EZNk}Y) z+AMmqT#LLb1$%qDuzGxRe&NR90PV8I=v9R*2ad247Yb-@m$ZTr6{(M{*~p?;i50rpInv~Lt&cZ#1~y+2iT3x+2y6y^$`CMrQZZnn%yiQ zTtXXR+MwBZppy{Wg4GFOdYyw|&LUN290_I)?v5_PCE@MPX7*7xGR-%B*bLH|iuGl? zksBW=ArG<6iK*s=EG9kbPImAhcIabE@Z+%D11%H)02Dw4{J<{ULqqr@Kte=5(0~~f zq&H~5a5jJt=)n|LMm?Yb88n1BAiyaYggXd zK5WAeET=*==W}AAc9JKaQDwkMC4eTylwC{i1tL!j=xDW}V9;by@=vq)OCr2CRU6f<&kqggGq0cN#>ku&6!wC6*( z!$rm_MiA>il&Y=bs=}~jl9i~l9;kxW3u9><{@`R}&7uEeFlbjW9JF+q@jcmuI>od$ z<-CL|A;OPOD5ZrKhP6f(xw_dJK5JH-Xo@OpLQtf=ilK|jD8KfrzX}(P)~JmZ0vIGJ zp!y6O&_PV$Bby>DqIwid721c;0UcbFqrO$uP;5t))KkG%8a(VWYE^}NY#dlD!#3=A zkZeAMETK|V#dg)nrq_XxEX<0jh%|yNG{Yj4!7D5RA(X*6VwXrEsy+qnJ)x9HF<1&- zCO}avL>aA(>J!o8rjQl_K#5d?ENvB8?L{Ff)#@l6K$O?MTgMiav1JIQwt%Gu3#PIs ztTZPM#7Z_qfd*8-7Bu8OEJFj>fCe-`6D+4c41@m?6o3buL98?<004jin88781Fil8 zthj>)oItDu?hHtP2i!rdumjy1fUEvP;6?#)p20i_!whJE0pNf>Bmors13N4M3KW3f z668LZgKz=>0i42l7DPEjfdtrXL;8a&oG#&>K^1C-KbS7+#;rV50ty(w2aH0j&;tkT zfCfZ>2<*bF^zQH8?LGi!;sOABE(ANQfdn+b5;VX^)&m@LKm))4K=y+x#BK%TC;N7Q z0f@je)WaHdKmlC9DJZA#%76qA?j0Z};wr8gtZwW61N-*v4;Vv1yl(6^Km_NjM=!y<#v{67jL@>%S(k68mew3M`kZA9lUvn6Qw|Y6#GwVxy&4kuFDj?I|zP zh^HYYXeKF*a8VTt;9MqVs-5wOs8@(sQ3z_9t-W!U#%!foAQ&Sf8@KUzxWRc$f+z$s zlQ_bY5P~1aF*sgnXwDepQPS6b*lFV0AMJ58{;4D5$evbSp=K>5qhpSQ9z2p*qH-Q0 zx6S9VNZPKguiQf^{Axk0?hEXLJJ0|OtO6>?00~T?-fjUb-0}o8G+0A>?!z^BXF=?PKVU)v5M=)_w}CT6!a(qY9ISvTOhYHY$~73k5!3=MghD?Y zf&;7qG3){Z?*sLI0WsXN0z5~b1+)P&{K6L2gBmyhC)9!^fCKezK{2cXI4Ea7BmzM%f&mSQ2-Ef<_*7-V|9CzfE zCR!f5hd4X8K|BBAP4^Q~JFnjspvy;cUMhA#kI zfadbUgUXqB-GSI3$Xg~oR{K1pJJzRqXe1LW0I|wkY zK}dL&vo42Yq`a4ahS%!F%RA*3M7>k|KFE74dmoBVIOO(wLHNTg)bsBCL&m?j#)CW! zWVo*aD?(tZEC0iLG6E|j{K3;|J&b|hYA-AAd_lbYKQuYY|HFU#yK@=@10Q`u!u-6y z{L>@4M1(mk4f?a%q&KNyUyQY3yB~{)l|{34${4gN<(b z2)ZASj|~f^igY!Mfdgz|#?w2M-@83TeEjF9)6?p|8-&WQe5M)$jUxd-aI-cr+`fI{ zDrs+Yp%iw{MmLa2!3#42e%o&4@1V(Ru*RCQg5)wnF5% z=W7CF(yVdg2JWA~Tx$$C`Rep0)QJ0*C3ptY;bC&;CQ_Np0M} zftQ}`J9zQdz01%h4tn+w@u-u7(ruDj3vUi?Xy z^Y3LZf8V=H^4{R#=hxqvfB($4C<{=)0SOFhr~(m8P{GJ<0ZoEDAdFDL2`Q}5!VCW~ z%uvG(IqcBG4?zr3#1TO}O@d2MOi{%ZS!~h87h#N1#u;g>(Z(B5EToV)bi@(GM;kG=4Qi_A;d?CVsv#&mhM1_BF3Jd{s2Xx&qy;=V2`YauA^0DI`I3pI zuJr9$!2@&t#~l#Jh={6+5*r!{fo(Q;A6gVhn5TuKa)*OG{<-FWsJhyxtY@^2S>}#T zLO5rCBz}hClLosuDTrF$Coz(g^4adYeYVWMy*bm*@4o>L{Insu=mI~%^&{Ny7Le869^I_!>HT=VSOE5q^3MH6rI_l76~_0j+7GyU<~Twgsu z+7OR@J==K~jql(8!&~^_B|DJ#)iN9reiZ*}p{3_u&^d%=zn&@qRwPm#I7T??wM(mx|Ii zEc&spQhPdJ`M?(@W)ZM_1{_}m6-YrB5$aO;vlIU`$RZ9pid@~&R0uBt3Q$~PRjQ!I zs|djc5_<52C`8~0bM?JlEs%WA%Av1zXu}&Ki-aZIl@Ke4!ymTDe569+wUqe4ANk2! zPfVA%mdHe5@o;-r#8noZWu$Y#>ooJCm%Z?nysw1iAKn0gMuz_egH;Se1|;ChG6(<& zVz@#BB-qD2u3>;J0HYETaDvVpunJs+!Y13G03dFWi$zG_0SUXuG7Qj!RS+W(0TabB zl;H{vnBkHJIKnM{VG4g70%e2Q2nbfNid;QTo1{}5~Hx7IO7`b4A0}|#-I@@7k zLkb=^XD&u@4{cb28N?XFR`kII2UtQEtawIZ@S>NA9H0%lNJtJ4smM^c(qoC7r2>qx zvZXAhZpXCfMfC=}-}R289UYzGUgy#B;7&B%sn6*|%9{Vy$tR`ddBTup*E`Nhr#jaO zT}xLJJIAq9bvVThNn4s8`#d3}!eOaTb92l&W|$URANGujRF% zdDiplSHT)qv5xgZ*n8qxQP?CdT_Sz^LlRmG7$+oAQGRcQYm2&Ps01pIizw8S_%h|z zzJ}0%Y{lUE?z$pE$!V`3Ost9;)gu!Q@Ubc4AY(D;*vi_Eh?1qE1P80Z2F7Z#qzWzh zP^BtXx#|^!phK<@1=`If5sOF);%wQf#3VIwf_L>HY(IEf0(ucxbaf(biL0&MnhUwu zQXg>L)m#p)D@julu9C=T8Z*}GUQ;C=zm{2wTJHa&98oAh1&+X#e_$gD8aVG34C40V1%1XT$>z?ybNV*dkvUNT2~Y2%0PD zVSpWIAOa%Tg+crw3=|aL0-mr7dCiMnw&ZLk#muTjlZmo_$fFV?{y;qc!Hy-M000eu zK}45Q-t(pxBK`P;1`MF!oz!Cy?u~#BP63g6puxc|^Tvn`po36Eq#g|}fCo%WwuqQ5 z5fw-=gd>7q{gT0z|LC#?8t{W%XiUs>d-0v`meHvC=c#@6^KpRs=hlD}HL;7SpD`!s z*Q}Ir>Nzy!W=fsUg~vULHjPlf(^E^U#&Q3G)~QoZ^XN^drVJiss_ck5>fr2|Z{Ef8 zt0!|+SkL+~TkR@Yah+>j@0!;UGAnL@T`L`>femcXY_JWhCN`7-3~YGPb?d)zN_YuWrb{fuiZ3OxW++~oV_tbr@I4qmm(T(?y?7)U; zCnpbfxHn|;J#BO!7uhOgAvLJ+iba$G4P{6}75^#OF)l zInjXv(4kxG=(K*Ztanm$qvyouQosMpQhHK!ty`VvLT?OTtPYf=W8LXx50IW&-5FJ{ z-KT_Rd#G!797ijaql$Zbq2nGJ%h5eQk@kh>Y|3fAuRT3<_ybDsP8w1F8PkXlP3saL z>cOwB@r#dqY0~bWoSU8VIDvZSL0=gM^_ujhH~r~D^y`1G9!GlG_*vUJ!0yewi-$FB zbuIOJD;^evf7Lw_8+)Y&ipkrD9aCiCUD+?;>iA}IRPhsqrqMp1+>wHk5}`jT;a?Vj zo9&hxG_G1!!O+;FNv7Ck$ba_r@)^ zg6j+gNDGI6Fv~-XA^lwp?FN6HY|FF>ctnCkL>kQkESy1KRT7~>( zX!mXlT>Nhj`S20ZC0wY>5UJ&YEHPQSkh#im0PXM&JrNT95B|Dn6e}_R(8{_f2mwb! z0n=y+Y0Uv;5!RGYLHhq;5CC8oc@YA{>289i7KM>AFt7+OV+fIPJL4Og3!159g9iK{fK#c>9ku#2P7_sUW zQEA; zCHm6v6FUeYjgKPlhxq!Zv@#M#kk2ByMG#F9uaG4at!1)Yj#5f;xCC(|QA8A0ND*JC zwaPCgCuOo|@(m+VCfBe`kdG&O@(>T@w@i{!_zzP`aVc#D6&VE-UvmGf#3`S0xTKPO zTv0S&F&^tNEXDt_c!uX7qTwvhk{P67EZGvziqRO8F)n{&IFOMp$zuf}$1bUn8{^{| z$;0me?*%U{?_|&$M{w?#(bNdD8)>jUqA~G)@b1{L1n=%0Hv=r&@_6VmGl!=M_wh49 zGc>QqG*09nP16c@Bn~;HPU>nY53*OXuqv~}_n;Dj=I|#^a!ZU7M-tLh7Hc;zGJJ3o zCL!`$@NhV31o?~;{RXioKT$#Yq-Qx%)VxZ+bjw-Y{1#ZzjlHu25g*mH!6s3jpTgt{^`zLGN$ zG(mS_GZp`|L5J}zi%>2lbkU}b3C0iP|rm_zer5C2u+QJDwot*SkX__ zB|z~cQiZ5MLE}JqbW_E0M>+LVIS)cJa6(BH204@i^%8Kvkut}F(U36(?{e;dLqr90 zG(7)wFB8+Knkq&GhX;pH9WkvP|7;wQ@f=HMr*f5}Y&3X4)vB5mZ+tXJrFB}La7c^v zS~qAV|lYFAIQyQ`$`^WVn5?ud8TQ#GUa$c=3UO(kdvF%^|Dkx7<`xx~_yc6MEr5RMg4G6V;$}?flQ%!ktV&%|a@iY@N zc0cI^Khw%SqjHNn)?>M4D-m)N39wz(^HSqwUbrh3pLJ#*&{JvlW~)k6Gp|&6mPC1V z(>#!Jpiv!T<5mlEMaKg~Ujs0;F?A|!2v77kR`q8wlxlA#-t>SkO@Ux|DCl#mUomkHteo0 zOH@D7H#KM#bV37Gp%!UzBUo8gaBwgg?H4uhH(B);Yt5JLDi44IM{F;HY>EH3F>H2$ zeIi=fHi9MCtK1fDE!eVBQ)SV0wz|g;`WA9UEB8DYBQw`GMObjJjc`X8Vec)nMp%77 z_;2A*5l}LQWztf(L=h5Q>iNI4If-7YD(QhG#4W1dipH7Vo$+5cnL#w^W0cF~Rn4NYH>k z;{;JvbTsFENh5wm!&mpRl2Np&Fc~+9^;b!mIgV9WSEqj?Pk<%QF2nQ%KHv-qLxRAAy;dx!9;L-VzasE1?Wt;T6Cj4K&V8 z<8R*Px#iTkR^nOT<_&k_El3dB*;Y2<8u}7fkD<}cp(A#T^^Fb+n&w_sUSbxP3xsBP zkrxfX41VG$ejs^)f}%ni6GnO$OZqX~K?uZ#mlqT#93}_4A|9l`WoEjjfntyoBo{NF zdlAHH0+}*cn$Dtvm%o?QB6&iW5g8}B?OHi8t9k>gk)u5MGnoH&M7MgB^|zH*83x;T z15^1KgD`)`IxdOUG<5KkjpLSWI@ao1GJH9h^?I*0WSEP&m~+pIKX^{a)r-$nv-Wnj zuGC$d_Apnm)Ks$}<#4qGhXpqNjB64c zK@>#ch?DqXFFJK$H@7slv4;|hOjfZCHMvqd{zlQae><&$`-_L0xPAAr&{&Oy=N`mC z7l7dt761@{p%|XQsEs-&?2JI18@i>Nx~)6AiB7y7Sk@Ssoe;_($U9{!hL8$j}u1Hd;Y(p>)#bOcCv{1Xci_MDH0=no57cWzY|__DaO!yNW%7hGNUvxUu!XKT4(7Uz&BWH3f4 z_+b%DK)=j@AH2*1nD-wLW+|{?2{fPrs=zS1tOE={1fIbhc#!~1qP*w}zPv^lW&p`> zz#QcJAJ&HK+@@}53*c_(m!l^JN?Vf;3F0R z%Raypj3Ut&z0o6r9oB%tmY@NW`X>4u%S2!lB4XK_oh!_t0Cv&R=>Y^rKmrWl#~K;G zqe{P__M~K|!rSgtM@?xR9<4K6q*f4=HCd}6Tvhju;pg|laq6v~<7?g5<6CNfjl)H2 zc|7R)!yhBW?|Q^dJm!NL#Z&yR3!5R^@b+di#&JH#H=CRp2wpY!Ztqa&mt@EXvdDR} zaYItFL2k5;do|k>gw5y288WnYK49fMDf9nyDz%=pMHe|!YgKH)Rb=~EioSDq{$97< zOVl1KJ-h9rq_*D_i{zd+*Suow9_;ge%Ck}{xw+0e`ivIPm`Xh&FaidOp%#q6A8_Fq zh#?XzJ)p7)1dafmI>2S>K@A*$6KWxxNCFV7K^pd9XkrN!>L_3iA(4n-6fgpz6r&`% zX3r&}6q@N5pvfcXVVZ~m^`l0jOka^Y;jXVrADF;p21*ZV;h_nfS<$h#Df+0Tz@28mwR|`eF4~;TIwynlR!9 zB54ftqVz2v^8v!iK7C0XSo#Hr!k+(s3>z{ec;i;CH3t|m)V8YFCk|%*nOgwJnzViN z3~bSbiV22&`y9G_2{We5nKWzKyeae6xt%YzeB8&a8 zhaZD1YL_96Fs^vwj0?JVBaV-}7-NX@tw*AYLE?zyeMNS7WPLR*nO%-f@;IR_)TlyD zGp`WBMvYhoIV6owUU;N`KaP2$i}sy4VVXKBN#%7zzR6~Ta*`-!opzc@W`9Wj2xOfu z!WgKJgywl-nT+~*p#)5^Kq(6#c0tm)?3KGz^{%0o#&!B9)4+QY#f`z({dGyY%# z!9Dx(Z(YJj2p83miL02`rVm&o%@YEKR#~PYbr)lfF`brG zlu^xe7j%sF)znxcX4TVQzqQw1nEW*cR%0h^nAmGu#uaIxeRlQRot5GB*lR5|cVcea zjTmQ2izav8V;%pE_-aHi&N#a4HV%2@ukkjNZ_{0ldFGmL&UxpaFIOF;qK{5`>DQ@g zW1NQ;xZ|TYD%c;CIr3?s>oTHlyMU{22q%?p#xDDySDKz;>Ut8$JMm2xs=DwTj_&4v zxsx~h@T5oiqmfNoc)g-@qDiFbNAmf-o_AVLgSs2oMrYxC(rCro! z%eq*ND0iu4F2&-sUs9!PdO6!)gh`jSA#*8&>)KMvvdp;j4VKN+j93I0&9qE&X^P>R zHO0cp#BC~--s&~MM-fw{w)euPYiM>8;R7WeN5-31%iS~7=8DP>WN_iSlJ3Wx57y_V6 z6Q#hL*7QwDeQ5$CBvlOQucy#kDpSD&z^e8Sf-VhfRS|SSrDX6@nHr}RJ>{!^H1Zy_ zIDj6afenuQLxud{LI|t@Sdo}ZSnZ1IwyIc1GN7>``uHL{X3&v{AyJ8?Y9ctE7{z<_ z^#qwrr)O>QxJH`tU{a{py;vfSN@&0VAWK#ngUCj6m;@QxU_ud*H359cAqSmZRjdE{ z2m&+oBan)eg9BC(4Ot-4wNR7;XB$~ZGvLFofwe|A2D__k!R#fCWMT|uy9L_XmRDUQ zrLk%l*UzfgA*&3h(Xt6&S6a<*O^Mpya;ePtjwP5-W6L)6I~1y=>`bY+_h@ciuZeAQ&J(LxmA#>-i(d@m z7|VD#_B^YNZ>+q2cITiY#qo9sDk6(M&&LwgF?V=;Q6h^pt4e**kbS)5N5S;TI9@VE zu`}hTmd-~S-LXhdO5{s$`Kwmtsg}DsC^BbArDqo1Oqu-B^TpK0>SN!Q-uM3s@-f*; zhzhe(2PkFz_1Vw&GwP8A-DXG)2+%>^s-LauRXCRk&Pg4spaMPUN0%q9Nm=U#OWZ*u zHgdSi+DCNv+NyqFB8D!x#sS{dt_8qa)#n1@v6%ZSS|~smzx7~T-2nnJFl1ZZdg2bj zXe?&YaK+4KSI2%GYL`Ui|7#q2x11?eF-0vm~7(8>|u)? z;&VsEkm%C-84mH(tHGs^m^6~u_Xvi!iAY{pQ`;gQDKE3r+1?SOhQkaW%zXXkP5fSE z!VTBT#Noy_ivMyh6)%c`ePK+$^m4--_Hf4?9JdTJ_~c2!n}VyUacuvxyecw(<=*7> z&7~+@HK0DY&t;P0p9}pZ>ul$YkB;=DE4?{2*0j@~ejbJ6b;tyXtuL4dpFHHE*WhXz)#idu+b7c=96L3F{2XY3FLx=4jFfDMCH3_}JX0LNmj z4FVKYvEE4RM7{;FlyE!u6EmlTWU+E+aT&g3H~h7P5!QtD6*nYjb5+=I9~W|C zfN~L6aV9r~Lva~);09ROacG!LAa-ABn1=UdOE;HcNr8l@(Q`#8bU}xQLRWN4=ZAj? zh)LIUrbmc$R|ss725g{prWbjL*ad8$h>k~S{KN)b!3O_vAc>QBh?SU#nO2Bc_6U$z z24HZBn5TD}Xo;TqiFOhPj+h2iwTd3nid~Tg_z{a9Vh64Wi??_>xk!tg7mMwq3X6~i zXix?v!i!~wh+t5Q4Hb(nk_KIYjJy~n(RhqxMt3g42BY{NrucN#Sc{WKWTea8 zBx)k~5Am=F8c+Zc-~o)_GxW9(*$@R9U;rMFD>DNJ?x>IVAPgu_02lBs?E%M+B z0x1C=a0dg24{P9#74QYlmk1SbkT$tR#L@vy&<_7CIg%A{2BvZi1yCp72DYbdr&CgmowsV+fcLc5#SdUm6ECgBh4DfS64~OKwOtfiZ<2*B8gs zUtp+UVwjj+Gjch1a*i2aFxLXml$bKh;o3-gV zgP4rDc~(Hih^s?(V&)&tSaw-wA`Eq9PDh;Y@jJ(foDWqfVMmA@rJThhjulir5;8v0 z6PhRFD=`=_x)9 zRC)TzKl}-K{s}#RGJ53scfhEd*+Gs*VUDbcP8(w?yP|8tVlxJ_E1gwu(o&%>u`0Im z8a8uU8`=;XilMN%IJMy^9}_esI-X#7doP{0ihOZGa?#; z@W!GnDx)UaIDM&_qY0P~=NV7vncAdP0ieHb*QJOX)zo{ON3aS4OMW}K2XfSoDAH|$vg?DpyWOgT@jj}x*g`SXV zo>JyL!U<)FmK~a)KGz{sUQ$%pSZR$1R*;9P4dfk_XQ1~KdON0hkjksVN_F*lbqM;W z*Rh~Q(V#;o4$!~^|FSsi5DmjXZbV8GPgJKSRvW`bt+A0vI3W+w01Zlj1T1=PE7nNe zdT>bUmrA;(E{8RRDH*$@q>xD%PO7GZ^QB6trIa~KU7Ab(I)JxG5uH;0g8CyocWLvV$N)*rfbN)aJ1|R}J zvp9G(mt=4cw!y6&yMB(OSF^E@Hen7>!>@xOU`mRwow1orlV5--nOpi8jR}Wi)38e@VNd~@7xubKh?(7#8Dt7y zrP*;7t2mjfUK=aCM%ZE@i@eDjh$CCF%}YEBVx7L(V;!=xZq~Be!yZU$DA!B9l*&Ib z3ngq9z0MP~le)Fhn|A*KL_T8Mt3aEc(POJ^f_LR>tenceUgos(vpj5jJm(uAu{x_? zvUvPkK=ebZQ2U=>tH1k8zyT7haWbs?xr-1Spw_9Z&U*=PI}~#JbGm}L#S6l)LA;Pt zq5fbE(GU&HfWpxb4j&vj*1EzdEDhlh!X~!4NZ7d@$E2`iuTB`HO8B`-V_&xm7o(e) z0qYkK2ZgXp#54E9%(R)ji#28{uNx+Z6Z>IJ++e`V6Bt{=j5EStyf_}Kyk%_0Fvh$X ztj3U1y+$Ivph_ie96W=1zeQ$?zGJiWYaU!DwpmukQHIBZ>Sp_k$J^7udrZg+mA`c& zs){VB3$?#}Y@Yvv9La&KQcFU$@p-lM8NUvURElPIhpbh20?J)WCX!dm2;3%a3sq+u z#}}-|8r%XLEXK85!(seZE9%0mXUm^;!#kJ547bC=bh=bA%z=reRP%%pOBWnBnn>)0 zMeMp*6T7&p#de{v*Ss{+n>1m?TH%f;v5#l5^P=xn@|bH?rL&hnJTYb?)< z9GsmRQqHNz4I;-Ih0k@|vq>^}k(##RW1P*CzC=5X1(e77lu_F2PloKzy-J;`V^a}b zzu6Nf;j?y?Y(Ae%d0quRTV>JfBdc4|B?6qa4~@zn-N+eD$}FwQ`(Z%&?7;mQ(yGW( zQ6P*z`ipxcf)IRsi3Kz^27Q}1lG};`R-h6VYo5fv$#YZuv zq`SHTOBco58Qko-Qcb(r3^-X$U<-T2WL>Xp9be^a&Pm-kM=jT~LB{Wl*Lgi1@$A!m z{W{sp&vXoS^^8)-3ddqq&<-WoIL60?tw1#WI>xC`nmW?d^Rkv*(UmJs6ACUU1_wfRSJx<5llU-EK_EyXO8D6 zeyts{Ov`nR+(XAM%%BU+?cC4Z+{}>N(@joGJz`BwV5Qq&V2u>V446ht%+m}^^g5b` z0nPuF!QFKs)+`sMp%KOPI?iJl-%(M!wuIKm1lQ+G-L65``@I{-tJeW8;7q3!)%Z3Wv{$qASPUOe>Ri%gE z*kRm3{b`@o532BxR#Xp&z6K1n1>WSDPS4WwP={@Le4J7e{^<|i2%$dEqaHutyNc9lsWaXq6IJR5{fT=Q z>nhHOqFSo19=`h<>n^^E0@4HZ!3t$|0ZhSXmk6VY%E3}NPx zuJ7og=HbNVUMlBfT{zmEnE|g~{7P|jKAMo()k*xA;yo6BuEPc|#AY2C_YGi+UKsEF zH5e~UjlS=*0qG&nUXyO=Cr{~ot?4TtApHRb*Z%8ek_KtOjN1~W zi@=Q9nV_2(2W8NVRDYn`NQx;9?YUS6ZV)DJf9ttO2TDJVK<({Oensqn1~mzl?W!Bz zpaCt^074LxGhyyBfiNfV5aIq2ZQCZaV&Y>v~0ezeABrp20(eJGE z?-X0;4Yw6^U*Iqa_Lj3Q3*~|Vh+F@}jwM^x>{+yD<8kp2s1~U$ z;PfSdlGg6sYYPAY!v)6xnSE*LQDAg;EI&CX0+a2RNWrtiY9`!UZ20cJUnzA9jtUW!DL@PTv(b(WT{QnBLT>`8C_E#bG)|lRR0va~ zHl4}Jlin0XAX_M+=Aw)el~mME@znCum9W$l)|hO1RUlA#@)TD}WxdoWUv~wTAYG4D zb|I>U+lni%z-kdKcR&EFvbjd+z<>`z8LJ*RG-%)lV=zm=n1A{igoMECp}~yGwprj5 zu@HLzoPWR-mt3*v;a~?1A`oGh#mb37f(qi=2QdH|#vxt<_86;Lzy>RfohURgV1;M$ zc~>lVIFOj1a0~F@j(;$FY+9CKQ?azN_DP`ta#U;iW}I`@dFQfh6Y*!>JQR9p^qPB) zXr!w$`oR|d>q5Y!4|I;{s1u)yHZF55%3*B(y0 zr@PzQxVGJvu^_B5y@pU z*L-s)x$KDZG}WASrZN@X93__Uyvf*vnu_D|(^K!0^^yREU2{3}92HX91+DbgTuV0{ zccI*jlFQeDKUPlVM=HwJ;WMwacY{E6^>mvojg#10alcY~ktRX4B2_Tb0D?e$zvz16 zh20*|P)}EXclHx)9@jg;m#L`uyO%yo&ifarS>ZgZD_1=iwN$+Vu)FRDW=hhdw9$YAQPDpad8Y{M1laP zFc)MJm$;YxgB(vNgji0K8k>Dljca5h;d~~z!2L~*L?h1}6;#K!sfTZNJdSk+#K-qE z=Q>aG8z7~Vps#@qKVvgw)6VwCLN<~*9FpX3^tK-4P_mNd*^V6<6t_q&r$U>Y4jctn zz&57RWvXQ5YZljn##v65v!rD$ZF$QaVa|WM&&OSX&N zqL7KD)hS7M$1EN(m)R2iIa7AZgv#@hN6lpajt(k_y4|GYBu+H3FPpw=l>O2Psrj9$ zn&=!9u@VJN;{io{mq-;wSmg%vZHiRxTuQG3YR>m{b0wKtr=F5kC3{9Hm=JY}FEt0i z;0Q2UsJz)eupxs6G+`8hnF|yGGZ=}PkcktMA za!^7Mwu=T%_=m;zu@84S!5^6T;8C|h7{nBjGeGWMYZaoIhGck&E09DH#-?#X5HXIi1w3(jJM}7L)U0PJQ!{ue0UMJ7uiEg4kF{YPtN2fD2mrBp2 zCzJS8&L`!rx=b=kLxovQ=uQ`T-c=Iwmb<;3kQbt=+wPLc8PD~KPM+^Q@BJFp-tr>v zpiY{nllGY^Rg~`)(5r8*9Kt{6MijnZIxv2hso(;WOVpzF?>{F1`^oT6f<*H+tMbC z{{RI5%5X-q$TiJ#rnAoQ>e}A0mb8M^vtmW7T0%w^kdWJj_blNv9t>lsdDE2Y`xt!6Y~)$C{^tJ)5R zlJyoms&LZpz4>LYxZ#=Yfee(O>^ygQ%dIC+jL)Cu+iyV+{OxXY&%*a>FuK=QVSn># z+3W_myVsrTO>Ou$9hO%A;r8JT5ICWvUVYa+gpA}8++!OAkj5Cu5DW~sxDRnuLIVykh7<$y<$au757EE| z2h4DfV63dwtNaJd_Thqt!8NW^=X%#?bLUg*rqp}o^Vox9G)@v$&~|H&*@xpb<6KQU zisqwr5bNmtM4GRZ)U>Dp8zHx+2b6FNd}-GXYPFBnI)%4N*g=$Pudk8Sk!RzpX?=Oj zXFk@pMtJ8vAKf-#SHixwcI>*uscmvodd!ScwZpr)(w!HX>L~O|MN0YI93=Ad7RDV1rz^=(XVj;PnZ~{`H(>vF0c!FxPV2tm&yPtdXa}g zsG(~hfc%>|n6em<0RbrJ2S`vcd0~WpkOOu>3v*ZiLHHP-qcRh7sU-L*mJ%6tv4Erc zsxza!)mXECD29eXqpfp68@xfZ06WLK4aPGp!0W+LJG7#ak4keJv;#t`V6@FryS-{V z;lMja+PlBPioQEM$0D^JbeccFBqa1ZNeZ>K^FqhkLEeBr9Nd}7J3}{u5zT8uH+)0O z;k@;mLpm(~rqDB%VN$(b+BHgXJ#Nz+&v7<8QMS^vsO}O(ZOflOT$bm#r=Zw2^=p#d zyA<$>MC&TPN2ERCqOV~&K8y0UZ<{Ae%&&qA3Qy#mc;hEk`KRPTL}VeqJruu81V3Lg zsC}ETPwc+zYaLjuLqTc3t9ZYiVFxb=1Yr0Dzc2&(`>J~20uitv3__O|D*y|a2Yldy z0x&_68zFW`f+B0iXKW#K@s}?EhFo9*2Y`$lT7_ZQAs|z_UoeFyQ?de(x+=p!Q8)%= za0RCevIA&?Vh{!j*n=Y?fTe4?Das2#z!x>V3mE)|GDrcpinE5SNXpZ}9Yn&vDLWuk z!aGX;G_J`kAaue>VnRbYEaGr9NYf7~ERHH9Eiq)Rx%;fb`@vGH!tWTR9wfuvFhh%E znKb-K#bHA@EJ~w1%F7XsB=JS2Y)WZ6is;G1*F(5n!wJ$`#9oTMbmJ2@8AZ^`r<(X3 ztlXtWyq#y76R%7#hC-Hh8p~Z8w{&aEw9Gf)i_25YHBiI}-dR6y3aEi{%VnWH>w5)4 zU<1FzMXHoVfy1!Qv&COozPZdU$4m;Lh)kzE2w=1dVbmFRKm!yg0B!+<4l1$w13_?+ zfN|M{u`maxQ@LQ+qL@)B63PpSInC4*3wBrn6zDM+K$ny;m;$JPBT%4vSOam1fvy_= zt7|BLx)=+K!3X0E&L6X?MbLl(XaF7XmUyU60Ehq&V1#`r&Il69vv^3fkTdd3Puapq z$J5Buni}`y$O(}#-N#%f9TOb<&ULjLr$`ee|j zVFQ~CJf74IpH$Bi2}%oH5z9kL4((8+l*7vmQ4wvOHlc$wm>tU$6qZN>FvuFTOi_oj z0|nmDjhCrQPAS`~~)gEXLnGGGH&{5(*ZQZtQGKvB~(^}IBt1I8TxQ9a4b zs@P1lDnPS1s+74ov{(#2O_`XvIX(^49P`u8I4VK~)B;3Q3sn(j&;?1IR7#apX2?)X zr7QLfy92Enk?g@w6&e6pPzmu!BqX#0p-;DgyW#*)mfWNPRgRbZLY>se#ml3?(=$wS zPeKY1QZ2O!9h^)B%3)=h4fRlDO;*eUQ95nbW(~w6CB#B#1V4aEE|tvGyRJ9IHSM}R zUsSef^@BVBOFGOQYBes=bhJyH@{dhyWvmSGb76 ztT(>I6M8MhI;@|94U>K2)|Q|HeH~Fd&5ErUpoS|}i%l~Oy;zM^rA~(f!Fj=ov9oMt)xmwguYC<+C34z z>N-TT{Rwc@T1>=Cxg=YtdS>C%L6+&#bnrxXaq&rCsmxcjMzmc z?ZujSFS=#KUUbaIRhG)6+JqwxJY8DNO(mt>T+hv!j>WT&6`GM{Jd%{7QQae(-C0mg zSy2Va4nfu9aMhVT$(kKPlXRPv1=XKLG?N|LwW(E&EF?|iLd`1w+S@qV&$W!sU0%y* zTBwa)>5W6Bv|Q_@T6B$9LLAGjU0X`bR_fW>ZKYiBB?)ic!?7KS^W`P&qMo53Is3zXz6=7md z{^aKsVG_QZ-DSM{1hqixD;Mra)(uG_jLGrXRpd~~C^W3wylILV=}>8gzC2@@#AY9D0%MUcRgn{4&NWBwbVw(PPfY9&7ZYNbAIDQ4=#UhYjiy)W5fv%Rj`!{+4? z=Wg;tH~uDao1N^2WUNKo?oQXUjbn4mE49{>4 z$8hu%?&20@%|;N>dS%Zh>0Xve*ln5PE@8Jj~aTX_S7Jp^#_~AYqX~)9h(H`;^Xl)z6 z<+>C0=;(2?>**ofoDRU;xnl@_|ierb49i4UxJ$iI=C{dL;+4!LoM<-CBMV~^wRHzVAo<4&{%{p`{ z8#-REI@Kyx=F~V)=434QOn${nJPDNa;8yCnXluXhttHFJUVUZr9Ts^UM+jJNeLcr zv&hXtMT!(7Zv6``d^qvq#*Z6!2ZGGLeZuu68PUPOhfu=n!O_s*hp~OZ5*Yi}Zx9LR z_Gp-K9(>z^Q^EPkc>wMocJ17Q)8nv1Lj)1K)Rz;51Ql!n&OYz~kRT4~(Z_{+%?(%I zcH!+q&jOxQc;P)D=nWU0SG8x=0=Rg^ylv7e!Wt6vJnWdIna@nPqUxLZy6JHTqYABkeYKmqTexB+kqo~6AW*M=D+3A?9 zW*VrKyYea}a7_XmtguD)IIOY9A}gFg1ZmW)v(G{st+dlpJJFUP(Uz^Y+j6_tRB24r zZB~UP=2KFi6(TNFK|R)!9exy&Mjk+^`&3Zn?o^0U;nrK!z3#%h6u+Vz$OYG9Ub`|1>YXfII(<6y_^_aj4hYXWtm)P=38iX|S%Eu_D z9Mj1EC7bpW%{6OG6&)D!9JEWeZK>OCz5SN#arqbT`~Wwbe?) zZd|cJ+DLosx8t6>?z=17tM69Q8horn_<3iiWssSx@L&=T>hjO?`RbOQwhH~BV>)j= z^q5kgeVC>60%@d^j!~)h(JO!cp|&Dl{g~=&FDm?Xvi~WV)z2?H{`q&LDywVi>URSF zjMA@oXTaSR>wpTp-LgJXtp`Fdf)bn{1s`%Pph5(FCala^TDs4^AzW;xrth{u=0 zRAMB=;J?DM!5E-G*&GaK zZ3RdW02=TGa4hqc|DbFMDipT&R2CnVRnK`mD+gKS50*9QzN*jufOmqGoifYu)SGNShn=okZt%&Qi5Aqt?S-cM(OXI`s*k<&9H$ z5hcHGhL@rG44?QUMXC7-w7r9(1MR%fJ!j`q$YJHWkGR@+r<fx(l#y-0M@d zHANh!1T&i9jAzuE;w&dQj%I#wPN-aB4GtDdh4rHX_u&l?IKjF3K+ioS3tMDvg8v#`U>ue|9Y+{w!PEJ{LXsxUJ*XV*o}DC(`p-EpRm?+$2Du zIqN_L6CRyh5Ts{4?a?!OGOVL%-pF>g-Zigtr`-te3c<@GFRl6%VBvjN*Z>aapu(Hb z<|!M!qxw?!v@~CS+P8cGU1+rFq$YD#yW7({u(-i}(Nih^xZGwsc6%-Qzb*m0R}=2_ zNH0w9=x!Lq`rbFcJ1pWi13ch@>0n=F1LK=U#lF_<~1V=c3W;Si@wo4dT28xHv? zb%`=YTgMegj?d<N z=^l9uf^XL#0M;{2NmK?$IZ)^aBvi{DM)X4tn%{hrejRTrse4oZ$sTr^$i1ojhQ3SSJbmdOJZx^K z{!8C>Q+oGzZSnc@zUM=I?8l9z`mtNt>F#}&Y~>X+xjyv6FE{W3c$?4fYTlf$roE?c z&3yMe``X|BwEnI1?}I-p1gFehZ7TF9_hjZ{fpN)+VlefKh5hG$$@>ew7x{Zj;UniM z%!^Xw{*Md3v|qve-~9cU02-iJSy=*toB;BLn!(@D4G{w>6$Ap{x_sGKScaIP5t$vG z%k|X#Ss(>Y%oc@T3o)HX%o)_>4m)^3AOOQJz<~jnLFLs07l^>zcunL%LIGI7Jm3Qt z6u>AE2Xh4nJ0wAC-Czz%PI%_G*OoM2xs75dV#z{16fL$u@QE9NRSzUqiS#uh0tMssafC^6-!UR%GDd{= zonSLMBL}6QT$~VEtcL!@pN-*=Y>b~;;9oUX90{I;$AROM>6rZ$-INWWSU}l0RuKYf zR3Ua@0~brH@DoyE+fOIV;ZYSGUBiC|jU<2j<4V62Ro{aiBy9Y4O&Y8c&`tzVnv z<1_L_3Unr2@ARU8I}5W;cGHo9N=Wn;I@*aa$;#EDD&sU|+E%m1y* z5M`XUtmC@4BU=@qy$D%E{uq?e=E_YVa>|%cMWDv$CUJ5Z2_~IvY~UHCQJDo~a+;uB zDd%$L)j*ym22mtOSfq8?QgJ{Cgye{NxM!!iXK2+@ry-twBA(im9eg53Eg8prb|#Mm z2Q%nGfg0$67AP|W=z{hdTS6jYdI_;rlqU)bv_WVKSm=1&3S}Bfh9ahiTFMjb6Yl-f zUcw%P9_E|GVtEnIg>r;qI@GyIW_!V?TXw-^PDy4m=&*3+jv~uvie``sslJhBc^c`F zy5_{d=5G>AlG2~S+?aF!`inJc491D)Xz(V;*=EM*5LrDbl7&oBnIlmRXT~V!0j6Ba zj8$~D<5i^0K8j41NvZqY+?8h0LaIwaYA2aFq|K0LjaiwU{?(Df8JDD|k0Pq|^=P6p zDuy{I^tov9;blTmsESUiU0!PZlpd_alZ*16rJUlU6z21!=!O2Jo2=+S%_3rQX!EsV zIdN$3JpqpTN~3P3ttt(W4(YD)DoPb8p#rOEb`Vn?TsrP%PN?4t<;9$ig_DLObTaET zeq(KdDILipwN9tCMirUL=?B%L$dO#MO5jz2Yg>t{_gPqOM~t3+8QY9TkHe-OU&88!LM)hM z;)Ql9s)XwJ=pM42D1@$Rg)(M0#cJ%m5ABtr^XXTOy5+3WDwODG!4k>9%50J7YOmsK z&Qi;-?rYCFqmH@Ik{auqBCAvtD@@I%Uce@6Vo{d*(3aj2kg1Sw4lS2Dtr2xA9<8a; z){&hqjB+Y%Kb~v;kt^5Qs}u!l*y^hW>8ZSW244|IY(_1<8qwPNtY8_c(-~IH^6f{_ zY~KQI>>O;oCG44;D#LE7mn>{werh=}n19)c#6svRYV3$YO74vT8h}B`($C@2BIly& z$nGA?;v(q(hDyp-tfnSx8N4ja2JVvl?d#si&FXCJ+Ac=$?A_|__nnwhL}|c1hFehM zn-vBd2(R3h7*}`&8z3)N1b#h9cz-kLWIs1wSU~hAzbpl$Yyp_Ahbl?+GhQ zG2U(qyYNP63AW7d4F7D=0^GrQ44ZyXkLe2y5ikGwLHdoU*76j*2(kO_-w}BX#N4nJ zMaB~Ucjrq@QDl@O5|5k{r)v}Eiy!2{$qaE1733={0?cp*8_1CrlSWSb3=IoS{obz% z!*P?Oa2(TdcD3#~M5+LXo?NOdhB`2-a_~SsF6U`qs5G@a{NL=j_g==42>-1*rNSrAzGbz|gaWVUH7Hh2*ArW+Xt(5JAA54NM zOoBnC5nU~_-LkU8xUt^SSsjxzl8kaWqx1hpn2WB8BO}-#iwY=$tUN~>0mI@UyQSp+ z#tH;u?ijehA}egAswgJMUa6{2s*;K%V=M)~2`{?y^)Pg~p~)SGG8~_C|CTZ;YqagE z@;7@l(h5uq3GG=q>rT}&Nk7~US1WTKvA4!@j_ooX1v5(orwMiKS%usy+XOl)AUv87 zGyjw`%XFF&l`{XdH;)7dZs!Nm(RY4y$b@rlJY7W_P&V|z-wg{kGyzr@hgClfI>Rnl zi?xoZ^L9-xL8o3B?1UvN8;Dk>K${a<@3CCpNh1FfK*JLVw~1T#C0)Y`LLZ7>Uvfl~ zqKsM(1NZe1Q1n>K4r3QbMsIXv_i9H!b!9KnEORN8E-Ox8_EA}>(BWp7LaoXF#k6Oy zw9U-s7u(fL6WO+k_KMlWF=uwRg4_bC>AI3*+1@r$6IpetX}bW{%J^IwbuqoN8B$wz zzeM%XjI(tu!|UXTKM+HA?1*8^u2Kx=mZ8&dOqY_aPp*ld!O4GdM@b zaB@R<@^&`TeKt6jw2470x-vymVdFHP#4X<@Yfov#sW$nEIGwuoZI9F zPFE3bZ-r1F8FDA5G&j|Y%Y;&UpmCcRk4Lz=EcaCJj^>P3Pd?>6U^jIC;|L+*XXMQS zOqN|RTsLxLcY@DsZwZ487=Q>^2XW|w6p$7!X?fq4^+x5hc$Y3*)}AKnbLrj+8@NHj zHts%K?xSF?Dl$(ae^Y(;w|?a}VPi0acJlMwVnX}3vYm>7A9#1?FJw3Pq$?w35Ba6D zYx<$_(ayz%k6edeFFD>=&W-j%3USBf@?1zQL!P*_mUj6zr>fg_&e8Tm`nJJ|E!m#T zE7Q1E&~5n&xlIT+HDCs36n7L0#-L(4-WH8Gvmj!XLISKp6k5U6MfpEud5%E&aj*jo zbN~hvrFSI2SF>lfpZTo`$Kq_kFVq2eh`ADcK{UuaSD!n{)`)AaVFZFg(CE96+TZo|Rt>HV8;h7D#X`g8`TT;LnFY$U+D7 z! zytdI32s=EZYrI4adW2d$g3W$hqHdt*cejO8$8Yz?%WlYzeDUvF$zOf)*O(6v-OJBL z%ilydZVUA9H2=x?)SkM_pEhl5oQHE2I$nQB6le42I(YVc{QW%A*?7?ny}>Cx`dj_Q zIeh@ezgp<2E&QA+9J}{(Rj>oZC4mD87BqMeVM2uq88&qI5Mo4$69r0WaS>z27A!cj zP>~|Vh+F?imNa=1WlEJP@0C&jj-;^86;pXYp?~D&I#c5UHe(9%8OEkl6SC^?=w)N=a&4RqPW7Gb`!VwR;zD zUcGzyn(RihDU^Nx_{qsIxTHG@cjonV{1|d%$&)Epwp{ntInA3nclP{wvqsUQNtZT# z8g=R+UAhcO{Tg;`*|S$anSF7{lP+bR*uMQ6_~<9RgBLe`T(@h{xp((I{v0|+*3o~v zDAmhXcI}YHbdN&4MeZkd+&obZ9zFFTWzMH}e_DK*F3yE_d4K;oef;Wsm*H*xxB2!P z@V7E90u8|gIUDJ+1|58`uD>9hkU|GBJQ2kdRa}w9 z7F9G&0*Yjuk;WQryb;G7b=;B19wREGkT`(PDI6G}v7RMg5w6D>3jJO8Zl%StVEXcB>Jp@!6Eno-3K zO(k_y$xmH<71kUrGOZ(zKoY6Kl>8~>0dVFK=Mw|=@CTEZ?zv|h3K;pStFw}2BpxnG zxM!bT6?mp8GY~uJnr6G*MXO-0{mKEaiduk?f0k*spF|)y3o(Aw$YI-D?Y;Lg3Ecr< zu7BEncUyO6(4YVjMyVIygcV+x;mb1rQxM|M2%NYD*4m>Ox3oDn(JIIyeLB##U7jNvduml?X*pVG1j)-ejDz%P_jahrO#OZca6?xe9HB4mTwEc?!(^QAAkDlR&dDif2-7VgPe^jT zH*dU6yZ?^U)6qfi{BXi4{ap1&k&INL*I^$WNXz}a-JsW1Cn(fQMzzHjQw?psp~6%D zo%!Y=nzgiAKMLt;e0K!^djKx~xMLrAOF+yX8lX_OE0V%D<9x)nS>Tjx5hhFy90toL ziSf58m)U2`r$O6w_1|X}z4FH}q9B0?Xdo+HQ=q*hWDkCk}` z1|jsYs!iINJ96pP&Ul@j|-i~vX;FpW-_Ch&8TC;i}YuP zG<=Q^g$SLXnXriX(N7Xzvo!fEQ8+DRB6R5U!Kzh{gIVm$*0k6~y?m_&VN=@}$yi1+ zo)L{9Vw>~W*hV+L(MCbqQsnUFIo`3cZ<{*ElKSL1I4Y!Wdh8vX@^(k(m5z>iGTk2y zq9x=JBypN!WI-hN$bkU=E^m|U9qT@aNx^ASAdfQKA~zW*P(l(@v;$q7M5jsFsVZ`& zWMuG0RjN~^YIm_*)G2w%IOvf^dbh%&y>{gQWK?4e4gi<;z{kJ*nU7x%)D}tB*FI;W z#2p&Q9`<^*mGb!yn*A%^J!tU~Zx~<;$j}B866i&D?nOd@AxU8lqmuBA@16P7XBItZ zMFmaqHLGb2K*1x>ol$W(MEqHD2nwFz9JGlE1yDm__%j^lkUQQ1k3utYGAK5*G#>?N zaMt4=p^ely!$E04f!LdrA#J5AQ;t6)Hq3qQlZ!XKDHz3=MxXu^s6iF#hSu0iqaGEh zpUPt>9rrjxGSZR%mxPoblUfi*c1dznt?EFo%2d>~5~-r}lUG^!)IU~oQ<+=dR#}(U zuWpqfZN=(a;d+Tz=F+Zoh3hL-nb%M9l9r?@UNdHwyGypJu8G~#FGmwh>MhJ#M9Bve zFaVBzK;k8XSzo%q`HyR$D_Yq9q4gnC{hwW zG-(%&*~~N=9gdDhhE2<^)Upelr-jF(Qf#kAygOfv#7Ac>sIPrb15@TI$fn87Von9D zMV<~7!3kFX@Pb!VRK-3R!V$J=A=r=xHrP?Z13^+5+>izgXZR9FDgzkOuqd|1FyRE}0t7gG0u-HuK+WSUCpfn86LoT7w*`LZ*0zDpU#uYk#@JP+ z{b37B03#PxNWd=MCuvik8Z-Y*(0WJ6-++dUV!83pM59(TSJzO!(ycBH!5iM|)C9dcA$Q1@HPYp7Pbjj3=|?Fty^nH4p#T*) z0#W{fjVKVT0$Y&E0A(P73Y-BkoU{tyNVBp`xNjJ6aGFh)NVgzwYA`l4WIbB`tg*%NO_os>|5){?%bYx z2EjdghK>8&saO5#(UxwJzaI9KlViV89PhshWZp?l+~epr`>pQ&_DV+5!FB)dRbh(w zVWresxoU8MpVE_H6=h$K8vWiE_W974B_-whdsgnT`&ES#lLAXB!Nwl;B+rP+6^NL# zXr*58%1f!~QZK91e~$fK<7XId=+?+d0>`;^rpao=V}QaQhhIu99z(e1~wt&y~V(A^3_68OaP4BFfG$2s2FmFoOMT&@P?{ z509$`_s|aotnNZ@q!4ffNoKoTs6SE=WDc(b|GBDU0j{_Z$HX0BF zKZX+Z?h}{e1V>5)8?glGD-v69*-8)w7vvAM<`wY;^>~mLYjFpCa1L`(7uRG6*{BGq za3ONf7xirm9mkSlCvdj#61u95Jjnxo4Y+)DSstzyW4r37|I?EpOsSop!AH66L?GB_Muo3mE z6nRaejHnG1H{B;5gU>J?~-OPUnn7s#u9~% zhXRBnQ%a&DlZvu!Ab;o-xyvJ6C^HQcBhw2c4e}&W@*HGPFZqHcPctuGQYKr|HGhgG z-%>Vb^KX1lZkp=hu*4_brrxeH7-!EnIfW_rgc;$+8L5#|`0X~Qa8Ic6Hqj(F6XFYt zGEk!P`e2DVcWF+>(mE%F9esp5pHn-1q%CQajpDK%RZ~5=CNLlSE52ZDP|rQ&dHT@+m*1j<}@%JCnyYyV3TLlSc}tMJ=T_ zVZ|7gayy6fRVpb)#c&#jbPc1?MQw*iOUFoc=^58#EP1r7mNekV@# zb4mw&`An6nD0Cex*6fhrgiV{=0?9_!K5)*GD zG&8be24p=lblC!xq&9P8EOZ1B)z}mipiYrPO><38B2CwHL`_svH*>TT!C_O_{5Ro`4Pnl=3F9KP6Ek0?$Fi z16+luA%EjAg{U$AR5l!yx@L_+`>S42kWuf$*+xcQ`HN4HBWFm`h29GzCN*2_;#$u% zQ#qAk8&*U-)mbBUHgmEoYt&Z1(Nx8fRez^AHMU59M@TCcIxluck}^1>l4MI3S4Gyu zKo(ea#QHe4N>4U(QkEQNR!b49Dzh?6lgC)!rdcI+OrX_P9?L_qp$R1DU?n4Amlj*M zm8NLOpc3(3C9i5fGKD%ST~+X3M@mmq;{uuJT{jT&t`=y%c4f?VrM6aI6%{}7H37pm zJy?*|7V3ly)@fCuX+v~j9oBFE7Gi}~aBEWkd3@A$lF??x5;zkDRo%!{Yv&2!=y5S; zWF^-M85cU+Es%;)uN=2Zzp-P@-V%GVyf2B5&_3 zbBg?wY$FP!{LWCL=v;qDZH;4JGje?Ot9(s^Zo?Nnpa^f3*HYzITXFDj?-zeHByeMw ze{)e(*U(~7%-{^kC=>TpRW*4wmX|sffGc-_FPCsW_JI`#ag;O(Ck}B!w+zwpseJXU zPIr~Y(+MGkOCxw$-6&}LS0ZM&Oc#d#9nb*hsLp-pVutU69hd+B3cvt7pbcn_?WO>D z>kqd0f>^c*dknw~+(8JEu2REJ7-YZz%nl{Q4vM9iB$lB7vM12!S1+N~pF+q!>8m;1 zH&5C2+PZ)a=s>;hbbXU%T}1;yRc34_5;pqPZt0a>wf8dR7HZD7px`zE0r@>fvTi9R zGvk+w{~>wbvv2d)kzaFvRalaLuy0m{kIDH4NA5Jz^IoFG0|KEINI~an zSS6UbE*uC6fMG09fB={{08zsKn`lli?m--M0T@1E0RRCQiosm2Sv4u`Cw`$0GVLT9 zZ41=6wt#{gHjf@ADdIyrB@UxJ)wv7=n6_sNl8)}Xp(_{`h zY9zFY1ex->_CF;Wh0@oK0WV-TdNvN3G^e#%7uh`<`H@c=CL=kRSNin~4wXZh-UhgF zBdkp>xsX7N-;NW+#OhE=dEsW(f+bAhg8Ikgs+UC>s9RU}j9RIADTP^@g^f00_QmM7 zr74cs4E#YBIw0o004A;)0Fd|}>H!WqpaEb&e@r5M&Y~W;pjX<(0`?*6wypxSg&mf_ z?V130g*Uh0fM7g;duXBmeEz{4kd7qW?-~#QgGhoNl%?hhDCXK=5w=bQn0SC@Kmq{U zo=xw!AV8a$!YQBvCfoup zA}ZQ?1y&*d7o=ddOG27Tq9__*58!$q%z*;Fz!`o4TEe6>5I?Yz6y^Si^F)KyQV%^TI%?SCI^M{zWh zU1?)i9pW-~86gk?n~ z0UKms>JA3~#HZ=7=V@N{VTOxh)U@InE=a8(C^5*)#;@T3qYlq zs~eySl$Kb!X|wJ8)bja*R3?lqvd;w*xJNL0qljE7UDBnk*L>Su33R;RHKZI}@36PJ z{gu;=rqV0Vxe1Dpua-}@n|?!GHAlVFlYS=0JJp-MCM((B6bW)%ox*?Afe(U#m5Y=oiL+NF`FP4Q8gZIi3D97MZcMvH(92!Xhre@NnbxQ^@CXIo-CF*E=QY`h-E-~gI{)Ye_hz2~*c2OlZ{ zvpWEZN$VxDB_;Zuu^k(n_~GF1fw0*pd>EhW%wo*L34+{3f*?PFN6Kpo5$x2R-u|)7rE3pyYtwMf9w06W97wRB!Go6`6|xh@ zj-5x35F%6`hzL z(x$a#wyj&05?aWeOSc7!yDU_sNHOBpzrTP33m#0ku;IV^yn%3%kA@k*<_v5>rj5yq zeT^Ug^H(YXGH%wmNrSf!usz46|Lwa*VNbtA7WVD)murjxC;RA8VDy)tniBVdDR}0O z76CocuyJ^-dyhE+#!>@bjo=hu-Mp72c=pfti@)?1FtP^%321B9!bv~OzPh@+GL?f($n3;DZoGXxJ_1RA}La7-p#dp@nsI z=;4PTemF!IT?`T8i73+b#1mz#nBt2tqBvrSG1h3~jW~KpqKP@mwPG1vJi%j+MB?}a zjYTG@WR6G5$YP66EGeZ6rS#&*rb$Th8ZG@M?yKIm}n~LVw!B)IK+=Z zMyaBlZPuCOns&1J=94R)nIfKaZ7ArV7y2dPp@=4`AbpB9>gc0@-7=R1c~olYrI==_ z>86}^>glJThAQf)q?T&xsi>A3q6BZX>gubo#wzQqw7Nx+Rkh*-QdLr^q?JXz=86sUBlRBWE2?1jQ91UU}`+7o_g#lf(=BsTRz3-N|uT!~a}! z0B@?T_YZlR{iBZ*4}kMpY^rTm%5d2IbsBCDKhw`3v0>&|#3hsx^I+FhcinFPXvZBs zYJ9hkISY7F4;LlKmNCLiL&zvUa$q1^V@?DHwbU|K{ol#pXuMB6YLK9D(`1)z_Sp$i zNa)%c=BZ+fZqM~2pmBFdX5DzdI0W2MzF9_#e&(%rkb)NuB8fG^DWu_bQE4TXS8B=S zm|ZY#x!h&U`8VB{>zR4yaqkJFi)923dfl9#Ze*E3nr=6pfwC?CyM>0LZTszv-mbgZ zlFCJCs=x;?{P4sVZ~XD0t_tw-%s21+^RYUMEWo?IBraIT#`|sc+J@yUz1m;9EKgYd zIz9Cc!5jWc)t>(^RMR>|E=JB5MgCRm&a{5AyWa1VO!})IzQEEIdUR+Tg-vLO8-v)I$m$&;u}X zF^YQxhCEdO1}-Xrf(v+JA0yj`HY~vmVvHeV^Z)@2Sdoh;Bw!a6TL2)yF^dBLf*H!u z%rzpw0Wyq@I@SRX&wTa|pnc~b;W@=UmSKPN!m!YEoe?Wl0BqvEp2B~d!vI`xM7+0p$!-O~0=`zQ%YgDsU_PJHErD(?fdFl2 zLI-H8dASc-P&uGk3Rtg!#_ydFVY5B*06XY_0YtEi z($qtb&xpq&Gys4Ic;JWshzA$8Gq#H9OpMuqm>E?=G~W1Q7&9n91Xl3WZjvo`{tyNV zsA^TtIKUX25iDW zx4FU%W}oQdOlp31Z7Sugb_KJ|?Rqy-lR~F>$4lPw|C%>b>LjUp*UR4ax@Dgh;UBRI zS}S|zYQFx1mH8YxtAEmpTni z=zlGG;8I6zx@(H%G^(}Oz^xC}5jk$PJ?Ua|q$}mY6%2UFvEqA-i zy7Y3(#Kf|QSc~RWR=3SW0+i_D1ZNn%xy~sP9h9_eT_p=DyGQn`j|1)3Z-(={h)%Sk z7d@)y2 z1C_9Y(d8}`6mQ#QidMMoiox6d#PxjY=7O_92dF z$l{66{_dc&&FyX@EXjVxP@7IWOux+*Or*p!ZAEK1#T9NuYF4+5N~b3_+o_he#O377 zEM<8+H{M?26TpobTz}i>&U2abbKAUdgTGFh9}4%My)9^pchk^}&bY=mu4qRq`{N)F zdGn+v>Y;G&)3rWH$%R7DRRgSj#hwbOV_wgF(w8jr&9uJuOY@dIc;u%>xyi%T^HDP- zfT_l{zBpX;gM9dX)e81TKPqx|BKv_L|7UhxoDFD;CrH}wd07EOFbc10cH3r8yV~Ca zZi!bYO-+uixd#rTE<3zNcJG|xz^o>E-#tcEUM-7=nX=fN+oxD8jl z+y<_2x=b^EMq}OgDYO zv~P-kA-G@p*-z*%-*nFjDtqVo1o-cAIrKPM^rtUB>Zk@6yx4i+T|Y(Xt$*j$C#`k5 za6R;9BQp5U2Kw=v-|TI7yO`qM+$$4_{gOWsyG7|Yz>QM#@dr`5@mAZ&*U0c$l1pXQ z0%w+g`iF3)6is~BZU|_Ab1RHay4jb{1h$N*G?AIgUewQXIf=d3EH)r^VJ`#s@A%Rm? zh>ABNAcBDyqJd(FC}3EL5CVcExQU!df_2dabTBDaIEtiLit2KMD<=@#1BLD-gCC)4 z#kYet=Y+dQV!g)^IroF#{}NER_>==*bD2M{5I*#~vEW%~Wg{y8od=FR#*mGoiJcgc5~*=@K?kAe zJJFbt8kvzKXAt-#a;~U~Gxv)-7m^9lY9JYO9+@r3_-F>kU&}(0C0P|P`EwzcghYWZ zGI>upNomXoX;SEsKe>_8xE3SEP9|oN*LWA%NQn;llyk%=%%BTYS(R2vmCOK@TG=$> z=x0g-e+GAs9uj!*|JVXEf@WgrTnCAW^LRS$h9mcgcw||YZD}V8hli#`ffX2#c~+3j zRDkh_f3c&G=iroE2_N2gnCt!^snl$I|thwA8t&m>)Oc#ry~OLG~Id>JNi z_?*dQoel?><{3@uX(#3Ba1cnC6=ImmSs00VpMk-ckJ+F8i9DZpk>GTj1X`dsnFbAE zg}Z{FY(Osx|GE%qKnDn#nZ^bZY(NKPkOnvioBPC|z@ngW5TR_q2G+-V5OJY#(4ZSi zn{42rCCYk*aG^VCpa5f($@VYRD4=$MjVZ;A{4fX^AXy3`54zAbf8h-kfFSxQAB=*W z?BS$K8l`MUpXU%~{TP3w)dK0bom*OGZ;6iY>2L6eT5$LxahXeK00!t8mVQW&wgsPI z>Tg%Ne(tF{dg*|W7>V?0pHli4`5C4B`JaM1sHjqr0(ycpny8A}il}I!BRLQqxq1Lb zX(}nHFGx>3Xrh=#simoUuqF_)W~obfl1KNV6}k}Q!%-CKUPrj7RhOH|l9W2yn`Ofp zA;UD=|4;z9!5)+~1wxu2=I~bk;0{9I34Qt=P1+t%daTSU7?-3A@PL6i0+xUH1a9yL zYe|P=YH;=UcpkE?h&Z0ewRa(MrdxsrKtP@AXiR=7h;16KaY|ct%1QC6ZpWpN&{~+y z+8%$pq=8DP02{EL5}B@Aum%e~ky@cI=xZg>sLD2}En$*C$&%@Eixv8*2yuKficzgf z5E}b&9V?Q+wyIJ1lR^2gwt28BXrow1E4#U)OxdGn10cWJC{WV@5W^ng#~wrzMl80k zhmovL3baIfN$?P@oOdJC`iC>}rGMC^e^;g|BADTtt<5F1jU#4|6P{7P0_wUqYg#wM z|K+VxVzqQQr*1R0^?D<9`Lt@LkVmVpM2nwuTNwW;uy~udc@UtYsIq?hw^Tp=%`jJW#Q*fV)nx`W895 zlm(MwXLApwaI1kKR2t9#Kag4f&{z^s0b5|C*boI0P*k}~7|-zwGH@S%!46B{QnHI! zLBtP>&;c*C0;muLHiZQDFdMSqycG~xLsI|%000DV3esk~xU0Lo>$^4kn?idS%UZWm z%A6L$4YOk-s1&yHwuW=ZhTK`L(W#~Hs=xGmop(4F=E_^@indPXjztomVY#+_|1+<4 zd8ZCYfwKd@vcso++OPU~w|cw5gKDUKJGvko!n>%rAmxKGXSnVJvHHX=qT3d*$a2C* zQp9({m0H4(YZIE=PMmv+LD#}l2ZK1=P(F-vm@C34h!(bh#HQ=PTgaoTYc@3dx@zD6 zmXHfp5FqXV0xPfzs2~F*&^60&9K_%X8Xz|7@fs!24z%F9^uPgMKnz_hH9@2>H!wpo zZ~$!p44?2pf1wSlPz;~29RENxfM5;MkQ+Rc#arCPU%U@tYzf3r2@Oz)|1=)Y-P}|M-tg^2%px zOlmuBt&C=Qs;6v|1{5qP`D(#Zioy4(!5rMok4dmb9L>`FUJkoJABjEHynLAXgBGjJ zMCUye!q&oj((<{u7>w3j#4M4+&9lSUqR!gRE2@23P_plAS;m8i~46<lV7%IHY7)tbtQ_@?qUo$C5p z*ja(Lyq+xb36Hb2xikhYK+6dE%Z7882dA!+CwC59wpg8rCo(%)|3J)x61T`4rOK?F z%+d-^^>F z3U%X*Ka2f7jUCsfh{Pi$6sOz7G5f@|$~AyNv!&r1B>*%hpfsm(A7r#KsL|Q900DCJ zGG;7o+fW^IoCL&s4Ftf@P?I!w#k&!p0hdwIJHrURG1@9a1Eviz`!EY3v$No6$%TQ* zHI3G5qtiQ`Nhda@1%j$_BW9L7mhNC*F7G0$?BI zx&_@Ezkv^2K-{Qp1{VEP93vec)4fLiy=cTUgDl&yu@4*l7u$g3FQXrkfkKusGz(zT zyTK1VZW@lUMi6rkw24ABq`+2HJmj4?es+r%5& z(a{fbAT}NiHNRan!42)DA?xbId3l#i}UJ(KtIp(yuNfXY)~x8JRfUN z$0+o*zF;HH*CX4)pQ)n|FjCXK$X&PG$Lfh3V>Ky3A*{-gS_4R22wAl(=+a0{$p3@MZLYcB(H zALKVa=I5)J_dXc;uJ2muzB>Ky35VzS3;MZif9>egKaH0NY>pT&d0yKBi%ivg}KdTOOJ#TWe?(_0YVMT9zN`Z9X-~Q0=x5G{i1rg(z zow~@r&!u4G0096%iGB6pXlU?b*S~-J|H?%vP~ix;efyR*uz|42GlmT9(SXvC;Wi3; z=uu$A(AY#>}{~<;!iR{|NT?;p!T>0-OZs@RH9=&#D>D46X@?|9>S!O4FvYYZsHD==t4=o+HPo$4)rwP8uUgeoS6}^S zK4x^GwN_hcWd>GVcjdKL|6l8}3!c2vLodC*5?c*CWj`zIu$h5JrG*yT|8<)!{M%%U15WYAHS1z>YsDSRTo)jVd^pRyt^9L;=f$ov;RqLf zHtJGeE??nPo0s+K{)G&1+xM!JZ{63zdw1Wza<~PEGbX-xB1Gn89|E<|L=Cp2O=u)P76uyVr0`l|5wnOY*B8QhfBK9)Eoc<-Gd+H{}Q4e5f;& z8vp!hq!aq?=RXdyEPx&A9|0A(!04fEFwI-rqarn_-2DzKpR!;EHK>)|ZP0@s^q}9? zb30=VPIlH|9JsUL9ln&xuZQFT|G%N0Tpp;c#_0j7|@ESVJIsMu$bL z4Z8mDIwTsW|A&bo;osI%K@e)NgH`-p@P?;6E_Tt2Uj$=+B*Z{6meGu7{8`Lg)*~&c z4~-l89+r^g#y4gNX@H^-8@E?SC*=%#m*Cmf_*kLz;SrDt9OV4&_(w!0GLKespCZNP zNDDzyNNc2#At|{@PNK+xjbYma--bm}mU3@bG-WDP*)Y8nEQ;khViRd&7#TWlH7u+S zEoEsO)I5uZxCB>dc3B+EWy^F##NlmfIn2`hkaNFeremHMP0y&tbO`#9PC_q2Sm{7V6oa6*)NaZq4k(Sh?!0YDU zvgw*)PHu%LjO9w171QrzM_%-5sZ4iB)7HcboBiUcPB9ZyZR$&=L=|de%0RelZZoMZ zSgK@F8nBO^^lnxyr+(JCRjzh5o$btMSj9S4lHn)~H4-b$(m)3`oG+tlWvg2;I;DoP z;gVrJ5*zAz*SFeXt!(A%T;s4-HXKl}Yn>=r6QTK z)XtcYbuU#;3^`lPsH*Um-^%G|uY=U^q|2%Fx}j<*^IFJUbD2J*t!$AMx^vl-iL#|# z|LrvUmnmBIs>bD&Ila1E<~A2&U|noQ?{NMXvZeVBh)8mBT%UZaK%= z#@Q5^ERC>7p6fmT_Elkj6w8$@U}IJXjZrfG&K%iv~Mo7eH}Pn)P>1n;F_RV6Td zNE+k0DA&0+#&M1h1l{`f*vCJHy z#SnZc>SPSj&#;4}*?fUKW~$vcf{qd;jCs`$RqSDJ?C`=aT18{H%|{pLz;mAU|BUCe z(Am#@YjNOAJQ&ZeI9<2R42B227-3qjb2W9=q8r0tGZ#Qik@ewLLa74<^5A-jzP2KohumqXKTG#{xXj>blw4 zEbNB2uKb4T1WQ`c!=xc;QkZGQY}lp8+;nPq%kQ*-I<@u`%|z}zVtzLTQJ}D6+6(NfrxBGCghgOG72CNt^?o& zbH0i@gy4yNq-}387_~fS+dIcW*(2xn*f( zDHHH`2aj$4efYr$-Zm*VI8ZT@agDeAEgrZ0Rzgm4&Ue0xCTDu+MK4bw`^x|ttT6F-_oJ*hz% zT%=)SlB7$;WlWPHlpv4lm3&A72(Su%Ag0Xn z0E#dN1ULn(a0d?915N3NLvVmqAckF-2W?n|V)z6O7(+NTJFxpix2VIdxWj?O!#zYW z1uL`+14PkcynCZ2LyQbR%rr+V9RHgkN`wvl!y1u;ctw8@+Nn3bzNL21R2fkluhGM@|@|74VsT@0BQ6dCvtN@OESKPg5+ zv81NVy{F{GYb%*B!^y1t5obg*XylcBzy=v;fF>9PO}RQvISDtr26pU1kdO%{*avfn z0G7CiS*QxEum=zr!z_G>@aq(QP=g#0zmy0_gmjOB)QW>N%m`G-;nFR;%QS5<43GT7 zl+>w5tH=R7JdAX-0u(roOhC&aJQ$+Pq_RYoI!SjaNp7M%mc&DsoWoF@$=Re${-{Z< z#Le7nl40Y?p!~&J48isK8QROq+mp%{$+;W^Mv*~Eo}|j7w8|We!QZ^W5PVME#Lf@l z%C>M2|9^l42$+XpfPpc90>I3Hta!)0bP1Rs z!(oU535Wm<_&R`8H-TJC3H%4eyb1+9(9CO0%~Gv~yt^`>12;HLp&~@t(n!tFO!_O$ zeqlsTTTS=-Q0tJyol1jyi)n<(JmE{?M$gWnJJcF|z>q{DiR8Bwaxh25P(hqK{~973h-5s@#H}*myUyy+yIWCf>6{W>3{DNT zerZu@k+@AlqQa(9Stkl(Q)etcCN`#S#7dX>2{laTFfV2AuxXcF`2!jjQ z1$wxEMW~8a5krR9Pfe-9x#0&nAXLI!fRuPu`AAed4A}I0(5doNQ&rXaJ3Ppuf2 zNbSS>!!$}n)gl_r$FNk{3e6@`yzo%il^WI7NloeCR9Ah~SXDn8t<{z#xm)Gdn9bEB zJrQ5UpOlH#urW%cJFlXAIh*TQ|2HYto1NC&;*FN2cZD;^M)dnu; z*MBfVBnXFsRSU$-3I_FCc01UV>d2dlrum~k%OtdXQ!s{A(dHRhnY!3r+EB)*T-C~4 z4|6Tk*jV6_omE|q5rv`{P1%5DS(jB^Sc6%qb=@ANS@4lXqz#!T;Zl^jlbn^G*ae?s zJtL*<-Jc~k;l$l#Eu&*xnW(KEEe)I7eO;-gTK&=$sr!j01cY;>336o!gOGrPSO}Hy z$9=emU?6~YeA{^BOa9D4|DOPg3J?l7?1xV<$H5hgfi+0_ZM(wlrrrA7d$CAK``^Tf zKhDa~&AbeXB+-Vw&m z50qVDrKq7i;eT?Z>);?T)0JjE4N#(kz}xy=40;2Xls1YS6RtJsJn zU0Euf?fAbnc1Q|NypnCW3^v^jMqLjE;XTGN5gy_{)=FR{q}f$D749-2btl{1pPPfH zUQD)SvnOHXALTWp|EQc~qI)Oi4Ps0N{S2IW?};wUOAEtU?4y*s)43F^PKIV? zyq;%EJ$+K-9^o#rIxiU3W+H(AI+nEe#ap=_eX9VP8kVV{N;^jYl>Tp?LnQCfg zIwA;uM23FgV>)1j9;T~iCSnGS7gb4mGvWy}YP3t;jFxLJ+UTIRYYxnrw35ARPOCQZ zkvkG;8hkn6y{`Ky+K1|&W@Wj;=H$E9)uBFW^?U2cHm;<$ozBn}cVT6JChJPv=g%_h zMN8vW?%WA(;J^c>j0LXF2BLhig9qzkhJtdd2`(y1D%PpUR>4f$c@E-N8^@GkXk z@n*XNXYrFFZpShtlAI4h9+p!7l#!o=kt(?@qlS98^0DWjyOa2rFzzELKi9?mkfgzozZSs z|0efrH$JNTrsdvpI1mHy(Df}h_zWmtOh5m#1h?{2j~FbU^Hs04yjHdgcM&kBHZ}J> z6_h#S%{}Jsa$G+eNxpTUc0uBu^_ymOI)4lzv>-K%iYin9j_3-1AOh5KJ63*XxD0YAaeAls$5Yw z%xjNlDo6EyhY(dS_JQ}Y;a(r#B*7m&crpJGF84uNuP$$1csCDrGU;g(q6Qo0N zg5S{N%AP8*tGi^_g8TwQfUGK;|cXl~%@Cf%+Zu+Hu_e)!MNt=2|KOsqPSWr{)CZ}|P z#y@=zSN(RCQ?cpF6XhZkOBwDssQ^H_(y6|C04E~Ja+ zy^L@BR0R3^xCe321z`Au1powKCchd~*R4#HAy81*U>#u*f+y6t4 zEY-{GbRc4KvL8r(k9~hn`|95@-#+~8KRz|$8Y2anxsOF|4o-{5_`I)5|MKsC!}oji zw?*|AzWPajV%PqUuk)_F^H%}GwKQLTSOgOQhyo4F@PnhFfQLK({w+)JY+o=1&lWDc zw&2vhj0^M8006*%nSb@*bZ7u$qCZzMBp|$VkK(_0TuR*2xUk_fcN#o;bg~a$B@_lk zgo0`GDAJ@#mojbY^eNP+-6(GJphr%LeNne^?dtU_*sx;9k{x^N9NM&M*RpM!wgud{ za_7>mTldM6GI;IsjXR{vlfHrn6E1A{aN!|(5i@Q)7_Z*IjtS=-GWjy*%!Z$Iv8?$s zGJrkP?hUt$@8GY2|2KAP{J7d%WtTH= z?scm3=+dWCycJhMp6uGUbMNl`JNWS8$CEE_{yh5h>esVR-&ew=`10q|uW$c8{`~s) z^Y8EfKY#%WI3R%q8h9Xr2`acCgAF?PAcTd)5l0~qBKU|M8QSrPg#{L32Za@ONFatF zZaCtAABKqHfRA7p$B8Wd_edcU+EECHG6MKwj5_j1qm4ECIHQR<4yhlI6AF1`e37k2TRu0|^11 z^aDu(mS`gfo?@!H>Q>M#v=2X6X~in7wc2_su1B4P9ItH!mz!jUbqUU{4>x!W7*f1TzUy+ zu4I~tW)e`m`j1xo*u%jdnmPoLL@@ayj0P2KVT@KB|Ctf>H3{qj^)+-dnn6bWl#(jc z?2KW64uEK6=R(^I^p87KXEb%y`wGrnzW?+i>)?qizPP=+(mQXlxUDO$ZSS)C*R_^2 z7FyQnW68DR{Rk)0zH}CZ{a~ zC^L{i2SCD*s|CXW6Uo#*}eljTZlhO{{esku&@9ZVUz`CwT-30WFOk7ga#aN zHk>TP9yGv#R<_Z?7EwH)Yb1Gr>xM_4laLr*6yNJnJh}nbyYNs zVmik~;kaguR?LfDzGxcMnK3wuQKPr41;=8Qv5m#*U1o42M>7(~j&z)3U!vG62R`wM z#VaHeleawSF|v`4d?X~bL%jo1vXYj(Bqp<0GX2?)N9ogK`7qWYPXe%KGBaNQ#mBu< ziqd`>;@I|T6v|Q_C}p3-o-AjEA}3|Cm%jWZixOy;1s;u%v{G6GC%BM%(Bc4khz2$| z5E45D18z0+M=%z^h!g%Jg$Y0gH>|-8|7m~&hBCa!QNqTA4BUf_9rw$&?f^14WK80Xn=x%9L@6j3iETs?(jSXOh7DDNutd z)S>o=Wvx`u`!+<&>V52}7kb%J`xm4KLA8?pb80PL8CCTe6{}g@m{nCoKL_!TsAfGY zQH5C-Vm8oT5M&w!D-}Z%(qNh#%vw_D0TPZB@frtU#M2Cyh!}Qr7S^QHAmC}IGI@d` z?f}80W>wRf8byhcoh)WEyBvYO|CBB8V%D&*xKh+0bhLz#Tu1vdEYrRwjHW&5XxPZw zV~I3$dsJvkXS*!bIkdLg%B^lQqtdx_);KZMtl(&h+<;z(r_OyYbam=ev{JXa*1hh} zEQU$}X-uiVZ0dzHbW2P6Z>#nRA6R|KO7qqyeDM2jSHqj$UgpoMM7j}n^Q+$is+BHm zMH;S<30D-(f&kBqrd=mu5kT~5A=vPOC3KMsE6^!cj>5$#>LCTI03#QpxCf&S&<0)L zFb6Qf2O;|KC>*}PYR_PY3~msOK!rmdkPxvhexZlu4sM@_<1vtf+!W3h_bs!tgByGs zT*M%2$%Bzx9qCe0C+9J>|D)v`x-?2<;VRj3AMLVcqP%66vg>wW=G~dcEUq-urO0hL zu8{E+XTjYxx^})Zo)0$N{qnibe*Uw9Hfi6A@raW^1@DfkDpXbm2)*NluaX9R-uJPW zfLG-%{3^Z5`E7SUyaY6;L+!Bs&gH*wR@GZ2*ffg7V-W|5fCm`SPCV6P4XN4(Hqda8 z2Iv4&K94@{_0eAv{6Z|A70y%=S z=Ul5K{#e}R1~QS|Osy3Ca}-qNDomgn6?dy_`Xew;T%+vRS4lWyP? z&5h}(HC%$jMYJw;|MOZ-eQq%+cjEkNZk{u)@r@^pFYpmH$U`o2P=Bm`j(+q|1?_3^ zYC5bf%TH2UPDxG!u&ifI(v2i-bF<>C)AQN+$b&9)2a#GXrXHR~qUMyOU)Cr#q10eA z()3J0&EiL_xYe^R({vX(Tun9?vjRS5&WPRKSSCBe8|rW>1H3S@O*`eT+}kw*7w&zj z`{iJ(EWF#jE_|04#OtMXT48~*LtEBd3Xk#+Zq{@G;=>5{1 zJ~8hzqdl)OKIiXbK(}ts4K2XPv%d8KDtcUwZuo_mbLz9d`t5W7Pp%iYpuTme-KX4l zzTgGP2Iu$N|Hq74loB7`!xzjOb&KW9So!%8J$@X^fYI43oZ)}DOyC8td+8K@{9r-+ z;?uAG=QiH;?tef0AEw=0dRNqfW;w_$7NR0u{?I{c#OQ@u{s7>6*qAKo3$$?sT8A;}eA^&t9pv_`@)#8Wr zNG_RSEoKN8t|Bm6R~x<|C>Eote4;TXqgPzuOBu@*VIm4D;+5s03ZmUzcv0U89}IpA z9YAB+LE=Wy;N7ucyd~cZ3L?6YW4t+{U}z#IDx*;#BRq;?Db}Msvd1X~qdxAV8ctOd zs?vSLB6c}i`&^oSZJy_em7$?t0M>^=9%KRXqeSZ0Fm4G00T?`HB;jZzN0J3I4%8j3 z|DC{X-$-d7B5Gp{YTqQ<8@yR!Aku-lNTcfk$a zq&zAkJ>DZyCZ%}f<3u*4Q%0UZ@|;*jRa6qy=QRnUp%tYq)kEG~L$cy6YUNixC0Pzt zMQX`K4rNEKB@!(JGw1?b#-&`sB{Q(4T`t5&3X&U9V`{k0O0}dV0_KweUpd+!B1)7v z&LlgU-E9S8B_5_u?v5TA6f}Y(@{yxE-lb9$WilS6Qhp|A<^fZdC25u>$$8H&9uO&c z2x<=1Ri=nP2Gwf{2rbH{FKQajg&`)bo@w^xPo1UFw3TKy1vWH6xDn+-=mI({|0i=c z=W^=8aIR%uMiE7sBx*>GWvY%yZsT?ira|SKVfx`A{-i^Bqi#jt4Srd8`XOHi*OvvH zOsZgf5=Lf5XFS@cQFvx(?x#JDrf>cyfKpd0($`e>pL|rMB_ZU2l$Ux@+Jb~0eT`*- z9X+a7^$lD znd)JPAluFAmgSaB_T7@6rzBd&tJ>X?PN|IQDk$=*uWszd0qeGY|18MLPnqJ+m_~`S zQVg@2Y>-T=jM%A+bmf~?>&r^(_2eSUhAhrDNVj4nt=vN?z*9=hz(IJx891nfi57JvjK#60{1M|gw=Q3X0>gidgq zIrW1ppunfCY8w&k^BJtPSc{X)x5i<}B>S zu9SR?&m3#RoNS$zEX{-^%E~O1)MoG2-@?GG#JH^N9xs#Z|Lp0G1-O>eAvnq}M8aR~ z1Gxf%HAus-70RI`%08sYnzRW$aKIPn!YYIVEre?~ajo-0?;;eyr2I*sIGcb$&DJJ> zF_@D%P{0>B!!Mjo_;7=!y)N<&F%etq#YD_(LJaOoNuk~Bf@Gz`7_ZAfaqiAn#1QYoWNQ&`@sTJm zpZ;t)B?8-YZxZAH_0kZTm<`&{i9Rp^6wHbPGeXqR{{lRDE!QrJ7`II+NW{4s#SBGI zMJ#}*M4ev&@;}6}R=5KVyfLJL&^8c&F|=_GfY>1P6A)IgQd}?w$Dsy4PU4QP!r`d0 z2%tE+w)8Nu;;cl|(BJN~7|6?0r?&)-}V!m>|rjg|U?5CPCW5945 zsWjZ3@LaI8^x1IciqU%(qE7mHxD&Y+s89gRpq6jHHYc`WOK*p zpKiKRrY$QKgU>5bb&$B}gF1ClclGOKiACHU)0B6nRbv+Y#f!Ml64zXs;VcYZ0lgGEKW3XoJqf zz8f!tAZwqa35)5#&EB|^4+wYDN}qnWfO8v1z`!lALL^JU2k1eEeHePnHAUD1 z2p9@6j6ppg0*;lKfL~ZBNY*?7|H3Wg!Xik(15AWDX@ey&!>}RyNX1=&)`}B--FIkH=xRyuc+SoG;oA z{e5IR(owdGHeKy$J=FzPIw1uj+n&^cy-x@DzA1W~)n|TD z8`aY%dvzK8up@nb2|LuwrqZ9+ZR(fQ(?^qQzU$8i*2h`xQO7|)#Xg9GGsuD(r~TVY zXWa9}-!IwT_eJo_|8mFMmdtbd@yA>7_v?uF#`3SD;;&f^%TDyG+2F5qZ2M961D;Us zu)XHI<&S^I*~Q1bKKgTUj$@VW{u$_dUg@Ki)5k~rpVc;_zO<`8@BSRqr$0bk5;%}x zL4yYoCRDhPVMB)xAx4xq5u$_^7cpjR!Ga?T6)94Txb=@@Ns}j0rc}9-WlNVX`z5ll z?`6%E^e8a0`LEv~10Oum+&PqJQKLq?9aXxNX;Y_9p+=R;^42-4SFvW*y7j6?uNa4P z=`!SNS+i%+rd7Mv?2|5Ko}_h4mTg_Tck$-M_@oS7y?+6tbqhCc;304WCsw@p>*2zT zA$uMC({Yow|-UvMepCihZjGde0lTd(Wh6x zo_%}w@8QQ+Sg24O`T`%>(QoIGeE;p~i^GmW@XJrY{{Bl4y+;bM!#)BpF_1q6DJ+jc z2k(op!3itu5IhF!8xX?$2K3Ox6H!c2#T8jJ&!V$B@(3i6f~(QS8*$8WDc^ML(Z?Tw z)U7Jph}=pozD9#h$s^0atTC~cjB>HLq*QXU*X-g8%PP673$ZT$qKvTAk_6MtviLev zGQKd||FTNi)Qq#OGBp!(OgROk^R6QKye-H-dE*h#L7^J%qT;kmRMABlZPd|6A(f81 z7AdXN(n~STRMSm4Ess7n(um^`1UqFhzcSolgTqo;tgnnR*dUcv6+eA7)>&7)Fbz8L zkQLWofelvJVGVlGtQbEE2{%HSZPr;I1$|c9X{mi`$UgZ*E3C2bG*e8|TF|oFal_Jc zT)_B(%gxTXJr_?W-DOKmcq3CSUOB%!m$f^q1oz%E;goV-f6pcOFKqi}N0SoaJ=JR9@ z|8PK?Z?@3EReKIv=%H^mwk%|4R2br=nSR*erlF2{&}$L4t+T%V?J`}l+ReI4$GnCt zv?k5ntBbJBq!;bZ*nDDLywY5oOM~4V`0dRCmODzim)y6_bGr_#>LQhvTH2=#Z&qT8 zH*VbV$03jWxQ>ag-15sY&m33=AJkkTnSJHFM9(2wdDMb9@0|39NIab&`Y?QXb%sck zefHaN&wV|kzd~Bs#DNc9N5q9M-gu{|9-OPPw$)q8F6f|xZ|Ca_och1UR$H>OuUAt0 z?ll@)UBC{z8+^v>U0eL=A!Gl1#=h5DG(7VbT>07xKR!s}_3v?U$pIKZ0S@pw|CH0+ z0TGx$19_EODYpl`#2pC5>&M|-nEa4sT zm`6QsszLS41jvu_+)pAK!cPZYu6FM<=s|~N$&6q!NB5vb z0RT{d3jAOf_h88;PwA3;(7+6$G>Jc;u?7i9bPE|h2`Nn}PKc?}m9B&(O6oC&5(uRq zkhq}%I{FU)YCx60d3-_x4S<13QL+q(+VBK4*=bLI+7f>Vg94{0i9V!oLj*YWALUR& z0X%RAkE(QOw5%mqidfCSPzg=L6f2svcvfdV!3}iqqFU?1Ok;klY}AA+FaNcvK4p&e zt#@5ZU)|+5w|UQecHyR0yvfz6gj2DFA}2Z_8(GOp$}HVM=w&gR*>`eopgmieKE-2C zfQGD*=D}cRZ&q3h^>JrJ3!!FV8`~Bs6eA49kv~e2fK>n^7gjhxP*#G`nrt+uC-H|Y zBp?D#zycL9+$u>(nE-G+x3SD(X-ir8(vrx-6*4HmOi9v{8!#gp(Fn&s{4t9I=ph$O z2!RYyf>QFDcOU6pZ+qXXl6`0c4h2{MRsW$6C48a0(Qu(XXaECPMB)H@sBTve3&e2Y z(ywZ1-jP~UVX{`3Er)>%zc_prxr%jQXfk7n|2o$(7M5)&mRDZ875_~b>jkiRiLjp@ z49*k!|Xz!MUOy}Oxh?Lnaf>f z4{a}E+Z*Bb0n^>bMsYxsY(zl=71)BAm(c(l^t1`5^v5u+>VY%RWTQ63sY%=cf*9X^I)AA}B zx5Z)?iwiVnt>%SYESI$IHQN^%Fl{jb7e4r>0YA&Td2h+B;bU9Y?Q#(fG=(d zuxpP7dIc$8`E-N9$$t>t=q&%oG6(<&VwmFI!O=8!wOf*XBwN(+-~tlPTM~0DKqot= z0TlWX2?rSCqnHSRG(#{GV=k+3)7+ zEzNpK`XSVWLLZ`_0}9{*_Us?7VX8<1s&W9jP9p6LumP%I<`^)*q~HM$O(o1B*hs=1 zW$FffD&FkaC0TF@n8FA7(J_Wy403b8PqDl7W9unWB~J*F)Al+Qzk zuT#d*L&7lm^rPU=&}AGhMb7XG<*>-6Z{w0CM{o;=ED{%irMYUDIq6d6glv}Jjx%mVGRi26izS&_W|lyP!oS7@$Lr+F(Rzc$J*XUiGB z5UzSK#GHiN81ETX0KiE*zl(w;TW&s$mQqU>8PB z4g8R!cG2+c0R#vUBMlJ|Dbl!ds~1TEA0+Y;IqDu9O(ZAM4DLa=%JC^Uv6cQWyae#1 zNR0&cLGDO`?py-5OvxN_A}7zTCG;*O{xI2=jqp;cC3OTCl}8whsd}&xZJsh2sWE$m z(0Qm)!!m=e7|*UqY>W!SD>+OoyJuiv?A_oE9F-FG)^aD#Q61qjE}w%P2eK~hQuhe% z4dY|UoDW0v5*=CKpZc|8J5D9N^GscE2&jd-5 z@gk-YZj8|eukxXDBgDM5oT`Sy_vC)7YOG>;zhAn~vi%8Vww0R#Xs&|qK{ zhT-UTG3toH6*Rym@8KE@U<-hu5^`?T2mmD6p$}Gp7%E{E)6Ywr zG#JA4x%7@E`oR_~fw!z60d`>@5DW%xt^phjN`r$b2PX!x4K^TeZ7dH7CvU9Ea~tpT ztl}n5$R@<1lJQ>URlM`8+Ec|^gHA5BEb`M&SAsuV(mw;VRMT-lGc;9IwVmYAKNNIW z76bX9p(cQ*76B~vr|;Uf_(3MA?XT9eX5kkLru&SYTG60oYS zssYGg7KcI60AQkaEzyp(HS1vwUX5ET09i?bB|$Yxb8|OWDJE?cy!K%jW}pBh-~;Yp zyLc)Bl4>7lAt^~B(f>ry1HM3pjtXBpNniQZB!-eFJ^=*^paFCs6rhXJ4p6JkmB+G^ z^1yR$EY)j}F&Vd0F}RXZpb;R;Tc5Mvv4iMSCXGPN!~wPH^~RLhZ6 zO?78)4^?~hXMuKvT6I10NiaL*_yDsXVf7vX6OoLTkK8cg5GiP>7J+^>GJ!-W3{5o; zjcZ%NI<;;Cp^GNGR_n+XY;ATwb2Eq7mR;kEx}K~11}|*MR;e&yZfgQ=(Kc;`<6_6n z@w{bG<0Mgq@nhRZa1Hfk#cEQ`g7d2BQNz<gI5OOVXRvdMfXF*rr ze70&yw{$&+;QxqLX+;KU)kAeb<{w-4R!IhS)5CR5_jZd0EvS!gdG{YW*D2~j3HD%b zS0Z?aw|AulP^(7W2=_ZP3{MO<1`m}pFi&q(mIoVE8li}B)vd-_b}W}sP~Ad$ETd+5 z_jfh%b3=E1C2MqX_kH0PW)O5d`0~gilzwG5XomJXY`0``6@Pa%eg$}BuD0Wlmv7P6 zDTw!L5BOP>7h%SY7z<`S=cWmzH+)f}dZ9^iAD4r}1#!#LgH^0F+6HBj=z1Mhgj>LT z5%_@BmwjQ_oZNSSX}E@QwLVa*boL{FUF&`)qJQ-_YQ1AtXNMly@F5n{hLu=k3V3rH zSR51hiT@Apfw3jq##4;Or%J9E39}M?HuhiA(_=9hWI##SbE!-JR`MxE*S?eb#k!?g~f^pBLj|YR*v_Nj_tUX z0SJ#9IhS?0LQwaDHt1J3Co2PTBJ|*-SoJPR{nTX%jVgqU%skOPyFDl|eCd4Xs*9;X(dAsSPnxtgKWH<&>eFgl|(8l#zk zqGj)zi-bMd*-A2YGqf3vM_N%SSYSdq2D#TV92c5e+VfahK3AGP-FYnOSuK(Go~QV+ z_Bp8Ucnc%CsEryvkZhszh~VNN4_a%p2q_L0?wveHsgL@q{bQn~1s^KmcyB8g^kA#F z+N)h+OrKOgeM1+}VXfJ^t=C!?JQ|<<))_5$i%OX>wiuPq8G6h3Gs>Bho%g2kMV)n; zdg1weYPyJb0jA4))i&jB`Wgn9Qz;Ox+Qu$uI~+`iR7-rIc57=UiP{x zlY3l3mQZKfW%*jL!6dPp>7~hMjnQVYD@?o3qOn2Mr>icXC40OZrJq~-ye~VR*y)f~ zrH}JSwQ7}}k{G?|+dW>}M*87e3%~#Xwrm3|32u8Q@(_n6z`s?3wzn#_ZQ>ddK)1h} zBz}7(A{@9eO}MQ_t)|xopZD?Vnx>x{jE_4p{u-4(ykA0`P*XaYQXH?yhOp&lWG{lc zF~Yn36ug5QvdKHgGse8@yT^-Kf+Q&p-CKc>IUxjUwE@YheSFEkw1zGQRg-WIUJ(eT8|tcWs>B#9PN5eLEHqWit+tnnUtAyOaZN=@g#qZ_MozcY^JJHYgvHuU{(fPe%cpTIL zzL6UU$w!8uO~#lt=+Yx1)9sgs1ODL|!pVPw)EM!kXwK$vPUjSSA1?mpYINjapcraF zw~tfRgn}M8;0uUB<*HL2V4)bG!3xSOCJvwtZsANHaO0Pu0@}bC7_8Xn0R&34x2oNq z(cHJSz1b|hHkxTrL#!Fm%HE0F-Q#6_&K<_D5#Gh-urpZehlt+s8oQ_4>)!|L@e|)$ z7v2gwuKpA;Jd_2mApN?r#OHT@$e# z>63oPmYz1|O5B^NxiezU&6(`EWSnUb-N#+`>t$0{!|cB@UR3!_u>ONNgT^ab-zTQ+ zpi>`~Y00{M3pZ}nA!y~=y&Lw) zlQL|_n#Bt^u;3PY2OIvX7j4_YeGfZ+oV5((yNMM~zFPRQ=E<22H~kDc=`Et9OPlUl z^R(*KtWDm6Dj|>T*|clhzKuJ#?%lk5`~D3)xbWe`iwnOh;ga&@%$qxZ4n4Z`>C~%R zzm7e-_U+ued;bnTy!i3t%bP!sKE3+&?Av=UR45L7_w=tnvJ=P7qet%H%P&-4fYaTV zAAkMDH=lqCK39kx`Yi}ygc43jVTBf6h#`9tV8ud*EU1t|3L}ixno9g|F#$Lz*#m+Z zCOs60C8B195Vgpxm{JfPx9^iaS^L*^iG3jaTHIIv1IvK*AqLJe(0fYOcwqnnr~NCsUivN!Ma?-YM4*dzn=io_UghD3A&$tVKfx@pM@bFUvn50R%#y$}Qqs%i zz4=O+V<`&sXwr{C{$q}f6EQR-LJHZ7$^XAH>cd3|^MJHZKbR=+OqbUX@Ql2wj!aaU zIFXEU$||$@=BT22Dk-Qi&s+u@Zag9A%$S;$v(A@knrWaud%D-qlJ3=5Ttyq*sbox3 zRT-y_IsG)HRD0&Ks3fk;HBhK_4fal~w&3cmW}l6A+G?+zTdw844R_pf&rNsTc1stZ zd~-9~Y=zJQC^v!LO87|L(ZbEFws$Yic;k*Uey&yNf+*tFYStr115K;~3o2WLWWW}{ zR3d>B`_Q`rN!Nrvdg=cFe3Fg{tO5)$x*P+J!Cf}Yj~YlSNq{j4DXa{691aoe-A$REoU8C)nBc3sri0#^%T^dYQ)CG2Orj$Ih*6A0(jCGe z@(*^bAtMb)oj+U=#R7QX4)gej6|tyAC>9_BE9lrhvH^#TQ~(Cxz}^MB#=SEga*>QI z)%YOT6b4G=ev+h<0Nb~x_y1K=Xb?8A^JSto1c1y7Vwf1~B=MTNcWd zAEk^)`*%RgT(qGj1&quNlhDuX(x52wB~4KlOk?VFr#u}dGRFzjpbB-UM4iwLzo{#4 zN~@Z{QmV52gREgCuK%c1t*TXZRnDoLlU+CMs#i&4)31tktS>=mOpo$PQnr+n8y)Ea zTZ+E5UX%`~#F<=`c2c?4k1A@tE2CIyQCQj)uYR=)Nd4-;#}nN$-3CRE?L$B znZzz-vAboBW6QgmoK|+d>}_vvE(_cE%6Go>J?(!m6xz3qc0&0r*R@j1-)q))zy#iG zR;994@}hUajQ>0@gC9J>-o|u*$@OknD$J<5-gSQ#&I?4Ja!TS_cxfGmn)})Z*b*Zu zuMQRLaSO#_6>~Q(;#G=*Av_cZ<5(!_b+3p-S8UvC^wEZOkQnmmh>3X-0pS!YZ-o#4vQ&yere5(oD`tJ8nW(`SRKkd!XRtur!LT6D%x8T9{ z-?069a6u<3rOOuXVMn}|hZCmO76z}hr(JD-Z%^c6YqYmdj&ihto8ByMxyw)3WbdGx z)b7p?fWwnGnm_KpI>%0xUk>!3OUT|Wz_<3^SOs>HyrBGEy3<_(a0s@5%|l~o!K+*B zqiMWmUFZ3Om@Fgye$`pcG|}>ZE8O~CQTRlwo{Jxyc=ibLhrlZ z|Np+NnA->4;9U22+WkWvhFa#M2E5}RZyur>JyrQoLKaujB&E;2k#*m^=l>CP^4V|e zjuN=nQJic^X?TDUzjMRiBK8)i*y{_7J+V)}@tT3%?Hngd+|Lp6r+2>Jch|e|kIx&v zLw@vW>70b37euZM65lzQqzVz@VBf~9P|=UrzJQm5B;f$@96 z=XArTZ^egv8K{A>p?u)yfgcEh*9YR|a`2P}a zV16&5BLgE(E#ZFh$4eIIgZ@T;E;ASR_a_*3dPuk_ds2XdqJ&rXgcpTur6hn17lF|A zKgxB5xJETD_G`~J850%2!c&kf}J&j&Jl-01y!a+hmGfk zdkA%O< zcQiWKD#XtAb2pLwVe=U%I zonm{7!irEhi+B-Yy{IU)h-SYS6>B$kTPSE(=!G37kzpZ*o=A+bW{k)vl8>g0+Gvs| zDQ^wJ25A6g@>Mu&5C<$tjhF==Y(NKjFq0^$lSIair&{k|W8N?p2aI37COtWvjJ)ttB{(F#m`1wOTnTn2i}< zJqd_I@r^gg65@CgMtLw$f)Ixw0R}(@B{7Kx@B^k$PgXfHd1;zmhLv#Q7o%tw4Aqs_ z<%*udW^cJ%vqzSSa*!~ya90PBe&K%#SC?>BaTKYAn$eM+h?=anmwoA+l=YX6DV@_9 zUxIg4%z}r?L74G{jnwI#tp%C2B@}{4nJiI==~t98Vnz+q4~OspR*(Rp07lvX2NDnh zhnSkDlArIln&o4b3+Z9DsaIoZG{*HOzgc3lNkG9lGY5!(0*ZyH=t%&IX2XeRsdQI! z`4!2ziOacY&H0=mx>M2loh53bR0S=J*-Rx!m@3LlKX;-r`u~`+C4)XW6yPY70yB>4 zd6Z|gnHCTaW8eUgXc8f@0P(n=rsAPVieCK*8gQ|dc2SV}$A9y4mY0E`bw;79$e@){ zg$3uJ@sovS2BCiDkjD8@8mbi>I)+OsW*{n}aq3f6ksLB=r+2DZH)K`Q=yQhSqCK>j zcq*uz6`sP_66G0=r7%0U;7_}NnY%+InWqm@fC1o851N1s(+~*`3R?SO03^T zr-O>D$qH24DOBB=hj9>9LFKHT+phOu3`iWga`k^8EZXE$&H%Tc}gngm-) z7AhBP8iZ~dX2V*n6RS2PTCEq0u~D{oE82aG2d&x3u`QXgBfCu3nmy{;uBrmDDN9!G zDkrK6kX9j(^h%%$)upQEug?Xr2ziSOI*{$du<`S%Iuo=drlyvXiaARuN1GK6>w_z+ znkGlFQ!7jsOR`sswM&H{e_A&=haQRtvOW~3SxdIoN~3=$o-C_xP^-3H<+4k`udWHS z20Kxw>XsOavp-9abo&^vcqa&3aJb4DH@mcaJO5EdyIgWLN5!n^QOvseRicqyz>Te-XcR7q))u+lOHgmCP?jgx|e1GU^&7M1gy$=yscuuKWsLa zTfsw2#3H!0T`Rf}{IS;SE7M!VPmEP(+l?CxYZ^?&ht$DNu^ED>XRn*WtfamM*SM_o z#Z0rpVNu4yg}<9|!#^{|vHQjj$E)=_Cjk6@R@|h>3&eZ;Dnbm!e+mKwn-`?~YpUF!(tI?ztIckak+*s$cKmtEj9ayQ z%kP}a#w^bXY@MK$#KR)Y#Nx#B%+KqA%*^~?>9D9f!>nT?TgG(X{x`4cfDF@xr)P(FSS1a`DN9HPQDQ z)oz^5Al;@StwAO2)w&VSH7(XtwOIt|w&)6<60$>Qv1 zO)YVqbfpD1)uPmp*p<`_RR6KOEL=ZP^*y%Y~_A z4I;916Vny4&zCLQv4t+<7nyUtU~-Mxrc&3B(%5)5*t+@Jdp&1zTVj7*OMyLTvCVqC z?I#?q6+?YpRSne_eHg^eky`z*Ts_&%jT@Cc+R>e?^{gJDJuaWUATTQ3+f5#Cz1obW z+TYDGt1B3GD;7ZwSGb+O2VKGv=i3Eq8BaZS?|r|fEXs*}x3;}zM_p*j{j|*O+yNd! z2+Z9D{=6&=Z)crC*iB_?ZQu{?9o{Y8Vin#Ko+hmgC^AeK`t3=bjArINk$7EL@*P-D zKnFLIyU4BBBCgl&UH?+RZO(D5&YoA{VkOxEPPxzx;X7WUiTSn7^3rj`;OAl8Jig-+ zZsA>3<4G=SYrS9s^ z!RLUkPo6I8q#@{T@zbBg;Z+0Trl_lt4#!~LSKNHQrh3>U{!xm4w{v_x{N3M=&BKws z=AjPH1peyRuK%nEZXFM-f@wW13XbjJ9_zKvdE`D;w|?G)o)?CWmdYNHRE{X^&1{!$ zJ`vZicc$(e#wT4o$|{!WUydi7E_?t^?O#3W;g0aj=;P5r=gTDL+MV#?F2y!#?p{Uf z6%Q2X9(M5litIk+8m`99t`)U8b|N2nHEtNt-F!EbtXb@C9Ge2Ose{ z&xUZw*+Je+JP+Or@f39NMc)$|pB246CnAn1Oz)c}A9hUWi&8($W1-tb4d!bJ z?A}%BwY1n$@%0<(-;i7LHec;0E%a-Dr`6Q(Lgn_U&h~ju^hggrM{oB<;pAe`(7@~Q zUYhU1#sBDwPVcw5^8TCkR1NZKd@1nj;-?2Rg}oUwzjS!7PoR$WB8u~K&-vhYEOZd` z1qLm6-ub0o_j#W^mXG={q4aZs=#GNk2I=npKKS<6@+xfgTB@{N|4M~Fa1nUUXjc0z zmT`ff+|VA<((c2VPtu!T`p?gNFNrNzMj&+H^U%-Mr@#7Dx&0ix_i5()b9?EppM=K0 z@#f$3xnFhy%KP~PxU`p7G3@VSFIOJ^?67RS%0JS~pY~J%5E3p8Bv{bkL4*kvE@ary z;X{ZKB~GMR(c(pn88vR?*wN!hkRe5mBw5nrNt7u;7Ah2nrAnAFAwIGb$Ic^}Id$&j z+5gk$PoP1C4jn0>#Zjb5Td-itLPd%cBX0epTGi@RtXZ{g<=WNjSFmBljwM^x>{+y5 zyQO8@*6mxkaplfMd+Xd?ym|HR<%?J8U!`5T3;|r&@L|M>0Y7ud^ z%$YTBHr$vnXV6F+GY(xk^OG*7Rj+29xN>XJqb~C+PQUKCM|ggYR9v84+q_w z_;KV&%OqFY*ZK3jQ|V5pPJL~4?AhDiLMkE8cktoGk0)Q={CV{0)vssY-u-*{@#Vii zERg7Z{Q33o=ilG|e*gm%a3_{rDrCR_X}SqP1{-wnK?oz1Feal8Ysx98q|$Cf4*xs! z@WZsO193zWOEhshyP#8%FUW>)j5*VOdl5#ZMx*gY+C0PYFUB0hZAZvZ19HgHjLWS@ zBZ)LENhO$LMuJoD6ZPd-B`q^1M=go!4ba1!)TL=#nXQ9LU&?82v_l8#JDE47qFF)!70 zQ%>JXu}dx$L+wW_6O--6QA<^o$HA~{3`$jnTy@r?WIYZzCTZ%~BhYg# zB6Puan{1faGF}V$G=)!wvEtzjUUA=nH3c~4N~yKBTby&&d1s!%`?g-7 zgBE&dqKl5Oz?Y0JNI^rDcKT_kqgLr&!19%pW~{RYab~T%_S&t2UGD2J9aRR5V&Ys( z*=*!Y))h%AFJ}8j7d>X~)wNf3du~+o2DY)v?B-j!!FRk3N3o%U`Rfz8W_(1OdzO51 z$}5NOXQ?ySd~?n_FB<8lg?=}5&r3J`bf>BQ%W4fDcm4IU9EW{&+W*5&T(80?leq92 zr>w1P-kIBbSit=rPVV538=3Cn7iKy6+CZjFMjxSn9(vfMXYO|A7N@;K*}umwa?8s% z|NO}@M}2+v+jsx{`&x1-=+WV~|9<@QR9z|7y%+!g$Au4o1B{vNxObPuEH8O*YfY-K zmo^3VDp)u|-UD+pJR->mgIIEr1#e}%()@;FAncX)JeVUA!sdW{@gD)FBS06HsXOSS zVGV5@O+(i(wPH216%CQBwvy;9mqIIP9S< zMjJdKYt+U!T&>K6U1ZJmb~Hg%agmIw8RKqnmBLb)agCdiWB+YdxR(}6(JfHaqglvz zLqG;nkm|`H5)FAsL?+T)NE0Hs>ZeFZMpBXyQ6f^9*hftME0de#6cxFblrPRPDW~F0 zC`DPu!xfHVaHL}@Pq~^3`pS1ss^cpoQ%l&OF=V*3rE9QAoIC0zkDQDhG2`;bK_*j~ zf-K}Do%u{?Ml(O4W7H$1c};8@v64r*q%pk-CO&>soOJQz?L^b6Ue?M+QTk;%B?G+R zA*r3Afu}oL2{By)Nn`dbO&jmlJc#*|pOF!0%YuoQVUE));Z!JAkhx5VMznm*%w|O` zdQps8M1GCj6A?4|QIM8yn@ed*q*~Wdlx~QjDP<{H%Kw?T7U*uEN6}(r9yU`t?#_Y$ zZJ;Z0dYQVNET1%r;7<|5OE(s8p2uRPQDcdmgCex0WLYUoA1YC-W;JIN4QW@s`qgIw zF==?RCRojSR(g%Jn^R>gT&mhuxH>edcd6%0NjVuc8kKB1J>gJ`<5Rspsi|?}*iv&j zSe)*YgLpG6jsP22Qz6zgb3I2woyR;0)7)-b)rXJL_}Sm8#NRwA4wE%}<<;p&z) zl(j5eG22khc2>LFjn8LQ`(5yc7ifQS3F**f2mg49SH0_P5NnxY((2AuzSos+OJ6EB z=+bnZqqJ>)&qiDiuCkTV4J=Y6ScammCc*hd?%PI4OUcf(pazXvDJAU2hB2i*<;k1i?zja{ z9h?RuOtvHQbHQ=EtKo#4yXV4)x-+(ljK8Vj4rf`*A69Xfz5M0-h?S%HIW3sYd}ffa z7`{|yb5*R|W@6UZU{4-$7u-OHB)hZ6b}gCl>iXmcThPc2j546}OhKNm?9k~nFl(mV z<~JJ?%UY&1ce#vaOlMltD{0AC!;D_@ZvR@;qi%?rT?=O_M;g_bl(VwvJY+ij_SHiU z@<9Cx%39wzsG_{JW^#SwB}*{T%3E|V0lb?>vsu-goOGp~z1d5XTH4d5wn4~Sh*0mO z%+==hs7>wSRlj)I;f`XfK}F}A(z?-%?(c5H_?KPJ`Y6H1UaxOiY+J5dRn+Sk1m&HS z2~+r>7M|+3GuiBCCp@Cj?smf+er9!zIVRhFc*Vi|?URywwg%U@3(egnA?vtCvSx6h zg?ra{%lp`UZSpNmF64lpjJf(&?!RODa;VOg;4S5N9}%u_pbwJa7AJbq*IQbdc+}`i z_cF$J-f?gC9P0o3c&Ki?Umjr{vj6EebZ~y{Uz#tl<%sz@gYg~52WQXb>LgOKQw`^z z2VL$q96HnOes{DY-6Rypd*8w9^r_2M>VdBvWv|}u!i;^UD;I7T{=kN_^BU*w#ML~* zKG2vK&fX|n`;a4l8Mn`P@a3N2+)WSBy8B)AtGDR2v%L{QVVm`{|2tyVO85)o9Oc@gDIbhNnt8v2aW}-vDHjBzvWve2gFbhXKE3J@HYmU`G{XSH8{}sYP7mq){BlXhB5h7{e^grQi#m-$OaM@%Y5itH409Gjnd z$E4aqS`kA<^vDtf$s+4Q{`04NWHf*jyFOz^%3I095J=dvNbxDfgS^T1NXUrXNuC6d zKk>$%3`(e($cvOBnk>po$w(G?L6Te&U&NS2{I{k|JjL@Mk<_attGwO1%EWqt$Llwn z^T){wMMxt^oc}ya&$>gQTuZiWOScR$qD0CjI!d{u6s6n?KBLDnYDb8P$0wW0qvFd4 z0?ePnC9Nz>n0%m7QA2qX%hHg^*P_eWu}QS7O!Cmlx6Dk<+)U2YCfjQ*aH~r_l1$P3 zlDotmetJZUX~YB5OT8k@#27}!Ow4*KKz_q1$MiAb*hC?7Nzj1I%Q8#L98USb%+5Sc zi{%8|9}l<%|N2&>{^U?Zk|fG@B#srT=>;#zIUg zSkv&lO-enlyETiAe)H6a>w&B>0W!ADx+G!-+ zd^KIwjb7=U-oIsC{e)eb30>^%3fWbqvRzQfg*V)t!Qn;QaAnu>j491+pz|fFxa~>; zHD2HKT#vmzkab=sg3d#17;h9ZD9M0 zS!LukqJ@o}ib=qWn82NoHK=k*f59#zR?g-Yc=?&M-N$YWk+d7fu_zLRE#X6<0-7nbJbYUEeKl|^>MZg%Ay z7L{_g%3FTmf)-v|2BY@XjW{*hBkn;Fe&;%j=X%a)jo#@0xMzIE4t-`}eqNO>#@IVc zXahC7Fx_D<{^ExYl7qG&f9{)wP7YuWW;kA6HoIGk20D!9XrK;iq2>vX{%Gqk>P;Ex zQn{k^{i2t~!roNenTFAU-qdrh5tN>lh~`J7`locB=r|arv~Fz2 ze(Z-R>bH)IkS1WIb`l%Dy5M?cu)}NJRKA;S&(V?kVO_U*rBH()K9k_qh4?qM^ox%55mEAe55{%T=X(w%l^ z*cL+Bu5Ikj?x4PH+-?iq-d^4wl575Lmox2z4eTRxR9)ouU}Z~>3(wMNnIuHpj+lkf&-^Z%Y)IO6QY^6Xta9J`*iy_Pvi zT)x0IPa5V~}3@4Wr*0Y7mRA8_tY@Uzfw*j@05{qVq=%HS604R4qlzeji+ z!1e}G#B^KE=<%2g@tI6)5}&*4PH`n)^8Q_M7B8kJHxU@W8{ek0x#o>TuGJ0aB46FH zt;S|jvTsom^2K^@Ih_^!{w5cnBK|(|(@SzDk8?RcT_=xnu~>7$o$}+ja(T<_$ZGKC zlkxOCs@)~m`Hq{>po0w;^N>+(c|>y}k4z(XbDuWxIlpvFpXWNabFjekz}55N@bhZ! z>m2W4L3b+fq~+T>^in~v^&a$+3)3nGk~F`?5&x%j?t}A8-*sM})=lU1g#vcSiECOq z^};mv#mI7gM0P%VTvlJ$4d-w$HYzfAo(iq@!l-p)^7NW%b6gKPUGH^qANM}}bz$EM zZl_vMzaR-m^}ep)XEzmQH(S?K&}NKxL?5|VpU{b2=xj!uNDt0i|8~<0cXB^?ga=V` zKliLi_m*9E9lmhi5+g>xn|a5)Bb)Yk!uMkDjN}Hkch_b%u6WGQc4BgPg7J2OPdI~5 zc$a_q<6L-#zY3HmScpd@j&G8^uJ8lia(GpCt&R5U;oOpI>Q`}tkXH?pC&x)&c}i<} zn2&m?UrU*vc{j6q4!QYWopl6VO+Xjhr2psT)=>31`g$CWjBsA{4IctG(3Pd%q?$KP zm3R6|gZinzd%Rc3s>k}c-&UW=hIGAev>hNHCqDQxE*H-_$< z9_Hy*TDmWIOV4}G@BAs)+PbXZRecmzs zHR5_&4|w(*c;0_D-w%HBFMseGeugjpL*>#UWoqNDey3!7T!w#J(*9aeeQS?>;hlc7 z`Er10A#fnUf(8#FOsH@n!-ftY9{(%@aUw;A=PqK*sBt4ljJN)Q3@LIX$&w~dqD-lB zCCip9ySa=hb0*E2HviokC?OBeo<4s94Jvdf(V|9=B2B7vDbuD-pE6Y_;S$xVRC&c8&%D)fHS3H|$~>tkyWo&6 zv1jAXt$R1bCtY|0cjy~-@ZtoAlo?`tIrHWQZ99KBc(djCFsm7(k7&mS_Uz@1S40~nxy0}@!Efk;WUn1Ty3*r00vf2GgA!V(p@$-xs9ho^ zM51JrmAR&*lTwOirI%uwX-PGX2_Hc^V&~hFVUoHKbfq#xU6DWXh^ngx1xe*=r@m?s zn6oVVV4^WC@Ke*+%4;DZa6 zvq3wb2)E*km;dxOZo(~x{{N}2YG&u+y0r{cJto5?*-ybxbVXhU%c_hBcHtT%Nu5RL5Q=RyY%nkKE3sq zN>2MZsft%+7n#Fe9_Hca$ZNpOflhvTt-I=^m$IwhT*6J3PI1}scL%?b+HVy7^_x}i zf0x8|c6XLNJ07oM51wM-b=4m7eVGVgh!!GepBmVPXO*lwImkB|q*CKdkQEjr( zdefl9MCd|`YE-8*w4zE~DpQ;4)TcrdwW>N0yntA9se$I zi#t5XmWXG!U2bldTgc2BD>wjWK$ySPaf2IJ`z6qdHKhe1t#xAsNB1pRN%pG(EKS?1F3M-pj)GxyYn1iG7=psq{C+Dqb;*TkK-Q{C8ag zrfi63?7;$$Nq*w(E?yyw;Br=&rSL?lc7@a91Sc)XSu1jQm0Z#b&n}pg)n<*sDBlue znUVH=F_*jSwgG7AvLHv-a*^ZMY>no%HcE^V8?Yd)Uh6v+jFa?}4Z zd>ugQ**s3h&WCC2+$(1}(MsHMm>ccrM?*T&5goHt(ag~^TiSYRwo$0+JkvSPRBNDi z^PtU^TDWdFuc>H05*Xm}Xu7U0D zcf&j0@@AQ^kFC*j+k0`zeh&^kZOb=qTh4WzwuH5v-LU-o^JzwbD{g&*Wp4SsfnyG#GhY9HL6 zZ3WJ#XKQdTReY-#&tS$kZggsOeB?@BI@6o(^u3fE<;EPk)PJUOd}+AlHGDbDx7#Dp zCV0q!o;l958*zc1S2q*)v9N+}=0m6Z=yIo9(w}bkyW>6Ydbdi{tNux<`#oe=Ukxp_ z9>30Z-Lwf|vRDnj(^Crs(1~YwTEp|^vhQ@<u=u?XN(3SiBi~6bBY3UwH6<=vt zOb#X(4SrWC?cnYm9|wXM{kcg9Dk15OAPPF+6GCAWN)Z6QUfs*pVare<7G94W z0^*s(Am!+h4en3{!kl+qjsvzK8@gOQftPv#VK3>EA}$>K#UKCYnHv&5iyeX@RN!GB zl42>E;wk!<3Pu(S4x$DLVk^o>A&%0LA>#XJ-uW>iaQL7CLgF3O+0KoZ8$R9>(19KF zV($qI9A26yhGH{{ViTfbG)m(%QsbZeAuQU?D`KO_XyFbqo5SSdE<;5fHTqJtTV`bIjJ&I%kL8CvK)OX`O~ZjZxNq^m4oXK2TID_hq)ZZxQ)*@0bR)x*VMQ3%o3w7$} zW?W~Vo#*A;A}-Qq{x~Lh7AS)y=s3OO*5T&i$=1U~=7Y|LdrlpE#^*>b=Y4W$hkEFX z8MJzs0B`G{-h|Cq@`M>&WobXcv|Gr2<16#r^Xne zp?PNg1*v=@1d1JLo4Vk2WQcrfD+{DV$PjrCRDUCF%d2N{XFoDiY;s=LBkO4l0~s+put{9{J{a zAnHApr!4U(`K&5=dMU!ZYDGBe-$81mg5soJYOnh0uSQX(cIugM>aecFlXhvSy3wB6 z64$ZXm8!?A_R^>}BDJbVtcoY^WoBE}s(X~_tmUe%O67b4Yq^^1xl)p_8mo*H>$;)@ zvc{9LZq}IM9=(!|yq-{%-k`$ZtHPwJ23l#qR?UDaWe_nXuAXTUimQ;4E4n)D!$PbC zsjIubNV`((rhF>-&?xtmDtFqe!<}m3{cGf5t8|5It(5GSMyvUBE4W?Et#*>dwhL4) ztkLmm#Nuqu>a4j;?8T~x%=+wpWUT-CY;4jHtT=uw!$50nCas<^t8@u0{fz9uoTY?z zslEo(w_04d)+`9#?9PI1*orNp^lZ@T2hf@=yy8z7rsvc;YrIOUgSBkv#O;B#D#E0! zn09RJ)YaZ9?aOMd&~a_o+TYiX?cpMB;(kcknyn`_F7^yRi*h&dJ))+=420 zKJ8n%E!F}@j%w~~94)TEEGMC@rqC?ms+-{|?(4#C>^cbJKJI*^uFtBigQ_3pil^oF z+0uU1)RN8UreoChoAB1{M5GyDo5%5L>q@Adu#?bhyT-0sEZuJ9S2 zv-xJ0Zk_Q03+QU**syJTbngEvHSb$3D%zp%8wT#%CG00kZwOK^_VRE4`mbAP@Aj5P z_fqWl_MX4VCd`rVDq(ITBJcaM9Pjo9@v1KcGo1M*N%A(w^A-{TSIX+P1*zop+kD+U)w`#z%5>Tr9MuIbiq@uYf^$|(Q*d_I|m1c5eqj9 zavHJoA@LH!aU92P6GJg)sPV8$F&3{%cP8EyH){h^B=XKLsu*f_n6ZR)apkZqsc7PG z4sje7aT{yg8_RJeTQdLH(s3PY#vONR9+%bV@Nw5AFtq{iZ;q_*vemW4P9itWA*<2d z#un6|u?ya>B0^Uod$1V{JJdivhqLm z?UWQVT|V+M*0L?%A0_W{H+yrX_OdVE1Tf#JFk7M)eWlF2GOAxh^x^(aIboj_Lm7-Bq!}IvT z@^xV}*#x0H|8&&|wE+6_QDa$BGxb`tbw4`wQyUUo7i8o@m{_0FRr?s#XmuKiapgJl z1n)FZZPo`iOM00o0bFTyQSeoJ3=bGJyyw{&{9*$H=eySK3PpmIN1 zf#(u?5ARo_vQIL&UX2ZWyW&~bH*ejyerx!K;~jtZH*S4+eFQiI4mhre_Z083MYA6n z*41+FbVqB>M$d*}A2w@)q-$UJbgwCg^LUR_qlbU^f3xO@bG3r+i;*MbJeRnhrYcO) zxO%gei~}}v+qhlgc#Z=!b^G|1bGZoud4CIeY7+SkF1eSSxXUdhYMUpLBMh&Uc@I4~ zjDlZ!2M2{)p@n0)WAAvE^Ld}6;FoiEm>1@lTVN@N&zXN0pB1{m`e_$UimDZ{x`mcgh>bx|i==F?~<3yrMU|2|0ZWnN!YZ{Eu$@&jbCQ6Mfi= zeTx~rN+UfsD!oKTy)U)8MEla(i%-ojS$e`fsnB{+YL3na;w|UPZ~dcgKIa#e$BX{&1HbZ+zBrryAfkS~Ui;#+ z{$8(o1uwso&AiSrzInm;kLbPi6u<8HJnt`*?+5?)ga66RJv^-oXvcLt_&KkooU3xNX(O1N|oVM2uq88&qI5Mo4$6Dd}- zcoAbpjTj+9dKGI{ty{Tv_4*a;)ox+QmNk18ZCbT!!QMLe7H(X* zbLqkrdKYhAy?gog_4^laV8MEylzH-GaAL)G4=;B77;@ytg(X*h(#3FP&6>L)-uxMK z=)jFdx44|Sbn4J$RJV5hx$|q;E$Y^`9d{{P-Me>><^3CY*;@l8o(%b7QK z{v3LA>C>rKw|*UacI$c#`t<%Ce0cHW$(J{O9({WC>)E$={~msP`SZ&I)mzjkQl-K9 z_xJxFz_5G^kiY^BJWw~cZd;J9*&KY(wZce)aI`Kcyb!~IhA3l*4DmV)H4i_VP{a~l zW39CzB=pQg3Q24cM$k}<5i$mC#0|k5c^gp29?=?3pyIR}lE@;BJQB$ym6VP<`kZ_c z$|$9rlFBNryb{YSwcL`+F1=LAzP#`|DyiIjJQK|{3*=GFHr;&lECp}0k;Xb<1d+u$ zFSC=+$YSGj#Xbe2Owd9Hdr>t!J2Z5)MHzi`uOTdi^shN@G!y^MOr>H|(@vQJvIQZR z9F^2kO+6LW=9>JH)mB}771mf~ot4&FZM_xOTz3i+uQBz*)YD*v?Ud7DjXkzUIW4`7 z(q>D;Q_o4AomL=3^(-SqY6Z$xTS{kiu&_V7JyhCpA+^@rWf=q(**1%97fnz_O_kny z?Y$S@<5ty`-+ul57vO*e9+=>Q4L;aOUhnd?On4oBIKX!yo|s~@lvTGbb2U~B+7|cR z_)&E2?3h}SL8j5<*6_^p872wNnxQF-cRSMt?nx4tF_+xVw&ZG8SK4C&hY=^utzTUT*G88lu)zn{1(I0 z)`l5ww_&V%W3Owod29c&?)x{MgC3ml!hIh4>BJRZobkpTe;o42CD$qHpr+;<@XU4o zTl3D_?ON}*>>hofu^}v*bQ9a2wlHoBbv<>m=XOzTw^NSYK}o|7oi5Bh*NyYveAB~%||*xv`&eQkN4%Xjb1;@*E=5ghUeSU>|tM|sp!-~t)gKnFe$f)SLS^#+2y z0A7$-7}VgKz^AwS*^PX&LEQ%-Brc5w3Q*=Fp$Px;M>cG=5K9HbLlV8J~;l0SNc6;ImHPwXhJ5N1x2VT!&XKQp;4iqK_%O+$*6BeG%}-XmO0Ux zOm*&&o$nOsNU;;oe4Z4gDOKr8S^CR;5+#Zq73fSqI#Wto5@Q%W;Y3HnP@N7YeeYu* z{K)y!yl6CqJZ+IrjT#uHc8jAnjY>_i7*dj66|2rMX-m1^~B_Ssnkjbye< z18b^5wO* zi|c0WdR@H`wq)L{ZD_LF+VV2$wrgeXXNlKa_c}H&-7)Tb>04j>-WR_KL9SVwYt!}i zw|mc>lXso<*Q1)2z=Wyh3Jolo^NRMtA#3pI#=F-pSodVxZC%B7?8is?}$lU zViTV@k^7Y*fCI{57XMDbH%f4Ur~4rU&zLdby`O3|!&)5gMaOT%Ooby8>UA$$@#h6Y%rqqP1E9SfewV*>?j8bPD;c2ze z&5MciTj$ItC7-p+0c`S<`HZ|MUm4JW7WAMAeXA^c`JZ`4G}j1f<}pLF%#OZGcc(dF zz|`5O@jG8^9du(!n}*1Jy0cUj?Y%ws8P$dRbD>$?YFED+*6lg;qCHA$V}hAMpMG?R zBCYGvg?iI3lrxfNi|Nr)8Z-%Y^o8vOSt$N!57x=&lUhr;* z8M^xh^v-ud2lzk?O)Th}4o1uv|wXYA`>U-sG4Xkd)%^zpXy`D1+iaG;}C8i|Yf@;kP;*kUhEki)%>a-XE? zzifBUAHP(fFa7`WncsZpH}3SS_aE`4&%s8&9`^6`(uGC;vLoNBHk+{O|u3aCCU?``BRee69R8ZTDKB z0nO|H1?2$~EdnPH2a81cG>`{-&pHRl6|Fh@i%E=X{vOfYQ5F5OT>{1R*i zF{$?OVhWAw_kiz)gfHQ4FbBV|q$&^y$B+!m&<=#1y}zF&ekRmwW$w9qz3(o4XtMVz|au$UVb1?D{Y< z6C=tLSE=$CL+65y1rt!+5-$|(1QlydvkH+FanKcI5gMaW8sm=^Z;@gq(Heup63;;w zt%>Nk@Am2thVBrfP*BY91OTt=7u_ZqjR_mY&G?#89`!{Gr_mno5g#qE8nf|X-jN@7 zV;j2>X2|ibjuG;>sR{*)4kykI(y`b$5kuM$u~cy$EAkoh5hF8FBeiWG|FK>C(IeL) zAO-(&Aiq%$z3=;wED9B>7gy;p_AuRAG9oi?!zi*MC@H^2Z#qT1*n{AhMI@Y7}J%LZ1N^qF(-SHE4$Jw>FXzlGFXICEQO;e zjq)g&(x9M{3W+QsS&}W|NSeYWF2%%=PO4lA?r5V!Ix{}M0*Gpxe0EH#BJ3$rcG z5-roRF0rXG5pbK-@_p{I9Oq_bChjq3BQJ+L^P z<5ND}Q#nr%DW8cld6Dtn5|i>1F8=~1j|{_Fi6)n9J4>!RoAEoxlR+EQK^v$%=Tkx_ zltL>sbaVk8&H+O;G($JkLo?JuLsUdZltgc+KEqEk8N~@>(mz*H_pq<+rqTe#Cp#bM zFdc>&6ZGj8^g(;nM}HJ@BD6$@lt_!zJmDcjk@Ostlu45mM2!?mqf|=e^F(9kKD$LJ zmvTVK%PBv|KMQIdFYObXN;+pU?((fObyNa*6iD0DP2bdLgmg;hluql^PVfH|PxF+S zsuXvww7{-2-X4TMg$hvBZoDp&&I;8vYIKiowC1=|O(&2|;gnJ<)lzfCG>=nLHPt7JwpU^Tm&Zyolb{JLW(lk<$Z&EK6 zSc6qqxr8tg(^y$-BvZ9dS5=f=RZFp{OF>9cUvx8|bA`SXMsyX69QAV`wO85iSBF(x z$CX^=qgam>T|FyVm33LCwY2=NRfS?uRn`BpQ~{$kwVZWk3KY+H^;cWQUe$i`HQGf|yiR zXjn-_>7Hv-!Y59r2 zmey_it7)C~X(ts*bmYR8^Tzi0L^f>?7je%PW#5)@K?+sn z)=FuXhWs|cWEM~)HC2YTg~P<=&HwCwzHme2t}i5!k&HxPe!gg}w5DBN&GJW`ZfWg4uFt7e92xQ5lJgTGgV^!Gxnc$Ku+wQRLz zxHv{EmnUP!Bl{4^-C0Ulsn35~mk{J(#y~~4#?uM(Sk734gLxvbZiIfW% z{fbzX&-Zv=nVFjzA7gozqghkt*p}7Kf_s^ZG8u&Sn2LLNVslnR?$}I&4^0g@nfr~E zomrjN`R|}vn&0_*YPp)NnclE@hV0ozc37f*nQjKsi&a#dFQk-H51G$7g_oI~6I!9k z(4FDgp+iuf=b4@}igMemq8kc}=S>OmIhrz>hWP)vMvNH(&Do$=8KD;%rBnI>8~UMJ z`aq~zqVHKPJ^7OZc*nR|G(h>Ma@kO1bbm=`pfBi@gT;(X`km5QrIT8zUyY?*+Nmos zqGOuD(y@9Uj-&Zlr++OD1KN(Wdd*fSr~_!IJ*B9Px}A`Esnc4mebSN3YQ>%!u4^u; zrFyEviKod9q+bJ^0fVb?SbPB4MEV*+!g~4&+N`q*t=C$y7n{VII<6lZAm^H{>v|mX z8f1c*`-XW$EW3U@*Q=?EvloM~y=SahFO?7bpwpPKSDUq~&aojIwtGmjC!4Z)FAne8 z1ua;x?>V%G4Yv`hw-aNuyQj3L`Lt1+w-W!mwU?W@C+oFi8@kB?rfFL)O>&pNFSxjDcnTa&4jjRONWmLi#aFzS9z4Qdd@3fK!sSvzGTgj4T!UZhzI9ET;|+lGD#S(F z21)wFdn?6R9LbZMkX#(bo1Cp?d&V2D3)le1$tb`lcE7Q!%E{=W3)05%V!X*)$OZAd zi~N?3T*=d1%}uYZGt0@}JV0bT%G>|)zqP5(>-gs|@v2X0_O9GPMBD?*+{|kU&DY$} z51o3L9L`}}&gY!Yw_H&6yd+cR&I`)VBmJKptjp<$kPURLOnlG@sL&Ce)JuJG6n)Vn zywM%~(XIN@F}k}Xom$`O!{rRp`vTBChr~JPxI_J@PukRjUDy=~)l)sbSDn=}`_}Jf z+4t9VDqWnQ-I_%CF~VHTJH20t+}E#a)Q8>Mzx`;6-PofW*^^z_vAY!ANY>vczacNn zohpoSy>oWmO+bCyQ4ZL_UElW|g2a8?W4qkV{oK!S)1!+nUwzgM-dY7&gvUG;wf){j zs@wUU;wydw+Z>YrUE_&zPX+&;?4&()dR*5EgASUVQ4s!mGhNH$-Qkt-(|bMQ2|eE} zp5|*F%P_ueH(uw%BH%rq_CQ{{bdfdo8m}Gg1;4zou-#`NKIYGQ=4~G8qrU!d{;hZ3 z>IbUheO{M=-k)`GLg@1KkbZlA{JYXf-ic7qo4$Z1Uh3Q4?V-fquimA5Uh7?w>pNTM z@$bnzX#?GAH@-W@lPN1Yo+lWAD$sU@+H6Wi_Ytr3hY0v@1>R3VjnL)A80PICJXU$+M@=pFo2OeNyJh6QM|xDqU%Gsne%WpLRLAljzi_ShFfEqqVEouPmE_ z9m^A?*|Q{XeO$}7Ex~SX$Lhy0z=quw%=fO}n=3+qiS<-p#wW z@87_K3m;CrxN+DLX0lk$LPd%cBh=2FPQAMI>)5kv-_E^z!jNdgpCn7Zy!rF!(>o<9 zR=xX|L%6=5|Gqs>qebcK_i2B>f3W@i2bOpQrsds%Y{7-#f*jSQ(p`*2DB*+@R%qdc z7!u~#aU6E&;fElGDB_4DmT2OMD5j|5iY&J1;)^iGNMdp_G1uI4(J`pwjy(40z$_Q~p=R5LtHFlYCx6Rb+wE32A0Q3ZALv zKMuA4VTS*3#wq8Vbk_OThBD@<=bn7_>F1w-1}f;FgcfS(p@=3b8;vp9=p1xqt|{rH zlvZl#rPC2PCR$;3>glIbHVNud0ggIqsr;33m8s`F(FLopssv`NK5Z&qq?qoQX0AK7 z`KFz~1}p5a#O8&kqR1wz?6S-@>+G}8Ml0>K)K)tjqcAy&Bd)x5>+QGThTE&H;n8aD zx#%h-YPvWP#jdAYuE*ZHS)odAlJ?&F61iw`E3S6C{=1#8#TIPv!3ZaIthEd`?C`@7 zM=bHg6jyBV#WG_1lD3cv?D5AShb(eKn(}Lsz9^?m@470tRAtLZ<{Q+NFb6ej%>v5Y zvdRBu`8%>)0slM~!3h^_^w9<{jPcS;H|_M(P)9BG)KpjPo5n72oTJcOckT7pK$gsN zN;sEoc9tx+tn=CD-3*mgSh7vi+H#W@Z{017eUi^$cNBEr9ubZ7;Di@`q0&|-uK41N zH}3f3kVh`La9FpbHQ#_|uKDJiOC+}5c!w^!d-JO7?&ze)jaAyHuk>>3=DB^g-X>w* zIYocpZjs=I_wM`ef+0Tn@WdBy{PD;qul(|XR?gDpx<@bl^qYS^Htg7EzxwO%-mSge za4B>h9Lf50 z7(yKigoG!|q85RbLK%ATi(m|+7{^FP8Pc!?HngG|*T}|?@Q`0jj3W?*NGtEjQC%A( zi}=`v!8_h$iDrwUNT!&>Dq0bXTTG-P4;Pcil<|>}jHDzdNy$o1?2Kt_qb4`WNr$|V zTz(8C1L}Czr|0W`5FEu8b!3Na-n4O4B9Q)JhUn2FPpPB%AD#B`t4g%N*izm*`CA zoqAc!cDnPO@QkNCi+RlDBy*h2%%?ut_smUs^Pi!krkA=2(3ya z%`7Jl&#BIeR&#Ti7IDbX8J)S^JuB}P9=)S?>os7Os}p+b63lREXO(?e;IZc0^{?NLe$y=GPc zBv1&}w5lx_0xV-GNPK>!n9ZzaH_KVN-gTsV4XtQJ)>k7H z_O$Fu?0;U0+OT}}KdU@fP66xChn6*>&YWyzce}{TcJ{Zx4X$v9OUchFbF|1!?zc)S zp4K`Sf-OB#V_i90e0B9x(>-N%VfNTgM)rVe<*j%P=Ud{M_q^y$uX>MXT(c_oz3|l$ zbIbMI`o?OTq}y&)vx~&&n#zv#6>ICd%gOH=FudbU@X^Y<-Ud7P!4Qt{!`d6)3R~Dr z^W~I%H_R&hqUW&A)$fyHTg|a&iaya8>#$0D`WZ3b<#4J2TkZg8~V_c zq41d(&FHwK86|9vbTyf*6%e=9$@?L3la+i^0T1}LJk9Nc08Q$m2^!I;PPM96onA#Z z`qi+ei!3Eg>o5(0(r@E5OjCI;H}A*NsKxZC^vp&+^HaB_PIj?Q&FW@5``OSws;gs7 z?P^2h(c`JLw&x7&rx20I!j`Uo1w>d5hx=2+UZb(8=V$+AyIVrcj<&q#P49YJa@y9; zx4sR6?UQZ$-=XUER-R~X6RVA;($)2yv6pT&t~;v8ez(Nu6mNT5{NfnTxc~6I?~doY z-z5RK$gwK$nJIjwC4ZN%+qUL%+ct{sHQ>Xg*Y1hiyf78lxXyRZ^PVq`;~oz>tU*qa zksH0qDZh`w?R)NkH@#gaSLxF`)o?4$JbE?1xz+)bbDw+t>tGLi!+tYYQ;0I6m=80LP$2Gg+&5U-Dto`w9 z$K#ssjy7CZn$37dS>6k|_h0$_^NnF=;YUyU(wqMtP-I`c>f_t^b3p#}u#Gz^+g{Mj z%boJB#eDWQU(3#e{`aAWi6c)>{Nfw`_#tZVEtb#x<~#rS(2u_Kr%(OrTmSml&%XAz z&;9Ou|NGz%zxc;b{_>mu{OC`=^JfkF_UnhvHgWlhX)pJ>Uw-oRe;4n`>3iV&e=vZD zd;&Ot1XzHZVO+A5fC{*P4A_7U_<#@?ff6`@6j*@~=zbVTAMiI5_V--2XH}Mm6u6f` zBbX)oCqh@JJ6ZRCHy3~g_<}GPgT#k`7FdHec!M~YgF3i_JlKOiXj&N-!Z-+YKq<&Bsh3Ur%Qdosn7=Hf|$AVg@7cMA+UigJz*mE@agJf8SW_X5Z zn1*V&h6*HvZkQe$$P)6mVIO!ln&uRB2vB*be{9%?e)xwBn1x%ogX~Xj`)a>7>Q;0hLqS}I@5v9g@mxOay_Am<>QGlwvi?ry7m3WKh;VPB}irT|#aTJF;0bui|J+)Yj##n)-c#8g)imlj;&iIVz z^@_(hjnr6;)_9F6g^Sv#N7Uqt=9Yh=bBCR{bQ@M%42O;An2u95YRWi>%m|I}7?1Ke zS7XQwz`zRln2-9nkNnt={`ijo8Ib=1IgkWdkoX7;%zzFj!41(+3=a8_5E+pYIgu1u zkrsK87@3h8xseWO4c3qj3)zqyIg%t2^jW#(J zX(N04wTGy~iE{&v-o%sPq>e;cl-b62?MR5CH;+u&luk)pG{_9h@DKZ-LsF@bB*6{b zP?b1TmE1s+S-F)t3xtB(n zj7j-<@A#C0Ihcg$OEd@!`;eH5xtNUEn2!0FkQtehIhmAMnU>j@z+e*5aG9LhnV$KX zplO-WfR!V$nW1@_sF|9o$(aA6SrVqXny?w0vKg7J$$oBmoAvSpZa@c-7MHy?cRAsk z(*%@5nSl0akjR;w%K487Ntz^aoXZ)V(piwrc@oe$o!FV3`&gZ>$Buvbe}P$;;yIq= zX-0>aOd`Pwv$>w^DVwZd62;J-@;RTNSq#p34)IB!`njKyX`dyLpZpo10=f_WX`8rt zpipsZb9raP`8_`AIt?04=6H^>B$ZV8Emv6*7K)aKzgI^`JXTsRLoGU{j7p}B`lvHn zq$ClaUh1fp3aOY%rd(>Im71xZda0l)q?QYa*9xro8Ls4-uIg&7?O+YzfUfHruksqL1v(OxI_six#tbkdl%zCmYo3bEvo;Z@81pBhxng|du57DX*Nst3DE3f8S3^^;X z>u?O=Fb_W)wCUOo#(swNxvvQG2ino3%+1g0T8rg4M9C zgNaads~}spIO?$%o3>htwr1P5B8!wHTe8BZvUFRwb_+F&IuClgw|v{Te*3q88@PVk z4yCXFd+@jSAPfDF<=v$p%Y!27%RK)bLTynrhX zx_b<&YrM?cyn;KttE#oqJ2ML_M_|iRtt7S~wm=kHwch)p9{asiyAR%7K$5B5L<9e@GhP`vUWv#-0i_h7R)OTWOIx$s%M%)1W7APwj6 z4c4%`zl*v6%(?K;x{XV~l?%Q9iNFLb4+~5V&}Twkk_5YQ9rjzC_%#MtsCQ`?j99zJxlr@f*cb zJjMUW(xNgfyX`;=4_+pfg`47(c+jjO;xJG6t$3=Sy`?|{b+i3~wo!Mackx_}Jx01paW z3_z<6CQQ3;Y{|tC4(iaj;sC?#It_t*y2|j!#~=;X0LYHqxSov3(r^!atjY7xx`KSk znf%7{z{ywq4%6Vsdh5Y@%*YG;$l{Q@vi!Kl?8utD4ygsuqbv>N z5Y(9K*&?MoamK)inkN~Sd45VNM z2jB?`ExZ9;x$Zy%M^FsEaML7k!NMKgeaq0r`p~2n(G^|Z=6&9)(W0uo-XHxA*N_0l z&<@Lx0K4!GHd_LiEf0qP0qQ^x96$!}pbi3z(TdI92EMZf-qB$#)nHB6=#a;u%*S^u z*OE=iggn)stPVyE*6&c@mMqocUPx7|q8W-ry|G(JQ{>9-Y}>O%DI!pbIzt%5-hm z@IcHQ{tiN2kc4b292A= z1aJ!TAP>VZ17my!kIN2AfC2?z05Gr%dg~3$uISI;>5BmBqE70jzPj;H2`FFyA}|V_ z%f#Z%zEF(b=$`KC4jk(3I{@C+~VLwm`Q9LbbS;3f|bB_H&V{PL>|)~5WB zp$p0lkL2hu$`9GQxNPEJO~}UF^TIsv1h3}T)8<~^F0uWKKFqLj^X4!G#6c`btl-w` z{SMwB0Z5S68LbVlpbMX10A`R6H=EM*FzEWg1uL)$xsU`Q@W=)}501XmdyEMR@C*T; z1SN3qAkYM>;0hq%1OlD}FrW)BP1CS&_hc{+^}q!VzzP4kUEM0xA4-1U%{-P3&Vf{F#r!XyZN2p2A^*L zp|7|X00_{q2JnsM99{bj-NfbYZsfi0frAH5el9LzqzELWT_;K2!*g)j5h4i@}4K@!`5+;nZP#Hw{_1 zbJL`yd)LlnN|PAXi44avTsoQLOrk`n64^I$){c1;HxeO7Y2=KO3#U=(LU_e0S_HXN zszRdVxD}IzP~0(T=g3hE2QO$+m08uvl!;R&I-mdHOrFJh^jz4fb>B68O7WuIsV|Wk zg{k%DQF7`+o@6Oa-PWQUjfoXn_8r`CHb)wr%Xcc?yq!IN?%YE3Xws!kpGKWp^=j6w zUB8AMTlQ?)wQb+Vom=;A-o1A}Df8rsZ{o#`pYAgJ_;TjWZd3OBCX>fr zAv;RP8lhN11|-84PB$T^@>21)M*DRbttR1t9RlRileKfnP=W} z6k=H7g&scFWrsGdH{o;`8)&l0M7lR$%LZB}UwGO|$zza-{Y@Lj|4*FFq2~ z`8#m=2)8_OH4kh&Zg(_*8~_7gP^=scEH5Afc<8Bi9(evfr5$XR*js}vbGQe<&Oaw1 zooje60E)X_H;+xx+#Ixf@4x>CKYa1WCx6dEeMLWg_19;=efQsoKYsb=r@wyt@5euX z{rBg;fB1n_&9I1NEM%QSSxG}+0u{JG1~yQE>|jC;5Ll2Bv|||tXo4kvVFd`#1QG{m zLo0GY104#xE_$M z`H&xdVOkPELRj2ELVsq(8~SX=J5t9E8o*!`)2PD(o&im7aqblHltTspv;aW(b0!+; zW}C{lQkJ&Vr7wjkp3dh#n%2~&H^pgAb-GiY_SC081!_=*I#i;j3V^8*V6l#sEEjgt zsYyf8G(VOOd6fTxM#G3g;VOWH|E!}DC@6pgJaC6|Jk_i#>|;~U+C^Oyqpj;iAR~)0 zSFXULW5sZ2Cc7c!;yR}iJP>^Ts=mz$;`_r zG*ql!-*Luy!3$&P5Nt7k!9>|25VpSb4lkuUUFufXy0t0WEw2kTwQbkCqERJmq@&&M zl5&^j-41k{rYx6z%p4LR11&-n4t$K^1?j+2By3Y)1#I4RRowATXe#nj19hH{jp9H*HU z)yh}Ka+bBcWiEHw%U=d_n8iG1T^$uQNhQ?1WmuGr{;oX?HKapGqqKmO2uLUn-6_&4 zB@H4S2F=hzH`3kRp@4LE2}ntobnJWZS!+G(|E~S+_ua?;!``1c4*0;pao*SOysn$( z#Ym|!U-eYqJ72rRm4?;O)Spyu4eVY&4JULcID5V={heX=sfj4*^q|Ej%zz;WQ^}dQ zekL`;IBN)}qV+g%{)|u3Adw2l8S>#sw5MWuwjpT8ZRTuTk@_V+#wlZZj44q*LqK3d zOJle{Hp@Z6^clDAH@V<6K8K`>OLNKMbE-h5+2d59U^DMTuVMPfi{A|tEVN@NUN-Gc05@ZMPbWkV>%4Ipzq6~cqv&j4fY2jNLpGPRY7bi+_ z-n5oBuU*>^`0h@RZ|+8-fvB^WI#Z5NlzVQ)|b>;My2kfAjG;4->_rpC6chB z@rJ0_YV=$iGN$&nM%>E}r%Z@^z>H;vzj`UjG1u^s62wqW;sTcnXU5rOc4kLVlVBf7u{=nI~@Xf-yp2n{wrG)y|;oHh&` z6bp#?hsnScVqV=*HMYron&OaB)lX{lCG8>}zM9z5aeJ8}Vg%@-WnJYoS;;UjLLTBH zV=)xffTkeEz3kyM(k~>qkbnK@HRDu)s6owt{aGND2@tPEWI-J8zQ0yKC~clfEM1xe zT*gv&mR~v8og7RhscWZ#M~Xr&Vf%qOGo?F4w@N zi44tBS!`1j;|^gES?PWZ zD-Z@d=&_j>8~2yj>^3~6BL(P_%9Jy9TQfB{!^U_Cz>8dyUp^$kd+K04=ofP5vhZ@B z#oWW>vdT zB;*u$2(kj#ICB*V$~aeoe9~Ms3W9?811SsfqN47w0_a?PUSZ9dE46iyr#hR-cj4#) zgP!g&OXY#D#D%eK>Iq4e1;Jd~l1dAFp4AKU$AvYE+DK(0D}SeMt7>zn{ulOzG7R*u z51KGqB`6tl{BIw${}(ssdnk=qz#lh<`9+<}=&G}2sNvM5_@$YJmh6~n0nxuPVQ_0`eoSjjq6-PO(98-To?cv&By4)8) z&6(!Ka*;`8hgSdIUHBGwb6*MR=JW^eDugsOUYzXx?D?Y9+@!b#sl30YA*8PXb26Z--q9e^e-5lffuuq%MoQbHxlc_3|dBP z4fYZV6zbys5%l0u100?jn_D%~|$$Yxle5Y>+vvVuP%{L2c zR%J(Q%c9I?MB|!)V(LpkS zQWj|T{GSh6U`k#YBP}8oO~K+t<<4sUZqwzl(5rl~zZ-{0>%37B=m`5Lu=$Uhldwvy zaEk42-9~0ou-`$|!&m}~o0c1CMJJ!x?_$m_IOu-H$Oa=8c-ec<%QInl*hf<+UAv65lrdA?clo#R60#Y9F8D6O~XVyEF` zUYR)cr`p+i6VlBook)(@?0m9&c^HBk`hpR4E?MYk(xmv~loyoYNwfE50j2jwHwv8xlpd^l{IdS$@%nE-b^#n~Phh^!1sV^f!uW z8(}uMxG0+@G2Z;19}L&P`NpcHlU^r?Co3zjxC4y&`sq#^Fe2 z%>cB?&1B8buVI98Q@v!C;hI| zBkudeon%bWHxc?Np2R6N*)Yty#t+!uNoWc=qGzUq4vu!I(BO4KJXUw5VQ&OsUyh`} z#31w2!!$~~Thi)j%&UuD5%J}&!S3KZ^CO<5o9u!uZP*g+%z9WqqL={g4HwG zVcS*miE+|^T5hTvj8%pqV=2MjGu3|#DMvrE;ITVE8;C!ys7GNpz%fu6tvjwnQ7x=w zz?qr8nO29DNkE>z>zSF4e^3o(`DOG`ZgxraJGvhuglS_^`={VZ?U0N(wG+dkoK3_aR6LM%?-(l@ z@xZ@%rlk+N9Zxo-%t{JI4-`AUvvBQ4RR=ACmE(H!tly)QQLS=^PWHU#Esv+v1+f>O z-SmMtU=fS*CYU|7{m$xpNr$~_;N98*_xar~s0ya1_;rKud%LMbeWsfnbwdcgopgEy zvw6k3;n+`wXiW*f6lWYqlJP6E!q_%c*It4%_$u?}0ybXO*OeB2sx0_Tv8gqqT~ygr zSu_^E`Rc;8fbg`kq-%OppRztX@wIemXrE;QlMZcW@dc@}IJN1*_6_3jjuC`2->Zd3AkE`mhwrxV|XV(-@ z>JIzS90%&>Px?=qE>(;qGh#hEH zeKK&??{(Q?Qix(9}r%Nf_~b^jaY{G}kzmzZ2( z|4TvctttKa9YJJAz)ydxApgri?&$4-a(bGhamR_+SNxlSY`0>d-laYFmw~+hvoqph zXtx|TX&IRH=JnqUWT78js{M*LCyIX**Yp0Df=rgXpJ+#7KsLhQ z2s!G6-A^<98O*e413KEMgB<8RwSWHr=7lFwI5xE62+7WqR5m9Jq z&mRT(VG*nkTTNRuG_Csu3mDg~r)IC?;cmlG{4dd3{Y6)3Y@?R$E%1z--RuZ^n*eGbCkRfMef8*AJi#mSp6Q;JiM$Bp&~6D z8Pf7YV$Oh&z1WLg9=Rz1bBK2Nnce9*t_eYka|h|5|zXu~|6A9$1+J z#1f~A#GLFq5rv4uod)?K%+JoT8x!wtu1Z7 zWEwD#FXPbf9*B~8E<*8%A(%II(rt7Ur3Q4%v{)tw5EV58Uv!y8f^6w_R>cCpIU*P; zj;h#0q=K9{hEL=v5hqV4uPomI^Cj)z12D%^mX16|IzqNU#Qn$%i8)fRs7Flkv2AzI z(3#W#$@J+W48OKhR{J3QD(q*|J#r$^jQ8P@Z5hl`GO|}T!;Bu{ z(#%o*knCI+1n^G7^={nc9|e)*wOSI_Ht$%wM$IhI%4{t~b-l9Z!NZoojE=ndyC zrj({lkm)nmwtH0i!T9?+e}o`R<--JSHve}QQa#}aHy#fIj;<~w=5S0?Wyy{D_c~1< zCZ8I~^5KNvcqTeWAkJ`eV3@8%cGxe_r@Z_HTV)1)1&>nc{KZ8p;v(cO?UJAX<~$K3 zAdx1f-Cxd<=g?LPi9gC8O5^%=gL!V4Ec3FX2MO%Rdkx}kLUJQdy^(Z z>kKH!({`E9d84E)z%SAP1-bsnOf4Q8z?|RVsxPIJtg$0RvFT+r0L(dotNBV7J$Q}2 zsX5WD{?ItePxqsY_KfUA9pQeVk-eFMw+HsiNrNayyaGLX&2gNLN=6W9OOLc?@^Uds z-(Eo)0qxt48q-wM0$JLUv>^<5zvr7~jK22~cv(TQ|)q7mE4Gu;2*@4g3@ikzheMOGh zCUbScRaG;1#m)i~bArDe0R?$?wPp3yQXZfnU(JLra}}<1oHU&>Qr54_J+NOrX$Bc< z6Dr*WFo(=+D|6d}v{x@4uLe+%xw-l}AJ6Ud8*^I8XA4_>Xu@e5 zbZJjfHVD9+n&)&F@8mTvmndeOpV5tO1v~W`K5no14#Pi)RAXDFqtudmE?gEKqnpOR zAJU~9QubMPs8ga=sav!Ez*QHv;>92Lc5SRI_In~VhemCtkz#p#)MHORr>Pqnfsn2E zHF=XcVj69eCflSF;O&y2$NeAiD^i|}40yG$6?-XGr17Hm7InD{Awnt)@VBMO<<5s= zi*UFusz>GB&PQxgk5a29%#;((N3~GccV&Y&)a%b#(pHc1O%yD0c;ZJZ`zwn=>CC;T z94A`v9cB4~Hv5w;c%5!}a1v`|dio zZJR(z2U>4g(_H||eYu$1!+@blE_mKl3Z*{LM{PJsTE&;%n7_oYX~7ys@y5SgKn-=T zC+OcZA#GTMK6h%}r``|1(OD!JaIU;xv>!t6wsh~#SrL7Ubyz~;IQ31+X_v;QUyh1_#5@=)?{}bl*SM+oZh!cj;xW-k{g&y?-qc9HBUW+aw#}QpnV*VIpn=96=g{4` z!+xiuoyJ}FiJc#)fPyTmx96ku)P_;nv|Z@BCg^j+avoE+o$rR zn}&6A%JZRw`J&9{jT;k!$7A)M3JD>Hnr4FW1HT`%^S~(c zU6yMPz0X&B_upQ;q_{bcu)PL5H(#CHbRQkw+ zM|aW(X&{sNPLpE7^iU@meNCk~Ju6U6Vts*gPjCvl@u{zUEZbkecYC|wMymi7U{3$H z0iTJ||036FG!^rwVAPFd)=EQLAO8=zmh&M#kN9A|d&!$u>(u}3oc#el`n45aG${QaKAa<5r6hw=^F8x5`vD>Oofu<{uB6iO@UL780KT|%jdy39L@2UoQ9u6VS`a1x_yo4UBg_l2q}5o# zcg3J=xW+k)zJEGr1}h7q(LU`yI5Ye9{xJIzLS*NR`DYN%xGB9TJsrcW!vxFw(E#wI z$YQWKiPep(5 zO^3ixOw*_UH1>1uqYejoW`cIrm)JIeiGNkjx@nTIf*<*U)FDs_V%FHM7gQO@IIIdc zZ$0}@t~Gp|3G;8W9ZV1H-^*5s!o5+$W{R9rl>=tt@-~Yaj;F_S(R1@QU}1`Ro+{p* z+5yG?=$wtjMD9zFGlAK35c!1oQ3bH_j$s_$WLb;b0JW(0jkXY?1nsUIOM$Jsjx05J zp=<}pwKjK~t&_V0>+{Uz5cyIc6AD3-OT*YLe}K;fveg3C7b<`q+|!Bt+S5-5;~-PF zJV54Jwsybnifgr^Ri2xxlzIv&voaPJ9QFgiXJ^z%>|F?=6l49>aKA?o(e(UJGdG2IN}E%9-%pSC-XcV+}Urcf1O3b1g?nH5{X@F$}Y-+g$6(qyf%N3wr_P zRO1PdYgwPRsojvHPl>X~BNqImIL?+Mcc)KgWhRmwR}!6e&eklMcAgB2`ImLV=y1fb znNzBFfL!Yb|FMc0E}b$r>J%X|*V?J~2pG^CWz43u$3iqCJ7>MmA8`JBHpT%>2Gjhw z{Ef`D%syW~i)6~WBi;iWzspHEH>uC@6wgEJmMcfi!e*SDQBEp?nRzpEVjAJ-Vt z0PsPXENnWrdOHDQ|vvJGEeI?|G7W!*K{tp}o1%pj{#m8akqGB;vX`7yom)xec!;E{65&Z zH~pT|xTIHu3eDBU!UczlB#QDKcQ*j|NPiV`+*=N8^Q2R`mXh9|3kyT$S|7)xQay(J zgyVh&V6(J7v_6Q;k!MU5ltDZ{X9?hoqr2SFeEuR2$hCSi!>P=m(u52_5mbz5cXE3S zC=O%A4OU>j>YTN$WlU)d%aAZ6@EwYE_iBn5L8V0c!+mdoFYf+plC~IBEnO}XX#n^R zla{-fzO^t*3Sg9mED&QnJ?Xj`__QOL{5f)2IR_$gj)e-pmd_C-Wu>rV^-eI}zc1X! z?C!;Vlt$LKZm^6cspqQ-iidXcpc|+JBY`gpN2*nm7@LAP6$yMM=6C&=j8s#IWuPNsnvUSRux* zhXC+tejy2_@xIE`a08E5(^ZxNl`~cPhfwQ#=y#$E*EMG{Urt?*SCHhyL2BwqRK`S<^3D?L+ zxb$_CeHZ6RBCrzh)#pg9W zvmTuVO;WYRpD^VYR#U6fL3{!3IK2xPChr<$wMx7m$m@4Yqb`Yn`qP|6qWaTzUAa;*^L#xrpmO&7!Um3BwuC!Dh6KJYqgf~gsl-=N z#j@}T2_ql-pf}OsV8p=pI@ZX=_?X1_7>2B;UgZm@Y z@SD2lisgxGx;ddl3#i0QiK&zo|>p6!&dgKa`%< zlWPVp7F_ozcL^S0>^#h07d z1BT-i9YTek(Z;y_?$!W5rzT6;(0g(=MsQ$*67&qnwS=Vmtr2Mw9^2+XuEn`z?@fvO z%;pP_Yt19_Q5T>9&5Ahoo_wWj+P&is15bb=8-RH%-vKvFNj=Ag=b2E%z|*p+>s?4j z%RxMlYxT_|`lUV|<#0Y-6IwVMt-sz+B!z9hQMzdS{^_`KpmACw)NSsfX`}kb`L5rO z{RN_%Q?a$iy|95xPs--A!FR4pG54=FiYa&K;qI>r2R?rKb~Qh<+jMg(P;|AQ(7aMm z-Fi0h#&+B9%hg`?2_)zK&AEmUII_C=8cW#aeD~(2+4nPu-+hbE1%*O$qiqd1Jj8$5B{wyoAZ#66|@2uD_)Qd5AfCGpc`*uJIO8_m)5Pev;*_ z%GCzB` zuAQczbB>NvtltMyZNd`2k7V#zMwILaa9@56Z)bP_MAN?p9&*mCarYD+4u2WO?;o9` zMzG)&dc;}r4Y_|n~7XwN(11A^)!3*A1 zHG!Spfnay92C^Vc@4!0dppIDCCg-5;nxNj>&ec!@t`Su+IaD*>Iejhc|H$&j7XklW5#=#ggVv2!T0bH*P^pW=UU8tU~k6eNIf zqDP>)ARuvw;wM;UgXq}*rE*3NcLbsFrF=p!MFsCc$OXa`USKe|gfqv5v(|>Q2@v|E zpu+~kxw{_z9fuzQI9!Z5^WTQU*#jhek<9*SZN3Bl`OFLCpTGpeT@O~3bnz4l6kTu0 zIDO)RznyviHNk*ML73vpw&)=`h4K0?9RBA71L{3XWh^364xWEsV6f=6b!J!lwqhCH zX7%RZ78p)n^rO0vhX{5XbX<|FgZH6^Nx`RDjI2jri=Z_P2a7GU$F!Wr-qFLahy&|o0{)Gmb!5_eMg9u&vW zw);TLI+%*2JGkSAJXv(pU|hbD8&`V@8ANcde(CRm(<&de(5Nr@IwKyu28XB;FH&R5 zbc(KW1ec7YsOmz#d(g23)2p?LEY&u>hY0;ugv~+*102hjD|% zBn;SPd_<Wk21T^N(*OzK{EHUvFHQYp@3_X#LDhW#bp7+ z1TQ@i32^3>>Q4Ho`WXA!mJA=dYR^X45%SFYu5D^yp>i)3^$`oJF6&4#fWzrprrA94 z5gYz{3dNKdN*>*#S%MCanC`Y*oM#a$Kw1c>sXG(?%<&e-}AR$f^nX3}eP+ z=rTHsF{)qG-lc%0&GqPkGq0;U=!;nAYjipO+ku>+Q^U#s*^$Wh^CJ=tf zPW1$q(2jK@q@)DRFFoyuJRhsA=p#MDpqliH9t%uS$`2t}=*c<`JAnSYAXk>W+| zzAcN)mKUKW^^QV+WbK&?;PBc&7r3Pi<{T8sfW%?Nd$H}8HCI`{nb(FdBMR&5>aik! zzjJ>%`NRk4lg+aM_x^oLJXMp<-~5AcMf->eu34`Vm*A|I6&Vj+i3ooS>5c5K$igx; z3ygYbpMYPPGeR0KNi_Zb-aTM~A^52Q6IxF;8#^-pocsNb#*)wDo<-m0Yr`GOn$-!G ztF27~O3L@yPY+6C`YdziTpJ8`EXuPLtddbEr?2T8k@;uBtKJuL_|-Mrzb$XR?)Lvw ztgiEL*!F@u%i8bHpxpM|MaE* zHRaah*!pn^!w*|*5Rf}=yyrzvzOYt)(PF$$2CgW+tj3j8f(`lEfZZkLQ$T>m^Y`L&%5?S zEH0OU1%~@B55(d>M@);{oa??B*UzQ1*>b!8iyCr%bMjs3Q>ZiyM6m8Y-!pK1{K5#0 zfTr$ZP3g0*Jq`FpUi02v#<2OZgmyUd^Iojs$U7-ErmGEaKuU;-Ye=jfUzPp89U z-%m`MUV_qgP1#V^oKHez-ZB$jSdR=(o_LAIdSgm?Lr_3>;oh=jKBpbtm?&OYWFD%q zJ|HO{3=}UkxQ{lO??HzTMyliK17Fil8zWOF8jye1_}tO=&;#;MO)Cp&C^Z+D9^~UN z>DTD!hZ^?DZQakC-`brS%B=|x=(O@<2JPKAc?6RA_l?7UefJD^_HQ4D`@{VcJ1v6Y zpFT|br^T8CLp}@e2js+>Mnb%ECj;8mK~n1hWt|psq$oK2fiwPDWa{#0jSZ&t!+1i}>=!vP!?b_igu z4ZoWi&UO}#fgZ{w5J7tv<%@I#f6JKyUtGjf7iG{?1WZ7dH4gj=8Y#&l$J*r~RU0Wf z1x4$MR2GooFbh-Bic)up(u|AJu8q<)ixgY5~6;nfxiPIYMNg%f4Fv8mqF z)IW_{+g@_G^q=nLzn~sw7@_Z2Fo(yHsi*xbx#q&{^WaKMR(HKP|+SD?#Cfa2e_Mmpk8uK6i<$1 zbopb$hX?MFnJO$TAVZp4Dmn%4?ib>Ja4Mf?EErbt?M*l#)n=VT;1)&^W1EjkrT(@9<4mUG7?*%pH zSlV{|AE^P{QAoRpO(S9F1?B0WP=R*v}mfr8r_8%w$R#qmmhm1_mCM0^-oW9S=xQ{pCW3_ z>V^Mg+`(x$2wc}UJzz4nK?;Wg59>PMHA!;AT?=f#r%bbfjC&dd&mYzx9R}|~BVdR2 z2{Y1zzFOW&4epr96zz?Wwud5|@9?BrxZRVg7l2(gAmbj9I2CDP-~dgaX1Z_vjPm0+ zU(bjM8Ck(?O}D}#WL ziU#8r>Jj`D-cuCO4?y-;yG#L)MJy8})GI$`A?|FR?|5|ci@_HoZUOHW>L~~~1!gHu zo;ni=!@+Q=pfqAYYA9rQWNc38K9u|aIR(!R-({o@rd$v>roz z@w+K|SxBh&?F;v!UZ#`hlX-&Dpg@yjnk@`u+)BEYpwD+H;Z*9KPj$!J;?agycTXn= zkWz#5`5HN%LFLt$EscDIj6k^nRE>)`jRt^ve}_YY)cbsU>CMG!tfVlZP@tvmwQN`D+?W4aYeYSX&?u!xjzO_O zQzLKZcL`j<^6k0nFy8oLwEnYcP4pBj6k>H`#%+A{b<$H!EpxvY>po{aAT=CU=>K99 znWyNRTM-BNej7IIKMlB>$5nDF+c4okDfVuMqUiQQU{_5yXFRv(0TjHYL&GC<Jd9kAM`73Nd zYS4bk<+y9CoJ0&u%}8N~YxFL~YirW16&62z2L|~}r?s&6mxlaiF<|7FXcZKB&*Uh- zOjkTohut^bQ6cm*fmw~1pAUfgOIZd^vPM~veWn}$>LZ4`Nkg*U#gsu*Qt0txj= z)NXdoJ3N{73OlxeL8DR+_Z7XZb{y+o zvq(6bF-i$6s#O?(`uQ|`T5-FFTeQ6s3P`9IV`+BDz@!_0kA(UM%7b@24_9^)mt;cg zM$ZiGvVL;RQ8b;5R`)ynW}Bml|EbqVKL5Kc;g#SUPDp=@U(u2I#gd zl6DM`aVsWN&=*+)72F?~O3v74A8Gha-VkTJ0^H3en7xM3g3#$H;BG$mD_*aYz>Tuz^qzl5Qw%v=IQRP@Wlo&tL9vLeIrtK<3#<{u6IGH z`Fxx1lNaLtJ}VVd$%N9)xm)HHy36Nly@6V_fZ1z6YEbg{eC-L1Lw&5*t_lWr)z*p8 zAdfLlHPFWN@H9P0I*IP&h!IFbNqs($o_f&m6Oq?Er;Jq#Hrf^@q9H^eOFRMGf8JXX+8ec3CUji<$(Ik^? zji22l)REtpI>qk;Kb%e4Pln&unG9|t4G+@v@V#+{e(pq}pM*y;yN8-W9pQe!{CT4E z=a^F;@DK_$0xU72!Cp?mFlWD6vXE$} zU_6?D1m=)+XU9%W-xYpvTWrW4+_i`_jLU-q+b9+~h|=|J9_xCngAFtpqVVF8;o&Curpk>^#R;x3U5$KE($ zVU6%eMHUO$TIfoRmy%YLH%S!sei*G;ly0uEW}NrbWR$@#(>HNY3V~=-7Sp#{P;_^= zPF%E2oS}sb6ul)JmpsN0z(0$*sO5{_KH zoW^}Q7a*kHL%TTpvSl9w5=;qaKtXd&=_5ud@K3?jmZ&99z@tdDYkQ4Nn?mTC`j`O| z4<(gsI`!UpDh)*%o$T`gfix!9G~}*YT^ieT8pnAW7ezX^U^I$7#xU{~#DdMeH% zFiu`Nj8%w{B12qOKwZyQB0fX5E`w+NJ+P}*{LNcgFjGxCbAByDJw6jbpQ$~ax$+px zWg*i*mQzzO%b1l{*EP$$F3VET?(KAzjVreqMK&;~=2&O-&NbUro71i?`_p;0`-Z6t zMUJ;D`$z2@czjMkw}ID9T}}uqi{E)pxL|H1#j9ZL+}Lx*u=w1>>D=Tx^_cVAGzx|U z!MrTjyqs>O)cCxDc-qYAJm59EWvsIKg85b0G{vs@b#?g-6cUxw`7L?(YAFiZvI(XSUA1$;E{ej@ZpuFG!pZo;X;;3Hy2AN*iivaNuG;c6@N$%*b!_s* z_@b@pq8)9PwezBbI?_$S;$zq1Q*DO*_~J`elHb$CAj%T34$XyN35L$y8`l!-`V!ng zYV?^B=nN4SWht>vDG3hc9k)^n93rCn(t8)BH1%ZUlw}M;gw#67SvA(pyY%&C92Nu* zF3Pxt%6amM*l%>o`Q2;;>dT+bls|i4E?i&!h_XUlr$TZD3UjOA7OId1cGV~=WG*UL zdMZ?PD%I=DRNN|Qw@7 ztFm{ib`C7GOQ=S%sQ!T5RV#3#tU2AN_I9g*_vCpc)a;tq1YOi1baDeJYu7hwfJL=f zoE)=+T9SNal=P~^nc@`6y2Ep0LmGHSeTh{<9jQ=V!Aw!aMcr6kU71dO6=hDTTYbNI zZQV?L)5G-Ii~9ENdf+nOA(YnY*3cl^&^^=8ADGg0(NNyqFs#!!j`L;6t+7D1aeAh4 zUM^|M>Y_2dyKzaUY1J)Z(XA;_wrOLgX~!+@*F{rAchiAR^RZC$zFTvEZ1ed{^Yv!L z*+sKQcQaVG1;a87HdzY<& z8}CV2zXonp|NB|398~$=St}Uu;?umO`k%Ka=VVJHa45l}kOexJ4Dgh0?7s4!Y6YA# z%pAIqJ#6)0LJrwBCj5MHf9>YKEt~(T71XoiQxNtz)BNfPeg5ym=2la_Xv=&V8EhMs z)qjS~Z)*i_`ahTvdo%#Ap|95g{(;D%JpqQz|7MvD@nWRoEPs7nn#$YoQE1${sp(&} zf~Jk&w~%+fDXCyEU>YcA#y#kL*tAMJP|kY%{2#S~NVR*To&i{u(($nHAU+ak7pVZdS|6%{;|w99tLP)F9dRa z#g;3eGGw5P2JP{Zv};LciuzI854HwzcQ2f80_{oUviZI0jyyEHO&lge2%?C}H`hb5 zU_g>KQYF{DRGPvWYS`0M=?z$BAWWcEU@zgBM^W1z-dVDa&w%;PT+MVGSK32VnY&iS z3#XOJ>2}$i>IDNjdAK*sAKF$#VcxQ@+rUcob|2QXJl@Mr_vZ z+ui;>%U;R8r-L-$oTWox*c_-8q=P?ZgN6u_%D%A`tLPKU4(LRVpz1GSvuPr01vcN4 z(#MCkB`b#TaVjtvI5}_F58J_!-0}}?Z_jEE6qCn`@$H>N)?33Wekf!o1%bLC->Q~w zEwhx*S(RVI2w7Stz+EU()D|tYgXP5cGjl-*NM!FqD)Ow>aMB+&zLJF}K;>1#;XbUw z^|5LXjP>*4a1gm{&WEBrIiVeGl)UTlh5+P-@Jy#+&X&*R0#8Q?Xyjh}a0X?!8b)wCY@V9PAPptL&cG+B@B}4Cf#U=`U4Cw+;QsXl zF2(bK0@xv{`l&z2>!sq*;$u8-jy2(260uM_SW*XH!ILt$y0P$zpJcgYj zBhaoPr6D8@OER7y`1T20Mm7^t7Pyy>z}-5Hfa!jXa7BB|Vj|O{Jzd6_%^e%dKVBnFwdZG599HN8n;iDSID{MjmDBQQTy27GG&xk4Fk7VgBL0D`##j z6tuJmn79vf6|z?FICAdDc#~DF#q=62cI?Bl(5+==@IH>00fJvWQ9XI(9WcTmPJO_P zusAH4ZK?+)grys(6-?h%dw1l6^?^c(3cR0^+D(&uS6YJFO=ap@l{io@SC_MA zW))~p_Wat~gVc$Uv*{-ay|t-xt!L+K8}p>g(+%IrgsHZIyky<%0_qZx~++MOH+Dqh888h5ao z4h^Vgn-S5tW$orx(09GH5kjGF_QQKxg9KFF+_&S1$~)^Sob;yo3Govu@tIA>>ZTJs z6=xh6KG^h#^`+*n+x>(e5G8);D?D?(=lc(i6;G<}D((j~mybQWa%!Q))!N!&SVGT5 zWAzQw4@|gR{(fWm`}ZiXbxm{vGtC2OT4lg8`$71#pCp0l7v8>C@9Zk{5lUep$8E)}Tu-rLn!DQShr9ul^*SwifI!yIQMM#Nl3G2eceZzJj_L&#zCF&B>l z>w~`R?VI&#VA*^Z`@kR}o!{T{<6-^HmET6g=2G?B%d!!} z;Ds$CjWLuwTk!CRD!u&^8nA4BN{^vw2(uUasqP@>^O>N=g9<{Y5f0t)x@Tag+7zks zbHW3t6%a1n#p8n#XBbx;YB~^q5=!-81!@KG`)qJ1O5`VwbVGp^R{@|_kmJQZ=!u*8 z6Zr%_U+RUq@A-OJ&}!9P6{r>DP^m#+7${aUZ>@PBVew7+0K?|R`#$Id zu->oY7ZP3qw65lwevS}IOKGV3x;&ic!?RS-xTBvZKRiCn@9w&uWtFVtdvtGL*!)JC z+&9*n1Y+qx>}~ZM9vkcLws;q7-&62Jejp9GY`**m%+dmu>hwbQ5c5hgvW;~^1%Wbv zWpn4dASjCTr1Zg&rlB-(Obe#FX5d%;ASK#B$m0JX?>&Q>-uw045Lzf|fY3o{(xj_M zRho2#pwf}vQ2_<1Ql%vH-g^nXLlOegdl!_d^sWm~I?DOMTF=_+`JcU?IcH|ioEPVH zCT}vs44>#a!(Y2eyRgSb{vI`*uc6b?|;m<@ZkiJn1Dvn;j?s9cf`U?Y@WPP z5RG1?3Y)wzoAd03r=!&DIK{n{gYL>coI*taDYF}`5yftD&dWBGtHwukQQ%OD6Xo#f z+h*R{u$;9p{Hds`y->nX>F*HN0i6debRpLOu{jTvVk#&z|6XLid4(HQ>`2%=I+~j& zikV*1;q8-~J?8sKF(UL)xAdOy9fnGt2g25X`kHOz-B4|Z&yjpAk@tjk9{5H}C&wMR z#qbpgJYN8-nfR!R$3IP`WcP)t+s1-@5znULpSx4)xI;lgke6c0U=u=inYf41NaLvl z7rF#eR%8^=ZWe*4Lh%a4s2f%iyljIVF;EH?sNWQxTTz0yds2uV)F&BA$pU4UNeWC( z3QMNniYG@J(n$X3BZU^l(wEcz6Dr(|MQJc{|`D0;m7PFT67bIx%JR5^txI+=MS znPLR5q!)Hfl!{Y%SFHyvn8HK3r(PdR?b?X{paQKeN@kBr=sr$+mYjx9kp_SY3da;o z5p0mfdSoiSc?ufto|Y$Y z=Gk%BL2@!UJM))#7T$4Yp?hiuPbL92tIj5q057w+H;b|_{Hk3lGfNs(O7@6NX2VqW zGA5IOAt!G#8*sFUC-csOdXZ_L++CY*iZATqHPi*H==+A5AZU-&W zOMB*&5r9Q8oNJ@-osc?3`C$@8!)vHXqT~roUL3Y4%(@5+0tMQp^Gi^-w-gnem}T%H zc^L}SvPs`L7FT+h6nUhih!;N*e(lFlf}J+an$C9ifJIi8wDpxl&}ZwwNvuRl`}$02 z5vZr8WGl6$W2z<@JfJQ+>diZ4(-Ovk;`u6Yn;C}kp=YT#Qm9d!Z>QEUYS$1iRFag`$ebEUl@xk2)GFSxqVuR#m9(tI);^ZBh&id%LKfeWtkdo< z6Z5RoCo?M0t1vjN!#qnhk*r^^OtJ8+|7r=gX{;Y4Byc#b$J`|V@6)bBc~*R0Zi^l5W9KZ=k-Z zm<&dhRC}n~DJIVVTi}UBrDBU4f%6+%eu}MRY^;`S>}VxWmcZ1eHf{z;SRop*r;S&Z z8(SoC9R@gVeTb0>uCMVzY(8{~8)0l3lWeM%BzT{N8c%IXk0k;w@F1$cUZwv>Yux`o zL}CA(*X)1%N&d$V{=fgNI0o?{TqYW1c6rxQv? zM%T~egCe{}(KqF$z~=u=mawpzK5JHy-Jc{}0yv%XkDx|no~Xd=CU zOyj@j3i2ws8s|H4;uQmiXon$h+~0F;0M&RHt8xB(35R3d7>(B?{wpke;e@)cziVO? zCHRLSDXqK~sxa02(g}6hog=pk{;G4b`+3%V)QQz3fbPG#a|b`ObSPAN(qMKdz!bpx z=U&@IckbOiGtHZ-%Gn57MZ*3_ncuogf9495Io+4T`Iot~eWa?_pGH09{kuB{?#_!{ z%`ObO@&rzAkqF2VRxi49oX?EQM}Z*0IK7$=PXtA$wdRBwXVj~|=h`Sbr;vg`SXhlO z6eZl1Ct9gFeiJ;-=6iP(l&dD|LmIjcIH4}W!a*ohZiJc0MxGbt`NQtgH$u5#BAvbr zcEz~A!oq1eK`2v5UX>6aR8SgK?Jh%aVoNIjl`HrfezI@Y^E&ZnD>p|)#3*0c$f~L) zD#s3xk6q>p1SmYGUN4@AC}Y+ZcS}V&P?FHb$`SjEy|&WIwhn)L<>pfndl<9BxSyiP z$Z}3tt&hN8du`cHUCyu2VTw{4aGNZ6H)}74+@sqmSEau7T!w|E8jkWoZ$Bl7d{CS) zeZ$=AH8a4!RXy|L&$+g_U+UKBi8r^@m=$PU?u>oaYFGWp{N%;KMXtcr!dS5y^(ms* z;pM2(X$*w3cwWwR%KoohK{<6Sp91(^iSvzp7m*|rHuCOgq!+mYotN&90viYIazkke z`xf&D_Kv}!zo__1=~g!)ic z)5^fG3v}n$EKpoHrmOFL6axaUy~peDgH{Eo0^PZWo`-d_JAR*$^P?U~QaU02EIQ*R zv;fr*#a8hcTf|ZMRLhH;Xs~!WnlgO-lWGW?E^e)^$4Z=NQfEOHp@)zjMTx!WD4a5r zcl3wteFB6_l-Zsp9w`fv9LTogDTk6upH_@>OuWMK`ka3$O)!QP~+$kq_xA7(F$cye=jaTo0B}sBo`?KGa zPrN}l*(+3roKvV=ro4=Jv@j1|apF^3!(>=Y+yN)lj|^|MwNI$9AM9(oTjXm(6hK&5|LJp57uW+vRi(E%;H160wTDWoV=*VZx#4Eq zyKWdNbvqII5m<{%q3u`-;Dqv*u-AsgDiujF z%jYBHAaAGTV6BE6vforE+ZaT}Y`?8(oNTIRUA4$CmoBy7Qq%i5UssaAMr!U;jPu(u zMLCz1+9;{%cXA};-k;*rC1xAwNjRvh41b{?hvic}w{+z$w!EoKsP=RU2n)9~^(EF$ z@pcw`$_0-QaLY1I&jVCrM4B{KpGC?zYU`Qj#P+D_g03I;=ekiKSJ2I<%=xUL{?W>o ztII8@x?du02cR0VB6B~?w3`%{z6-{m&b1B!vV^Nbngh3RTjc}XsdYwszo(zCwrRFN zBPs*Qw2T+B54lq(UWq6RL%)c=ZDYAw<#p=}OUCZj)XV;mjrq)!0_e`Q-rQX!m%4ZM zNw&RSX35iZVClM!c2}uLRrp<|;gyrm-O7)hP5lfFL#K3G8J|}LBT>t|2Fc~>FJa-r zVP?Jz?%g_9Ym)3!EG;{)HW=M!FDMA>6mA5|9lklarDqQm^z6QmG<2^rs*4 zz4}IcWfqe;Ne=>X%j7uW3`I-eBS3d9izKZ1_8-e60M*DjOe1-4LvJkWstXUv3)^%P ziI1T~Ep%R})#cxMg3d->9vOe{g-HB)b zV{U>Lov+RWY2O1)&l$J_Vd2SA*QSc_?+&^8Q|~Kt8fVCXT)~<9&-%j=(%)1s);#7S zo7$d!{k0R}$&@}Jdbm2K6K8OPX*A<}!VUQV=*|%fEE0Thx=mCaN#{Eb5?X)#z4Ub{3ay7)->GF00&yaZe&tijL=IURqG>~$y{nUT0>i|xu zwRjh%oKIXd8ZN93zxS0Q0VmXF?WtC@OAcCgZhKXJ#+)8-LjBTtowzjRY3BTho#Bb+ zdE+9jPjSl==N;)Pu{LD0a~I%*df|+7x)t%ZiE-{*640G%eEKr|RN!uy1Q1`B50RU1H>(e2qR!NNSg)e5Pm~V?*lR;E?5)YD#e2)%^9An^ zQ0iXD5*&W8yl0mpcQa68_1*Y<(W3)o3BlREn|XfnPLB92Pzq%iAz-hKn~wHKf(s3! zxd$RO0lgb}C!G|iI!O~tfd@R`Yp#R&HT`cx+=qj0?)CUfpaX$ifw?d}I>?3+L_+3f ztjg-EU;`RhdG9b8)J9DMNECou`&=o2Q4BZU0XvHYbJ_$QB--ks z-e(;K19NSX=fZ64LLqN-&GHlcLv#bbbp}VEL(?WH)hR=r#X?irE!3St30XjdmBD47 zLrW(SoUI%bLLo^ert#cfx*?(9d7_kc1a1<^(8>`20nynQ)!D!}6GIT|NT54M@5JuU z4J^A^JaR%7x*U`Yu<_)g)|KzGgtdJl|n7DHClSZX-E4Ru3Y zMo+9ZQL zjuU;4DXy8tL)>Ye!jeL4eXp^Bo|7b4!yksyCx359dajZfa}gGX9xWusCtvKfxv^fi z+lYT>OA}0zg4*yn5>C-MPAWQ1$qv3j(UMd~l3IV9aKs9guuX25N;TlQo)4r8#MAV7 zQn2EQHclxWn6zisX|?oWc6da#Cd31J=~7(RYmU}-q85drkd36dbMcIoqx5d^ z5S$*(U?s`&RL0drri9Qm8$Z&!8yN>YFLp>WT6I$nr!q^EGS_&5?cgLn^O;15%t~2k zD|d#u9|?Xose=$y{%sbF!LBzuYrTl3eFQ>1ot;C(cvh5-PROvN(7x`G6Gg;`12_jF zM}WbG7m*Dvrr|uv5oNHdj84Zx*gL>2?w#bSBxH#o?8!Z7;$?{4L3yg1=5ocErph^% zreu+oz+RhqTyzG#e!f1bkB&YxfG)?H;)#Jo0r*qCJi^Wao@;?EV5ebx&JgslufUnq zGtLz149S0;QkZm)-h?+NB&g7X0fo3n&%qn)&5H`zd>d$2XnLN6iom)(>Oo1JpyC+b zzVs;Y(JxAoaCILoe2Xp0vU72VqfFgU*&f9=J`-x}5Xb{yQlbdOP{MzYpk$iRa)j{t z`yvXS65Oeld6%mbuM}gC3*>Xybu^+TozkHLy*4VUo16#gBYHjRSh_));^{9|7E?Y+w98Fi~ z98fQK6#SN`RCO&sJ&A8utt2HgAwrfW15|_2>>I##h)@)sRl9d9V5zorGgX$w6~v7t z*CnfW2rC)MKufAXuE6lhRwYeiwGf%XbJL39<7(k^&zc;Z&(ZutVd3P=OUSOsX+fcc$+3N->$Ajod<=1@f6m z36xu>-p=3|-w0T_B#Wo9-dRm6xRS^`v|LoO!NXoNSO`KModARi-WZs}`fL0>(W`GD zfynZZ88mS`M5G1!Y6~4_|LE#8)Z74*;`u1C5$fKE$x>4d9f1ZhVhhMrf*miZMo9zG z6Ph`Lt!`9gLqe-08_}r`ouL>~VQ_M4W6O+UzZs!A3qBqhNR|TEx1~6lU&j*#*0iZ( z8igP#ai7Sfqhz3P5Y1R4#XBJa(Q|0Cs1U&$$EMXriS%2bsr^O{3St?SX3-r2B{Xu) z;KREbZGK@AOV9`ABw|++Vy7J-Y0zR5+l0RmBOpusn2bQO5+4jAiu4U6kZNU*Z9XES z3I~QrEAe+2n`K&v_?27PN`)ZXl##wA%zPi%?zZuH2@&x@X$`5kW?R8R1V0$t_|w{3 zW14R|0AD0xOe@jIg8VFLS9IVPo}~i%0t=E*$(DqD_YSQvUcu7lxqd3@r%eP^`1&Id zxKyW!AvaB0rKw?8(Z_bpT>>Xivej&tgI1>sAGQ8=*BczClvk%qT6Y{(x5sR^&y!A@ z?QZ`tQFE!DAU-iauO7tt>}^N&F63Fyjn~~#QoV78y?^L*CZzR>#WttR_GX;*CIt6p zN%j3~>&^4(L#6fI;OZ-$?Hf1iD`)Djmg>*$>Z|qY&ja_Pas9a2egUigW~Kp$oc=b$ zfiACs7Q%rZ+<>awz`)tS2-Bct{=k^wpwQyLr?kOo+#un@!P&DxI{(3Wsi9@Vq3Gqo z)wH3XtV5f#L*LJa?gkF+NDa@n4*m2RK1v%NV;?@59d0un{>?N3mLBm@A0c|g1o9ps zZ5ko}C44qJ0{uou!aNEy8m0Ml>zel{gApxN)5TmHOFAb#^B6}s4YSc0clsFbH#YXB zF@YDVuRI z=f*XeC$!RO)TAf0e^F?7Pv|#I7&gJ4%}to_Q|K{&vM~B&^^4Nj`;(m!)V%4_%U_=y zUr^XGf3`|*j!^&nX0X|<=`+6YXRo=57r#FHOHW#T`yBXU!q0mW(KHEvF&Q>D9{OuC zMtVx>+hp8}@o4X_16p_~0wALJ^ zvwgZ+dZONYM&-pcHhrvUZpI*erbT)jCq2u`Jl&N(+xKgrvuTzge0GR=ZY;ciP$)^u_Lf@_}x3W}CDV?W_LZ z5f`964=~L|QJ^fsQ*QDRK%3Oil?&}5RJZ=F&WMt0SFrjAiP&o|wskHKXZ;g#z3@OW z;iU+652Y!DUipOnH|@C#3fWKSPQTchk6{?<_-Az{!)5*3GOkVS9R86>;_%0RRc9y| zl^zR83Gx{Bq(=Uu4}Y+hE_*PS`1N%L^@R`gvJbCqv+(o>D|ZIN5>KmK0BsQWV#uG` zb1-)t+1Cl{8}CkB5*9D?P=ESB4Z5b*a{Pt;(SIYZA`6AC&Y1bwrJ`&_mfwA`GPDy9(5%^%8(oF&`UfF6p^Ql6qX%~{0@u~kt(ig{8T zK~th$G8}a4J9;_6z8vm%J%wIS#bmL+4nf*)ll!H9a}#s)r}n&GGYh-}PGy~FR@Y@*Ct4?(XHKe2$PQo8-BJ$?5dG}=>zDauuKi%7L`lj)DIyvXd28TcOPz%xv zMyRZ)GYO)voboZ`{Q1jmB8z`&&pq#qGc>{8)GtMy0%4w4Z_7_MOB;rc5n0HL+Z&3Z zWA`|F(|(K2mLGmU{iCIw+;iRP_G3?Y;7@*_Jnsuu-MI|ztXvgr6bxWGf3nB9^zK9` zF;Eb6Lq}8Y7vKY}_?_{IHnQp9zSAo#2o>nl%K=v3Jv%u&1jHnwcE(=_;+u?_AHMrS z1v={B@|6hz`$8{$pe%R--@S?Mkb++;JvfD526rG0=B=6((09^PEI*{UqtwE7-U|VU ztCt2w+cD%#s4$85s=Jl&DhE^`?XN!kbbeq!A8Y)b$p$UQ%6H_;?f92{_+5mq>>`O; zoqVkLuIIsP(;Jl+efZrlsZll}mmUSd`*5!#d^QH4Is^3KIqaUA(Gm(FuOo)vYvFQP zF8c7C9FddLOSF=73V1)Wqc8jLp`FwZ{oU{l&0(-!S%a1;zsukbeS5ayn0KJ61tVdl zGQ3hKDlZH`T$uaWl`NFOeHOeJbl<}mFpS)bgFhHRT-c$6X!I9>sSsTAKK$(gGFP|| zKwOkplauabXI-uDu)^-X$?FLu!xMjKp8{yl`4~iAySG}pzV>{yoOO$lXW-36AAXru zB)<3j(TiP$cgUZ4WckULh-;vYllOE=&HXo=Wkms{z@-X*Q1&`|a&PVN@}W9jlo?f2 zDM}eYT!P=Ia`VSfk3rMDHljj#H!t*12)6f|G1*@%^5vx=YL|Mb_>qUNQbvRPsq*mY z%{2k-dBNUVp2DLdIJ~>26hpsB=zVh{t$r{2 zNFLCht9~AlsVfnCzjm)k;xV30PPs4O16}#(Z(#LNlXYo%V-@hlT?P8^;iY>1ZT?zJ z+M3T_lstFw7+3uLtUBvTnN69Nd_Oj_tR+WZgJxkM;b5XFH@wWjx-oX_{P`!^Y?z>THLP+0|6u=Qw79Ol_5m>Bi$M;=@l}HPO*CW#*a_}m; zP~FmN@u*$e3CI~}M$zd!>v;wsu3)`(2THp4;!`4tgd@wpBIwTB%_C~kti@pg2AKw7Ux2&))e5$ED{X^h%3XSY+pC- z=^+OCY~Q64=)><{No|u77R@Ex3ADI(Iz3tNrN;d@*6@%X)N}PsJ)nmge36>`AiBPw z-3X}8G`?Q@k_WFX-Q?6Un7ydZw9@>M>*hHPzM+K-=)-^5o>x3> zDEQ;s4#Ggn94d(DNM&-=e15jX@<68xS!OSa@4Lu)u7T-G-xt5lMKOJU3Jr1#|090p zY?Y>L;mYk~o!q#zrJgQ85A}}c?m^lz0Z&V>AO$1`2=2I#Vfq_Lek7fHttQUn1J#-R zoAgba_c0Ra)XVCOlJRH0wr4N)xT1btRA)l@#JJynPvBx)bN*<=4e)N4=lF z@>5^9=)(tqHC*Z{ezE8r)h=>rxE~6A`K|`PvwT|lp%19eaKuTdy7b3MGji-@0S3~N z*T=1loj(aN;58kfI&)sI|3Uw$)}2>Sh4ERSI@4@H_hGK_l;8lL9z^#}@N8A`gMhpW z9-J=o`2^ehL$FEy)six4xh#-}U!?k4AmNiF^eB#N|f0 z&jkphj3XLg#j8HxR=*3xg{E{7^}p@rS6BekaD-k%2Le7&_R&BYU4PvJ*cFJKE?tlr z1SVtyr9m0OQ84=i|J#S}%#VT`ZJt}M2g)j&7#+c$h(SRnubcqH<)$oa>ifn`I?2&K znHYqh1>&6yk~j*EI7bJ-Y=St}@4xSPp_L87Z*f&V3Q402Vod@g%HXOvIll`VR38~$KAkMb(TL8;e5!q|rgpY<`-NGp8LbG(8 z!6Wn?Az^?XN-R6932iCdLzBuKK7Hhk;|>KmhR@JNECLd%NrVBXzbzc(AQZ8E_Q@biA50{LsxXezv@N-tG2$AVDLsDIXw`j zr8CclCW}VXiANoBhXV1P>%9@gdg08+(HuqLtQ&zKy%=7e@IP##2hcG>?qQ7L{>OB& zqD9E_b2RjmTdY(vf=k?=eJWOtC+I;@u%LLHvPv93C=xP7laUaoN$+sm-B(tHrg+31 zo*bW(5G$Y;uYVj*p&O@|9AleJ8UaqQ5x4PMkJ$^MiFZr@Ly2w06HT?F`*mX-{77Sz z61`L`3^8HPH>lf35(D)t%y^)ZQ#2^eq%b}6VDZ;4LTLh~lHxF?_8T#dreX1z9A+&?$sW^ATj46cM z6iw_@YKOSNhvbyb9=!_sWZMN&A87hyuc_Kpn)3n#ER#A#pJ8+E zl4b=-v8qa3OwQ18Ng-cId&QcvNuR0LnI;gLVh?|?mz=47H{BWU{>gFXgNGT^bZIXs z;2@7Ij+b!YkXi7GPM0QdUP@S=#naaK)k&|7J<89Xs;?(`W)9xZ`2QiAbW>2M||^ z-$n+HDl`|9r)8%kN{Vn|%>^%HJ;CN%!g6SO^G!~SWl0e#SZZEg=mM<3&f}pNHcJN! zRA(MOn?}6oqlwsoIHeTczEjv_LtCF!=u0YZo&uHcqp{wE&(Wd~C$a(O(@0AMbubH5 z*DedGUv&O4FH)7p&7>%8^MRLLP&z}g?@GQlZ*hS{#+B%zLToYHv%-+%;8KQ?M-zEM zye0LUPaaL98n7ko`6Wbf6po>kYNdoQySUAxl*qEQ2U}VbS2A!?N_dm-8%f!?oklcJ zosocZwnO_;%D$+o%IpBu8Fh7`vL%o5HG_v5^R6iIpTJ~L{LYSc9r$h zvfhWX?y(a|IFz_jwccT-{$-}t8B$D2Bj$<{ChZh6QPqf6F&-pEi&AHSb7%_-XJV zb*cFv^#g|WvO076K`Gz^NU9~f^#g%d3nZ;&neC!F6KdLWm8q3ds@12h1?JW2h}TMo zYh{{kl{9O;&eZliyOqtbjnk_Q3U1@ZwZUcE_|DpdnA&Hu+knx{2McYYY3&lY_7d54 zsk3$wzjhg^4h6%G;DvU@w2qss9jdb(kIy=c{5mwHI_X+Fo_clargc7G?bM&`Bs1-N z&eUZl)y3J`X(82R;?-q`>vCYC04SGUT9>0#_nX>M|{<(3Z=!R9pz_zGH1QjxK{C!$U3Qxsyo&KQJKG(t9>ACN&tgH85WKVbtpaakCq>fBe3vB3IK66joz{wW%`As|24`cJ$B;WSEN3+t`6l2AKOOu^9?p#|23A2yd_1= z^6^I_QLA&FXwyfjU)e3|WB(7?3L8NKXq4Fge-EK(L;?tf`Q$$#l#(t0q15mEw+O{3 z*vvq|X#u=F_rVvR?4Oe=PG(i`afpzDUN6I4HC?ph0H$W`p9qDFfHApx>vJ4t=h>si z`foFTBNUxr1_sE?-NYrYd-(q{Y+o$Lc|6S)_(ZqdX#@m-zS!rTSN>yC<(KhxJDKy^ zN;;BZs&DRcQsq)9nB^glf!>h)LE@OnpfVu(4}|hwgTykxbiB;+!2A!22(R5+POIndA3kmkk<5Hk4!xujDAQh>`xg`?Op)FL%YBpy+0Z-9X5A zjENS2Q2v}$Y3s~ko$buIDR?l~@Hx?hH+ePvFN9*Nr721<)t^-b!*z zAV=Y#qR{Vg#l?~6V)9b;#m()S5ye~IY9saZRQX~%wQcz9$kiO+MbolM)fECN-~O5? z6zN>7i#be<9j47*cJVb_Ae4K@FZmp*dER&LU$qZ_b40?4Ik|tx4dzvL zI9wofB6Ov0TN_ww``dM(4#4{#0E54~vk?XjH* zt2o{5;i~YOd`BH8%2|S(jos2|&lnKuG_F27n0@<)bj#rB)nC)CrwTngy*)3_4!0Zr z_24Jkc%Ccd~PVP(WTWX9O{#%BA1mt+!u42lrfdpQsqJKpAUg!Yo2Q z8~xV_?p-X$?MPAPWi<#K-QFtF@VudZF{vUq6X^If3dKSqNi0d2Q~6$OAp7cDnm_DY<9;|e#;ddWk@ z{xob`uIp~7fTu^F=L9nIh?uGv0fz0KGX_B;l717;+!%y9upFoID2)H(+rc!Y21I{b-=@{=UNbW8-G$47;B> z``Dr(?+c}1C;S1ISn)cE0GBtHekRSyFF%RWNpSNewx5|iU=3YGKbv~>ayiil`sxx)+7 zSJfd6dK#d)I{-pK>P>uib!qxV;$Xe;Y}4bg(P`q_S)6^`S7%yRF~SOu&yvrUpC@`L z+P>_~=+`=!K5XWw`|ifoA1kNZN-Cnsv%QJ@3M|KEE$(x@>hF%_f@Fc9*8}!rWase> zj@q{PwwBLqF_|zhh((|!z*1;|)ErojQ!JSJV*eq-i>?FYRw)x=vj_u}f`x{=XPeft znNoON*J!E&i4Dz}7>|42jaNNz-!`S|rfVY~wNcOS5i%!w)C*Y(HV|Cw(KC0u5RtVtWpb<_J?rC48E z=q;R0$MIrNv@h~C|B}&@)0z3-w9G5?4yF%ITY+Q~_OrB*a>6P1jO%`Y62FxzpcEW& zJ}izF+162F{0h3}mid#pKd&QoESCn|M%&EeFSyc)Pf-OL8@xa$8U)7Q9}gM%1{wnh zh3iRIV)ZIrzX7Q8d`Z4XXULf=+>0kWp$c>~8=L?j6j2Y1*46SYnfbFdnH$m9j_qH@ z_T!+unF>t-Lq7|)tk)Y9Nrwsd0#hV^ZR)OF8&B_pg=Bh>fi*oo0n2fQBsVjDuw%!= z1)T8IWnp!H=I?h`0-A*|`K=&zDkq_)^ zU1;66UvMV&2mWN{(!F8#ZgNY4EDb!e(!c{gdlzesU2GWDPH_I)-}{w?{b)jvFC@%Y z-j*NN8h#&oy+iuKK4KUs0`_k~cVmdJKfUh-RX{&K8i{PyzW>S#%5GeZ{VFXB8`)h` zJ3pNd?mO3H)AR-zKIkWlApJpN<{KJ({%a?*Z`=0OujMaBJU9)|MAMD)->2uC9XinN zL%qpPlgCw7#H~K(4Zh@)lz6)D*1Gi%6Jc9A(3c~=bV+`~!ahH(-w{BJwH8dkt=>Nh zd>MdAl@JOhG2iBorcdF1-)PO>NBQ5;4UnOLb#nQ#h(c~aY+1RXCu??WHUYq-%Im-Y zB0O`cN&n0Q50DUuLl=az4g@AuAgzAP=)fOONFN=+;!Q3lRY+K2OMVyq8?JcEswnR# zyB20gL5fGd5Md&j8n~7@Z}|!=xf1FC3Vx>?;OqvKsV9ntl0=P=B~{Wg=ukhoL@2(W z5}=Q}XnCWU>?=dG@j#paLVAHvlG?iacAWK33@DC%c8=~^aTTb>} zjGLRCAEYV?IZ7L91u>)W4aL%hwb4;#>LNici1wtgK4r=xV9p+Wfl%&Ef@>#{;oRXs zN(kDD1k8ieN8$55P-UC29y%Z;6fvm#&eAPn8xm0iLDWx1?9qkKa)%6yMII?f@@qy6 z^+X;YMOGz6;NzKZL86FAkozdaXSXQwjS!NefZvl*l*d6!x=4!9i=Yb?Cb~vD`T!ke z%PPqv9+PqqwW1Wmt@mCQ9(CXrZ3CoSqGCigtglbSIAxQ1pL0VifbLVM#odiCXP_@L z604wM$tfOHM;vD4NBVFoPO(0QtO_B!5%)CN>;Xx%b8Fl)Ogs$@Y+@4mX7sJ0c)}qy z44xe43@3Rbli*PFT$3bHAep9qB;n15k&d1>-v$j(x^dM^e5Ydg+&$rqpR|u&QoUuu z&U(0>ZBm%K{;6An(^OJSuk+i`IQI>jcA?}Hcf)b+q&GmxrZPFFS0{u75nV)cdonQ> zlVZA`rfk~*rq$)j2sRJNEr5jE>O>!mG$}NSJCjm$a39O{h zkfaUJr}M9*nYhz>a;Hz)!ZldjcHC$q<{FX=(j)*xii*z?8n{HHl{KP>NAR! zX~~u{e)c}@;t4@<(bi~Yp3y(%_f72zP6N76+Vsh5Dp?S_IAhyLlIbi(+YH1;7A3;$ z+%^MjNArUR>LirSgjL>24g~eloQgwJC$l*vtjTyoxUe}#o#`=d*>n=nl(yyuN`|*#-;+jN^G$+yz#fIu;&KF^>X=lqW>087~+LO(ycYxC&iWQ?F2Dzr_|x z?&pH53cMIlr%&_!^-%(rSwSf%_V@y#^Xx*z35s~75DY>^=@<3n5nN#{O28I<>>ya} zEy|jH92`}sN?%-{|47oYxENbpI$g}dioe>6Dwim!)i0^{C_(o;%|l%PlzDla7PrJxe#DR86@Lu3(Ny9L^nsGvTr!e_5kg+nx=GV!w^5VC6C zRLS4iYJpS%S|s)ECUM(wwdi>X51S{oyJq#hnVOxNU@0Ia)W{`VLM_7rl6+mOBw4F& z&nZ4bjh(91lB|2$`0}Aao$i*HMk;_%>Yn%e>YUb@F^U>U)?0bj+w{AcrUD2>#B!$I zk+H#<(b-OKW8?WT3(U{Dg}3td&iwjpK}# z*|3dUosu=Jjc>M1pp=^HtWCs=;+9mqs8_q#0F`iByHqLk?rggZQ-_=srKD7c?AZlE zQN?v!g?FfXwJV=>Xi0UdYf<^^96AjR+w{&l0ffT1-D$DiYI=!Kh#a~c z3|no_x}2rD_qMv;Y_~Xhb$j5tzaT5%j+tHqZEW_k`3yZb410nMTU|e;^?=f9ru%ws zhV?|9wIHQ>Pg1*qlu$|dR5bq)YW}lJym&0TH2wd|clG@-ih9R$nI7 zKTXzOpVp6+s;k5Gk0LKpLT#nhO;Q7WWCLAk1AXe{ow$Kk~PMeqkC~G(^ow4WY<}fRxZCU%?7)C=)sKooRSaJ@=c`a1z<@LE7+%de%Gg zo>Lqy;;iS~3r8e2GH5VNRE8$HLqPJPDJqI7X7&Q1;1|<_jVS-AdHL`1CI7jm#X^7q zeIlOyU))=W;rIXjpTsbBBL8!R>NDG9qsi9hTz^Bw*MGv1fbblvteCs136)TmJ5?+F zNw@!NZ}$2NXeom{>Ioxdlzu1~ZJv35#(%*P&k`N+(r0A%INtYfefh`ynA!)1@lLw{ zoaXC=oG!8Ljrn%u`3;Rf_h!$_npasWwr3k|=xBWSml)=2v(DD{UABjB?Kn&W$oRZI zfBkE3_99=R;cnUPLfFKm>GcEtkG+MjKHp5c`-2S8L0SI)*juQcXtNJ0O=1TTf1-Y~0DXS>U0XOW@`+IMJ zN6UpzW~@K6N#Xc8pB+p>5hipHhY$%9@#yC_+T_{Di@Sg$irTcjnN>FH{e|J-PBuAG zqo&26a2hI}f>Iy^a*;0~%_wMk)2Eh_c>?S$giu=YGNVL_ixaB<+MC@rk*$KNq!d!n z_7^rrY;F}5m1DR662mY|@Nw8ybDFS?leXL{lKiErRNoPFu{Zn4{tqBsrlX3PCYdMW zoH&q(1G-hnKQ1a%J8k8gsaBCej;6}kElR>JHWR2EIbZ#x7P6i^_)j%!ZhH~Qx?sy@ zgsD8-rDOY5(=NF4QQ#@crn!*P*~gg-XyH-QhD-jY32U zh;m}N*awyq)i2eo!*=^M=LRp}=+_mex3a`u{k~AMo<~deW&GYZul(SB*k<$P*X8`! zhywu)?Q5OGCj`A)1$J);RWe2%m>e zCf8gJ+ex&5y;(rbYGC%zm{0TRFM}LnBf1BI5f^YImx)VD(KkCf*u`c+sO8=z9C=NS zl)Zl!lCx0t-slbcB^(*rxkb#%F&dSKyX!i7IX`v_(kpwC6NT$rWJo{ic$5ObkuxJM zBypcS^H{Ku`bCARzu(>R%1QeI*Oj6!eymVJ9eIIJu=w4BWy;X9u(n$dCZ!%y0(%Q# z1#Mv)y%qvL67%Bqb^S;AxEaZCuBAM5R+u0Xy--MX~-Sls>~ChZ16=IsfUVUOw8 z>f7qZB0QnzRGiKfNrxAEv-){nn|p45C~(M-^j+-D$`d_glj}Tg;S~LmO$Y4F(!$_~ z(3kIbI##9b0Trs0HxkUu`g1bH-S0Cl_ZD8d2C8X1j?1rnQ>6a3?_KV)LFkm&>ggUo+ zU56gzH@{(k8`=B8nfL8F&p^@4B11z}hRcg@A(XQg5SHR@K+SqQJw1G!fC>8c#r9BQ z?z=}~A@0|#y%EjKsMTjoUJt?B5B*;bUf#icdX}vrFgm;T#lqp#(=}QZKWMy#=I2m4Ngt6*O44MfIbRhZCS?wbtrZ9?wPv?Gexs z>$aGW7;T0DaO9ApSI439F)5xoC!BXvaejY-G4jz9+O)u0&3QZk{|RW zMmAhN7^rtwElSBqTq(GkJDMgWFcWI0)p#=TLjJZ$`_zUgKK;0P(1n_{?(A9Yr>Fy< zcQgp>Ef`o>zA1#0m)ZHvpG=NK)DOj6**2MxXelkPt!)^5@d|!AuC(h^L%6g3GWB%! z$H{?GIGck5730O;LjE}abhfV>OT(vn+~MFW$sYxgyE8+{Lu zJX^3(MQcq;z4VtqTcoqrq93-4lUg!hi5o)qC`IIkKk!)md`<)T3YOhVXiQV!G`7`} zy8rS%Fg+_aEFMT;`zbc}Yy>Z2=jM?kA>Oh+P@%%U(LNTBxbc3~_%Z&C0_cN$gI}BU zYi18L7BZ=KANv9wXF1tJBy2 zyYDrejem?k%&U{o;FZM8%$HRzG857#G`M9hANq)-4~>X>o>})GC?}1xMPrvk{0;9{ z>CLbvG8sI4!KPiHLY0qtw-2)M_IYqEo|v`+v|J9%k99xzM3dLT(id5Q%+EO_fCNq~ z1NoA&ui#~_2dB*+Za=|Ya|OZ7F4U~|DPR=7?~WS0wz#M@OrWD&zE_WYeO(kb8oWv9 zs0}%xBg7UCAU~!_Ki+IlVm#CLfxc>1)MO#AD6HOG2li&yb@yrgK|=nE`96=}kl>cL z4A3`(m45t_0rzz&KEL%5=`nd5M?Jpd#CsH=iVh@`b%U__X9SYi3}w(c_@xCLbl&~m<|u#w4GnOFM6(2G>AuoqHPK57a$Wb6)rCSi@#0uP z_Rx!12y+{CNNnI+w-6}ApA^ru@sNS{JcCIogZL;h(Z1SI!~m4YiUyJ%OnNbvtI<#l4N8cFb1H@_IcAbL z)>fEYKri;GVzkHky4Nc|QqiecvDIja4VpU}u?nGPSBrv0ifDkAp?au+lDm&eC{1xo zz$3l*Z-j9!t+Cpe_^VzlKu!~vKj?+GyZZuDi^BOy#L*?1)$2}!bT zjY*hFezuZGRFrHb9G{_=@`O4uvX@rS0?3yVFV{{>JQA6u z&qzFXO`QPLtVL$cfSPr~`ipxgpk{SCNM+T{*wM?>QAs~Y&QwT9N1`%++nRq1g;pJB z5+F>D^s*qu#v935<<%)IhNaQIZ9y_~- zN_pg|Piv~FLh+~bw0NI9l*rd+P=6W%mG#IsM8H8ic}5HcV+2fQ`UO&T_*N;GYE};_ zIG|=_D0G&%RI_>%x-n4j#TI(msmgyW^u?+`0X3_HlDbJ0(Qd(eEb8fG2bhxuL?MJ? zm%Z3-o)0YuODQUS9Ss(yudsFF--Vb|;?EZq74Rwov5Ewb;!+RsG&d@se3LX?Tub`U z6$oa42xK%%aH@AJJg6*p2r#^$c@ly*J1?73N>`phiuH^8PD(j`l&DtWYm7ifJjyr} z%4|)_fC|+tTbbGdv5^qL&@^FWW!#sP@-p_4&FS)LaQPF8``er4KPB$VvVd$51&6#K zAn!4&UjdTj+|j4z(1Yq{LGV&9)U0QsmE@;Dg{n$_y^<18vwBwHDOYj)tA6mGEgm-r zaG*(ItN+C(^4Ny@Jf+(wIXl@=KR|gn7TbORvbX4Q>Li$ZzI%isYyNO9T&CG=yHL7 z=s|JEE#n%r%boWd8NPwhnSe;+uPac)2NfQ$y}Ovd%1=S{JbRMxLh@Y?4X{JPuY9{-j_&$Y1Hkv-W?n_LhH9 z|NYwTFw_w0NT&jlLwBl_NP~!yBAtqKgETXAGedWGNrQBkN-H4>0wN&N%KpyaZ>{Uz z`&#$4AFMxNUi0Mp{+#D|9Dl8Q-ORZ}?S~{PTx$1Fc{CP<$agF*klt_sFczuRKZ1^7 z7FS=(R8`)N3+e(IL8@@l+;9OHC_TBbbgLA&0!w}6PA{3t%E69ml!I~ELdp>khVS+F z8Ev^6=fNDiS6ASPUm}-n8&!O7-IlUl;vLuQfPS{5;%*|IrWa{HdN2~|f#@fBwrv;N zDlOaB4a1}hjJt0Mmx-zFqb1Y_!-~=55e_tFBz&#+ZfXtG7bFTCuy7sk{G5=+ugLEE zeN@KJjP=kYag563m})$%B(L&xKA(=>L!_rDHRzvw)VpTOSU_c%VAen;GcMSxZw51 z&t7tVjncV_6&UN@*%qN=hsVdP&%eb6Dtr=-Flyy)I<5pH z)S@x3h`+U!A zx&C;6sI}_y&&Ba2!$lV<1qQJ(5qZIpSjoeQU*F@nJnpOqDiUfIqb1ZVTe?Gv zdRV0~cS~^Al{x$y5RXy@RSN}z`js_A_LHV-Ww?C7q0)GdYzGX{SKydWjZ;hp_zR_l zfRfA%kM~Daz`7^SYt-UoIen|ffx%21*~8i^0mxgPNLoK9vz-erQju0R@2a0wdM;;u+pP3KR}xvUro z^{qsEZA{CQb4<-yK*P z;BP0jjfWTal5#3ysm%2Q);%?Tt}Yzg_g*bR`IaH*D{wwZafZ@cjq6E;`0O|!=qUd6 zLI>qBx5aT(JEsb)3{(uFFO3O3;J({jDh7+60FXunDIxF=bOgj76?CapIt8eR-XPSd zm*UuXPTjh+rGH#A_L9jl%qr1S|7q?l0MejO`>1fwUFSo&9DSiAAm~V`{6ha6$6E^` z!Y6|Vkk>qxN0$GH2zUG>`l3My0{u?@&f+2hP9Co#pdvrHt#aR1tM}Xi#_Lo z`FL4CL~xS=1R7^;o-+j^a-*Wq*TtkaUh6X8GVFP&q|c)x@(^=AV$Zcu${yWbBo(tO z`USap39RSBx zg9sme=0k%ti0OW^1vHa#KcoUZvlmQ19^E(^IvtJ?8b+bgEd#3cCVbWFb5X||3gJK5 z+<59i2W^|m2Kuj~zM2UYeM`7Ssz3H(@1WqJ+SZcA0>a{G2t^>f0AW)6<4FyzDrVOkDylui}PTf?%jDcy@vMZ z?dU5|*VD!F#>QBp;cePwd_Y3|Bly!-}p~2PwO-q3*u9 zW5F;+C*fXj;08UGAyuksUBU09Z7;r=o|7>=LUh-k1J1M;9MiU*l}btB(NOXH^)M-M zu0Phg%+~|}q%jLiyotPr%jN&+3oUA~B>49L0W^?Z0azJu7B=6G?s{jDk8W$p`b1vWeR>|jfuFMOp_}+pXIA9j*+4%Y z8h2BoufY3{jE1cIU(Wh~<3L1kD=2^mg_B|{`rl6W!-xBW`9Sg6mh{L#7!~Plb||UX z-8*pd#%gp#4tr$8L=i}aw0&A*BytiY4WW?X2jkb6_XtB=3d!rB!K!n?9{jC+97`^66h$&U5)F3&#N2mi;Ft;vL<%E>BG4#h_Jh!P^7yWDf+_Cj0>e zft*8RT9XBy!1YcL`MTi(IS9NO^Em5p0HmQG9PToRs08q!iX=Hrh&)~N6-a>#Qo<#x@YQ#1&==(|Z;UN5r^=p>^LQ9>P3wFDGs_2(FzLnKc;1&F+ z$ry;I%_Ri%bCbeC8hQg2OEP5TE(+fei=(23b5F(saM~$k90P$R(NG+tUOb&{T#z;8 znRPsujrkoL${s*MjWFZ&q{Iq=z#S6q=_P)~O?2TW&bCTa zRWf=|106@ksEH@dHpFQT#cHFH>cbM1N|KD`4J4ZpzCe(Dl4Oa{=Z*yvV}WjJBCN4Y zQEs_YaVqt)w1NGEo zKJqnxP@E@9PZ+7GhxC0UfjmX2_93H`;vE7AUxQMM=N|*m25(eq<*7Y42q*YkvaN|y zm1i0yOX_pQ)E70uO{ZyhekDc?rPxo2c6p`)qq!(g-@*Cx>cX@~gK6X9878dhQA!ze z&DO)GA?c`$Pp6iXdco6|^JzGYe#@Sj#pW5$i<5m#(!n(`o77qG-pn43tRp@1RaE$A zrOX7gwByq(=lsk^idjCZnZU}xSw8!@B2~0Q3a~QJNz8I-%5pG4LA`Pwz6X!aBMH5L zl8!tTO|Cq1_Jd8zFpvN?zc*7$uBd#ft{#;~SFS*~EKN(YpjTeUgWM8$o|J?^TQl}u zn*72id7AS%vR?T?1$i#;eAO-8Hl-XjngZzu`E;;?r-aY1$)xMF6x{ojZ+KRq*O1dn zP-xzwos64g0bGH&1-1)?JH0s9-WJ+R6fKe|S}PZMq!xL#6zMY-`J5Fk;DD3~i-Yxx zL%oXGSBu~+#gUf_#nETQu{0&|EyYjyN|IBRpE6+QiGhQ>N-}Nb6$PP!#$Jz5Bnc~c z(h^VraiDTqQt2gpg0IA3?6rwU3S`+alciNHWwNBW-FjuhHP{wi_HFv*Pf1I`CfEsj zq@E0*SRovjNyv5E^7pC2Cj&1fWblE*u~r-^7mNQ+zhcc+_;RX5D6SOjScWfNxkD&4 z2m{S6R33QA)GSavuECZD;r(o>A|5wyljXwx6RTayvE~+BYr+Z`{1~(GhtB zvvcbkKS0nC@dO=_FEaTWG{MuF!bdbP5jjKHc~iV(b7GnjCL+Hbm)4xV*qmt~kB-P` zZ>33M@Sv^t(GhtWUBMy-51J-{j>uJLtGruVT3g!;gwYXs8g(-*8V}m9!i$c`Rj7Je zF?diF4s=8=NjYZFK9|90r_fL#||LqIH%t@?>LAc z+m`G+^6os5q}@;Jyf7gB1w`a@U0_wJbIC5eND_2J-quCzLxH>01#P>Dj>rK)M>*LI zpSLtSP;^9o@s^>Dgqp6Kd6bLAr<*;!o14EIR{oZL3B5Al8|@aLd&_IsBbMGnquL`; z-X)5O$gxLzWa+x@8}=%u_wK6nDo1ucT9scO&}i$ozvwS4>vz~`e@y_FIfRsI1tM|)q(N6Uls(!4MC64& z!#`oe#ZoOmL=H?0Docl}N1K6&ywPVQ0yfel)eJ=B9Ty`mr6XPCO+Z8rfHa=MMhEGd zfQWqjVpLGM?R5*N*qmYWFfcUW6qH&SYiq@ut}kEn8Q=8DPska&^&j6b z{_l?)w{SW^i}+^$dyg9vN!)>Wzm@8X|HsD-;eyF3<1n{>M+tqy(_ifovhe?jxH)-{ zZyY1~{!jObr{E`c<(Xo=?(V+X@#4q-;y#I@ctIu{>a;!1Z5%~H$zx4)TfMF6uluB} zOmnI=Z{z7tNsph~b9Huq-6sS@m#!wo#-1O+O%5fuI@-^V_dcU3p&h@o*KZuGu{^j& zxivG-w&MQ}C6wXm=L(Zazc$EW7D)lO^=impN~pClQCHG21Mg+Y@uEgGB$kPbt9ElW zg0CM<37xUdQ#zS99`wVJ(Pi?-+I_zk%k#;4Jx-CeWIbNBBW#%lsxV~cwT-nw8Yd_6 zU-nVLuYu883iHdsGF$nhsdgmPU(+1=F^?O1r0}>zf>o65To+iQWRh|7&I|Cn+zdEt z>1J-E2#n1k?vP|8KXG?9i^fbo?yFkBb^Xnp=up@eni2~0WjLCS0F_p5MF8f~OQC)$ zKQN4)KDg3`y}0NvCA8eaONWGbGFM@HRU-0=Cfebwzq+xwVn#u}RwfzN`L!5CIc&&3b>$z@~^~ znMU|~eg%4DV(s%`*uYi)-zD(mx1BS|?QKH`jk^hShxw)cT8Gny?r4Mpsc2>s-3DF* zFG6ula7fyY3j{L=!ypu1x|^7l!9WF7ftPK9A6}Trsy(4tA4IHYvPTSAAkHonk~<374`bcKI$!3M2+J)7+=)UGF&l% ziMXG;f6qIo?^|Fgvlsu`E&2n9xSy*^$y6opavij=2}Z6?x&QcmypkgETl$Sv%Qv-R zvs|g|_AsFTzc(=Pq zp+`;{n+fVoR8RMV71RF@sxQgrz3$QZ4%gmy3E+3>40cn%6nGnHS8?}??tc-k_T@qM z{|9>-;jzJ}ZU(~3$8$aC#|=gE;TtzS?xp2xxPqHZNC5jNOn-`X;wJqs^UZSBnRP_# zoi%dI<3*c>?bky(FFJaw?J70@UXIt z2lW3Xv_e7*KQjVy6bWs6SAFk%R?#7)%Llc72}_^VA#WR16s7_)R107_-&!>&_MU8! z6sRjI)vEB^2rC~g;BiNY>F{tS8|4#lZ}Sm7$c@K5ZX|qF(cK!wyGLEf{nByNLjPy# z+>(x<9Q7zl@v-OckwUQnrSTUpA3tkY8{&%~c&KGwo4yxWBt;*RrTFD0^6qKjRx#po z#PjTD7U*NV=1%j2H)F7jJT4Y8r8tBi-XY*VVUGlm1d5S%QJ-b=CFc9b&4V9f?4#uJ zQ;NNl+1tZKvd4O3aX|l{4_8C!!^v=@mOxH}_ANPj8qDKHKgYKR+hNmL<)q=aaZ9xT zgu+asP-snehO+apR;CEXK1yVu`6#tR*-Yyr`xD&i#}xoV!J0l&^C9JjPPHWD$_pEP zG$l0iOGzGfnL(ee68phB3__tn;N2Q3x~h?D+Zf&dhlP|;2*1#EB-Hu9a@GHr83@$! zNOB1)DCfAm>i_>fC^tWb>1T+L0hG{+7rgN`6PGj-#dHr!4Xs8NKOHnS=G7SigVkyC z*qJwjYLzbnS|5CNeV5kvq}-`U<>RP;d(@lnLoCsR10zoX_esXK>o(gG&h9!%NLSCq znf`}8z&>h4|AVux6;toWg@U{j7@wV-9e3VKdUZOQMk)%tT^w`!6TkTO42@8@L0)~! z-E;+e`MASX^VaihGjCg5C*5XA1ZLQ!MGva@dNSXWU^O6Ttzrvh6`}wF35U(z9_)~z#4TqUklsAb5Qy%h~eRN&s@#tIek)w(4i!jhZiHu|LJ z^OJ>h;;z1Ax&!*4qUgrPH)FLn&r@gF6!@!~0sH92$RfuBH zZ2bGt-fc>RSueC;>5c(pfuC=q5ejzNj&W=StFwOH%;+%tg((nmdxpx6>leI7G2nuv zv8DmBsnps>35}NN#m5s9jjp!pr_DV#4V|$Ve81^VNVwsh>9xy#i`Ya0T*8Kd)MOz%m_v!cXsc=R*ky!ZTYz4ZrVS>QQvGGtfqt`ie13fzPFv%zUAqt6x= z|8Ren+{2=LE?Xkz$3Vd6KS|_xzDB#uQ~LZa$nD3`r-*yI1bEWlVl;klRpEvXTitVe zexLlD5a$5fF$n#*;kSXqf{QohOFZJ8#C|9E1pT;C5Pz|AoN@jv;PT>l;xf;8`A?a} ztKXvjIGZ%TihRBaNC?c3k1~NKb= zJN{2=08T;GlE|IbpA-N}Z693YRHxL6fUp8^O4MO{WXloj)iQDG%*EEZ~i68b10 zgvi7cc*JaYsKN_9!r2}n2po+=;Ng`g;k>$`F@xdNx)F`Y zo9fnx0*?rQ5~?-_uCNZx+>Geejf`ZB$hVFhE{-f^kG$y*AEAmu&PCQyMNWG}6^n)A zVj+NtJ4Z2!$vWzjSoFI&u(UN|O)+{40&i{#FKCS3Yl5#dMfFg{9BqaUvIlOu$6Qc_ z{uG1%riy)X62p&-27AWdM#db%f&PCW4hOUz=>N|L$T&vtTE~*2;tq;phl}EF&A-0! z&HvX)9J9C|on9;pDxMV)$6p-J# z33oUW6-r!1IN~2RC)&&=I1k3FQYYO?Nfh8ndRpSd9h03XCcEg_Yd1%@qEdP&QY;~f04227GTMXy8SH82u7`v- z+xncsO;N~b0xRG*#fYOq8<8=JDCCe;a&uG^KnWc(ixUsiKSkv?o2NBL6`)d8-BQWt zP^G7-d*rG5khJ=F)2MH$4XCtXmNci5w2sr~c{ZV);^{v=Af1)c2gRSY*@QNs(#H{c zQHYcY@r**(wD+DF)eY$}ROxf`8BrgQe%~_IF6VVAN}yxnnVa+43n)LJ{~zF*xl5fD zjhl6#m!-ynj=1msay^^RLb;~@q0ZJ1$pY(VWA)+SrDhYhWD}oJuFhve_0@4`a>!^j zn00fg2sN)EbLb>AY~BI(Q4I)9F0+KXDqjxw6eLD7my1S*c@ReciZwZq!MYE5R*mgF zmn(60zd#Ne69?9VfVNR2K$a{Ln>6wv zK7w#~QLq=k2@Sd5B(9t$)Z&t%IOMGOi8;Q4E!2&$Bw3%|E1Vn%t`&jDjbYv}z&mrOn+ecwi?fT_| zspZ4r;b{Blg80B$`LqOJ9}Py^N0mjVQY)4g0EB`c+CJ(fv?x*e)vIzd+zo9Xh4Ft` zsNAEeI)J@G+eb^ee|S}$wE*@}8?=2?5_U>cjbl)aH)4vmk4my(w^m;VB5p|ow0(4u z`Ii;|8{Tzdk_!B3 zbyBVL!i#m%wDqzhGLn+@3I=rdz3Y`*>s3_>)XwYY;_5Yl{=Y$k+vEDDX$?t?82jjX z1Cp@Ow2a2^s{ii|(*^qfDwKcw|Jy9+{=YZH-~N9qBf9@@K>oM?zjzDN|0ny~|Cgji z_y4^~|MvfhsL}oZGLnD#{}kx{|KiQR{eN0=bpM~|=HLFm3Msn(FA4qI|8Kns^#2>r zTl>?{{eQeiZKESCKyw^$pEPf`y_akO?4t{ zlgN%L;C;iO<|Bcg8B^llhk6-!(9lZb8}x*mbi z3T~+$HKHCgLcy?HxUEMaqURpa|6eM-E7g0Ks2AP;k1Tr7)+-Xxt4`OaHJYm?)yGZL z_cR^gCuBcq>tl|{bXxkKFZS6-))dqgJ4!Xig6Q0J(fxla zeHz=*|5%O3yc^Kt^njM}$Nu*k@ER%qnXotv-~qh;{qw*;wMW>$c^*(ezTuzxe?1R0 z1Nsw>yAik4TI#>OyLuiF)@gf`SpKLsIE1LZ@?Qyy_T*JGa)SwXDESs~_ctd0i?DbZ z80BQx>@KHdD0VsVFL;2q$$jijXB2No`+uuZOXc1^gz~mgF@@0l{Ls~{Q7tsL^7_9B ziy=X)PoV*!4gn05zxLNx;5SUI*AVQ5nC=7Bw5A=DJx`kMmf~}`M4VV|gcP7gjgiLV zFn5z_hUP^oQdr-i6waSah`xTE<4dCUQ?x|n?8$nZ(hNMCL~PAPiNA}iM~%O)D_$8^ zVgBu(=Yiq(fpO1comAr{xG=YcKjWCId*=@jqMoZxFjTZe4) zZuzps0_Ak!n|W6fkwV)~$?b=0DqP^+OA?|m+hTqNvb!&p2eN|;or+7l{&pXz%R1T? zB0xiDxuGDlB^ZNxh(pVEQBJh&KMi=Jkn-{lzO-`bDFyzDESKsU2&{)VLA7xq^q=Q} z+chxFu+Uy7p8Dy7V0@|wps`*%G$)|cexbmHejXV8o?OGAlg(&LoW9#4!mTwx15S*G z1Tr-cp8kPHvF?aQz@SH8PlYPCJ z@#Qe-d+=mDF>4)s;b;l-JP?U(eOy};-+DY?p7vcupa8;P`}sl z_R`p1{r)v)^=cnzE9JNTY=78^xA&g33PV`DS32UoEVX>sg30$Ztm@U}?~{%D=I71l zwchpnJ=CZAI(L6xNkl@L2HM_X?b%qS-NG6x>LSz!x({vYAC&_n1AK1yY0zeY0!81R zSzL7=)E+Zm7q~$>9hHrUZRm#CL{@jYK!#H`s3q9!(&= zZ6Vk}8-3vE{TP4Ze1`k)WLa59!bDp2a6XD*BqG}NdHB8ogF=7CUijuSFpCZislznm z)#URuV1P>33ylZ(awhGm_~;0S_(kFhafan2ai{61$<#js^vC= zz5uv|hLTZM@2mz1G~k5-SjmEfI8lgE1nYEHzpAZM>I!j@Sf}f#(iu2yb!6z4iuj0Q z%g>BGvZvx>uIfU8qpY%rmQolsDvxdEY&{#SdWFIZM_>R^TYZx>WI5Av$uqIGvt%Y1L=1x9;z%%D+E{FUfNW@ry~0{6(bR$ z7hLS(zC2*Ab+!I(ZUHU-XY# zJjs=rgY6d6>1U@;H}EDP z4FX;Ye7@KLcmUmki?nqwcd$PmwrB=u?d zk`1PC5cILjTzK(xTx@CO(M#eD*o}P9i(xYPl&MJpX)R-S2if#%@2eC&jSta zn|Uqs@e%g*(u9s*mAud1^>H%)R6a|PJrN%QN({w1W48S@T6uh55G6Vn8v;ZvADYI0 ztr@9p<@PquSkBZ|hN(D{66^Ha(j6MCIIxWPCUo^9@w<_0-hjmkq`;`|i$L{t%c#z0t^_Iqc_G15=8)v>U+jX?^8i|#%w7k~VEKRx{Q z&A=~cJV0r)WauevQahYfEtxeF!83mG0q)D z86t+|PGYl=1F(|6Gzhdg21rDLslyZSrj6r2i2QiM-yoyA{A%v}&$072DH)o`wQ150 z&UXBcgOr$LCz9u#@oYrfDByV@=D|r1zVtqu%~>t;^4ZFb*O%H~PcIhlYhG+>+;fXGyz{cB{%k|zva)9R_hOaf+vdR2v-8VKA$|?8rk@p=CCI}cf~20)fnMuZ8FjWH zpb8)v^c3FkyFMq^CKy1|6cFn8n&7R_n1B*8Hh@kykhO^t;4%_o1&&Q~#YzXVQ3VOi zQQU$L9^1cmLgMjKDqPq{Qt6^c6RB-h3z}!u8>!53Rhy)}eRSc+bBixFe z)2PC8i=jzW!6{X3I^A>hC2;g}j%Q9hGECqNT5O7NofgpnsR@~62>CKdoW+bUwa%&MXk{Wf$g4|_8 zB~zRG*aY46M5T+HCN_I#P^U5`qhuhcT+h^M;aC$yYPq;kmLBxwd}^)dv;0$JooCue zL247=4tbJBY@OOhoo-W*)~%O5i<{n$O800;9iC73EWk1TmOhQr30r{j!I@HTLLRp@=XPq@?UCd|w zInA15!IoOZ_uS(Hx(~2k9558C9Y2dT2clt&t$qh8If)yS?Ey*6X~@gOc?;&?1Cw;6 z^8rhEz8tbtJiO8zSn7S0ELk)GX+jsCBts51KaPuk4rgkf!y)7uUmngrj-LZTOm?39 zf>KB}F7S;ZGl?6*m;c}_KS&!-4vHf!4SZ?mX{Ht^%HvB*=jopnq{-vU80Q-67Y4}# zdwWa+J~hL064QWhNt4;bvEc*UHS!|axZ$xye#2saXT$&Zb@0F26Jw61TR4ND75u^f zy`yR3KOaqYBRR%l|Ndy&1&*eFm#IEQzS&n}a#}0d9R@}mfHFJ&Qk!jC^!yo@W8(s?=9x|f$K4Sjp8kl+mmh@YD z^XGpt)lOnHKasm+xN0fB4I#o^a~TSP%CfHnlL1(Ibf#)zf^(~vh&NO*2anS5eQcom z&BCVDe+uL5pOxf%t@ETsU}8)`?1k*Bk-*Wkjy5lvdk8NSGsBr+gP+x6*mD(yK9c1T zbCpPWtS1}(#nS7>tN2l^!C5jr5|{woJcx6+7xjh3bjD`mim4_Xr}q_Q$iAPi_M(x% zD!u$-a0AFxw>I-)XY}$w76Rf-?p#8Ok8@n;N=MV<{${FMo^pL8Dg{=hH$w`A9WM#l z_=lO5H%gkmmTp(J9fi+pcHq#KmzL4w_EQ0YEQfk6i5#&|KKs^o{grv~Xr`N{9kLxE z{q{N&sJ7~>JcP!Y>i_{O6*7ycpYOk#4Oc13G9{NiWj12lk`%Ob6QVDM%DS=A# zNOiDPFiaCY{a&0lwVzF_K`A&azZ@8sxx3C-fQTba z`^vm{WCnX<_-tyq+mL4(pEE<11036a^vMTfUNkQ$hmF`W*EU?^axruk7=ldlt;9Y= zn-`b!on*T0>FU-9L^IvzlQ2xR6rQOsI2P9h*V0qEn?Mq2=%Z9y@&%xcphVAM56@P%Esp@saLhJp>>ePhiAN@DP!oL4Nn-{?Yd3SezPf&Wu z%~0WZ@SVLK_a_1hUnnFm7T< z1L>xWcJKjnWL>`uLl?%UVB9_otUgq7!KZ7k>XNx+=uGv1838iLg{0|*QBzD_9Zh2K z>q*_O^%56v+$~}ez%bSBm>D|sf0U7pGCVY;{em_x#)Wfd-=V>Ua&g=9utgNpLUF4H z?xW3%QYH-Bb9dzwWY|!OJq%Ehj(%Z*_-x_=_IIK~GI-n3>(dB!5=8YZe{E8t1W}!72=`%aBNgHaiKuU&}im-t#`5Nj5;hw(TKGUH8)x) zvi)lmpKvEu46BC~w|daX9y1$03Y~9%b+pS`zLP6_H5=9rpkrplX1x?e4Kb5O==Sj7 znvQ#;nQC9+jfhDq{l3bRmXrB&5~X68YMdlQa;F6M(#*Ad27A$1dM!d57x&%6B2^}d zN8!on*|3eXIzV9g8k~yHS)^hC%!be22N69eQR@*`&oKH~q^MS^B`)_4-*z`cL@8fd z-|Kw=U|!UHp!yiAu(|RJGiee)S&B@>VCjSAOSdF!NgdV6QBNLVu=F*>zZ@od5ZXfo zvn^-8s{B8OYc@5sHq|t+zNfQ$jtyk05>Gjby|Yc4lV{VKp5#XOVhZE;zKtZdJ+@Ij zQl7yS#<`Wuu|)J{R&mO~No+FisS6923rCGadf)G{wI-;*1&dI96%Ju4O97iAx_dz; z>O40m*v3UF`+(UnwzuIAT!-eAE*pAl6SYlsAX62#b4@5qV3U#o;Zg-jQR7#kGu5?g z%qFdr-6yNP*RVOdnwmz87P6pj(PrSPHe(j_6AykEK+vHomrhluquc#6QUK3{aq<}>PMeR79OilFa?dfM6hgb_-Xc5&@2rO1;Yk%EVwPBL`QZ1vC2W*=>{b~$9&u_r9FcBwbka!sFCMpuJba5teEHB|Py;U9G&^Rmg*cyA;&;!UBJy{+)B5pbTr}%b zyF}5T_w27soZE$57I)zeXAThP4Bk>Y01wPnVhN?Xbsea4^KlwE{Sr+D=CmJiU{C z5}NNQ#)zShrp4lCn|vd~RF;hX#+qi-pWy}{@ik7~FMSO0>8D*I`9iO#ezXO%VQQ!+CbMeVqr;k{${deNZHp`n#e~wLb97WWASnCm6 z)GIl;JOT>iMgE@{KE2NVF~C=R0GJmm=1W1-%T`XW9#AFt1Lnn;gr9lO&+b0;)tw?f z>Oq?qpHI0?iTZYc2uNI%%maMU=0(WOi6W@k3b)>&zr0Sst&@N(_W)qr`)Q3E*%iP5 z6vhWBnSet{I*`RfnY{^J7=O9?ngX3--P*7!S6AK;mCx&;wL6yhlj&mec7Qbmq%gtIfVA{F5%Vi zKX?xISD^i2oJHwWUAIT%QoTl z?38eihz>F5+RZT60K!h)NS2g{pKl`in<7W3B3nG{9RXBXSLA!D2yPJK2|UVi75~Fr z)XLY$i6+Y4&8T(7m(6dWF-?>`n$bJR7c0ofG=QmA9JWym{RS}AAn;#E=u&dbANJ7m z!5C0>)TM5$yhqd~Bnq!NmXj)$M=TbY4GV9^J^?2CsK6h^kv@!ml=E?13ULKgF}K9y zcXgbPAaSp6K45N+$HI#*P>gk1g+zD73lThL<%s3G)Ju@C@m6obCeDfTed{bKp4jV} za08X#FeN45oY?avz7C%FD$Y|?JgLzl@rF{8?z|@i6|0E?3ga$MZGxFjlgtT{H3|`gsrv{$!&j={Bh7_HfQ=XE$5DWo@ac5VX7kbqmT#gj1)MqSW&cei~iD zu8chELeR$Q)W)IIYy7d*)Kre1X&v*b72;ucs?$34(nG$c1S_TYH>ba%NDmQ1Gu1*v z)4{-OSjqYsA|99xn<->m3}&owSkCY2p;q-WL0>a?tTVSt%sw|~?lzllDy9Aq&(cxI zJoL=k`+z)Y&cd?Hx;V}1E64&#WaH>(`0b0;awRR$0{G!I~^ z-T8pPjsvqou_T58Ed3+cULGNUrEdXd!}+DF_!=uu)Fle2EK=q8pptwzCl7$xu%;sv z2Nw(HnM5IF1GcGhq4m{lc%jh#tk7YY>=8|o3yq4EEw+_@kr$y-LQ|1n%l-dfN7Egg zanQ&A&D%&L`9B6qWk8_x_J6pI{)fKly?=8X>49{GLuEPj@+=96C}kx7rEjX%dNh;$ zNILA(SXu;#vN7mi`lfyjA#_-6a&k8+`bGCpDYbU9<86SI{-4{(GmVFsQE1%&L`gYo zVW0K7;~%6_=W7#M$bPPoD{%9G)qcL*_*bM7S)UG&G$}GlyHa!?!a-B=@6`CgUGelG ze*>k>wTOu3t`QmVS%055eakvNJ@{L0BxpDt^54oXW)%U`&Gkqs<+mX;N*Bp@R3wjz zM}Y?Be<782Dc>hp(=f4w@uX9{i*}h@y_1rX_|I+RL&Hjzs!^(!L9yz zi@A*yVBhk^2)?LrAqzP|Xl&WBmQ~^7&Flq#1105>f{yxyQV_EAlC6vCkq?ZN(Ry7X z5>~1yNRU_hH&EIMEN|J0knSL6f>t#4*DKP4$KoNO*)E>{1WJ~cHcVh+5*2{?G`UmP zU^GNR^}f`bn|B^eyL;6)y>PSm7712*vs?asT zvZa-z?E|4^IA}rn3aM1vgWj~dY;lj+*YnYHNef_e`y7m6kV>(QD}lpcLTfn9*7d}F zRU0wRE-s;<7rcLwN_m@g!>t60^&@p)u>^JjL2k{#Cn=cQ$am>OyKy*2OI3&J<7qI< zyZSNPjf!LRZPZS+h}ZYAAx9v9zG_bWyy67Io7VHEWEQJ;=6rcPXMX>xZ+fa4M=I2O zEqH|N=%dDKjIwLjOFrj@kY|O^6Otca5S^9hfR(<(b7$1)F5Wkx02A@84z?;_O#AS= zGjlu6pPD7SWh3XUF)Q?#)_W05G>M5td-_)KpFh1=T!3__|)Pl(?-t;CVRk(dHOQI6%<(70WYMw7h3gAtr z49dR_;0+$_?!|ej)r-o3BGj&|^jRmGZd%M#< zMJv1Zqlr$9IPlmd6szqbDSMf2p_N^3Q&!%@hEz7f3bsj)Vlm3DAzAr@n~|@}mFTJz zht$0e5{T-}S1#BU)Z+Ky+33D0>MkX-mQzF|n4yB*U%VDGrrj{~R1zgoHRD3ufw`is z^p9V)5vNbHKTJ@YA&DOV0;M9)T61N4RK1<$wJfDEd#|5q*Xjy4s|iMvpi^-@IKY^8 zXxtR>*lk_N;-lC+#!4UOB*Tj$ztnh{n~-*bMk>KrbLq^DM}zNBe^Wvum2$WRiUpS0 zNln0HxoD&kBm0z{mJlmN!xsg#m0sW>FTQZYY>Rdb&cJH3q5FZ&6Z9nyKkX^CSg>RI+h z+gliAmja1FCqw@_0e~m1G<>Nw5EQ`z0ws~geDY;73$Xv%r>6`^#ZXRxSAwtpY1^4mXcoAx_o z`5;^=v*f@0o93kJBeC*{F-j>Fr>PA^4heV@u|jBoOk&VB53i>~lGdkpf>$3z+IqBnzHmCjYK>1{ixeHh3J1HUE=Ue9<5!99r9L|BCZxF3?F#Q4g zrjb3Qb{>QBjrP$jswS)kr^7eWYj|zBR5Hm1tKQu)yd>TfPII5cQK-*n``zk( z@Uzp%t=y-D;;?>?L+LC(0$Xmkd&Z5uAFtc z&7)SCS#3>A>p~OF9jv0o)00L8yD^sVt)>+V|+EFE>D{Vrb}uk+IMvXPlL*hTsXdZEw}?nrOx1^hWqTy ziq>Wo{*2e$_<%9(kN8h_%!!A+l6d*vUi3W%c+(F@FIPzg;5)71=gdpCC$kfOI(0A4 zzP|c!kO##TwFx==KGFGyO~CI1ttbg-j;JD#;8&QZP5@!mo7aScem^$60U0@v?Qmp+ zivVAhu|E+qfM%2Y_lEy0?(HtDz$P~Gq&<9Ek3hmX|HNZ|o0|&YY_!6gJSG)I--HJv;o&FH*SdzDmrd|kDg?v?P80x-_dvwX0htdXT@0RB3~+)G zxng0dC-6Lv@O-p+ zA=gc!zRg9a>O`BlqXQ*7{Ak^WF()U{3y`SOxfmm>n5>N$u#Nj(lly^KETq{9ByLSG zAFHhstGf|-T|7?qP3(?h92J2R^wd)WghPEA2eXPJB8X=uus`=e_e}>_<6-mhr*82) z)CoKN@dA1Y@B5?JFKrSehOF=pA|+1~+Cmeg#S^#P;^aLO9as|;n-lvj6ID+WRSOd} z#gj6>CTe>ovADV6$0g{_C-GY*8Br&n_u*WBn`G*l48cpbZcd)SO|~3LcKG(pmO90S zL*H31#lzFY9hKr^qpLrk;y?6kT?=uC8X4+|grkt*&B(}kWVENMcL|Af*GqyEWb&yJ zD>{ZD1pqppZm4W=rK4lgqbH~w&s2p5Z2dh*AtJRB^&qc=Ol}f)>NvHr`EhtG9+Dgf z$YzW+A#bSD?a0y;_8~SaaqZOj1<`uJ@EIfiDPLgDuyU zF-x6EBiDC_gab4V!2^_CmkAkL^O?J+nS0;JcBnCdl4lk#e->~Xp#vqon}D?o4BSRr zSy%wl2k4v9Wa4lA#|GQ~J-(sCnFg)nYyR&o-!xMHqxlA%()P(v*Q$%Qv(6>7X%LT;;y@g!x^7yu z>R%WEbuK|Z4v@waR>C=+Tu{&DC(=9{k##$S^3N}DXy9u@`+@C^|M5h1Prkq2i< zJZb(4e@Ws=N(0W}kA&3-VH0M@qA!uer^+R8F!6$=_p51bAR-wvg~!C`+isN00{c|k;c{Zx3fgs@72*6FfdOiIHpSIQe63LlA}p}Dc- zs5Y?%i{(qmFaL>2X~H;TtQEaF4r%MIiB}NSg2XO&4&MPOO@k9>OsNsm1EPBV=`FwX z(J^ri?xQ*Ll$RnFAER5d8TAIrACEmJnj~(px-#EnB-h0CUgl;_2Kkr$s!;Owb#C)Q zFW(|XGZQp@-?U}(77+gt={A|YP;;0ZrcmKOJKNyyWXv-Pq3Hz((FDa@pD`Qy?hJnwEERZwA*;# zD4L*jyoNU4>`f^8oHp6f^(|ueaT90mW6U?qH%=>c?xR?^UmKe}zq&-AqS$nU-%Z^* zv3H}rZ(OA`)r0ps@+@eq%`B&3&mJknBR={b4Bl{^@Gl?jXE z#j7fT#J~R+IcpsC} zFzabvUmL1Wa*PSbq%^9=*WNL_6l7+Pn;*3WmTw(imZx}OJVd5U_AI@a<=cImpI$+B z7A&2fP3Fl!wJowJa-2ZUzOXDl7M=!^UcFSuEZ=_JxQmY(HymC!+aUwNPN*@L2>2xy z|6}(`?-^wV0(u2r#^I@GFClU4DCP(5fs;)+rg^u~)wa@93J;>xJM<>98Vef93x|bb zYQ(VTEn`1D1?_1nY}CV)-{;mk6qQDrfAMKiPsn{=tQl3Ry(r7S$Qa{rpB$oAH2k5` z>w~Z&_p(-kJL$X>XP(CIQs5GKny*bBs>40bGQOpq(}=FN*(raL7_2dEV6Ds9o~5wW zX{R}=hWA09KM0qinOP@@CHE)a+8Z-}Us8=g!(F#g)kd$%qsI`$u(ZeuCjjfC_FeX* zaF}3WBAW-0>Jn?|XDGa2o6(m?%*L>uuQU13Npj%2(0sO&dfX-!wZhO!yMU6?X~SiFoJKswBDVcfh)G?T5^I#5@+Td_!tiDb5oapxS0TaXE1O8G)20 zjii(5!>bVP@)g`ya{%0RpNYt41pEJC?JdKiZuhqBVHjWlg`tO1KtxhPq*Y3~QBn~B zB}G6a6^9;r=wayYt|258Bt*cZ6akS|DQV?72fWs`*1F$y-_Q2m&u93^#&-Vx$8qfY zk6H5JtMI_2>1CP7t$Sw{Dtw$Sa7Juj;8=)^3i>~5dT3ODD? z6}nTJ#t_|Mm%!|Sujh4j`_&}E6O#oY5b-fkZF_Lo@kl(M9(wo!c?ur?wq#Cbg4xR{ z>8?SBFXD8n_e)Qzx~y+W^WkE51~ere4DPI=6=e5bE(x1(rvi7DhMlusp8bzk2 z#;r#h`801}GM;ud46!nQge`XzASLl4RiEZ;6&4tplCB@Wo+&NdWWB@7mT?`jD(U z_^xx&Vy$eYjZy5P-I9ZAj$gmdSh3$IlmRJ?;m{2A;c1%}+Joy!hb5vMx2)-J>TKY0 z_rLIEij>|P+{nn}6XZi^4BR&9__cSipcX@Gq9TH!iR75qJ-GL#Q0E~#jVedyuVo)k zi=P#~kCimfseL$EHeU%+8e*s>1qJO5xg^~#yO@@b`*a@F#2w$n3THoV4|*=X`vjaw zG9&vsJI}UB1wXXOYCU(_c_Di$K*0=X_NCQ( z!jBZgExz=|v~Bi1+Z`ukqI>1}`)lFQukVJpc;i5-?LtjN&NMlRoz!jLYs`7HrZl49 zh*sw2cukoLuxdN^DfG)u-{><}CHX+~co!_+ki1hpPkMMDP!nLjL0#aaPj7q#P7it$ z|4Xm^!X*6}0oDgjuR!C+j770a1#o-O?w|9AKmyJZ;I1@CDQ}Gr0b){tq;H@!3x0fR zfin0 Dw8*-if5KyY-}Z~9ZxSV*b?d2rx4bf5x0NN+R%;DPi_f-k`RRpCKK_+SC4 zU|J**WpA)mk)OpvkhNC`1M(j8PLSPb$g*(==R$~^6iOjB$WbcPtH@7R1SZrGLQE6r zjYPlRhTU|zZ;A~Jz@mE!LqyQ%@WUN+i)~OSJS+j}`>+==Tu+>c56e3jcF+@+wd0k+ z>+eTczIkwx1m=5%mzg}wUGVc54X;@UuZ9QWq$2R64=b_$O`{RlMnX^0+-L;Lx84WE zJAszq5;1wufewoXa91@q31s9DGU|hx>nm*V2tH~QA8uj{;6Bli`Fn%B(Q|4pV|I@x zf%#^~sb0!^8Kg8jj*Iw58(uMAjbb{OVs=JjQdOeI7h<65F+d?q?2Sp?igxM&ZeNT= zLCm)~V7_r8m5yaxyyLivnDvNdYqDn;i{-Glc3VZ9V2|Y|b8f$II|p_Tl3%tKU+2i;&)pS2j&h@lH@nN%)0@Ym6o6>?Y_j^I$oM zRb0tmZ8+G)7I#4&{dqdD0wgI*{Iv10^x2@a zQNr?#Pp5)8)nEI4@=KgMG>a`4z z(&Xi3zyQ`KC=K46_2eBEq%;VY?9$>aTC;4^*(^p}HcNB%RrPGPy=)gvMd5SW5g1sQ9$%`h= zQ#(p&KHBE#u;ky(%`-5|H}c7UOqOrboPS9vA7FhfSqg*-^8wtI`b+*X+;vr@z-g~w zG@!uc2<{pt>Z(K9wBMN+1t5R;UE> zU^2 zbyjox*6^m*7}4O^tTTW-nAJaN+b~nay!Pz0LajtBoBUB>hFvHu7MAqz(@O*gze+! z`w8;kB!S{s-=;~8CLF-}OcbWMB!MASIzayBUQ(x#d~=cxkaK~=Ev4pxPYNPzfp0SYb~Sp&u{;< z^s3!I(VW`oNi=!#)nSpkDvDjE{|)hjil={rU>?^Ab%f5BgWKcm>}yVr3yTcaA0GdM zavO+HX?&p&vidBTg$b$_kDAXf9PnAW`nL$SXhus=%L^fFV7Ze?$x5L{=HHL>nhO7G z={1WPuAd5sAT>p2vs}Q-=W01kaa#JkpW@O$EB~R~eg(eQJF_gU38r)MB6~fv@nY{q z^~4+!QZ%sce@csm=_*Ecb18Q;T(jw&8g>gZb5J#Zl@?VTCa_PS6kp=B-^>=s_aSLD zFJxKrEfPR5gmYNqdS)V^zl2EKJLH!a3$vW*k1jbbErN5HuHI6KyBgl1DOi2LoXcX} zwRe{bSIccR4?{Yn@A8xNXPauHX&$J16ZLo->%b9EauaKxqQb;n(#Yirh~l zDV=L3am#{*Q1T1vEt`x^s|44H%grrX$_)8#7RTWBg*N6@Zc5v-wHIujD{Fe&FRakj zzq@BNxrnc>{V0Q8tR?R}-6Oa$AU@*sK;dM>0OfrL`Uv&@;1>zb9r(#(5R7=ev@cn1 zA11H0rWp!9vGL|;>2<@_UYJ{E<3(`a70NufZiw+Eml3BU%B_H%4d3mJxS&4X)Js2` z-@f?cI+1dGunlz;ys~f50I_v+s2(?_CX^P9ou$o#S@ZBs)>4aJy~PoUf~=Iad4mA9YT)U2U26#oH4um|f+`+xgTJVWGP;x0 zw{(0>8GvA#SA#1!vzJJpU8%c1O>! zRWDa`y10vvurb4%8Mf9iXf1B)7+9}RgEMBPg%iS{-lt)<9vCT?%VD_Cp$USytg>4? zCk-fA6lwjS9kBPaO#Md9>xq4=cNDm`dY=>Fl8whNVo<*e6lfoJ8(w=fMDEMoV232;XL2bTh?ATFh zk;=gYYTARpPtld0(?KXLz9GFhkg+0Aq-q$Zck{Tk_*9Yf^;C8NmDIy?SC31J7g*l2 zE#FY3tC^~!lKE8(Krq*`CMokfO0%^hac^yk1d?U%l^8YlU&jw$dw3__L5o7cNZ{K0 zk{>ICbNE9e?D|8ci$&UHdRleswMW5Rsa2(c{QDrc$6>4|#7M965SRLDmsv46Cj8_R ziQ@N$LLl-OXw@e6{2fAR(KJDdu?nNzXLHUMbJY$il1^})?8goT2=h22h3o~)QRfb; zi0aE;l{TDpI%v^Pv^#F6q?7`68#C zqo)(ZFAFP1%JrQE!Q82LIWmT=2~%9kM8pWu$JM}fVoTi*b*V9Iy@7a%BY5c-=qM_ZLVq4tDE1IvBp=;)JOs4Hkvtmf^Gil$gWXHC(yQ}i(b3}hoJo| z!|#zW7*n^5l6=`LT;A@x;T_!9Gq~08{4B3vqv*(4IqNd~%o|simdWjm#IgzG(oM1& zBfT|v8|&{?AO9A`hKfE>WkZ2$s=#$3T)^0Msf%a1ijMtorwo<8o<;pw_n-pfk}|oO zKlNz-Dkv>hs;p5Gbu8+hrW~B76Ci*1^tUx}vMR)Z)zwS$)^L67TC@uQV?~m$wz-T<*9L920hn&rm7ebG=?Tvh%U`)&8{LBPd zNuys&uLb9D&kahc@4t-Z0gemF{AvDiG7}1v7R_krf2gA1qbRCgV`8LLd_9WV#Get( zO2g|<;ze+sm)i4lSBQA{Pwqf z6Y@!(n4niwLjxsX>$d1f>|^yqy9bX)(Q&*!Xf=c|0KpXbCQ2cav0)i%VUKpga@4$2 zc@gPg>4o>q=Y>E}A)vJAOco%a>JOG)*BiqN39b`&V=23qod}I{5rH2fI!q#=p%GmG z1S9nz79Tmd;QY)ktZxS_z3#o`g^ZX)joUfZ;k_nyqE;Bu?a5J7Ceh<_;d9vNo)1x+ zFQS)rqN_ZjX5oPI;`qu0lostnR}oEM>1E=yu@eIgvxn%Bf^)cu5oB|i6Jr=E@5>NG z6t#5h`34_)@7S!6Xk=5Y>s&P3ZY&3L9G7$)w`rWe=v|(axL@uuAeh@aOALZJG3j{m zF#&s%cq!eKc$ubnxv}`myYccVX0jZR4@?OvO{RCMh_8AlXdRuyBWvJGTmopzdBQo&Huw!dFqjSLUBGn zS1soEjsCjgw}pDS8tEGKCGSg3Y8^iH*O!h|T0RdC)~GAfOH+@J{`Xh;1~3qgRE)LT zz2*O=iLaV|j;0f^7{G&9IhYciKVVwbzKOj+oiWf;xHe-kl!~3G8OA?xqP1z`?^n4&aPm{rkNER@4kr6W9# zTiA??H<(57g)tqH7$i$^T1LflIH!gq{(|~&qA5ky*<=rmP7iiIz&QMwc`%W!%83@<+61zlr!ba?D&G>( z7l9Jj4d(E>&?EkW(^|LOO=%awr#o*zFON;I18F@)Ujb>8kNm@55V`UWO3BJJOUXlg zRX;)d=cE9nN%V-n!1Qf-Ahs)jgDIpdKt0PSlC4|2?|f;^>*H5>ZCKqKTNbXXf^G6# z!$_IW?lnU+p2z%!ZNFRRdS8x8W~NIF5mz66+WJT^5KaXZhPaQyOB6h~e16=Be-7Qf zxkGrB?|yy!{?*GAuP=i2U&PCWFe38S&U=eRg%!=Z#)`BHXz;jq>)UwoZet<-;OQQy z%Yl%Jy-BaX2a1lYnYW|V+t<9V8r|}}Lsj_K=DY3la%-@!LiOv377jl)-iHzlgw%dd z71Wk~Eon7Ua-699+9P~;u-Wpc?bT%N(>5*4lOKNHe;&We9X|>C?gkF6TW~cWDpaBf zc*b)(1;nTL{P$~be(q51q$0e^yJATcLOMwr^1OfhekN8rewEKLbM|Z4#mhJi`~P{B z&*34yaJkfzhb~r1^V3zKYDaaslq?SJ#|9U&HN&xrJEDY;Du;2=Eh#Wh3$5ImP0@H9 zQe9u<+9MSU;hYQ#-)1?(a^#+%;c*z4WNO@25rwWE;Tg%iW93fS$K10q(VjxfDiWqd zk$Id7A!<9DuhBmuj_`~ZbZGCO2guJHj`SG-1EI`8p0Fabik2BoVigFf$dCyaA+d3` z0;U3`QZFsQl<0l#TOoa;@EhT8Vgz7EQ=*RB_E^pfbLYS8^dG&-XK^C0jR(fq-zJU$ z{z4CV?Y(g=8}9wP4DsrN9)Q2_Ud(o@Ii=NJf;M9ZxF>SY9uA$!ejArO`}H!J#&Cd7 zNhU|`JW>o9uYdPV79y%hc_e7~OYu-fURsfgWdCax`xCg{RGfCSK`56&Z7weesYvJ( z{IhjEe&&%IXqXu|)I7+SdR45$diBB=cD_7=8+}^#xD$6TxgSl59tVmGL+g2z%I)=I zn%|XxDN(Khi}-Dd;S~C3Cv~d=81ir@q^$_kAEX&s+tt4@EUnJSr=!F z4i~@g{?@#CYka$nz56_COF!NB97)dFZtyBkyES(=CQ1T*U-zH|1EJgLL`)X?`7YCa z7t5=Agnu@~MVJyj2r9M7y(ZX-;j{CiJEc<{{&-huv)Zj|<5Dk#R&ShOAk2q-;=Fnz z@iWB;2kJUX-XZb}7b`PH$Guv-eCEsHsog$3syzO7>|mL=bU(l|G8eYmlpp*IGXqni z+eQ7((ONx5m(jH^2IeFT^$rsk-kmkyS^yzcir<|N6Y1LnwqDOto>`hc$OQa_$@jE4 ziaQI&2YMrl;8pHYYA2pfxu{`|i;pWPR1*exM(XvHdnB92MN5kYsWNxts20sjyqAnx znyupImP$cL#a>|c&Vut{x#z28$4|I7PPZRchH5)mbhC_fgDFw&_G>+2-!WhyTpE}$ zNNsv3)SN^Jsq$+!>#B!NQ6k@1k`WAq+F~y)yjh*yTlPO)HT0|xloFF{xH`HD+!Kcz z$@e9VpWL&5!NYRoo{;|)9mKSeJk^jjGlhuRiKeA`wO(-tNjrppQEZrW^j2S$d`dT# zq;YWj3-6(>_k9^1@L128>75Jb9~D7J79Gq?26Rs(;(r)$|c4i7qPeJNiQ4*sk#yvr+R+Z{bx<;FC|%3^iYq*ozRGx z6_=QOvxE!;M4UaLHvWP+ze1>7@2?-I5ej|AfUxT!$OLXjS#u{E5K>*1wKPV5I;rb@ zi`(Ldlk2N5l0&=cc~8Gz26Qq_*WE#YXKZEee{+@^^14!tG3>MWlCAFkn-dv7%RMhG zs`KoR1O7tXZtJ+h@*bx9a#06(m2cB}f1J12Y-!wH2L{49%Cjq3WI{t{Xu^`)FH`6v ze2&}`jVFRRtD;bpij#$EWkkCKJR`}IU%@cX-#bI?=D5sXy;irts~lyn|75H1F_gex zP|1AvAS>UGdVZ`6Td$Cz^zpEIcf<3)O}{DMd!8HHPKzMl>Kj?MQu! z0iF@-R<0Jt(rvuy*UJn9#efmZtC6gnbGer(cMa>&UZk>yIhmE4y4j&(l z+UFrd5J6soDG}B+*CcwO$aNkYy#jZAGZMY3<}~>{>*o}8&PX0lUfIv8RVI=?Y9sVDG@ITedX28o`{@?0lJgr?-+0Q}|XEf5(s&l#{ zkQW?2_EzWi#BeBuv#HnQ^~LiVmfYy8$$yzFV%?vnUR&@gRqDag$G+Oap-lNe3U-Rx z?AMyg@%%Uc;RJG8 zZM0#jPWc86yMI{%xzoeuhJUV?*;bsYkSTPOakmmMB&D=p{rlxUT3gFK_%zscwl7)W z(7M~WWp`uYE#c)3zNhQ7c=mY99jwm{PXE)(-EN&`o87HH%6JlW0$Ag~_jKS6r^nUd zSVC-yx>y_pI|C?Vrt{R;AHrAFxms5hwS)gy<-7?$kt1%Sb$!%@2}N$RD1oZnyH(_N&uip%j!4(IFJEi`|$L&yYI zJ7Dv(SmCy=oYh)`BGDHoa7!5xPRj1ii#ot-V-rqxugy?X6c8gu5pW-D^PM?$$3~A%NlCWw`f~Ku)Xo zCS!f38SMZ^xD9e@44iGbe*f4VE@6AqH~sdgbuwG9&Lu-Z$ou<85C9a}pb@2`R`Hon z#8LVZLv*=9J710<0E!I1e~vJRr|--xNL+q6o^T8S$k3mzUXVi1+1T1QKny75DHaMw zocF)suUO#at2b#Wf26hy;_EZ#odG%R+^x;;q>JVF)$~lEvXXuR1Yq>-%SQ_BjT!6m zJ{#%3c4m|Bx0O0>x?whCX`q)|EHel%_YvU&%Ei;~9`_CB%Id8=ugN5QPlu}XlEmuW z+8}k4Y<*hkMM`+Nt0`<$arp09Pc?aM$&bCR2mqBJxGFD>@_P&ib|-8fMk~7(yBaJ4 z+~LFz6i67kgP~!HhjulJncglT@<;A)uOyaJuu$mOw3ZLDjhc2XjNlG`V)ZOgKEVIm ze&&~g-tO~0YY{@CISLqL@X5UxFW(1T$dO*~J)MTrsx_OG9sOeL=~}ecz!{{uUU$IG zOt`f88R~kt!X;phLkDr57F|#kqi_pj=e~MCOZc8{fO;ete3ER2QuWR2(DSW%yr5n- zTdW>Wy4Jk}-BpJeR3;E!?tGs8+7!x((gI)3r5?ZB@0H%+H33z#D%GiZOWwAOMZzRkpOSWDj4Pi?T=!XB+_nkR&OsuEknqnQX3AC^xUJtK9@i z93IG*vbH*WDyp$l(NbW(p{ z+Xl~xMbj0=yw`EK&AgTAqSKP0@gaGoR1eSaY1nGK#VLk9NVDNnQ_{$h;r>zx#T083 z>SakP`JdkvYam`OyOH6t+jGCt0a}J0p zc>H`4YMOtRyIj?#Tv9>I>%To445;J?u@EWD*(0#JZ4z^*;U`KOme%$8=^YUgJ**_b9WK3Li;$-)%^y# zRkZG-hp;lLW_8~+e3H92UFBvw2JAONQmFD6xv;Vyjk90D(Q;1wD>4Mi!u zTd@x0_%){wtZ{T9YY6*a%QTGp1Erq;1iDS9|?5?*zAM`!5`fp_471A zhhx1$O&*02hAv*7QN2Df$grdZk2_K*Gq13;9ZzOS#A7gY8TIfl3Q7Ur(~I2WcOE5T zfjiu-oEM=9+~HWST9XL;!h=FDgeg3*X(wXC1I{oV2)?JE?t#&}5+DE?g^>e0kr&7y zvXH2EQV#-5qDFV_*(LjqjYhGnMouE5$(SN$OrnQXqQUp{C4BS>S``ogR=pfF>0&lb zoP<3PEhaI0a673Ws1j&xL14s0FkMTs`wcO0X44Jq(f9OS%vWLygmf%w?$&iza(59h z`iP<*i?!W?L78E&YGShv*HhkcRA*z20O6~OSat(up9SZYj{j*Bdqb2w{BW2=yeZ!9 z?rpi<__4e=2hpexWC<#K8WP?K8cl@n>6Kgwenc>^Jc*i0Fj7}mCr6rb#2b$#TI?oT z@-gZ$C)tpjnVKfqr6f5tB`u34IqfFdJWO(tPIfm<_TXc2_D=Q*GjMB4_S;QHF=L%$ zlLJh#koUH6^l|*TgOt{ilZBM0XFSQi*(ux@3h{<@XnO9 z0n2H`rUP=Q9fXtA0`gl|N#}xnfW9d`7l4FO=8MCGtbIgx`IBv=NA^`#b zhAv|si(u$7CicxVb0-DV%Um{^GJlhc0C5~)=+f-?3%J9Zg@|xjC&sg=!fna+vS|1C zDP^)5eX^0b+cY=;R_A3H2VnIaE(&v2nH(M&p3^=#{LMLn4%g0(gKpUwK9*c@vs?)c zU16VG84At|&AFHNa^+<-q*?Nmn@?Xd%TvSUY4BfFYR=OsVOQPDGmy!@W+ty~mTyAA zrjN_NF`jP`E^EA(Z{@&ZE>m#Vr@*dX;x?|psULag*c~1&>L^p_vBw11>cATJs6_DL zcp++!(HpqKfi;eT_lZwY_#Q*xVe_#y?o1dlvyzrSBxt;ZBrMTx>tO2`qsy} zh%B=bBZZOzT#2@5amjee#oMu&3nev6^hGkI4gGXw0IVKPn|usbmti7+)thPlfYp5% z2w?RR#2>JF2^|2dzhx;OZ6<)#&$^aR;>yNZDrU_p<|t^Ud@9;yDu6ru`%?MhUPVLy zQN0XTw&qh=qEWdwUiq89ba$^Z6NuvgSlzss$hRs{ql#jpii)y`e7`EX|HvJlT0rAl z9jtLwFVoCt-miYtU(ID+!?T~8&Qf}AxumM3MnJZ7f4ioOrACah(3l}F_M$+=9M==+ ziQ3CA^H0yzi2vVJvi>7rjtw>k0dCEIyDd+F+w!(j@c;kYQbWApdG6K!?zZ%^DJm_i z2(|jJT`iCbO}vhQ7!_kp>Ab=!|1}lL&}wp1Y==HPDd_aCsgPkQ584!U_gU#b1Lj_} zSVw&B2;ARPDg@C_uk^OX;NPjxUiZ{!?GJ8ewkENV56>h1PKAb2p8mR@;We7a8ANG( z-YQ4D{PW+_rKl#`DV+#J0$jKirTEuvc?6id&D2dR$W}y$ghq0rgefJ^(|=L97p(4d z7T@lTyue=_LVF%R4Amv4P^RPoDNeYXFr)on(yr!Bb9%8iQn?UuH%=6#tUoVC82e72 z!b|%fw?1OhGp0tol6w*ntY*;!sasm+?EpZp(3p=n#=!4uw|k5|y+E zbFjsv)IR7LXUiPIZ8?9rX-VOkc9Ae_Y}hVoY41kM_oJ?sV(EFz z2r-fHFtTcy-skhc5kz5VxmDp!DDQ!e*Ydqb+Y5!2zxOKqZt3m3o485$h2+xU5n%30 z+;=)yyY54Z%wJoo9Z;546w%VHO;WC$jNU<=yGn%HvXeqX)xQImp}XLDnewQsHSJ)Q zCAliZxC92sduDH)y&b-wEI$RM!k$K$b`YtO`!03pJCqu(k zdsGcTSL?*tZ7zR=78Q52RIwp*JnvCgE6a#a ztz&_ad>F-iIpBn0y!+l6fkgFJ4rUK5J5E?BIFQq;RIDFSxtmA^E>q2>gy*S?5=kGW zLK)Dzd>2v%Q;H0dR|!V)u)_kUH*pzM;&9nr_2B@PcUQm4p=UhY!XD~u9Hm01xpjk~ z;^$79Dzi(-VElECsNCKrdKC9)ZL+0qtL;kQBGtXG<%s|zdGeQlxPT%1%;$ET6rH33 zk^cEYj~BHFw`ER20naB|4PPq~E!fZ4o(m<{3N_yMa{MgFV71VDQ3cm#BZ<3yvecw! zJn7ll_Yc=tHHauU5R&vzKAR{2nA>Bh#ku%=dEQ3{=`aq%cb;^~FSR7o9L*p7`S?T- zkM>so$P0~GawjhVGYSHgyMZV4=V^t>!1#8Fty=osWgB5Y<;EFtC(FVQobBTk@zb@@ z>1exLpW{>r-Z_Ov^3qF+FxJueub7_>pO|6Uu4(>tT3?RxMtGhAYw_2oO<0$9bEUJqyXm4V!KFMc}LDZKR->V95qb@XK(9AUjx8=+J%*u?()D{C( zbI{f5;d;3F?qW!5I0*v*Fn9l+?IDft$PMNf1i+k5>}J`kNEhRRG76b%;I`a)d!5G7 zqW;>mi97Jd<`MP+S4X2jr)u$*dF>y$V+kLX%fM|Jbf-?wzC$#G{fVu}XNTA= z0+suxP0v&d$xbz^&RTeA;U&bad*G6D}HGn7#aur_r zwQyfS;(g=b!)N(yoGQs8#1HZqjSsScw9D6|jmkrwT6x&SH3(u;0dC93{7&~9?C z%X;^}qp0Qd)+;;%wM;o4SAsZ-1EfNJtL^Fv$}C>4@$sP`!dq`>FYBXXuJCyb`f3$*;;UA|zNv`l5gUn7j6xM0XV?#q{VA1JOINb48(q z>5`l%3>+`two!C;1i+lk8tX~qV>WmIk5_;)X8`?clkCud^E&}6uc2qu2q}*UAr+$I z$NNKu1EhBX(87J)rE7kp#X z1~|NQu`HE$h%-L~-}SmPt`cw?&62zdhYSV?=!h01O{x(@fRdmRGlI7uS{D^>|b z@mhP}{k^cE&O6i}IEZwI;r^p&jzbAFl?gfo4%uF%ew~GWvVg{oT8f#_Jn9ar$qwD% zfE;F>poPFD8vu{nBHbi7i_2`j}%^t=ye-3d1?fB3kj0g8;!Zj5JRRP^fWv4vpm(J2=zV?t8);M zKp-SpXMZDOuaiWQb7F`WLq5q$md>YnwO)->+I)mY1OVSwHEG3&$` z4x+c{$Y2ggOh*ilcRcA~a2!!_oWNp8H-bpaj%*)8#wQXl<((jsA5TgI0UfUUcErvY zQjsvK#Ui+xcOo4F$<#bb!<5wrPwboz=fjZggM$@8W|ERbnh4jjq`9=iwgHD(uHNv_ zBP~QnL>49aNE_ZKXP3Q`cx3}_F9N$cMJCadj9%2dw-^Q)V@s~$k8;6=NvC{+L0Eva z%k)9$R8lgKcBObk?SjMdLAErm!1TTj9gVg(uFTu5bPQKD=32>|TG!|D7~Gbot~bGL zx$77VMsw6Z5ybw<;mitGk-H1gf=pa zNFv_uW|BHwTj^s6hmdvyc6JuYnm5=j*~MU->3p(JGh`u~v)z-jyoq3UP{C|R((}{%X65+OFVYCFd<&uug@ogzn zC{tbF?o;@5v%m}7mSDQ%K;yAj7@(o%BSSEfqx%c|allBvbTxSV$VhIM7a>!e)T|Wa zQ;Y-CrSR;;@!~8qg%p;OJTP6-NX_&qDe<|I+gwrsrc2@R#VnmC)}3(5}mlR0We)!@+RDtX5uep%0GbV5{o-Q+T|nqe!P5&FkQM& zkaqD4fA*J)1Yb09Fu1KzHhMTHu{{TdP0 zT9LdOG4t9thtoA+x+K$5yP{Mpw_l6*uayTza`U>}FJQV}WQ}lSVe}q;^z|^6VM^{e|Mmtf-QiISK`0k;j3}~n~ayGHd{aRzs-2v{|cc&Qwve%@XtP=J~gb_bp6-vQ?1d!qQ)xsiTaSO0!Us{Z2=O=tu3p<=IUSD%+lr zsqVEl|NMtMJ6-4**XTJ^5$4^1gk~a-{0-fwEP9Qi?y~fju#~?|9ugF-U$eiSSqvOEM3NH`C77! zvlRKq?aU-IOG;>&KbUj504_cB-XVoy4wU;0CavJF&6INr1tut)YF$b%x1FbSrDi~4 zdBu!&oeNX0L;XTUi59uHbt3 zQ=t9stHukEB*-j!t;UeY9B-y-AI5eWxb?N=9dMV)KGYa~D#>(j^R?Q!Z_JdjST@a} zOO=kn@)sw`IG{vjaokW@6CB|D8!hNQJ<&vwwaHGZ1W~%2B{pb?|fnfQ-6W1PA zlh7OrZGS#$XR`VWH3Ws65Rjj=zjgA$^ijr(YQfaTxAG2xCga2`U^N>aZKlrGPPa-G zH|Z*R3Pdg**|EN`__-}5IXegHI9$=$|ItAvESG1Q>@+-=K2lorSR(szPt}W?}xwhnx5z#qzQ~_ z2T5Rt*N#E&bYHIQ(AfB~T!1Gtf;$}8u`KN^6(C6Q6GwMA=XG&4%uXWO^9Aj(JbN%G zh**@fq-?HOx(V2^z-CGSs^kyRGZHKQd<=T0tqz6qcFVsIQCeX>%6Q4lvq}QHtisq~ zH+%938SiV~^F=ud3A`A(HwZdng>G0oA>)m8znzz%P$7lkp;}e2qwf{@u=C>b-dfE4 zh%XAgNP$Um7_I&6F+${nU?e>IjPB)RRidnCA<+Y%ow+Nb5KR*S{m6KVtVUG_v@?su zlh4IJ%hf0mJ!)rqlJo^$Gk|zp%Mf6YK5A#$yh&oC4Cs}~(Ssxko)rP0_q#mg*PnCu z3f1B@Z3&wx8~s72MLLZF8v3JlraDJ~>ng^F@~alhn_`>wxTDQf=5z5Nt+x+WKGN_s z|2*tJLWo?YddtoC%6%rDQ?}&!<@nf0%_DiXozs9f#%gJnTo-|6DAOYg;ju>Icq5bv zFhiAs3^IibnTKMeT7q18s-neOwi<>lC&csB`8wo3PK799@(T!dtaioMUryS1f`7IU zUXZWuyyH~@2$8~mdd37U9I?K=L1M|faPj&=u6#nq`yqv%x^TVals3NqLxoWgXq4HS z66D!tvt=sz<3OE5wH}zQ^ zhXs9iU&bo&C33>R1^CG*8%hCn-$>E7W>m}^<;yq0ZhSjtQF3b2_vs21PY9YQfO zrx9x}C~m(jF-iZ1Iten~{r<~OuUF)r)3(=tf9}n@^11@a@xxv_c}O3R zN9F-}cBpbDJkk=zXV-bXiE;^62{uzN^h%8nFuV}akq)XYl*dgBiGYdWGjN9!DX*Zb zJPGYg9~^t^?zkD)Ol`T&#RtGSY>ET9dn@aKJo|IV1O?GHTkO5>9xbU73p$dD8Na^! zOzewK-+rs~?(q-5eb$S+(eQR^u@IJTKR?5Dy>3I#yWC2ni?!y(N6~{jd_H*kq$mD` zEt_lD>5nr2W@suxMFWXc0PW0e5*`_6m)MqruU5>8l$$~>@r5_OV9;JKZv%vg^;hzn z!_SmQS;ExhbC`H2lU=b852A5Luk*$y^S=g3vDnJ4eER*H-+s}&-*(5g&yTmC_NG{G?F5`Y_z^So2upp1v-W=5rtj~A`%F*v zMyb7jQq%rg@ok@(kW@R|ZrA<&B($C5i*Wni@?*b%yeGd_g+2Gl)_?CzoSx`Ay|?~j z=*bhH%z`XD*=It*Oq>smK|9ky%#sGu;R)KAB@NO_^C*Oge-6kvT~Pob62;?xRuaXA z49G3;=Q0V%Q3>F|1|)<8@Q)Jia1oI4N(J7FeBxHnHmk!u~Se%GQ{Y?r+&&yR1xdyfk9j_PkxYbHSrB($mK1VY?V7mJ-5$< zIH0xlcNk*i$*%JvWLEfLVmF8q|y{yufCPAkQArk7z?iiYG=qGl_iR71;}C>A*$~Na=QsMh+vR-bh8= ztB!o<74>p6augr+aWra@m;S>})J&23xK#9v{(rC2Bwdn82n02X`x!&ka zuNY}q%nm;0U^M2bUCeJJ2ALNFHN}v6W5VEs&D5?E=EN?cohem>p*4*i{(@ly?aZcF zm|85@OjQNOavW`@TIOTHW-8ze0cLo9H_kIOPDDE1{CS+Xcf1s^W09YWml=z{U>$#% zIYCi6q2on7fEiK{6JUlQ<9&2DL5DeUCI<+z5{x?@w$Ia@<>TmJ16i-d{PwkLS>oQGSm`Me8EHq~tuwxDGrsV{r4NIrHb*2G% z_Gn7_&Gi(35Q*xvqMJ*fndw7jNoUNFGcjHyb@$9zF=fgd%UJbxU6amSP|w_AW+EU& z0L+m5^qa9vND18s<|EKME}RUPWh9zK0W#jbEVnfR=$*4O3xM8{xNIZNY?kqC`rFy3 zK*lSRBi)(J?UO@Hl*0=$-tioc+d1c1a`=xkUNe13TrN_SfDpONpChuDOVyvN2=4Il zECruDQjI)~@jM-$O!d9IUwuaik@0kWpZqQLd^3>oI;5HI<$voty2DvgKYACOqsaJL zT)+%i@8Nl{Y%|yKY#SMx|J{u3KPH){Vat%OWTpSMZ=(fCCg=Yu$=u9W3jJ@BOb;iL z((853uX8$S|BX69*tda}Y;4DGic|mPg0f*WsrmY^)QKpJ*k69(W9kGroFv$-`V$yZ zUlI0g9e;4}l?`iCMx-lm{@E|gJVJwdVJzsMRr60tX6VP9$HSt~$ILVDwchRR@BF38 zVyizlg%UcLr4-&IDw+!T(~|XK_NS-9(mjGIa1C?QdH@I`M+kvBF?ek{?EAN%KEbmM z#~0L>$Q_!Z5Ee&XnqbQFh*7!-=&0&HaPW&*lz!3e-gv#s#X+$ve_DqClHCz_cen=q_*#SSMPOzmsgGwD# z2}8TBNc3tb5LG=#eqoW8?q~9WU2(mhP;T05{Y*VTl?D95b-EXl)hi%n6qp)azFe^* z2;(AGGhPDnK7D<90hC$&!(>Tqa3 z#=)N~rgTld*B~FbB8T8#**n6)51yTR+C?kf7Q}j9Zz$T90AY-Pdkd2?=;*!fo%ys& z*thLH#+>Hf)77SI+5@UA=N6aqD5}^`4AlRJy|WIBa$Vd0Fwzau-6bF(N~(0XASt1! zgrXuP<zXq|%dMnf~ zY;Yh%Uo@4IWpgo1!S{9U4k@*=+dKOZMd-dQ`~W>^1&1sRp>GVY5+4L%%t_quu1>>q zZV6B)CR3`t(7D~0`Q&NtGQDnB1sQKgKt{8)9*163JRAvB+8Xo&t-Mk z;TCdcLJ&qqremiKI9`0}V3+_OBrK}esz~$1!ZuPgR3wD-ZG)J-uhE>A{g&1j9o4F$ ziMA5rP3sCiD_PUg?V^WguZ)9|#_6NFut}XdssnKFn)^doUvgY^>yVxi)Qgq3BR1tw z;T!6Js1y5npB-rbN)nwqqkIBvG7lef7cEsdZvvTjrSQkh}$(%-VL)FC6tvB~T|`_u5-AU)pFgynZrn^7QyxsVs+WfE*2>Vc*ucfvN#G2=pgz+{D@&nq!`2@Q z^d!lh=$fFDa!wbGsffPhKF$d4+aj1KgRg*;?EMG@8(IY`Kbod{~CDA(($OlIcEq@v+@XgUgT@bh`@xvH&4&#KAQAByZD%wpG_)4G4}sC7)c z0k@IEy{du!O!5_Vt`f)Kb|+H9b*(IdUR#XFybK0K9Z~4)AFW2I;_anxaZ}1gxt(rkH9+z~VqVhu%T}qshtugbbQuQm} ztxs`pk5itvA(0TdfG~I~D#H8Z7PdV3fwGu2d_J&e8L5A37SZ?3cCl}{ zaBFRDBe@>hWCq&$jaz)FA1eCcZuiA!-l4{On7?(gs^RFYNMBuEFG$HY$bVLms(-iU zzgVtp`NfxFyY_pjV>8K*#e*|46Z8~rPY(T9;`NlD;_r2OP?@oq*!%FV2*t%N=O5oX zV`OL5kGn8?-CoY8c<}Z_ulFmthb!e$lJCyw`)DyYt=86jTe#Zm!)_zV+3=-t@d?ZJ zIP;^9C&xibws(7aD}jhW=DUt)R=C+#%f`_45;9QHLqw>sIZSc9Ec~v5_|i?Ar~8gS z+BCoQ@pakGcj6=BCz#?w`4M)68xLCcdz0+^_)_)VXo=9x;54#)A2Ji~2av+N*H6az zQ|6iwGX%WFMOnQdv?$+4E)c+!sz+K2?%S+s)&saStO19SPv8{iEWKPN9+i8bsDK)8 zKK<5Opd_K1U^_j&S&(eFs<;Ea2M6M~0OCh=kP3r}lv%Kbm&MUk@C9WCg0cqfX4(uP z#?q$xwfp~>9Q^CsC=T2O#3X_E?|gIezpeVJKJcE>NU#?A)7z*>R_#IV1J20Aq(7n> z{KIV&pcc1pwX(W(2b>f7&|b5cS4MgECjN`OR?$=QzNBnj@TPOSc^`X<{O1I=lk zQB_#<65n_!kb)hA)%kR2hT$ki;|l!+vc0KWNTwB(?}8Grt14Nko= zqTomYDQrRNRNM^{h7f9J0lT0WdGZ|2c;l0fACiFTJ8M8&XxE-%L!23k&=TfEg%}b` zc7YaqoA-1*yl+3$sH_;!#q5DqgXyt0H#fc6nG~8Xpq@<=5)yj?k&No8j;<_cwa>O=f`U|a#>8mFDNRWnl#r=oyh8j} z$T!zDqXZr-Zi2*>sr@HAv=Qx~AeEHQ(7{nNaA?fNa^QogPhH$xonmSqC;{RR)CnK! z=MTA@!<^iq71?zf&aZJ-O5?D+6to&RE4AOK>k6P6vK{cjFXXH67as34gl?nq6_0tMJ)EHYTE2RNYbF}p zMolN&G2@EtPp+5r67mJUxsVp}X<{BkH2@_*x9PqF8h$xyN8f{xh^^H0dI^)Ej1+1}j zlR)wevJwaNb5SqSSF7-fg4yR$BZKuGieE{EOxf0<{Mz8r4{!O+_C~f2>u(EGA9KDEA?m?Ecc}+&7578=(+z;3eOkxKPiRdrQAWY3yKC1)xa~$fLINUq#|h=t(b7` z(ehya`6Oc1W)7ujZ9V}&H8`RA$WNCYzh#0@-3zEbKH?CXTN88*>(U4OL4IwUnfTN? z7ul-T2}hv%?%FE})-I`f2#@72zkH^l_f`Eih=-izY14|SOk6;=^XmZLTu&!j#0<>aRcr zlRfP>HWV9qS1e0U zG2~&FRe5j0!XQi*`P4a$K3i|I@s5-@zngDdWPG<+EnF_n z_1O!s#)$2XG~ysG`fhEFZZ>&5+R#VY)LPC)ct4lnsi;hNdZ$zIu5ztWY`=Vr6k6h2XQ zqN|l*rXSDgHw3>ZU9EnfvfvWi;Qb*CnJqR&^**U#^lmzGzY1d9hhqC;NPZv}P<`3D z!V~nzPn{G0u~Zr&Va#SnAm_kIh<`2ncuZy_%NSf!43Qv7~kB1R!BPNNWKC98vyjS{7{gvVbC##;OT@Q zCBPa3`88=u1)%yI=lvfU>lbTZli>gh9WWjc#xoHOuiL752^7l{gdK-b=?&W_!)6L%#V(LWS40F`v!Y-mJ#}-+XypZUL~y z!daG5A>aH5q0Aa!jR`Vu0jj|@G+~D%P8yn&hzSovH4qdh0qE@w28wHtZ_XkpJU$f1 zQO6XKdu)Oso-d7&_gcJA2ZR5L?SYN>6uTJUo8OFsd~?CB@C4b2INU2Spae*PF;Uzo zPRTscJT6Wx4Z4l`s0fz;1wbW0#^y;aM%AVGGSaw%5}-85HxD*XJ?@Yi?noV&2A2TI zP+i|hy-=4L4{oD6Qsb_rozYB7A5OdNn3A@UX4L`RM&)fJfgT`Z&Gf?I^wPRS_Koyd znRqUqn<N*lZvoNv?=je+iv@( z-)nY*vribgjvNcvqYV2@*(r_jQoxrh=kmuxStfW-39`a|Z?eNg#E%D=*^x(H1j30K zNcpD@M}pFwc()^~vy-t3kn-0rU`OjawQZI<7C^{uLi}8DJm&Enm3CGrd z7Mu!&GBF9*%N0TGfX|wg2cyX!D`nn+N_UE@Wec(iOm@5l=?~|OeT4kpPo;(<3O0Ut zaZUw@Lz&+3Tn{mRuMcbLqpw^gRUgbF9TNmOKVj=XQ|k*y&p1eQ?kH#mU-;S~fVo@&RD}KNT!`|}L@i2^tyZ{nN8Vl--KTETaSTq(OfqT< zUy>lrZxgt3Yk9!f^rE}(is;ck4pUFa@15+p1eNZr4nOdVfc@U;tA@AI7v4b1|D7je z6kPwgfKAMtjL}^m566`50OjweNd{AfH$J37${(MxXJaN4Lq%}$ejI-XQ~wDm|6@5b zl@Jx-s!VBWbfaE%;|2$n9)FugdW`ebJC?k&hQ@n@n zY3e?DRhd52b#9U;AJl)obosFbm+rU%D#H75KB)dPBji3*x&x>Pz24KR8LQCc3heg+ z6BYO35~g+?jFOgR!j`8Vq5b5jB;LX!B= zMnD;sWw_@Gl>dXM$b6>3%Jc^!r}~iQy`6*A{=7vl;Buv+KQISG61?0y&AxTMZd$c3 zsRUT?O#feN7N8cRenaLrsS4>tAI zT?E}L24_V>rHYO5uCBMqk65-1H3CLc9n(Z7+qxKbKg~EPXw18^<9(qVnA<9X?KAc() zYp>--h_rK}IBoqk(VVys%0Hwzl$-KFZp zRG^Ageq1maFHt%cJ(OH;+jf(>u{K{L{ zfn`QhA4?v>_S))sWge=-LI$NR*hkii2TF@pJv7!nmuNUIYn0#P@oAxEER=-4s*#X# zp{jy``a^{{8)qWA!+dIcXs57Ao<)X%y)!LiiEHh#uzmdEgU zDBT(U3I$DuDXynbEVaEw>GbW##1xV|9q>{$K~ES(gD)5$+y!@R>*#5pOT{bc`qrmH ze^D|lSLFce8iAiLyi`5xFPbQ4*l+@lr4|vK0ZUcTZ1*@#a}{$Qib4556Ip}pwRc`K zB~q$Q^O*C{+x@|T^e*e;AvJw9iaOkoz4q+ls^b0_D(I2D?J=3|`FUf;aQ`tG80Fu7 zLw#v#uDIs2cS{n<CZF-4)_>B#@c$Y%2gg^uzV}JzRw1n}ZXf%po-K=ztk$srr%Dwr{_F`O>lNuWc}T z=*wd7b)iXDvdx1CsfMCNJ`ETEG`JgKB4Mc5pC z0HBA?OVi;2sy|x}<~$Tys%hL!n0&poeTp?=n2Y zKtrL9Z5TZSQ2tP}9j0U3s|!N;!;dTqIu8YpEM%|kKC&=0lm|Sr0OcQ_3dK^vBMYJY zA$tup+d;8ZsAIbWJ`aV^L+3T0TYyKlwkuZ@Liqz|Xfw1_g*vvsLFb_oDdt6VIe=H* z$qF9X?uIH`+e+U*YPH5*5M=#eeFbss=O z`A>8%?%?_Xd+m4}KX_yf(u41VN7g~xC=)!gi9AR@@W@8S1;yKwYNJ_IrHFfdtZB$t z$O_~t3aAjpIMi`{DNTT$dLd#tcQSfb6%_8$3K!yGim{>;x3$y7$ehHFrc)tuP~lOP zbJh>N?iv3>fU@9{V*=wNL4)0DT-mCh-giqWP&gXqP`c?W@!BVxv z#W`j8-R2-#2C~;cEET&{O?eK`Lu++?H-Nnc&O@PCDzMjToC_r+0~^LNxN=&xtp)IL z|ISmS51yh21mW1H=%J)RW=jy^ej%&&^1t!Dr)Qs}m7?IR^jD+;u<7}Or$|)A%;O)P zB6nxbJ$^OjDT-!QWIjUrny2e0zZz_MZqSl3D5b{petUIc|ED*#S3iwnpCZ$etL-VA z)7wT zn}VU&X0xNQ-+NHWs?(g!39XzwrA#Xsc=#XuA!Rsge zQ3sJ7iWv%5g=9aKKc;h@uh4u#P2$nGSXrd-h`7&5IhzAhvbvxur)I=`BXoV@IS0wb zbTr?aJm`CmykS!DAp@6c!}6f>m&S4rpLdDhj_}MYzM6nZ1y<*THJ?T~DG5slYu&?# zzV~SMr8!a)sa`?X5vZDBE+j&hBnHZrDPv($LD%h?{ofBz3gI+d_|`2w!@^R=l3NVt zd)!=Dn5UNdH2A@$C-Z0*<|(p0tPhh4GLpKG8^ut*N2J<-ItG02IouO5dVznfWcAHu z@DwSV^n&j_uQS~bUS5MKc!um`fL~3|Ch_JJb15iU)z-NRQ}8ORNXAyD!1ta^e&8kW z6lIb`O25y7NCnphZ)|=9XTtU$QW`|J=Bu{MJm6NDkZ{W;=tAPUZ7i}t6#Cxl9c6Im zVN~Zt`sQyh5196{E%#fN!50!x$tuLJhFfJIQo(%97fT-b6S$4c$fKMH#AoP2LOP=h z+Vo^vO`9Ia0i*scSY@DxG$o}W(<^t~qqZ+bwh44~ja`JP4iDKf?It04;Bd5tzG z-veDpc(%jedl(9y#((!yG%>B044$G%qe$xu;3?YfB&43`FxY*H_UD^`RvG9iA_?j+ z|J_qmrGp!YeTov>1ror8gsaM#p6EPo%ZNB5p{Y~-U3o&WQz9Dj2Z&$x=Skz4KaVa) z;eBxmAbZ-;qighyLkMgx4>00f0O@atU!5hb+~v1nXJ`hw*78%BK9u7)xKyD*KtM4q-<0qlLm3V(N!P zR)8h9kp3Jg?*JdM9X@-cyvty~242R$$8(1wn5%EBX}?Qgz7}*HZ(uDsO|vpEE`!0> zf~q|`G@|c_NGaY>2gP5P`Sswh1@XZeM`%R%UbqIsWJ+R5{NWK@JX-n;jOZBGW3teQ zmP;-C0xjdUH@s$Apk=&fYYY^@ykj?3BL`Is%+UKmmfW9?XwZWVR}8=rOlU-J!#&uf zaPb!elOfc}L_%K+|2-o*z_5Lg7JMxn7|ygk1-=%N5}$~tFGU|CW`@2NXp<_y*TR{w z0fA?-BZf+s9{v}<7UtThF8^C!3#ZgbIfDf9B<#`x?L@w%m9qp8S4pGkiWL#I!FflN z1*?M?oNkUm6$7C7EB#Q|ZFvyE?0{i1yO!JtG@|)KxD>>6p|6F1!IH~Yqew-j;r

u z3NvWFr*p8p2lXNX0)C7>OfY7JAD6?YJU-;$=LEDmn+SdVAWgLq~S}-Kp254N3K`o5>_hr zLop1mOKO^@bLJnyx5ICHJglgT70hdvZ@ zvpk*!GHH134>_0bBa<*};D!0n2fQvpeT$GXhBhIuyIi5<`*L4Ww+?hW3}>JgmS2AV zP700Pi-!%=Y%sUOurfZPXA}!5W19@@*oBnw+b_wwKpD@7ERJ|%`Or|a%ct|6@FwJr z??K3z&f0P@|4r_fyVCW`$Bl^e%w%k7+!iAAMsg> zA!S^~G~Wu1-K=4F>{2j%p}-k~l<^Mj(%^5$?vX+rIQb4M+!=e>Qf%^9QJ6nq7F>Bmy;oNyFpF^Lvx#*psk4*rd@?3N1}4 z_nn$L{ZCCApp4<aNT)%8%|Mkl;n_XzAz=~|a!4#&IlmS*wjrr%gnLGLo6O!W zRt3X7Ok=0tS2t!5p|!g`zW9)^884c%a*Rj$u=TE+aDlOs7x=#Qq}CZ(r5AT_V|s1Ah{~1lX7W2a1++2neUMaDd!gqJ_7|ucwhu$quu?+hd7KOfSRdI>jKV8h1r!cV@1EYoXPw z)&r2Sz5L?na5R(~U07Cbl82=#E7e1)qZc5lO6E#p$W0Tas^tUC%m%qLN@n+)L-fmD?$b$Sz_Eg3NhwPD@ym&)mYX6CiT zCB>W~gz|N$4ePFS{RH{N+i-3axCvl;tekbg{UYz4T7s**Rt?IEdp&%PFtsz+g| zszx6GNmcH!PDrX!DLFw>RU=dCE4UV_qF~+kFBsbeDw(^+Hc>_CKQp#n!!B*+{xr6y zP4Kh2&au6W?1`QhSI!9xT-Ht>dOO8`0Er5=7yT(!A*TLsq^jZ(WE@s<{+r`dANMOT zV?E*V$xg(eQU3QOCk-C*uOw&sA{DDx5~U(HAA;@=E52uroxY#1mu=sX*;1ca^SkkR z`{7U=O57bcae`NYR-p4YW^8x;O0)8PtLMLt&$U-w_(WU33E#X_?!cG1^Goc$VeQM< zuh>{jB?;II?vBr&l_Yy#`g^f^?3X^LgOjA>KBZKvy<^MIRrtz`Bas#2u}a03 z37VtHTrm~jX*}uP7|GemPJ+L|g*sRvJ;15xOpH0UEN~5_1|587qQzls?A*P|BrX(_ zAo?XJkW3bVY+BpO`@5n`&3GRS>>m6)0~DzX*kI zj-DN~C|bb8?xDS)r-kDecrR!ppv)@0Lj{FzZrkESO2M&vOvN`gd;`YkUigMBi8&7( zTLQ`X`Iqqto3WTOLHO7bj@@I%CltH)$R+{f^F)&~^ri2WE#m}^Ej?|@1mBLOTsk)N zmV`0{p>PL`PaT`yV_;+Aqw9tZO;GP-VXS>h<%-C5z<|#Cg zoLouh7(QUe8fu-F1;>^E8wK*Y)lSf(MmS-m-1BbiS0Tm8B9oZf-f`q z!!PBjCyH*Tt8wJn^%a)ug5tW8w-S5fM}2 zjFz5;oy{R;dh%1D;L}?zYGRj9lkbLeNQ4EP`fj4Ja?v6ksgZ?yQ-5`C zt{@)@8@fLM=|3ZuokBp!D#sp|8#l55RTy?;m@=;cT0XV&ZBga#t7D40(+QWS(vfs1 zYM+FU%PoZuwi*IVD~#tdA%3Q<+LsM~Vp~qsk9WdyQLc=0g~`}SY4RgH@49XutROXh zb{`-9#FpcKrx>IHS1^%UH#5O!0haafG%O{^AHwe!Ke`2o=ZJFpo%cqOegH9Mc7nFlYIO_q; zyS1PTn0W`E8AbVFKC#`xa0L`NqabG!E>DHShQH1`NG`(ju7RcFF|(pSC87ih8`8as zgu;f9T!g}gzngcvauE(2?mC;M(rRG&6ua_h8XT9uFswrT*u*-U*T)%bMs}UemyS5| zH2qC$IKbJwm5c)}%5j0S`PPX8s$jB*=N(6pC^YX3POxlef(oX5%6PDRl20Hy0hUiE z9YaKavwT9i-2=-fw2EQ*0L2?17l{jsp&Ud|VE%t$-f1W@RQ@gp!9Bv2iOoUSUsB`v zS8@;%=8X(v{OTL+7E9=Vl#AMLUzGku4x&P-{p@c)v4@}vrVd?3HHC0~BErA3o>u}N z)Gd4Kc@_2+<#{=YKUJ_mX1dv;mxn({U1y zLA~_u?gs!2hs6XXlZK>A)rynzdvaX~XNfYrTrJqT$#?4XX zeFeIedr2{N{U%wFfc(y%>-js8nhF`_NWI>@A^}^^A)>J;L<;H83Hj56gyPtHCZsl5 z0>`ciIm=}^*SKdw=1J;ccR%<<6F(KuXiB7{nZ63iyiDik(wALRdbNiTR-Re|Cman%4^)?6U-4AM;3JwKf+;LgTLhJ{%4{gCdySXS%r{J7|atL5} zzwhMZR@VcKj0?~Q^~ExyM9D4>j3R8+baX*7^owY^B*PQ(Cdf-O#532E4v)OZ`wGXg z%finqU+}QM*h~m1LW+-0)U~9T4{EQ=n3B3jN&U~Ywq4=fk9-;ld(l8CCMj0xM*=Cr z3-|5l-@|ci-@(dbaFKv|(p8KJDb|5m&%5WT!xQp2t1CPq8$?*l7G8rmwntS|CGOHN z*!_64nmmFgq)mf6G$Ct>4`3$b@sDoM?nnC86?pfiA*gBL|EAr~KQSTW9Y|gNrKDJ031{&Qs9su+4+q5| zsRR@uk1iVyikx&jJ{=^*PPA&esMr$5GJvEQ5%qDz82cc)nR2_i(_*Bb>nx)A=npC~ zqWLj_8jutt0sMllN%kFsP~m`%L~TmP)IMJ>{`VEnuhS?aEi^tDO;8fZ(Qu`YUEtz> zaYe`eqZ0B|-#MdO8{ta6hi)y(bMbd5>e~OfOGk|el8u_!>GD5z=r-c}xO|6W@AYye z~jw@2bmurBk62 zY8*J;o&98Pi$ND7vyEd!9~9UgwG)k^3ZQc1pxA0xCLXQRE89F&d|AX!T+Vi%RAN@) z47z#$P$rEh*Q=79=ptLGc1`BTSyZvM0qmbE_8G6f%8*#dlS|lq)nc(4nBawERhYvk zLg3uYR3TP>V;-LBdQ~_@w*-$rZXiI1i%fYokX@3ACRB?nJWKOzk&|b`h?-9$A-POLMmr?%m+RhI_?%R>JE5GwD-mg%jJX>~X zEx(61e&6z9e~}gRj7ofa*ZLg`_;3`7kR3XEkL1bhA&+1g5wO1^4#B?{RM zl1)Tt3u=)24u3xpg=?!44l>R0#$kxm_0!>q0Uaak;gAYl-R(%y>UD|()QRJF;|!SQ z!VzZ(5fO-ogqg$whPx?+RG)&{)4sz2T#8Kk@pI?GQxm`L9u7^L#|OSgC-lf~GvLBjH0Zf*x0e1@|_FZgnEWIZ(m+kDNS!yzb07P*th zA=Mep(GpoC__dw;?$eLX7w;2tbe6$EvUWb7q`)UCeXWEZ^9kz2kpkEtS@m0wH#Y-W zhsM;HYO?R2D;tG_WH2b|#{g1=`16<=cWn9Cvtx3koM#?lkOA};%9|7971g=%>Ns&I zi^P2wF_~tD^Q6-}4NQ`nOv-NK1occQzBEE@>2Q#2Uc$_&tGSQohNRNh=hE*bb%1w) z0Yw4t0zMq#FR418FAUaYK+CTT2!GMR)T!PTtrhz+Xe*WDggG4I9YiBX&PjE{K{C&4 zBECnZ22Z}nfTB)Wl8CM!T^WKi&EZ?LAWg@R9m*7;e1mvA4p_e*QazuL(5LZdcw!ER zj+$t0_9bEthnftzN_TE~!`AOY?M-v(_W8VzA8h?*PrtuZvbhPR6eI)L5!dmW z;2;@DDX2<3!h=%^W5^ADIMdAF#)fwY6C}I)h64_gjf7m`GfpIgw0u4KfUEa-#z_G< zNTw8lNB(}GnH9=3zttq&30luZQbU<$E-g0)$`68u8j`+nra6$bLQAiBBEmZ#WSZk5 zb!Zf5a1|O4#t1~71DR$`X%&gmD=KQfAk!?+CfvWIUluVHITlz%{ zA1866~oob;OKnB!wzAD{C255o9p%s7( zD6)7B4u_yRRd6_z6w+EZvQip%;V#z_I2_6ok3RFZ2!Nu@c&!Z)9>T?^=}8`oaV1xP z!y)n&Ay9df91^2D50C-FJpdGyNw#1us;K!Q{bYc1TextEmPP;V)dyO_yv~-E7DLk` z)&5lI0~b#LWWea<2PPtqxiuON7;LWAiY8t(8AgYSx^a?S2oGXKYrmrp3@B{ia^WPl z3!6K+)rB>I_0Ghz(RrNQ$IS7K2yRoYbC|To zYx36b<&ma3l1Iw3NL>V!nQ{)i9jRP@D$Qr+@u1-y^)t?A3gnfYJQvPzGRs`Z_x%)% zcX^Z>91iVsE>TP;{UBt?Xsg{+nS6%+pJe_1`my9dXd=c)cz(y%0jXNfRd~32gMBh#ba4>d9pJ@yT(OX7IEQm#qT41KeHvJLxOJ~`g|%RTEAb!#ubhl z8K%B`?+!{{Zpouu@mbH*KRlKYUx#Ah{`2>eR>dbxlzD7Zq?P<}KQ2ktC(O;tF1bea z-F>k5yT=kXzKC^Of>r#h;&b494tF zy{6L<>_^sav3pF3XNX)gQ|~;FJNivulA1ItGZcFOv=`~ak1*gEvv1>4+_=_m<50bB zXrb@b{jK+S=VON?^d40)#TGWch*fgp*gtaiI`k;6ak?Y(+gSp>)UNA`Q_G8=N!#rn z$6nd;T$#;M(D^amk*&9SXe2>?JR~OZ#7864?Qrt=sGmf5eK35~zKPa!)2x@0-}yY5rS^oh-=^WP8k+HXCz=rog9pph9; zx1@&Q>p(`oZ?Q8^{c2wrPoNj&W9jh~GMTycA|)JZ8Uza07G1pbOSYt*v5Us~9r{c+ z@0NUj3#C5Ksn9NYuqVYlmd2(xQa!-Sk5fh^KaS68YY7g3;453u4_B?>MY~^-m~W^e zmX*79{M!g*e2x0T*^+yOd4Y5m7yM${T9Hts4`cMZuvv?`Q4z2T0=YphH_y9g^t)`H zbR)%4bM|lx$V|EiMf#vU=|Zg>O|^oXgI(KxN3o2pUE_=W%d>q)-Rc%Qv3t_r7+?R8 zy8iFVmi!-0UH^&E|8E=s{qC^@Tzc5}`v2{*gt+wJvGnRLvR(s^<>pEmimVvwhihe8 z1zdXYSOUI|>?(LHi|zTLez?`j)b8SQdyggH>p=Z*&;d}1lj(E7*8x;T&^>-$`wigh zU=Dyhp98)Q+&%s;8~{Ck_t|?5@O8?(o@tMMO$S_hUBK6QKDr9H^ouvjd;wK)6YzD` z0hfLaP!$1}9zkA?BG3U``gQ2B45SBKdhl3M0;(cEcq}bJ_c-9vO98%)&w3jNc||zr z9;XIedI7zPNYgHeuk%Cr~{_qg{QN`L(} z^4OYrFY4GK0a3+SC3@K$H?Lp`WVb^TFT`nCzMZ|zQ1`Oi z#Y7F~`s-=;hM9~BWfGN9mhK~sYb7o|-?rW(C~BJt^cDj__c%b8w}O7S)tvfq%Glb+ z-JMa^I@=S3F?fo;C0Ask6%ks^UdqcNsH;)(4@Gw8Weoh5ckIi7v?e$n86DmmdOr^)e#k(TEx4;mU9D6TiWExEZ`_r|aO;-iMqEa$I{TdZ~N zI}KwuZmzX3kJg+y{&2#NdHsppv6_(U52r3NuXR{9J=k>F23-1)_Nza><+DEJQPAHU zaLQiJCn#yUo3S|<#_)B9dYe{3Kip@Zovks7M@#F^^nZN4xw8%W;Wl3b_#@2Md9)3>$2Z^X zVE8({J3m18ID!F%#PD^z0GA#`T#F(d!t!;fr2{}e93AK$$MAKApnf>eJ%3je~Tmoy7H0{Y=nv3#9l0+*>4g8-La1;f`#4c4lKx%BHWUq?Cw6v7z|B2T7< z_)Gd(424*)huAWNo}T4alnyer%(~aCsZ(8tK<>G&5vS3d^WG7C!PM(r>5g5`PcCEQ)*4ut^80v>KDyrd*fis3uQ28m#2>F&?)~=@(YX5PlwYp(;B|m4 zBJ<39zj_+V@vyy95U9^+(i?$p8}r*4K#uz#+M~0;`8vs00$edW<;W~04Q##+<}&79 zK0Gos<_Gi@UZN#TXThF=*rwA!+t5u#1apuMLu8iC_kl7NqC$9?lZER;z*5p zhlgaSI`rfqi(Oc!?mq8Vws*Fq1z;Mt^h4$!nc^)YjeQgu0_?3j2x&QX7jzJ77p7PE zbcx?+8!Huv$0Mut5gFlj3x$dejQxEP@Zq?$WN=BgS3>Gz#7hFj)2IpRA_Fy|Z?;6X zEL0IhJeW*!`aDIl0REwD!)V&gGKwNwwU1gu6)P*0{9g07*x|!*S8HW^D>m=^j-aUu zzPQ9GUiff4-b~Y2OF+;Qb2xrsSm+EUlZ+e1gE<`Ux2WI7&x2CW z?oZaBSGbwHx;#vG{xtK}P&=S;r*zMsliPy&jH*DduoIwh5A{@6*K{wq_<&wv@|xOb zpwH;$*4tS<&@0>x`i!>TErRt6=oJQiMx#4t6A@+spwH;Hy3z9z)1pF{rhqczE7TKS zYQ3d7q0<~_N)#uq!VOL1?a6@^yms|t@07cgI0|=Cr8`VZt#nB38332@s)^{g^f%kn z(!F&(p5UT2r8WxLUfUa{x17y<)R~?>{CO%p0jbmi=ddS(uGplErY}=U$L%M zWaS}0{d`oosxWD5RDb}u<&t_hwKEbG#MAo8DO_pl^)Ym=ep9V5rNTj9PS-%MWAD<} zeXqQ5@h%H%SS&o~!b2BN=n=)W`si#x->Ytq-n&Se+MSDnvqwo|33k>!LK+eNvD?$% zR#tmrn=F0wDaW*THm@E&w(27ne&v7-V(|TsoeSEA8`qR=wkzBfH$HUxF7FKDXMH*H zhRDcw?G1a$_@hTZDhhp#Z-JEakjVzzu;HO+MMG-rgEYzULQ;pxRU8k6}I3pH7 zw{Cp%*)=V7$`Q|i;@oSD(k}aE19z;Yqfl@2AOCCYt9xu_oMByF%XLwOqL#&!dU%NTBO3BzRsx^XDXe?1Jv5FR+II3*Px z+OGG}Gd!{u<}%K%hoc!H;-w=J&0sELYD9W%#I2!-+v_lwQ92USXOy1`a~X#sOEG;$ z(lD3NE2=gX+h_DyJPh<1wMs`n#`GBhE@N$U*HCoNdNiibXu#~o;JPk12O`K5<}$Wh z4}(4<>6j@qY@gA`+L-yFn9u7mi=fY_R)Bi@)gT8yZLpn*XqlzN^JcbpBRzAyG>474bh@R$~2E?6Q(14zJ`23a6L4 z*@PoXU~;euwO?3^#G++g>z7zf-ThzhRJu1$;h!hF#T!f{T0No^V%HvWVvl-3!v2$T z_;z{nEYggyswG=B(H2#4=}FT$>;gZ1k>Ijv-fQ#>;UQn$6x|I`(aN`ar6u{i66v093GW#B4+~(th8kCBSJACj-HFVpj zE=)y&cnew7(Fc~EvcSQ^FyYFZG`)}$Z6CeZj%l@l?o`?gw_~2{&?JasPO9PCJ`Ka@ zm=69=M$Lp%)O-GGua3Bk)SYd85$!UoJso}H(<^o7?_et|c5zQff1h||Ht8!NaOw>P zzy#g)rKl}QP30WwJtjy4w!aABQ|r6ILw}kl7|&O---CcVu@uv41A^8r42ZV^F9UGR zii!h?ts5W!6BIlYJ7J}ROQm7^?ASF161dd{EGzG7Us=k1>96;uPJQ>J+CfbZ&AK*Z zfLI52D$uf$os(4=r5MKQ;Rg1()TD}GTiBE8F~@m@u^Ntri(3S z*l@6SD%+ZD<{-A=g0+fXVed=>$ecL#;M@w|)QPzy6Q^ilrRF{_FqeI(ogQrfIGF zA9OVAzb=N#fmR#fzw(1#P|NKJhThtzQawvCKHHNV6m{+DdSByjZchp9=+||c_IynS zy`W;TbzSH6exswewr3P5>ib|F{e4zLzrH^OqoWOC>j&=XtrS`w?Xu0sWze`1UF35# zKPNwEh<0hElHwIT;G2)U?pdu>KrUR2-O_P1B(TX;`s@{3An>(kErBij3yR|57{T=f zZA!K(Cxakr+x>YL5>9cXN-tQu#f?c4OVADYeEhpWI%A; zvqwK#>TM9AXk_g*8?;^DqaT5<{6B^g?+~C+Pe>B)U4NhFzt0ebzivvXacyS$Iz_&j zd*8)vQ%Z8P0B=0ceSmV#5IFc4g;WUO@(P^94Fr7i!5oNh{vmKsq|^ageD-sDp#X`P9%04C+=xK^Gaq;;TYk&B9LGhkCS|I4`=KP7O0z@%@00 zA2Swao=e&F+6AEyZb|DOITY@`V;mC05OL8hJl-tA`Ehu1YQ$;Wi1eWd3zdl543TER z5!rAr=wIn*4c%LSZ{B`9cQLAU_INa5c$-&r_x@;PoZr*%=$;|Dae6$WrRV{|qn+!* zuTpPxpNJkAy3untWRxKW=;%s!|0%DSBJS(6u#V0?3-yAA+>QBa_8T4jV?7qZh(^kw zam~?5OFsB%XyQ6F=`gIL8RMvB;%NR%N1Mm5u2lLJ0 zUeMDr$@b>SOVY@LyLj=x4nF*;B9}lQ5HCos?eFM zBxBz7MRMmr-kZ9WU%2D&>Ep4(=iI6}%QT5kg9Z zdMgUqibs+pkz|bB*pp<*5|Qj=$u6=aOH`7O7D6I>w%@(XjHx_5J@4Cb{I>qS|G$pw zzP_K&d0t#EM0uMObcd=y{+t@f-jG{B<}XQC1<8u2G!BM1bVTm>Np0~;q#$^m))C-I zH?5|zFb28fM95L}gPd%4s%KKb5{TF<>R8;FZ0 zRv&p2Y~=}wi1QLIeZ_DU=<`-_ckC#Rqpwx)#>xoP`n*eq`fU&mDYM$OGa3$rzKogofb7l|H#r-L!zmYa^pk}hD(M4-@fB! zsT7535g%e(l1W4AY_alFlk>>8rFEhw>ZQVO>RdmxIHX6h{#oGx^_ZQpb=wE-cg8AA zS(rOi*x{&?6EVev;R>iD}UUXq`Z0kN} zF$Uzt1YU!WzPkr{k`Wg@x8E2I9oSsM(}EWiQye+na#>;Kz{w{3&1mmFFT{>4i~6{m zF?R~Ts3f+|Jb!8IkyF22l`2#!V}@(8kUC{_z1sYyXyw_yfUXcDNpyk0iJ01>pU2~R z_rE)|{Dn8*N{D+fl!#zHRlbb4&Ajw^d+XeLoeE^JB>MARw;MROiUl^BbAoucr8dv) zOEWr^UwCgUzNvG2oaCnN;ee{&w`6H|uh6`I;0m?SK8hld@)<0Q&4mo*SMS5EodE0bC#-Z;M5v0pDU>wr-^>*_0jU-;S z@6Gx?^>GaO@nw6~waT9CvaMjWn-jWhr|vL9BMXc0rJay*Xw}QMke0w0WE=u6+fIR< zk%3)BuyH7`58B9Azib1>p;b5XJ-m5N#5483x%)~1yKg)FdD8Bi9gp2egA5Uv8SSa? zSytJjWtyE>i|3NH?yk?dRTs>+%YVb3+@yx9LWj}}8*-B$U6(R%jMuc|ZO>j11-O_>qB^~uqNk{a%L2)g{f#)6EOE4wd=G)F3V0@WF&;#<;K+qdaP zUC*_uec22yhDE?JE^ou-av%jnCG-{cgZn5iVj+jmop)vgt?I@IQJ1)2J`~#2u}(g6DN`mfS3k8X7n6oHx-C>_m@Et8O(&;_l`b`lUNllWNOo&?+9sN zIMw0T$MQm~t(v1%>@^N;WwR$biojqdT%-5$I-j3NFpR3M@E$Xkn z;6X}t#CwZaJM2Kn1aRo=NT^MuQ0%%LD;~Z)x+H-spP!-P{|Xj&YUrP$lGq{QMEOX)?SWh4JLqI4Xn-pq&Z;s6{uB9 zNU?SwViQ|1*(+f@%#wnz(|ldc`827GlKbr`k`ACSCTAPce0kStmI#Gg4AQAImAEJ3 zm(fMCc`{Km5Q7=GM)z##NIzKe?0u)v-U*dDCEGa&@Cnr5n-d1pNZ5~RN}G}g`C!Qt zx<>1tYZe);1W9uc_GA5@1&SnU5-ANFH!uNJXTD-E|4sw{BOSo+H1O{<@DJ0#zpv3w z^1S@x{(1JS94!hW{0ZYhczXs^rDxsl(FP?N3l70$9mOqr5?IsJg?HDIYWepfC!%&A ze2dbe5>YpuxG5j@PMKLrz(`^;kvG>)Q|AkxU*_cPd6o|cg70sg2bk!H=oYQJTiaR+UfVxvNJ|T58?1>C^XRJ1EVw z>R&!$Qc`Yz^@-N&n4p;b#Z1xHEv~zFsGIYnjRV|=1HZEC zn*R|Me|bondGJB>&4fK;8VTCVmv9p0m<^oy!>1*6Io=w#NupoyjXH*DrvxNLH)ePGdEPxfeucqxr^8l&-3@|uyg9JdMZ0E z6=2bk2PlNlQ5P+#oZR12VCe?k=kwj8x8UZ~aTiXxZ`L}%6lv+N%feHHlj&4()uoYj z^5CLCC^#LURX~dud8qiR@Ns#nYpL!89P6_?2d{hX(^t`kZJYJSbO77tzqk7idWpAs zphDfv`%uP(KA!s9ggQmMB7H+;eSvHAk>v@GfI;6dr){BtZBuC5H7CEQL79*uznel^ zZ_N57I!W&aY@1I0sj1pmtk6D@{+X%byR6WgCj9diq}lZGMT6pp_0e)z$KqLhMJ}Eq zL9P-?b>Ia9>Wc!(?OmE?11kIRt$=NlZ1?q~!6noO_C;>Sb_%`L54wbLuQdxAa@s83 z=|4Ohq?hYIrVwlr<~~W5>iBTje~AmcMh~zdDV#%2qC#kjLu8*&GR%dnL)oJhL-|>e zx@=Ay))-E)nk=HqH~#8>&uQ?-SP>{uxd~H8^68j zjqM0_d@DaL*3}Uc{_0%Oihzqe{{d{=JVliB2o{bY8oVt(-Y1k+ynPVLogb64goquXzS}sUsf!agpGUfrHe@S^hSCCb(3lu39gm? z9TBTyS2nXz9kbbY{R&c_kpHmVhVjGn=o69p1i!tYC1&F{8#mEx~<>T>8RnXJT0$w4RXVsDX_e5^xQ{;3>GQPRLPzwQ*O%pgjmY1%vhoe)|rx zjT=Vl1Acq5{0E$)2CmIy8#iRRgmTn25T}$N;DRidkbnzfI}`IC0NeS$H%CpfTmo2? zzXeZ`Hg33oN7}f58a(y8fA?=8^+^J*-y8S;jg5Ov`dSXKe-~q_WC!){+^ewE+kIzi z(gi5F_bt${lU#jbi5u>o9jFf zr2mc3@f&tJKv{iU)8AJGgE`!j8#xp4PC9z-%%R&_ku6Q9iW5-F>}P^xyPt^-DEVYO zVi(Sfow1QqnwV?R*Pc-CVHjlBR7HsSqKy{~t(d;3A#$+wTqFJis`5&n!5oOqn?D}a zJaNn;xM$LcQk+H2t;-{nDLqBUNOhMw1)Ecb!ySXis>W!?r};tgcayV^9^75iQCz?$ z$?)2`s$Z#-X;LF?N@Vzi!2FB-+vW08&d8qFMbX)DyN?ec`q9Q^{?w(Vf+EXjHogun z-Gh$n3V{CIHG|`b0o%e-ZH`grm&YyMdC!#1l;vIk`giMGE|ww>*!e##>7xnOFQ>ja z<}KOO%M`3oO(8MvuQSpIY}}O`nd3n_H#Bc#cCHYT_#8&h@MbfR|0uN>vqlQ_Gm8W( zmec7X0@)2nIqJX2e;C=wWw*3L`H#gR{g(UB3IPeL%i^%f39*z12OR$un>u2}e3;!K ze7c}y@#C}g9`x*tGxuLEj@BKYe=*)XqxrGy6Lxn;?;4$1RmSo$-r0uX=I{0)l#Mmln;+D=I5i+i!LY~G`*(pzQ#aX91 zUvAu&Sy47x{IB^}^GmDt@0RCUgUcsVR_ou1eAU0pO3cYyUaTwLu`p1vey*L+zmv>h z9~0z*5ukrb2l~qo(88rdF$s`9ong{vD+@w19D%H{=lK(`pGf*liA`GNdB1pK0Hgzz z=WHW;-fv*UEdw08(m6;g&K%AT71zj~_bV!Z6K8*t)^Q~4F#4Kf*Y)0*2!{H z$0}J?`V`IStySfPkjRfG8c!wIwZ%}Sv|A*-Q>(mUE$Bkbqha8IW4&6;+3C-xVoJO3 zc(XcF5f(02DaQ|+%q}RgpWJom0IZoyvvZ(}_h!EZYsIbCo3Vae{xAd@Plq!ut-}#c zoF-LKp6byu9l``K{1FS9*wWOtk$h<3qMkDgP49$_rvMlpT)6ydB^*YIiN!Utg)6;# z6k51!Vi-O4=4ZkjyZGcs1g$uAhd;Q0wfzh$J>+1G-O!sY=KUkS^SVp!_wISHl9My`?zASpDeDewr~Y+*LuGy z>GOZ~!nF&d1dxsYPBZrh85kZZi`(>bWMhF24Bs{)UHvad&0l`_@xu%_obFMF5HQ5? zAfn5x(VF&G3@3kw&JKfchGX0GuLrIC4StU<^Gc=b=vw{#C7$E(x7hW4b6IKC*S;A} zr%v2nd4B=0>)X!=BO_0fw*eMJGx|vwVhCMUMzmJ&jAeJfBEzn?2lS&76Ma%UNZF&E zytkp@1iimRXf&#Yh_Rm_vsSQ-uUIQ)qu4**Uv(GO!uU_5(U* zXgEc(aI%Y&FvN+4nwr!~7Uo3A=AHGD2Wi4R0fk!Y#>+sxO`fjo+njkF;PE))Gv*3I7dlZp7^>+t-m46SWoo8x#%>mGg{JF;s5@ z9(8Q3p})a2w_v47OAIP!xj{FE;c@X$2Gj;VO-<1Z z<4``)5PkzXEUo6|1BAapy^LegBkK7Q7Q;pGa0;`~Vy$=xy}!78iet_xMCT2`7~%~X zj2LcM$1HVwi7q@-Wmp-)5MNGW%+RDrhjq*wG!0FY1)m@A%jby}vjJ2f~82{c+0dldZ5|&86m(#xclR5$(EO zU5}mzvQ}K^;oOi_9mO&@3kV%LMx-Y|QOegU#a&2PfiR*j;$g4oSK$fnz^QI-$J*fHS!rPK%G zsKhe<2&AzveKy(wwQAi0PE-I=H=iut$$rp*`8;R0GU&imK1Wj_xx6qr?|pu8b|7o# z$xvPPxZpHCIGsu#ng}|6!;soeRv(669ej)LDSEZ zOZ-2FF7wBG*X9H0vN=3kkoZ+Vur|26G#`zln*?;sscM{!fR1@G0UZeFnD?$YFn=k! zOynAk?o^stc;(KV#;4r2Pd6cvKgK5i%tVJp8kAUm^?^_sWUIP6Yvq4pH70Trgu~Ky zrSQp`HF$6O(YiU0W?lV7UB0G6_iEn*;6?q1>n8Unu{+6MP4sBdv@SBMF@0UsK5Qzv z)%Z>FCelPN+di?UhisygVUv6H0=d7;P7p*Imc@K3^vo<&pfVF$Hx=Ue*&a*9dl0S0 zrf0nE61;tc|K-`ZX+3G(G;^+}B=x(@_wv%2JP0I+H1;H5i6RXPdtQ6JU3B8;qPOAj zx+(Jz&u&0~QJy-Squ!C=s#nDKjwsR)4#k#DR){y1!0ia#_ZF@RWBCK$H$1|dn-K1MjxjQmi3qae9@vV82VYNR}Qw)Xdg4 zKLMvXT7k!GLNaNDM zqzV#W>zn%?{@z*OMV9r-GNW<$O4`?-(zn2YIjrp%pC6KJf8D#6`sv?cxy>0o@ zMU}3{01uI+`5)f-`%Z5F@IucOq6U*g0T0owQ=J1_!HJ&XEC5V&0$4tYuj<|{RqoFr zzWacQ-azPgB?&^Dgj^5#(xlDuv{%vFC=3`)kz9&EzpLOa9)wXIO1wS&;oPlN9&>SM>ngz9qgco8@Z%}e7qg3Qm!Yu$4apW^SZEJ8 z44WdGQgyPpT&-z(l<$>Y|2uXyMDW*Alr Mq9n3GxzG0h0$50J_W%F@ literal 0 HcmV?d00001 From f5b1accd7e34d49c6fafa4e9defaeff7048f29cf Mon Sep 17 00:00:00 2001 From: ahcorde Date: Thu, 21 Jan 2021 19:00:29 +0100 Subject: [PATCH 09/33] updated readme Signed-off-by: ahcorde --- README.md | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/README.md b/README.md index 3db8cfe5..aace1fc8 100644 --- a/README.md +++ b/README.md @@ -173,7 +173,7 @@ cart_pole_controller: #### Setting PID gains -To set the PID gains for a specific joint you need to define them inside ``. +To set the PID gains for a specific joint you need to define them inside ``. Using the generic way of defining parameters with `gazebo_ros`. The name of the parameter correspond to the name of the joint followed by a dot and the name of the parameter: `p`, `i`, `d`, `i_clamp_max`, `i_clamp_min` and `antiwindup`. From a9b771a9f726df6be75be0d8be5fd06084b8e466 Mon Sep 17 00:00:00 2001 From: ahcorde Date: Thu, 21 Jan 2021 19:09:57 +0100 Subject: [PATCH 10/33] Added PIMPL pattern and other fixes Signed-off-by: ahcorde --- .../gazebo_ros2_control_plugin.hpp | 5 - .../gazebo_ros2_control/gazebo_system.hpp | 75 +---- .../gazebo_system_interface.hpp | 2 + .../src/gazebo_ros2_control_plugin.cpp | 14 +- gazebo_ros2_control/src/gazebo_system.cpp | 318 +++++++++++------- 5 files changed, 223 insertions(+), 191 deletions(-) diff --git a/gazebo_ros2_control/include/gazebo_ros2_control/gazebo_ros2_control_plugin.hpp b/gazebo_ros2_control/include/gazebo_ros2_control/gazebo_ros2_control_plugin.hpp index dc93ba59..31c1db79 100644 --- a/gazebo_ros2_control/include/gazebo_ros2_control/gazebo_ros2_control_plugin.hpp +++ b/gazebo_ros2_control/include/gazebo_ros2_control/gazebo_ros2_control_plugin.hpp @@ -44,11 +44,6 @@ #include "gazebo/common/common.hh" #include "gazebo/physics/Model.hh" -#include "pluginlib/class_loader.hpp" - -#include "rclcpp/rclcpp.hpp" -#include "rclcpp_lifecycle/lifecycle_node.hpp" - #include "transmission_interface/transmission_parser.hpp" namespace gazebo_ros2_control diff --git a/gazebo_ros2_control/include/gazebo_ros2_control/gazebo_system.hpp b/gazebo_ros2_control/include/gazebo_ros2_control/gazebo_system.hpp index eaa256ff..9363b0ea 100644 --- a/gazebo_ros2_control/include/gazebo_ros2_control/gazebo_system.hpp +++ b/gazebo_ros2_control/include/gazebo_ros2_control/gazebo_system.hpp @@ -30,6 +30,11 @@ namespace gazebo_ros2_control { +// Forward declaration +class GazeboSystemPrivate; + +// These class must inherit `gazebo_ros2_control::GazeboSystemInterface` which implements a +// simulated `ros2_control` `hardware_interface::SystemInterface`. class GazeboSystem : public GazeboSystemInterface { @@ -64,75 +69,9 @@ class GazeboSystem : public GazeboSystemInterface std::vector transmissions, sdf::ElementPtr sdf) override; - /// \brief callback to get the e_stop signal from the ROS 2 topic - void eStopCB(const std::shared_ptr e_stop_active); - private: - /// \brief Degrees od freedom. - unsigned int n_dof_; - - /// \brief e_stop_active_ is true if the emergency stop is active. - bool e_stop_active_; - - /// \brief Emergency stop subscriber. - rclcpp::Subscription::SharedPtr e_stop_sub_; - - /// \brief Gazebo Model Ptr. - gazebo::physics::ModelPtr parent_model_; - - /// \brief last time the write method was called. - rclcpp::Time last_update_sim_time_ros_; - - /// \brief vector with the joint's names. - std::vector joint_names_; - - /// \brief vector with the control method defined in the URDF for each joint. - std::vector joint_control_methods_; - - /// \brief handles to the joints from within Gazebo - std::vector sim_joints_; - - /// \brief vector with the current joint position - std::vector joint_position_; - - /// \brief vector with the current joint velocity - std::vector joint_velocity_; - - /// \brief vector with the current joint effort - std::vector joint_effort_; - - /// \brief vector with the current cmd joint position - std::vector joint_position_cmd_; - - /// \brief vector with the last cmd joint position - std::vector last_joint_position_cmd_; - - /// \brief vector with the current cmd joint velocity - std::vector joint_velocity_cmd_; - - /// \brief vector with the current cmd joint effort - std::vector joint_effort_cmd_; - - /// \brief The current positions of the joints - std::vector> joint_pos_state_; - - /// \brief The current velocities of the joints - std::vector> joint_vel_state_; - - /// \brief The current effort forces applied to the joints - std::vector> joint_eff_state_; - - /// \brief The position command interfaces of the joints - std::vector> joint_pos_cmd_; - - /// \brief The velocity command interfaces of the joints - std::vector> joint_vel_cmd_; - - /// \brief The effort command interfaces of the joints - std::vector> joint_eff_cmd_; - - /// \brief vector with the PID of each joint. - std::vector pid_controllers_; + /// \brief Private data class + std::unique_ptr dataPtr; }; } // namespace gazebo_ros2_control diff --git a/gazebo_ros2_control/include/gazebo_ros2_control/gazebo_system_interface.hpp b/gazebo_ros2_control/include/gazebo_ros2_control/gazebo_system_interface.hpp index dd70de2d..a0757280 100644 --- a/gazebo_ros2_control/include/gazebo_ros2_control/gazebo_system_interface.hpp +++ b/gazebo_ros2_control/include/gazebo_ros2_control/gazebo_system_interface.hpp @@ -38,6 +38,8 @@ namespace gazebo_ros2_control { +// SystemInterface provides API-level access to read and command joint properties. + class GazeboSystemInterface : public hardware_interface::BaseInterface { diff --git a/gazebo_ros2_control/src/gazebo_ros2_control_plugin.cpp b/gazebo_ros2_control/src/gazebo_ros2_control_plugin.cpp index b464f902..7abac34d 100644 --- a/gazebo_ros2_control/src/gazebo_ros2_control_plugin.cpp +++ b/gazebo_ros2_control/src/gazebo_ros2_control_plugin.cpp @@ -42,6 +42,10 @@ #include "gazebo_ros2_control/gazebo_ros2_control_plugin.hpp" #include "gazebo_ros2_control/gazebo_system.hpp" +#include "pluginlib/class_loader.hpp" + +#include "rclcpp/rclcpp.hpp" + #include "hardware_interface/resource_manager.hpp" #include "hardware_interface/types/hardware_interface_type_values.hpp" @@ -295,7 +299,7 @@ void GazeboRosControlPlugin::Load(gazebo::physics::ModelPtr parent, sdf::Element // TODO(anyone): Coded example here. should disable when spawn functionality of // controller manager is up - auto load_params_from_yaml_node = [](rclcpp::Node::SharedPtr lc_node, + auto load_params_from_yaml_node = [](rclcpp::Node::SharedPtr node, YAML::Node & yaml_node, const std::string & prefix) { std::functionget_name() != prefix) { + if (node->get_name() != prefix) { return; } - feed_yaml_to_node_rec(yaml_node, prefix, lc_node, prefix); + feed_yaml_to_node_rec(yaml_node, prefix, node, prefix); }; - auto load_params_from_yaml = [&](rclcpp::Node::SharedPtr lc_node, + auto load_params_from_yaml = [&](rclcpp::Node::SharedPtr node, const std::string & yaml_config_file, const std::string & prefix) { if (yaml_config_file.empty()) { @@ -390,7 +394,7 @@ void GazeboRosControlPlugin::Load(gazebo::physics::ModelPtr parent, sdf::Element auto nodename = yaml.first.as(); RCLCPP_ERROR(impl_->model_nh_->get_logger(), "nodename: %s", nodename.c_str()); if (nodename == prefix) { - load_params_from_yaml_node(lc_node, yaml.second, prefix); + load_params_from_yaml_node(node, yaml.second, prefix); } } }; diff --git a/gazebo_ros2_control/src/gazebo_system.cpp b/gazebo_ros2_control/src/gazebo_system.cpp index cd9fd371..a4566ade 100644 --- a/gazebo_ros2_control/src/gazebo_system.cpp +++ b/gazebo_ros2_control/src/gazebo_system.cpp @@ -18,6 +18,82 @@ #include "gazebo_ros2_control/gazebo_system.hpp" +class gazebo_ros2_control::GazeboSystemPrivate +{ +public: + /// \brief Degrees od freedom. + unsigned int n_dof_; + + /// \brief e_stop_active_ is true if the emergency stop is active. + bool e_stop_active_; + + /// \brief Emergency stop subscriber. + rclcpp::Subscription::SharedPtr e_stop_sub_; + + /// \brief Gazebo Model Ptr. + gazebo::physics::ModelPtr parent_model_; + + /// \brief last time the write method was called. + rclcpp::Time last_update_sim_time_ros_; + + /// \brief vector with the joint's names. + std::vector joint_names_; + + /// \brief vector with the control method defined in the URDF for each joint. + std::vector joint_control_methods_; + + /// \brief handles to the joints from within Gazebo + std::vector sim_joints_; + + /// \brief vector with the current joint position + std::vector joint_position_; + + /// \brief vector with the current joint velocity + std::vector joint_velocity_; + + /// \brief vector with the current joint effort + std::vector joint_effort_; + + /// \brief vector with the current cmd joint position + std::vector joint_position_cmd_; + + /// \brief vector with the last cmd joint position + std::vector last_joint_position_cmd_; + + /// \brief vector with the current cmd joint velocity + std::vector joint_velocity_cmd_; + + /// \brief vector with the current cmd joint effort + std::vector joint_effort_cmd_; + + /// \brief The current positions of the joints + std::vector> joint_pos_state_; + + /// \brief The current velocities of the joints + std::vector> joint_vel_state_; + + /// \brief The current effort forces applied to the joints + std::vector> joint_eff_state_; + + /// \brief The position command interfaces of the joints + std::vector> joint_pos_cmd_; + + /// \brief The velocity command interfaces of the joints + std::vector> joint_vel_cmd_; + + /// \brief The effort command interfaces of the joints + std::vector> joint_eff_cmd_; + + /// \brief vector with the PID of each joint. + std::vector pid_controllers_; + + /// \brief callback to get the e_stop signal from the ROS 2 topic + void eStopCB(const std::shared_ptr e_stop_active) + { + this->e_stop_active_ = e_stop_active->data; + } +}; + namespace gazebo_ros2_control { @@ -28,54 +104,55 @@ bool GazeboSystem::initSim( std::vector transmissions, sdf::ElementPtr sdf) { - last_update_sim_time_ros_ = rclcpp::Time(); + this->dataPtr = std::make_unique(); + this->dataPtr->last_update_sim_time_ros_ = rclcpp::Time(); this->nh_ = model_nh; - this->parent_model_ = parent_model; - n_dof_ = transmissions.size(); - - joint_names_.resize(n_dof_); - joint_control_methods_.resize(n_dof_); - joint_position_.resize(n_dof_); - joint_velocity_.resize(n_dof_); - joint_effort_.resize(n_dof_); - joint_pos_state_.resize(n_dof_); - joint_vel_state_.resize(n_dof_); - joint_eff_state_.resize(n_dof_); - joint_position_cmd_.resize(n_dof_); - last_joint_position_cmd_.resize(n_dof_); - joint_velocity_cmd_.resize(n_dof_); - joint_effort_cmd_.resize(n_dof_); - joint_pos_cmd_.resize(n_dof_); - joint_vel_cmd_.resize(n_dof_); - joint_eff_cmd_.resize(n_dof_); + this->dataPtr->parent_model_ = parent_model; + this->dataPtr->n_dof_ = transmissions.size(); + + this->dataPtr->joint_names_.resize(this->dataPtr->n_dof_); + this->dataPtr->joint_control_methods_.resize(this->dataPtr->n_dof_); + this->dataPtr->joint_position_.resize(this->dataPtr->n_dof_); + this->dataPtr->joint_velocity_.resize(this->dataPtr->n_dof_); + this->dataPtr->joint_effort_.resize(this->dataPtr->n_dof_); + this->dataPtr->joint_pos_state_.resize(this->dataPtr->n_dof_); + this->dataPtr->joint_vel_state_.resize(this->dataPtr->n_dof_); + this->dataPtr->joint_eff_state_.resize(this->dataPtr->n_dof_); + this->dataPtr->joint_position_cmd_.resize(this->dataPtr->n_dof_); + this->dataPtr->last_joint_position_cmd_.resize(this->dataPtr->n_dof_); + this->dataPtr->joint_velocity_cmd_.resize(this->dataPtr->n_dof_); + this->dataPtr->joint_effort_cmd_.resize(this->dataPtr->n_dof_); + this->dataPtr->joint_pos_cmd_.resize(this->dataPtr->n_dof_); + this->dataPtr->joint_vel_cmd_.resize(this->dataPtr->n_dof_); + this->dataPtr->joint_eff_cmd_.resize(this->dataPtr->n_dof_); gazebo::physics::PhysicsEnginePtr physics = gazebo::physics::get_world()->Physics(); std::string physics_type_ = physics->GetType(); if (physics_type_.empty()) { - RCLCPP_ERROR(nh_->get_logger(), "No physics engine configured in Gazebo."); + RCLCPP_ERROR(this->nh_->get_logger(), "No physics engine configured in Gazebo."); return false; } - for (unsigned int j = 0; j < this->n_dof_; j++) { + for (unsigned int j = 0; j < this->dataPtr->n_dof_; j++) { // // Perform some validation on the URDF joint and actuator spec // // Check that this transmission has one joint if (transmissions[j].joints.empty()) { RCLCPP_WARN_STREAM( - nh_->get_logger(), "Transmission " << transmissions[j].name << + this->nh_->get_logger(), "Transmission " << transmissions[j].name << " has no associated joints."); continue; } else if (transmissions[j].joints.size() > 1) { RCLCPP_WARN_STREAM( - nh_->get_logger(), "Transmission " << transmissions[j].name << + this->nh_->get_logger(), "Transmission " << transmissions[j].name << " has more than one joint. Currently the default robot hardware simulation " << " interface only supports one."); continue; } - std::string joint_name = joint_names_[j] = transmissions[j].joints[0].name; + std::string joint_name = this->dataPtr->joint_names_[j] = transmissions[j].joints[0].name; std::vector joint_interfaces = transmissions[j].joints[0].interfaces; if (joint_interfaces.empty() && @@ -85,14 +162,14 @@ bool GazeboSystem::initSim( // TODO(anyone): Deprecate HW interface specification in actuators in ROS 2 joint_interfaces = transmissions[j].actuators[0].interfaces; RCLCPP_WARN_STREAM( - nh_->get_logger(), "The element of transmission " << + this->nh_->get_logger(), "The element of transmission " << transmissions[j].name << " should be nested inside the element," << " not . The transmission will be properly loaded, but please update " << "your robot model to remain compatible with future versions of the plugin."); } if (joint_interfaces.empty()) { RCLCPP_WARN_STREAM( - nh_->get_logger(), "Joint " << transmissions[j].name << + this->nh_->get_logger(), "Joint " << transmissions[j].name << " of transmission " << transmissions[j].name << " does not specify any hardware interface. " << "Not adding it to the robot hardware simulation."); @@ -100,7 +177,7 @@ bool GazeboSystem::initSim( } else if (joint_interfaces.size() > 1) { // only a warning, allow joint to continue RCLCPP_WARN_STREAM( - nh_->get_logger(), "Joint " << transmissions[j].name << + this->nh_->get_logger(), "Joint " << transmissions[j].name << " of transmission " << transmissions[j].name << " specifies multiple hardware interfaces. " << "Currently the default robot hardware simulation interface only supports one." << @@ -109,17 +186,17 @@ bool GazeboSystem::initSim( std::string hardware_interface = joint_interfaces.front(); // Decide what kind of command interface this actuator/joint has if (hardware_interface == "hardware_interface/EffortJointInterface") { - joint_control_methods_[j] = EFFORT; + this->dataPtr->joint_control_methods_[j] = EFFORT; } else if (hardware_interface == "hardware_interface/PositionJointInterface") { - joint_control_methods_[j] = POSITION; + this->dataPtr->joint_control_methods_[j] = POSITION; } else if (hardware_interface == "hardware_interface/VelocityJointInterface") { - joint_control_methods_[j] = VELOCITY; + this->dataPtr->joint_control_methods_[j] = VELOCITY; } else { RCLCPP_WARN_STREAM( - nh_->get_logger(), "No matching joint interface '" << + this->nh_->get_logger(), "No matching joint interface '" << hardware_interface << "' for joint " << joint_name); RCLCPP_INFO( - nh_->get_logger(), + this->nh_->get_logger(), " Expecting one of 'hardware_interface/{EffortJointInterface |" " PositionJointInterface | VelocityJointInterface}'"); return false; @@ -133,60 +210,62 @@ bool GazeboSystem::initSim( gazebo::physics::JointPtr simjoint = parent_model->GetJoint(joint_name); if (!simjoint) { RCLCPP_WARN_STREAM( - nh_->get_logger(), "Skipping joint in the URDF named '" << joint_name << + this->nh_->get_logger(), "Skipping joint in the URDF named '" << joint_name << "' which is not in the gazebo model."); continue; } - sim_joints_.push_back(simjoint); + this->dataPtr->sim_joints_.push_back(simjoint); // Accept this joint and continue configuration RCLCPP_INFO_STREAM( - nh_->get_logger(), "Loading joint '" << joint_name << "' of type '" << + this->nh_->get_logger(), "Loading joint '" << joint_name << "' of type '" << hardware_interface << "'"); // register the state handles - joint_pos_state_[j] = std::make_shared( - joint_name, hardware_interface::HW_IF_POSITION, &joint_position_[j]); - joint_vel_state_[j] = std::make_shared( - joint_name, hardware_interface::HW_IF_VELOCITY, &joint_velocity_[j]); - joint_eff_state_[j] = std::make_shared( - joint_name, hardware_interface::HW_IF_EFFORT, &joint_effort_[j]); + this->dataPtr->joint_pos_state_[j] = std::make_shared( + joint_name, hardware_interface::HW_IF_POSITION, &this->dataPtr->joint_position_[j]); + this->dataPtr->joint_vel_state_[j] = std::make_shared( + joint_name, hardware_interface::HW_IF_VELOCITY, &this->dataPtr->joint_velocity_[j]); + this->dataPtr->joint_eff_state_[j] = std::make_shared( + joint_name, hardware_interface::HW_IF_EFFORT, &this->dataPtr->joint_effort_[j]); // register the state handles - joint_pos_cmd_[j] = std::make_shared( - joint_name, hardware_interface::HW_IF_POSITION, &joint_position_cmd_[j]); - joint_vel_cmd_[j] = std::make_shared( - joint_name, hardware_interface::HW_IF_VELOCITY, &joint_velocity_cmd_[j]); - joint_eff_cmd_[j] = std::make_shared( - joint_name, hardware_interface::HW_IF_EFFORT, &joint_effort_cmd_[j]); + this->dataPtr->joint_pos_cmd_[j] = std::make_shared( + joint_name, hardware_interface::HW_IF_POSITION, &this->dataPtr->joint_position_cmd_[j]); + this->dataPtr->joint_vel_cmd_[j] = std::make_shared( + joint_name, hardware_interface::HW_IF_VELOCITY, &this->dataPtr->joint_velocity_cmd_[j]); + this->dataPtr->joint_eff_cmd_[j] = std::make_shared( + joint_name, hardware_interface::HW_IF_EFFORT, &this->dataPtr->joint_effort_cmd_[j]); try { - nh_->declare_parameter(transmissions[j].joints[0].name + ".p"); - nh_->declare_parameter(transmissions[j].joints[0].name + ".i"); - nh_->declare_parameter(transmissions[j].joints[0].name + ".d"); - nh_->declare_parameter(transmissions[j].joints[0].name + ".i_clamp_max"); - nh_->declare_parameter(transmissions[j].joints[0].name + ".i_clamp_min"); - nh_->declare_parameter(transmissions[j].joints[0].name + ".antiwindup", false); - - if (nh_->get_parameter(transmissions[j].joints[0].name + ".p").get_type() == + this->nh_->declare_parameter(transmissions[j].joints[0].name + ".p"); + this->nh_->declare_parameter(transmissions[j].joints[0].name + ".i"); + this->nh_->declare_parameter(transmissions[j].joints[0].name + ".d"); + this->nh_->declare_parameter(transmissions[j].joints[0].name + ".i_clamp_max"); + this->nh_->declare_parameter(transmissions[j].joints[0].name + ".i_clamp_min"); + this->nh_->declare_parameter(transmissions[j].joints[0].name + ".antiwindup", false); + + if (this->nh_->get_parameter(transmissions[j].joints[0].name + ".p").get_type() == rclcpp::PARAMETER_DOUBLE && - nh_->get_parameter(transmissions[j].joints[0].name + ".i").get_type() == + this->nh_->get_parameter(transmissions[j].joints[0].name + ".i").get_type() == rclcpp::PARAMETER_DOUBLE && - nh_->get_parameter(transmissions[j].joints[0].name + ".d").get_type() == + this->nh_->get_parameter(transmissions[j].joints[0].name + ".d").get_type() == rclcpp::PARAMETER_DOUBLE) { - pid_controllers_.push_back( - control_toolbox::PidROS(nh_, transmissions[j].joints[0].name)); - if (pid_controllers_[j].initPid()) { - switch (joint_control_methods_[j]) { - case POSITION: joint_control_methods_[j] = POSITION_PID; + this->dataPtr->pid_controllers_.push_back( + control_toolbox::PidROS(this->nh_, transmissions[j].joints[0].name)); + if (this->dataPtr->pid_controllers_[j].initPid()) { + switch (this->dataPtr->joint_control_methods_[j]) { + case POSITION: + this->dataPtr->joint_control_methods_[j] = POSITION_PID; RCLCPP_INFO( - nh_->get_logger(), "joint %s is configured in POSITION_PID mode", + this->nh_->get_logger(), "joint %s is configured in POSITION_PID mode", transmissions[j].joints[0].name.c_str()); break; - case VELOCITY: joint_control_methods_[j] = VELOCITY_PID; + case VELOCITY: + this->dataPtr->joint_control_methods_[j] = VELOCITY_PID; RCLCPP_INFO( - nh_->get_logger(), "joint %s is configured in VELOCITY_PID mode", + this->nh_->get_logger(), "joint %s is configured in VELOCITY_PID mode", transmissions[j].joints[0].name.c_str()); break; case EFFORT: @@ -199,19 +278,19 @@ bool GazeboSystem::initSim( } } } catch (const std::exception & e) { - RCLCPP_ERROR(nh_->get_logger(), "%s", e.what()); + RCLCPP_ERROR(this->nh_->get_logger(), "%s", e.what()); } } // Initialize the emergency stop code. - this->e_stop_active_ = false; + this->dataPtr->e_stop_active_ = false; if (sdf->HasElement("e_stop_topic")) { const std::string e_stop_topic = sdf->GetElement("e_stop_topic")->Get(); rclcpp::QoS qos = rclcpp::SensorDataQoS().reliable(); - this->e_stop_sub_ = this->nh_->create_subscription( + this->dataPtr->e_stop_sub_ = this->nh_->create_subscription( e_stop_topic, qos, - std::bind(&GazeboSystem::eStopCB, this, std::placeholders::_1)); + std::bind(&GazeboSystemPrivate::eStopCB, this->dataPtr.get(), std::placeholders::_1)); } return true; @@ -231,20 +310,26 @@ GazeboSystem::export_state_interfaces() { std::vector state_interfaces; - for (unsigned int i = 0; i < this->joint_names_.size(); i++) { + for (unsigned int i = 0; i < this->dataPtr->joint_names_.size(); i++) { state_interfaces.emplace_back( hardware_interface::StateInterface( - this->joint_names_[i], hardware_interface::HW_IF_POSITION, &joint_position_[i])); + this->dataPtr->joint_names_[i], + hardware_interface::HW_IF_POSITION, + &this->dataPtr->joint_position_[i])); } - for (unsigned int i = 0; i < this->joint_names_.size(); i++) { + for (unsigned int i = 0; i < this->dataPtr->joint_names_.size(); i++) { state_interfaces.emplace_back( hardware_interface::StateInterface( - this->joint_names_[i], hardware_interface::HW_IF_VELOCITY, &joint_velocity_[i])); + this->dataPtr->joint_names_[i], + hardware_interface::HW_IF_VELOCITY, + &this->dataPtr->joint_velocity_[i])); } - for (unsigned int i = 0; i < this->joint_names_.size(); i++) { + for (unsigned int i = 0; i < this->dataPtr->joint_names_.size(); i++) { state_interfaces.emplace_back( hardware_interface::StateInterface( - this->joint_names_[i], hardware_interface::HW_IF_EFFORT, &joint_effort_[i])); + this->dataPtr->joint_names_[i], + hardware_interface::HW_IF_EFFORT, + &this->dataPtr->joint_effort_[i])); } return state_interfaces; } @@ -254,20 +339,26 @@ GazeboSystem::export_command_interfaces() { std::vector command_interfaces; - for (unsigned int i = 0; i < this->joint_names_.size(); i++) { + for (unsigned int i = 0; i < this->dataPtr->joint_names_.size(); i++) { command_interfaces.emplace_back( hardware_interface::CommandInterface( - this->joint_names_[i], hardware_interface::HW_IF_POSITION, &joint_position_cmd_[i])); + this->dataPtr->joint_names_[i], + hardware_interface::HW_IF_POSITION, + &this->dataPtr->joint_position_cmd_[i])); } - for (unsigned int i = 0; i < this->joint_names_.size(); i++) { + for (unsigned int i = 0; i < this->dataPtr->joint_names_.size(); i++) { command_interfaces.emplace_back( hardware_interface::CommandInterface( - this->joint_names_[i], hardware_interface::HW_IF_VELOCITY, &joint_velocity_cmd_[i])); + this->dataPtr->joint_names_[i], + hardware_interface::HW_IF_VELOCITY, + &this->dataPtr->joint_velocity_cmd_[i])); } - for (unsigned int i = 0; i < this->joint_names_.size(); i++) { + for (unsigned int i = 0; i < this->dataPtr->joint_names_.size(); i++) { command_interfaces.emplace_back( hardware_interface::CommandInterface( - this->joint_names_[i], hardware_interface::HW_IF_EFFORT, &joint_effort_cmd_[i])); + this->dataPtr->joint_names_[i], + hardware_interface::HW_IF_EFFORT, + &this->dataPtr->joint_effort_cmd_[i])); } return command_interfaces; } @@ -286,10 +377,10 @@ hardware_interface::return_type GazeboSystem::stop() hardware_interface::return_type GazeboSystem::read() { - for (unsigned int j = 0; j < this->joint_names_.size(); j++) { - joint_position_[j] = this->sim_joints_[j]->Position(0); - joint_velocity_[j] = this->sim_joints_[j]->GetVelocity(0); - joint_effort_[j] = this->sim_joints_[j]->GetForce(0u); + for (unsigned int j = 0; j < this->dataPtr->joint_names_.size(); j++) { + this->dataPtr->joint_position_[j] = this->dataPtr->sim_joints_[j]->Position(0); + this->dataPtr->joint_velocity_[j] = this->dataPtr->sim_joints_[j]->GetVelocity(0); + this->dataPtr->joint_effort_[j] = this->dataPtr->sim_joints_[j]->GetForce(0u); } return hardware_interface::return_type::OK; } @@ -297,26 +388,31 @@ hardware_interface::return_type GazeboSystem::read() hardware_interface::return_type GazeboSystem::write() { // Get the simulation time and period - gazebo::common::Time gz_time_now = this->parent_model_->GetWorld()->SimTime(); + gazebo::common::Time gz_time_now = this->dataPtr->parent_model_->GetWorld()->SimTime(); rclcpp::Time sim_time_ros(gz_time_now.sec, gz_time_now.nsec); - rclcpp::Duration sim_period = sim_time_ros - last_update_sim_time_ros_; + rclcpp::Duration sim_period = sim_time_ros - this->dataPtr->last_update_sim_time_ros_; - for (unsigned int j = 0; j < this->joint_names_.size(); j++) { - switch (joint_control_methods_[j]) { + for (unsigned int j = 0; j < this->dataPtr->joint_names_.size(); j++) { + switch (this->dataPtr->joint_control_methods_[j]) { case EFFORT: { - const double effort = e_stop_active_ ? 0 : joint_effort_cmd_[j]; - sim_joints_[j]->SetForce(0, effort); + const double effort = + this->dataPtr->e_stop_active_ ? 0 : this->dataPtr->joint_effort_cmd_[j]; + this->dataPtr->sim_joints_[j]->SetForce(0, effort); } break; case POSITION: - if (e_stop_active_) { + if (this->dataPtr->e_stop_active_) { // If the E-stop is active, joints controlled by position commands will maintain // their positions. - this->sim_joints_[j]->SetPosition(0, last_joint_position_cmd_[j], true); + this->dataPtr->sim_joints_[j]->SetPosition( + 0, this->dataPtr->last_joint_position_cmd_[j], + true); } else { - this->sim_joints_[j]->SetPosition(0, joint_position_cmd_[j], true); - last_joint_position_cmd_[j] = joint_position_cmd_[j]; + this->dataPtr->sim_joints_[j]->SetPosition( + 0, this->dataPtr->joint_position_cmd_[j], + true); + this->dataPtr->last_joint_position_cmd_[j] = this->dataPtr->joint_position_cmd_[j]; } break; case POSITION_PID: @@ -340,7 +436,7 @@ hardware_interface::return_type GazeboSystem::write() // default: // error = joint_position_cmd_[j] - joint_position_[j]; // } - error = joint_position_cmd_[j] - joint_position_[j]; + error = this->dataPtr->joint_position_cmd_[j] - this->dataPtr->joint_position_[j]; // TODO(ahcorde): Restore this when Jonit_limit interface is available // const double effort_limit = joint_effort_limits_[j]; @@ -348,44 +444,40 @@ hardware_interface::return_type GazeboSystem::write() // pid_controllers_[j].computeCommand(error, period), // -effort_limit, effort_limit); - const double effort = pid_controllers_[j].computeCommand(error, sim_period); + const double effort = + this->dataPtr->pid_controllers_[j].computeCommand(error, sim_period); - sim_joints_[j]->SetForce(0, effort); - sim_joints_[j]->SetParam("friction", 0, 0.0); + this->dataPtr->sim_joints_[j]->SetForce(0, effort); + this->dataPtr->sim_joints_[j]->SetParam("friction", 0, 0.0); } break; case VELOCITY: - sim_joints_[j]->SetVelocity(0, e_stop_active_ ? 0 : joint_velocity_cmd_[j]); + this->dataPtr->sim_joints_[j]->SetVelocity( + 0, + this->dataPtr->e_stop_active_ ? 0 : this->dataPtr->joint_velocity_cmd_[j]); break; case VELOCITY_PID: double error; - if (e_stop_active_) { - error = -joint_velocity_[j]; + if (this->dataPtr->e_stop_active_) { + error = -this->dataPtr->joint_velocity_[j]; } else { - error = joint_velocity_cmd_[j] - joint_velocity_[j]; + error = this->dataPtr->joint_velocity_cmd_[j] - this->dataPtr->joint_velocity_[j]; } // TODO(ahcorde): Restore this when Jonit_limit interface is available // const double effort_limit = joint_effort_limits_[j]; // const double effort = ignition::math::clamp( // pid_controllers_[j].computeCommand(error, period), // -effort_limit, effort_limit); - const double effort = pid_controllers_[j].computeCommand(error, sim_period); - sim_joints_[j]->SetForce(0, effort); + const double effort = this->dataPtr->pid_controllers_[j].computeCommand(error, sim_period); + this->dataPtr->sim_joints_[j]->SetForce(0, effort); break; } } - last_update_sim_time_ros_ = sim_time_ros; + this->dataPtr->last_update_sim_time_ros_ = sim_time_ros; return hardware_interface::return_type::OK; } - -// Emergency stop callback -void GazeboSystem::eStopCB(const std::shared_ptr e_stop_active) -{ - this->e_stop_active_ = e_stop_active->data; -} - } // namespace gazebo_ros2_control #include "pluginlib/class_list_macros.hpp" // NOLINT From 973e961a8691fce6336ca42f69b91ab7f4398248 Mon Sep 17 00:00:00 2001 From: ahcorde Date: Thu, 21 Jan 2021 19:10:08 +0100 Subject: [PATCH 11/33] updated Dockerfile Signed-off-by: ahcorde --- Docker/Dockerfile | 13 +------------ 1 file changed, 1 insertion(+), 12 deletions(-) diff --git a/Docker/Dockerfile b/Docker/Dockerfile index 33261f3b..74c4c424 100644 --- a/Docker/Dockerfile +++ b/Docker/Dockerfile @@ -9,25 +9,14 @@ RUN apt-get update && apt-get install -q -y --no-install-recommends \ dirmngr \ gnupg2 \ lsb-release \ - wget \ python3-colcon-ros \ && apt-get clean RUN mkdir -p /home/ros2_ws/src \ && cd /home/ros2_ws/src/ \ - # && wget https://raw.githubusercontent.com/ros-planning/moveit2/main/moveit2.repos \ - # && vcs import < moveit2.repos \ - && git clone https://github.com/ros-planning/moveit2 \ - && git clone https://github.com/ros-planning/moveit_msgs -b ros2 \ - && git clone https://github.com/ros-planning/moveit_resources -b ros2 \ - && git clone https://github.com/ros-planning/geometric_shapes -b ros2 \ - && git clone https://github.com/ros-planning/srdfdom -b ros2 \ - && git clone https://github.com/ros-planning/warehouse_ros -b ros2 \ - && git clone https://github.com/ros-planning/warehouse_ros_mongo -b ros2 \ - && git clone https://github.com/ros-simulation/gazebo_ros2_control -b ahcorde/update/foxy \ + && git clone https://github.com/ros-simulation/gazebo_ros2_control \ && git clone https://github.com/ros-controls/ros2_control \ && git clone https://github.com/ros-controls/ros2_controllers \ - && git clone https://github.com/ros-simulation/gazebo_ros_demos -b ahcorde/port/ros2 \ && rosdep update \ && rosdep install --from-paths ./ -i -y --rosdistro foxy \ --ignore-src From fe3a9019b6f658721ee839f235ee4552ead162aa Mon Sep 17 00:00:00 2001 From: ahcorde Date: Thu, 21 Jan 2021 19:17:05 +0100 Subject: [PATCH 12/33] changed log level Signed-off-by: ahcorde --- gazebo_ros2_control/src/gazebo_ros2_control_plugin.cpp | 10 +++++----- 1 file changed, 5 insertions(+), 5 deletions(-) diff --git a/gazebo_ros2_control/src/gazebo_ros2_control_plugin.cpp b/gazebo_ros2_control/src/gazebo_ros2_control_plugin.cpp index 7abac34d..42256ed5 100644 --- a/gazebo_ros2_control/src/gazebo_ros2_control_plugin.cpp +++ b/gazebo_ros2_control/src/gazebo_ros2_control_plugin.cpp @@ -290,7 +290,7 @@ void GazeboRosControlPlugin::Load(gazebo::physics::ModelPtr parent, sdf::Element impl_->thread_executor_spin_ = std::thread(spin); // Create the controller manager - RCLCPP_ERROR(impl_->model_nh_->get_logger(), "Loading controller_manager"); + RCLCPP_INFO(impl_->model_nh_->get_logger(), "Loading controller_manager"); impl_->controller_manager_.reset( new controller_manager::ControllerManager( std::move(resourceManager_), @@ -392,7 +392,7 @@ void GazeboRosControlPlugin::Load(gazebo::physics::ModelPtr parent, sdf::Element YAML::Node root_node = YAML::LoadFile(yaml_config_file); for (auto yaml : root_node) { auto nodename = yaml.first.as(); - RCLCPP_ERROR(impl_->model_nh_->get_logger(), "nodename: %s", nodename.c_str()); + RCLCPP_DEBUG(impl_->model_nh_->get_logger(), "nodename: %s", nodename.c_str()); if (nodename == prefix) { load_params_from_yaml_node(node, yaml.second, prefix); } @@ -454,7 +454,7 @@ void GazeboRosControlPlugin::Load(gazebo::physics::ModelPtr parent, sdf::Element &GazeboRosControlPrivate::Update, impl_.get())); - RCLCPP_ERROR(impl_->model_nh_->get_logger(), "Loaded gazebo_ros2_control."); + RCLCPP_INFO(impl_->model_nh_->get_logger(), "Loaded gazebo_ros2_control."); } // Called by the world update start event @@ -500,7 +500,7 @@ std::string GazeboRosControlPrivate::getURDF(std::string param_name) const robot_description_node_.c_str()); } - RCLCPP_ERROR( + RCLCPP_INFO( model_nh_->get_logger(), "connected to service!! %s", robot_description_node_.c_str()); // search and wait for robot_description on param server @@ -526,7 +526,7 @@ std::string GazeboRosControlPrivate::getURDF(std::string param_name) const } usleep(100000); } - RCLCPP_ERROR( + RCLCPP_INFO( model_nh_->get_logger(), "Recieved urdf from param server, parsing..."); return urdf_string; From 436c9f93a2c77c768e498c10d59650b749ba8623 Mon Sep 17 00:00:00 2001 From: ahcorde Date: Fri, 22 Jan 2021 08:09:59 +0100 Subject: [PATCH 13/33] Fixed gazebo_period units Signed-off-by: ahcorde --- gazebo_ros2_control/src/gazebo_ros2_control_plugin.cpp | 5 ++++- 1 file changed, 4 insertions(+), 1 deletion(-) diff --git a/gazebo_ros2_control/src/gazebo_ros2_control_plugin.cpp b/gazebo_ros2_control/src/gazebo_ros2_control_plugin.cpp index 42256ed5..7fe8a9e5 100644 --- a/gazebo_ros2_control/src/gazebo_ros2_control_plugin.cpp +++ b/gazebo_ros2_control/src/gazebo_ros2_control_plugin.cpp @@ -198,7 +198,10 @@ void GazeboRosControlPlugin::Load(gazebo::physics::ModelPtr parent, sdf::Element } // Get the Gazebo simulation period - rclcpp::Duration gazebo_period(impl_->parent_model_->GetWorld()->Physics()->GetMaxStepSize()); + rclcpp::Duration gazebo_period( + std::chrono::duration_cast( + std::chrono::duration( + impl_->parent_model_->GetWorld()->Physics()->GetMaxStepSize()))); // Decide the plugin control period if (sdf->HasElement("control_period")) { From 45aa6c96442a2da65ae25762b2a5d00cbc032f94 Mon Sep 17 00:00:00 2001 From: ahcorde Date: Fri, 22 Jan 2021 08:13:50 +0100 Subject: [PATCH 14/33] Updated CI Signed-off-by: ahcorde --- .github/workflows/ci.yaml | 4 ---- 1 file changed, 4 deletions(-) diff --git a/.github/workflows/ci.yaml b/.github/workflows/ci.yaml index feb46c4e..6275d50e 100644 --- a/.github/workflows/ci.yaml +++ b/.github/workflows/ci.yaml @@ -24,10 +24,7 @@ jobs: gnupg2 \ lsb-release \ python3-colcon-ros - apt-get upgrade -y cd /home/ros2_ws/src/ - git clone https://github.com/ros-controls/ros2_control - git clone https://github.com/ros-controls/ros2_controllers rosdep update rosdep install --from-paths ./ -i -y --rosdistro foxy \ --ignore-src @@ -36,7 +33,6 @@ jobs: run: | cd /home/ros2_ws/ . /opt/ros/foxy/local_setup.sh - export CMAKE_PREFIX_PATH=$AMENT_PREFIX_PATH:$CMAKE_PREFIX_PATH colcon build --packages-up-to gazebo_ros2_control_demos - name: Run tests id: test From 0479a9d7370b7231b5ff7ae0bf4c308ff4f76a6f Mon Sep 17 00:00:00 2001 From: ahcorde Date: Fri, 22 Jan 2021 08:42:00 +0100 Subject: [PATCH 15/33] updated CI Signed-off-by: ahcorde --- .github/workflows/ci.yaml | 2 ++ 1 file changed, 2 insertions(+) diff --git a/.github/workflows/ci.yaml b/.github/workflows/ci.yaml index 6275d50e..c3353eff 100644 --- a/.github/workflows/ci.yaml +++ b/.github/workflows/ci.yaml @@ -19,6 +19,8 @@ jobs: mkdir -p /home/ros2_ws/src cp -r gazebo_ros2_control /home/ros2_ws/src/ apt-get upgrade -q -y + # TODO(ahcorde): Remove this line when a new foxy released is launched (transmission_interface) + echo "deb http://packages.ros.org/ros2-testing/ubuntu focal main" > /etc/apt/sources.list.d/ros2-latest.list apt-get update && apt-get install -q -y --no-install-recommends \ dirmngr \ gnupg2 \ From 6047ae92cea95c2b73b225865e98ed304c0c8a05 Mon Sep 17 00:00:00 2001 From: ahcorde Date: Fri, 22 Jan 2021 08:50:56 +0100 Subject: [PATCH 16/33] updated CI Signed-off-by: ahcorde --- .github/workflows/ci.yaml | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/.github/workflows/ci.yaml b/.github/workflows/ci.yaml index c3353eff..49ca9cbb 100644 --- a/.github/workflows/ci.yaml +++ b/.github/workflows/ci.yaml @@ -18,9 +18,9 @@ jobs: cd .. mkdir -p /home/ros2_ws/src cp -r gazebo_ros2_control /home/ros2_ws/src/ - apt-get upgrade -q -y # TODO(ahcorde): Remove this line when a new foxy released is launched (transmission_interface) echo "deb http://packages.ros.org/ros2-testing/ubuntu focal main" > /etc/apt/sources.list.d/ros2-latest.list + apt-get upgrade -q -y apt-get update && apt-get install -q -y --no-install-recommends \ dirmngr \ gnupg2 \ From 30a6124aafe49e6622bde3154c7bc8de8a888a30 Mon Sep 17 00:00:00 2001 From: ahcorde Date: Fri, 22 Jan 2021 09:37:31 +0100 Subject: [PATCH 17/33] update CI Signed-off-by: ahcorde --- .github/workflows/ci.yaml | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/.github/workflows/ci.yaml b/.github/workflows/ci.yaml index 49ca9cbb..15e5a1ce 100644 --- a/.github/workflows/ci.yaml +++ b/.github/workflows/ci.yaml @@ -20,7 +20,7 @@ jobs: cp -r gazebo_ros2_control /home/ros2_ws/src/ # TODO(ahcorde): Remove this line when a new foxy released is launched (transmission_interface) echo "deb http://packages.ros.org/ros2-testing/ubuntu focal main" > /etc/apt/sources.list.d/ros2-latest.list - apt-get upgrade -q -y + apt-get update && apt-get upgrade -q -y apt-get update && apt-get install -q -y --no-install-recommends \ dirmngr \ gnupg2 \ From 240de77b86e2ba52a0743cca87fafc62c29820f3 Mon Sep 17 00:00:00 2001 From: ahcorde Date: Fri, 22 Jan 2021 09:42:59 +0100 Subject: [PATCH 18/33] updated Dockerfile Signed-off-by: ahcorde --- Docker/Dockerfile | 7 ++++--- 1 file changed, 4 insertions(+), 3 deletions(-) diff --git a/Docker/Dockerfile b/Docker/Dockerfile index 74c4c424..7ed945c1 100644 --- a/Docker/Dockerfile +++ b/Docker/Dockerfile @@ -1,5 +1,8 @@ FROM osrf/ros:foxy-desktop +# TODO(ahcorde): Remove this line when a new foxy released is launched (transmission_interface) +RUN echo "deb http://packages.ros.org/ros2-testing/ubuntu focal main" > /etc/apt/sources.list.d/ros2-latest.list + # Make sure everything is up to date before building from source RUN apt-get update \ && apt-get upgrade -y \ @@ -14,9 +17,7 @@ RUN apt-get update && apt-get install -q -y --no-install-recommends \ RUN mkdir -p /home/ros2_ws/src \ && cd /home/ros2_ws/src/ \ - && git clone https://github.com/ros-simulation/gazebo_ros2_control \ - && git clone https://github.com/ros-controls/ros2_control \ - && git clone https://github.com/ros-controls/ros2_controllers \ + && git clone https://github.com/ros-simulation/gazebo_ros2_control -b ahcorde/update/foxy \ && rosdep update \ && rosdep install --from-paths ./ -i -y --rosdistro foxy \ --ignore-src From f465d607ec8bbe6253a84fd33d626f7c6806cecb Mon Sep 17 00:00:00 2001 From: ahcorde Date: Tue, 26 Jan 2021 08:33:26 +0100 Subject: [PATCH 19/33] Added feedback Signed-off-by: ahcorde --- README.md | 2 +- gazebo_ros2_control/CMakeLists.txt | 3 ++ .../gazebo_ros2_control/gazebo_system.hpp | 1 - .../gazebo_system_interface.hpp | 2 -- .../src/gazebo_ros2_control_plugin.cpp | 35 +++++++------------ gazebo_ros2_control/src/gazebo_system.cpp | 6 ++-- 6 files changed, 21 insertions(+), 28 deletions(-) diff --git a/README.md b/README.md index aace1fc8..baa89336 100644 --- a/README.md +++ b/README.md @@ -99,7 +99,7 @@ The `gazebo_ros2_control` `` tag also has the following optional child e - ``: The period of the controller update (in seconds), defaults to Gazebo's period - ``: The location of the `robot_description` (URDF) on the parameter server, defaults to `robot_description` - ``: Name of the node where the `robot_param` is located, defauls to `robot_state_publisher` - - ``: The pluginlib name of a custom robot sim interface to be used, defaults to `gazebo_ros2_control/GazeboSystem` + - ``: The pluginlib name of a custom robot ros2_control system plugin to be used, defaults to `gazebo_ros2_control/GazeboSystem` - ``: YAML file with the configuration of the controllers - ``: Topic to publish the emergency stop diff --git a/gazebo_ros2_control/CMakeLists.txt b/gazebo_ros2_control/CMakeLists.txt index 30d8edce..754d7232 100644 --- a/gazebo_ros2_control/CMakeLists.txt +++ b/gazebo_ros2_control/CMakeLists.txt @@ -18,6 +18,9 @@ find_package(yaml_cpp_vendor REQUIRED) if(NOT CMAKE_CXX_STANDARD) set(CMAKE_CXX_STANDARD 14) endif() +if(CMAKE_COMPILER_IS_GNUCXX OR CMAKE_CXX_COMPILER_ID MATCHES "Clang") + add_compile_options(-Wall -Wextra -Wconversion -Wno-sign-conversion -Wpedantic -Wnon-virtual-dtor -Woverloaded-virtual) +endif() include_directories(include) link_directories( diff --git a/gazebo_ros2_control/include/gazebo_ros2_control/gazebo_system.hpp b/gazebo_ros2_control/include/gazebo_ros2_control/gazebo_system.hpp index 9363b0ea..1c50ea58 100644 --- a/gazebo_ros2_control/include/gazebo_ros2_control/gazebo_system.hpp +++ b/gazebo_ros2_control/include/gazebo_ros2_control/gazebo_system.hpp @@ -65,7 +65,6 @@ class GazeboSystem : public GazeboSystemInterface bool initSim( rclcpp::Node::SharedPtr & model_nh, gazebo::physics::ModelPtr parent_model, - const urdf::Model * const urdf_model, std::vector transmissions, sdf::ElementPtr sdf) override; diff --git a/gazebo_ros2_control/include/gazebo_ros2_control/gazebo_system_interface.hpp b/gazebo_ros2_control/include/gazebo_ros2_control/gazebo_system_interface.hpp index a0757280..8d3798cb 100644 --- a/gazebo_ros2_control/include/gazebo_ros2_control/gazebo_system_interface.hpp +++ b/gazebo_ros2_control/include/gazebo_ros2_control/gazebo_system_interface.hpp @@ -47,13 +47,11 @@ class GazeboSystemInterface /// \brief Initilize the system interface /// param[in] model_nh pointer to the ros2 node /// param[in] parent_model pointer to the model - /// param[in] urdf_model pointer to the URDF /// param[in] transmissions availables in the model /// param[in] sdf pointer to the SDF virtual bool initSim( rclcpp::Node::SharedPtr & model_nh, gazebo::physics::ModelPtr parent_model, - const urdf::Model * const urdf_model, std::vector transmissions, sdf::ElementPtr sdf) = 0; diff --git a/gazebo_ros2_control/src/gazebo_ros2_control_plugin.cpp b/gazebo_ros2_control/src/gazebo_ros2_control_plugin.cpp index 7fe8a9e5..a08269f5 100644 --- a/gazebo_ros2_control/src/gazebo_ros2_control_plugin.cpp +++ b/gazebo_ros2_control/src/gazebo_ros2_control_plugin.cpp @@ -60,6 +60,10 @@ namespace gazebo_ros2_control class GazeboRosControlPrivate { public: + GazeboRosControlPrivate() = default; + + virtual ~GazeboRosControlPrivate() = default; + // Called by the world update start event void Update(); @@ -186,7 +190,7 @@ void GazeboRosControlPlugin::Load(gazebo::physics::ModelPtr parent, sdf::Element impl_->robot_hw_sim_type_str_ = "gazebo_ros2_control/GazeboSystem"; RCLCPP_DEBUG_STREAM( impl_->model_nh_->get_logger(), - "Using default plugin for RobotHWSim (none specified in URDF/SDF)\"" << + "Using default plugin for ros2_control system plugin (none specified in URDF/SDF)\"" << impl_->robot_hw_sim_type_str_ << "\""); } @@ -243,7 +247,7 @@ void GazeboRosControlPlugin::Load(gazebo::physics::ModelPtr parent, sdf::Element return; } - std::unique_ptr resourceManager_ = + std::unique_ptr resource_manager_ = std::make_unique(); try { @@ -256,15 +260,10 @@ void GazeboRosControlPlugin::Load(gazebo::physics::ModelPtr parent, sdf::Element auto gazeboSystem = std::unique_ptr( impl_->robot_hw_sim_loader_->createUnmanagedInstance(impl_->robot_hw_sim_type_str_)); - urdf::Model urdf_model; - const urdf::Model * const urdf_model_ptr = - urdf_model.initString(urdf_string) ? &urdf_model : NULL; - rclcpp::Node::SharedPtr node_ros2 = std::dynamic_pointer_cast(impl_->model_nh_); if (!gazeboSystem->initSim( node_ros2, impl_->parent_model_, - urdf_model_ptr, impl_->transmissions_, sdf)) { @@ -273,14 +272,7 @@ void GazeboRosControlPlugin::Load(gazebo::physics::ModelPtr parent, sdf::Element return; } - std::vector loaned_state_ifs; - std::vector state_ifs; - state_ifs = gazeboSystem->export_state_interfaces(); - for (auto state : state_ifs) { - loaned_state_ifs.emplace_back(hardware_interface::LoanedStateInterface(state)); - } - - resourceManager_->import_component(std::move(gazeboSystem)); + resource_manager_->import_component(std::move(gazeboSystem)); impl_->executor_ = std::make_shared(); @@ -296,9 +288,10 @@ void GazeboRosControlPlugin::Load(gazebo::physics::ModelPtr parent, sdf::Element RCLCPP_INFO(impl_->model_nh_->get_logger(), "Loading controller_manager"); impl_->controller_manager_.reset( new controller_manager::ControllerManager( - std::move(resourceManager_), + std::move(resource_manager_), impl_->executor_, - "gazebo_controller_manager")); + "controller_manager")); + impl_->executor_->add_node(impl_->controller_manager_); // TODO(anyone): Coded example here. should disable when spawn functionality of // controller manager is up @@ -422,9 +415,6 @@ void GazeboRosControlPlugin::Load(gazebo::physics::ModelPtr parent, sdf::Element controller->get_node(), impl_->param_file_, controller_name); - if (controller_name == "joint_state_controller") { - controller->assign_interfaces({}, std::move(loaned_state_ifs)); - } controller->configure(); start_controllers.push_back(controller_name); } @@ -434,7 +424,8 @@ void GazeboRosControlPlugin::Load(gazebo::physics::ModelPtr parent, sdf::Element auto switch_future = std::async( std::launch::async, - &controller_manager::ControllerManager::switch_controller, impl_->controller_manager_, + &controller_manager::ControllerManager::switch_controller, + impl_->controller_manager_, start_controllers, stop_controllers, 2, true, rclcpp::Duration(0, 0)); // STRICT_: 2 while (std::future_status::timeout == switch_future.wait_for(std::chrono::milliseconds(100))) { @@ -536,5 +527,5 @@ std::string GazeboRosControlPrivate::getURDF(std::string param_name) const } // Register this plugin with the simulator -GZ_REGISTER_MODEL_PLUGIN(GazeboRosControlPlugin); +GZ_REGISTER_MODEL_PLUGIN(GazeboRosControlPlugin) } // namespace gazebo_ros2_control diff --git a/gazebo_ros2_control/src/gazebo_system.cpp b/gazebo_ros2_control/src/gazebo_system.cpp index a4566ade..7248036b 100644 --- a/gazebo_ros2_control/src/gazebo_system.cpp +++ b/gazebo_ros2_control/src/gazebo_system.cpp @@ -21,8 +21,11 @@ class gazebo_ros2_control::GazeboSystemPrivate { public: + GazeboSystemPrivate() = default; + + ~GazeboSystemPrivate() = default; /// \brief Degrees od freedom. - unsigned int n_dof_; + long unsigned int n_dof_; /// \brief e_stop_active_ is true if the emergency stop is active. bool e_stop_active_; @@ -100,7 +103,6 @@ namespace gazebo_ros2_control bool GazeboSystem::initSim( rclcpp::Node::SharedPtr & model_nh, gazebo::physics::ModelPtr parent_model, - const urdf::Model * const urdf_model, std::vector transmissions, sdf::ElementPtr sdf) { From 60e00224e53cbaf87e1f4cb6590d7f9653186060 Mon Sep 17 00:00:00 2001 From: ahcorde Date: Tue, 26 Jan 2021 08:44:12 +0100 Subject: [PATCH 20/33] make linters happy Signed-off-by: ahcorde --- gazebo_ros2_control/src/gazebo_system.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/gazebo_ros2_control/src/gazebo_system.cpp b/gazebo_ros2_control/src/gazebo_system.cpp index 7248036b..18450a21 100644 --- a/gazebo_ros2_control/src/gazebo_system.cpp +++ b/gazebo_ros2_control/src/gazebo_system.cpp @@ -25,7 +25,7 @@ class gazebo_ros2_control::GazeboSystemPrivate ~GazeboSystemPrivate() = default; /// \brief Degrees od freedom. - long unsigned int n_dof_; + size_t n_dof_; /// \brief e_stop_active_ is true if the emergency stop is active. bool e_stop_active_; From 07417e9854395eb77da548d2b899b582443a17be Mon Sep 17 00:00:00 2001 From: ahcorde Date: Thu, 28 Jan 2021 08:07:42 +0100 Subject: [PATCH 21/33] Removed PID controllers Signed-off-by: ahcorde --- README.md | 48 +-------- gazebo_ros2_control/CMakeLists.txt | 3 - .../gazebo_ros2_control/gazebo_system.hpp | 2 - .../gazebo_system_interface.hpp | 2 +- gazebo_ros2_control/package.xml | 1 - gazebo_ros2_control/src/gazebo_system.cpp | 100 +----------------- .../cart_example_position_pid.launch.py | 62 ----------- .../urdf/test_cart_position_pid.xacro.urdf | 78 -------------- ...d.gif => gazebo_ros2_control_position.gif} | Bin 9 files changed, 3 insertions(+), 293 deletions(-) delete mode 100644 gazebo_ros2_control_demos/launch/cart_example_position_pid.launch.py delete mode 100644 gazebo_ros2_control_demos/urdf/test_cart_position_pid.xacro.urdf rename img/{gazebo_ros2_control_position_pid.gif => gazebo_ros2_control_position.gif} (100%) diff --git a/README.md b/README.md index baa89336..0dca4b97 100644 --- a/README.md +++ b/README.md @@ -13,7 +13,7 @@ It is running Gazebo and some other ROS 2 nodes. ## Video + Pictures -![](img/gazebo_ros2_control_position_pid.gif) +![](img/gazebo_ros2_control_position.gif) ## Running @@ -170,33 +170,6 @@ cart_pole_controller: stopped_velocity_tolerance: 0.05 goal_time: 5 ``` - -#### Setting PID gains - -To set the PID gains for a specific joint you need to define them inside ``. -Using the generic way of defining parameters with `gazebo_ros`. The name of the parameter correspond to -the name of the joint followed by a dot and the name of the parameter: `p`, `i`, `d`, `i_clamp_max`, `i_clamp_min` and `antiwindup`. - -```xml - - - - /my_robot - 50.0 - 10.0 - 15.0 - 3.0 - -3.0 - false - e_stop_topic:=emergency_stop - - gazebo_ros2_control/GazeboSystem - $(find gazebo_ros2_control_demos)/config/cartpole_controller.yaml - ... - - -``` - #### Executing the examples There are some examples in the `gazebo_ros2_control_demos` package. These examples allow to launch a cart in a 30 meter rail. @@ -206,7 +179,6 @@ There are some examples in the `gazebo_ros2_control_demos` package. These exampl You can run some of the configuration running the following commands: ```bash -ros2 launch gazebo_ros2_control_demos cart_example_position_pid.launch.py ros2 launch gazebo_ros2_control_demos cart_example_position.launch.py ros2 launch gazebo_ros2_control_demos cart_example_velocity.launch.py ros2 launch gazebo_ros2_control_demos cart_example_effort.launch.py @@ -222,24 +194,6 @@ ros2 run gazebo_ros2_control_demos example_velocity ros2 run gazebo_ros2_control_demos example_effort ``` -To get or modify the values of the PID controller you can run the following commands: - -```bash -ros2 param get /gazebo_ros2_control slider_to_cart.p -ros2 param get /gazebo_ros2_control slider_to_cart.i -ros2 param get /gazebo_ros2_control slider_to_cart.d -ros2 param get /gazebo_ros2_control slider_to_cart.i_clamp_max -ros2 param get /gazebo_ros2_control slider_to_cart.i_clamp_min -``` - -```bash -ros2 param set /gazebo_ros2_control slider_to_cart.p 50.0 -ros2 param set /gazebo_ros2_control slider_to_cart.i 10.0 -ros2 param set /gazebo_ros2_control slider_to_cart.d 15.0 -ros2 param set /gazebo_ros2_control slider_to_cart.i_clamp_max 3.0 -ros2 param set /gazebo_ros2_control slider_to_cart.i_clamp_min -3.0 -``` - #### Gazebo + Moveit2 + ROS 2 This example works with [ROS 2 Foxy](https://index.ros.org/doc/ros2/Installation/Foxy/). diff --git a/gazebo_ros2_control/CMakeLists.txt b/gazebo_ros2_control/CMakeLists.txt index 754d7232..05e019d0 100644 --- a/gazebo_ros2_control/CMakeLists.txt +++ b/gazebo_ros2_control/CMakeLists.txt @@ -3,7 +3,6 @@ project(gazebo_ros2_control) find_package(ament_cmake REQUIRED) find_package(angles REQUIRED) -find_package(control_toolbox REQUIRED) find_package(controller_manager REQUIRED) find_package(gazebo_dev REQUIRED) find_package(gazebo_ros REQUIRED) @@ -34,7 +33,6 @@ add_library(${PROJECT_NAME} SHARED ament_target_dependencies(${PROJECT_NAME} angles controller_manager - control_toolbox gazebo_dev gazebo_ros hardware_interface @@ -52,7 +50,6 @@ ament_target_dependencies(gazebo_hardware_plugins hardware_interface gazebo_dev transmission_interface - control_toolbox angles ) diff --git a/gazebo_ros2_control/include/gazebo_ros2_control/gazebo_system.hpp b/gazebo_ros2_control/include/gazebo_ros2_control/gazebo_system.hpp index 1c50ea58..a6b9e811 100644 --- a/gazebo_ros2_control/include/gazebo_ros2_control/gazebo_system.hpp +++ b/gazebo_ros2_control/include/gazebo_ros2_control/gazebo_system.hpp @@ -22,8 +22,6 @@ #include "angles/angles.h" -#include "control_toolbox/pid_ros.hpp" - #include "gazebo_ros2_control/gazebo_system_interface.hpp" #include "std_msgs/msg/bool.hpp" diff --git a/gazebo_ros2_control/include/gazebo_ros2_control/gazebo_system_interface.hpp b/gazebo_ros2_control/include/gazebo_ros2_control/gazebo_system_interface.hpp index 8d3798cb..a05a0022 100644 --- a/gazebo_ros2_control/include/gazebo_ros2_control/gazebo_system_interface.hpp +++ b/gazebo_ros2_control/include/gazebo_ros2_control/gazebo_system_interface.hpp @@ -56,7 +56,7 @@ class GazeboSystemInterface sdf::ElementPtr sdf) = 0; // Methods used to control a joint. - enum ControlMethod {EFFORT, POSITION, POSITION_PID, VELOCITY, VELOCITY_PID}; + enum ControlMethod {EFFORT, POSITION, VELOCITY}; protected: rclcpp::Node::SharedPtr nh_; diff --git a/gazebo_ros2_control/package.xml b/gazebo_ros2_control/package.xml index e674eb37..7bd3b3e5 100644 --- a/gazebo_ros2_control/package.xml +++ b/gazebo_ros2_control/package.xml @@ -18,7 +18,6 @@ ament_cmake angles - control_toolbox gazebo_dev gazebo_ros controller_manager diff --git a/gazebo_ros2_control/src/gazebo_system.cpp b/gazebo_ros2_control/src/gazebo_system.cpp index 18450a21..9352d9a7 100644 --- a/gazebo_ros2_control/src/gazebo_system.cpp +++ b/gazebo_ros2_control/src/gazebo_system.cpp @@ -87,9 +87,6 @@ class gazebo_ros2_control::GazeboSystemPrivate /// \brief The effort command interfaces of the joints std::vector> joint_eff_cmd_; - /// \brief vector with the PID of each joint. - std::vector pid_controllers_; - /// \brief callback to get the e_stop signal from the ROS 2 topic void eStopCB(const std::shared_ptr e_stop_active) { @@ -238,50 +235,6 @@ bool GazeboSystem::initSim( joint_name, hardware_interface::HW_IF_VELOCITY, &this->dataPtr->joint_velocity_cmd_[j]); this->dataPtr->joint_eff_cmd_[j] = std::make_shared( joint_name, hardware_interface::HW_IF_EFFORT, &this->dataPtr->joint_effort_cmd_[j]); - - try { - this->nh_->declare_parameter(transmissions[j].joints[0].name + ".p"); - this->nh_->declare_parameter(transmissions[j].joints[0].name + ".i"); - this->nh_->declare_parameter(transmissions[j].joints[0].name + ".d"); - this->nh_->declare_parameter(transmissions[j].joints[0].name + ".i_clamp_max"); - this->nh_->declare_parameter(transmissions[j].joints[0].name + ".i_clamp_min"); - this->nh_->declare_parameter(transmissions[j].joints[0].name + ".antiwindup", false); - - if (this->nh_->get_parameter(transmissions[j].joints[0].name + ".p").get_type() == - rclcpp::PARAMETER_DOUBLE && - this->nh_->get_parameter(transmissions[j].joints[0].name + ".i").get_type() == - rclcpp::PARAMETER_DOUBLE && - this->nh_->get_parameter(transmissions[j].joints[0].name + ".d").get_type() == - rclcpp::PARAMETER_DOUBLE) - { - this->dataPtr->pid_controllers_.push_back( - control_toolbox::PidROS(this->nh_, transmissions[j].joints[0].name)); - if (this->dataPtr->pid_controllers_[j].initPid()) { - switch (this->dataPtr->joint_control_methods_[j]) { - case POSITION: - this->dataPtr->joint_control_methods_[j] = POSITION_PID; - RCLCPP_INFO( - this->nh_->get_logger(), "joint %s is configured in POSITION_PID mode", - transmissions[j].joints[0].name.c_str()); - break; - case VELOCITY: - this->dataPtr->joint_control_methods_[j] = VELOCITY_PID; - RCLCPP_INFO( - this->nh_->get_logger(), "joint %s is configured in VELOCITY_PID mode", - transmissions[j].joints[0].name.c_str()); - break; - case EFFORT: - {} // fallthrough - case POSITION_PID: - {} // fallthrough - case VELOCITY_PID: - {} // fallthrough - } - } - } - } catch (const std::exception & e) { - RCLCPP_ERROR(this->nh_->get_logger(), "%s", e.what()); - } } // Initialize the emergency stop code. @@ -417,62 +370,11 @@ hardware_interface::return_type GazeboSystem::write() this->dataPtr->last_joint_position_cmd_[j] = this->dataPtr->joint_position_cmd_[j]; } break; - case POSITION_PID: - { - double error; - // TODO(ahcorde): Restore this part - // switch (joint_types_[j]) { - // case urdf::Joint::REVOLUTE: - // // angles::shortest_angular_distance_with_limits( - // // joint_pos_state_[j].get_value(), - // // joint_pos_cmdh_[j].get_value(), - // // joint_lower_limits_[j], - // // joint_upper_limits_[j], - // // error); - // break; - // case urdf::Joint::CONTINUOUS: - // error = angles::shortest_angular_distance( - // joint_position_[j], - // joint_position_cmd_[j]); - // break; - // default: - // error = joint_position_cmd_[j] - joint_position_[j]; - // } - error = this->dataPtr->joint_position_cmd_[j] - this->dataPtr->joint_position_[j]; - - // TODO(ahcorde): Restore this when Jonit_limit interface is available - // const double effort_limit = joint_effort_limits_[j]; - // const double effort = ignition::math::clamp( - // pid_controllers_[j].computeCommand(error, period), - // -effort_limit, effort_limit); - - const double effort = - this->dataPtr->pid_controllers_[j].computeCommand(error, sim_period); - - this->dataPtr->sim_joints_[j]->SetForce(0, effort); - this->dataPtr->sim_joints_[j]->SetParam("friction", 0, 0.0); - } - break; - case VELOCITY: + case VELOCITY: this->dataPtr->sim_joints_[j]->SetVelocity( 0, this->dataPtr->e_stop_active_ ? 0 : this->dataPtr->joint_velocity_cmd_[j]); break; - case VELOCITY_PID: - double error; - if (this->dataPtr->e_stop_active_) { - error = -this->dataPtr->joint_velocity_[j]; - } else { - error = this->dataPtr->joint_velocity_cmd_[j] - this->dataPtr->joint_velocity_[j]; - } - // TODO(ahcorde): Restore this when Jonit_limit interface is available - // const double effort_limit = joint_effort_limits_[j]; - // const double effort = ignition::math::clamp( - // pid_controllers_[j].computeCommand(error, period), - // -effort_limit, effort_limit); - const double effort = this->dataPtr->pid_controllers_[j].computeCommand(error, sim_period); - this->dataPtr->sim_joints_[j]->SetForce(0, effort); - break; } } diff --git a/gazebo_ros2_control_demos/launch/cart_example_position_pid.launch.py b/gazebo_ros2_control_demos/launch/cart_example_position_pid.launch.py deleted file mode 100644 index df94e05d..00000000 --- a/gazebo_ros2_control_demos/launch/cart_example_position_pid.launch.py +++ /dev/null @@ -1,62 +0,0 @@ -# Copyright 2020 Open Source Robotics Foundation, Inc. -# -# Licensed under the Apache License, Version 2.0 (the "License"); -# you may not use this file except in compliance with the License. -# You may obtain a copy of the License at -# -# http://www.apache.org/licenses/LICENSE-2.0 -# -# Unless required by applicable law or agreed to in writing, software -# distributed under the License is distributed on an "AS IS" BASIS, -# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. -# See the License for the specific language governing permissions and -# limitations under the License. - -import os - -from ament_index_python.packages import get_package_share_directory - - -from launch import LaunchDescription -from launch.actions import IncludeLaunchDescription -from launch.launch_description_sources import PythonLaunchDescriptionSource - -from launch_ros.actions import Node - -import xacro - - -def generate_launch_description(): - gazebo = IncludeLaunchDescription( - PythonLaunchDescriptionSource([os.path.join( - get_package_share_directory('gazebo_ros'), 'launch'), '/gazebo.launch.py']), - ) - - gazebo_ros2_control_demos_path = os.path.join( - get_package_share_directory('gazebo_ros2_control_demos')) - - xacro_file = os.path.join(gazebo_ros2_control_demos_path, - 'urdf', - 'test_cart_position_pid.xacro.urdf') - - doc = xacro.parse(open(xacro_file)) - xacro.process_doc(doc) - params = {'robot_description': doc.toxml()} - - node_robot_state_publisher = Node( - package='robot_state_publisher', - executable='robot_state_publisher', - output='screen', - parameters=[params] - ) - - spawn_entity = Node(package='gazebo_ros', executable='spawn_entity.py', - arguments=['-topic', 'robot_description', - '-entity', 'cartpole'], - output='screen') - - return LaunchDescription([ - gazebo, - node_robot_state_publisher, - spawn_entity, - ]) diff --git a/gazebo_ros2_control_demos/urdf/test_cart_position_pid.xacro.urdf b/gazebo_ros2_control_demos/urdf/test_cart_position_pid.xacro.urdf deleted file mode 100644 index 9de83e42..00000000 --- a/gazebo_ros2_control_demos/urdf/test_cart_position_pid.xacro.urdf +++ /dev/null @@ -1,78 +0,0 @@ - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - transmission_interface/SimpleTransmission - - hardware_interface/PositionJointInterface - - - hardware_interface/PositionJointInterface - 1 - - - - - - / - 50.0 - 10.0 - 15.0 - 3.0 - -3.0 - false - - gazebo_ros2_control/GazeboSystem - $(find gazebo_ros2_control_demos)/config/cartpole_controller.yaml - 0.01 - /cart_pole/estop - - - diff --git a/img/gazebo_ros2_control_position_pid.gif b/img/gazebo_ros2_control_position.gif similarity index 100% rename from img/gazebo_ros2_control_position_pid.gif rename to img/gazebo_ros2_control_position.gif From 31399db121989415de4968fef434b63f83f5b746 Mon Sep 17 00:00:00 2001 From: ahcorde Date: Thu, 28 Jan 2021 08:15:59 +0100 Subject: [PATCH 22/33] make linters happy Signed-off-by: ahcorde --- gazebo_ros2_control/src/gazebo_system.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/gazebo_ros2_control/src/gazebo_system.cpp b/gazebo_ros2_control/src/gazebo_system.cpp index 9352d9a7..3559d85b 100644 --- a/gazebo_ros2_control/src/gazebo_system.cpp +++ b/gazebo_ros2_control/src/gazebo_system.cpp @@ -370,7 +370,7 @@ hardware_interface::return_type GazeboSystem::write() this->dataPtr->last_joint_position_cmd_[j] = this->dataPtr->joint_position_cmd_[j]; } break; - case VELOCITY: + case VELOCITY: this->dataPtr->sim_joints_[j]->SetVelocity( 0, this->dataPtr->e_stop_active_ ? 0 : this->dataPtr->joint_velocity_cmd_[j]); From 9e5d6856f003563d43ad48f4a2e40ae78442a32b Mon Sep 17 00:00:00 2001 From: ahcorde Date: Mon, 1 Feb 2021 09:42:52 +0100 Subject: [PATCH 23/33] Removed transmission interface Signed-off-by: ahcorde --- .github/workflows/ci.yaml | 2 - Docker/Dockerfile | 3 - README.md | 48 ++-- gazebo_ros2_control/CMakeLists.txt | 3 - .../gazebo_ros2_control_plugin.hpp | 2 - .../gazebo_ros2_control/gazebo_system.hpp | 2 +- .../gazebo_system_interface.hpp | 34 ++- gazebo_ros2_control/package.xml | 1 - .../src/gazebo_ros2_control_plugin.cpp | 23 +- gazebo_ros2_control/src/gazebo_system.cpp | 232 +++++++++--------- .../config/cartpole_controller.yaml | 6 - .../config/cartpole_controller_effort.yaml | 6 - .../config/cartpole_controller_velocity.yaml | 6 - .../urdf/test_cart_effort.xacro.urdf | 23 +- .../urdf/test_cart_position.xacro.urdf | 23 +- .../urdf/test_cart_velocity.xacro.urdf | 21 +- 16 files changed, 221 insertions(+), 214 deletions(-) diff --git a/.github/workflows/ci.yaml b/.github/workflows/ci.yaml index 15e5a1ce..0317fcab 100644 --- a/.github/workflows/ci.yaml +++ b/.github/workflows/ci.yaml @@ -18,8 +18,6 @@ jobs: cd .. mkdir -p /home/ros2_ws/src cp -r gazebo_ros2_control /home/ros2_ws/src/ - # TODO(ahcorde): Remove this line when a new foxy released is launched (transmission_interface) - echo "deb http://packages.ros.org/ros2-testing/ubuntu focal main" > /etc/apt/sources.list.d/ros2-latest.list apt-get update && apt-get upgrade -q -y apt-get update && apt-get install -q -y --no-install-recommends \ dirmngr \ diff --git a/Docker/Dockerfile b/Docker/Dockerfile index 7ed945c1..7b75a59f 100644 --- a/Docker/Dockerfile +++ b/Docker/Dockerfile @@ -1,8 +1,5 @@ FROM osrf/ros:foxy-desktop -# TODO(ahcorde): Remove this line when a new foxy released is launched (transmission_interface) -RUN echo "deb http://packages.ros.org/ros2-testing/ubuntu focal main" > /etc/apt/sources.list.d/ros2-latest.list - # Make sure everything is up to date before building from source RUN apt-get update \ && apt-get upgrade -y \ diff --git a/README.md b/README.md index 0dca4b97..592e372c 100644 --- a/README.md +++ b/README.md @@ -1,6 +1,5 @@ # gazebo_ros2_control - This is a ROS 2 package for integrating the `ros2_control` controller architecture with the [Gazebo](http://gazebosim.org/) simulator. This package provides a Gazebo plugin which instantiates a `ros2_control` controller manager and connects it to a Gazebo model. @@ -64,14 +63,28 @@ ros2 run gazebo_ros2_control_demos example_position ## Add transmission elements to a URDF To use `ros2_control` with your robot, you need to add some additional elements to your URDF. -The `` element is used to link actuators to joints, see the `` spec for exact XML format. +You should include the tag `` to access and control the robot interfaces. We should +include -For the purposes of `gazebo_ros2_control` in its current implementation, the only important information -in these transmission tags are: + - a specific `` for our robot + - `` tag including the robot controllers: commands and states. - - `` the name must correspond to a joint else where in your URDF - - `` the type of transmission. Currently only `transmission_interface/SimpleTransmission` is implemented. - - `` within the `` and `` tags, this tells the `gazebo_ros2_control` plugin what hardware interface to load (position, velocity or effort interfaces). +```xml + + + gazebo_ros2_control/GazeboSystem + + + + -1000 + 1000 + + + + + + +``` ## Add the gazebo_ros2_control plugin @@ -84,7 +97,6 @@ robot hardware interfaces between `ros2_control` and Gazebo. ```xml - gazebo_ros2_control/GazeboSystem robot_description robot_state_publisher $(find gazebo_ros2_control_demos)/config/cartpole_controller.yaml @@ -99,13 +111,12 @@ The `gazebo_ros2_control` `` tag also has the following optional child e - ``: The period of the controller update (in seconds), defaults to Gazebo's period - ``: The location of the `robot_description` (URDF) on the parameter server, defaults to `robot_description` - ``: Name of the node where the `robot_param` is located, defauls to `robot_state_publisher` - - ``: The pluginlib name of a custom robot ros2_control system plugin to be used, defaults to `gazebo_ros2_control/GazeboSystem` - ``: YAML file with the configuration of the controllers - ``: Topic to publish the emergency stop #### Default gazebo_ros2_control Behavior -By default, without a `` tag, `gazebo_ros2_control` will attempt to get all of the information it needs to interface with a ros2_control-based controller out of the URDF. This is sufficient for most cases, and good for at least getting started. +By default, without a `` tag, `gazebo_ros2_control` will attempt to get all of the information it needs to interface with a ros2_control-based controller out of the URDF. This is sufficient for most cases, and good for at least getting started. The default behavior provides the following ros2_control interfaces: @@ -121,13 +132,17 @@ These plugins must inherit `gazebo_ros2_control::GazeboSystemInterface` which im `hardware_interface::SystemInterface`. SystemInterface provides API-level access to read and command joint properties. The respective GazeboSystemInterface sub-class is specified in a URDF model and is loaded when the -robot model is loaded. For example, the following XML will load the default plugin -(same behavior as when using no `` tag): - +robot model is loaded. For example, the following XML will load the default plugin: ```xml + + + gazebo_ros2_control/GazeboSystem + + ... + - gazebo_ros2_control/GazeboSystem + ... ``` @@ -164,11 +179,6 @@ cart_pole_controller: - slider_to_cart write_op_modes: - slider_to_cart - state_publish_rate: 25 - action_monitor_rate: 20 - constraints: - stopped_velocity_tolerance: 0.05 - goal_time: 5 ``` #### Executing the examples diff --git a/gazebo_ros2_control/CMakeLists.txt b/gazebo_ros2_control/CMakeLists.txt index 05e019d0..91c4bddc 100644 --- a/gazebo_ros2_control/CMakeLists.txt +++ b/gazebo_ros2_control/CMakeLists.txt @@ -9,7 +9,6 @@ find_package(gazebo_ros REQUIRED) find_package(hardware_interface REQUIRED) find_package(pluginlib REQUIRED) find_package(rclcpp REQUIRED) -find_package(transmission_interface REQUIRED) find_package(urdf REQUIRED) find_package(yaml_cpp_vendor REQUIRED) @@ -38,7 +37,6 @@ ament_target_dependencies(${PROJECT_NAME} hardware_interface pluginlib rclcpp - transmission_interface urdf yaml_cpp_vendor ) @@ -49,7 +47,6 @@ add_library(gazebo_hardware_plugins SHARED ament_target_dependencies(gazebo_hardware_plugins hardware_interface gazebo_dev - transmission_interface angles ) diff --git a/gazebo_ros2_control/include/gazebo_ros2_control/gazebo_ros2_control_plugin.hpp b/gazebo_ros2_control/include/gazebo_ros2_control/gazebo_ros2_control_plugin.hpp index 31c1db79..5d0b9499 100644 --- a/gazebo_ros2_control/include/gazebo_ros2_control/gazebo_ros2_control_plugin.hpp +++ b/gazebo_ros2_control/include/gazebo_ros2_control/gazebo_ros2_control_plugin.hpp @@ -44,8 +44,6 @@ #include "gazebo/common/common.hh" #include "gazebo/physics/Model.hh" -#include "transmission_interface/transmission_parser.hpp" - namespace gazebo_ros2_control { class GazeboRosControlPrivate; diff --git a/gazebo_ros2_control/include/gazebo_ros2_control/gazebo_system.hpp b/gazebo_ros2_control/include/gazebo_ros2_control/gazebo_system.hpp index a6b9e811..8540fc0c 100644 --- a/gazebo_ros2_control/include/gazebo_ros2_control/gazebo_system.hpp +++ b/gazebo_ros2_control/include/gazebo_ros2_control/gazebo_system.hpp @@ -63,7 +63,7 @@ class GazeboSystem : public GazeboSystemInterface bool initSim( rclcpp::Node::SharedPtr & model_nh, gazebo::physics::ModelPtr parent_model, - std::vector transmissions, + const std::vector & control_hardware, sdf::ElementPtr sdf) override; private: diff --git a/gazebo_ros2_control/include/gazebo_ros2_control/gazebo_system_interface.hpp b/gazebo_ros2_control/include/gazebo_ros2_control/gazebo_system_interface.hpp index a05a0022..d2aef52e 100644 --- a/gazebo_ros2_control/include/gazebo_ros2_control/gazebo_system_interface.hpp +++ b/gazebo_ros2_control/include/gazebo_ros2_control/gazebo_system_interface.hpp @@ -30,16 +30,32 @@ #include "rclcpp/rclcpp.hpp" -#include "transmission_interface/transmission_info.hpp" - // URDF #include "urdf/model.h" namespace gazebo_ros2_control { -// SystemInterface provides API-level access to read and command joint properties. +template::type> +class SafeEnum +{ +public: + SafeEnum() : mFlags(0) {} + SafeEnum( ENUM singleFlag ) : mFlags(singleFlag) {} + SafeEnum( const SafeEnum& original ) : mFlags(original.mFlags) {} + + SafeEnum& operator |=( ENUM addValue ) { mFlags |= addValue; return *this; } + SafeEnum operator |( ENUM addValue ) { SafeEnum result(*this); result |= addValue; return result; } + SafeEnum& operator &=( ENUM maskValue ) { mFlags &= maskValue; return *this; } + SafeEnum operator &( ENUM maskValue ) { SafeEnum result(*this); result &= maskValue; return result; } + SafeEnum operator ~() { SafeEnum result(*this); result.mFlags = ~result.mFlags; return result; } + explicit operator bool() { return mFlags != 0; } +protected: + UNDERLYING mFlags; +}; + +// SystemInterface provides API-level access to read and command joint properties. class GazeboSystemInterface : public hardware_interface::BaseInterface { @@ -52,11 +68,19 @@ class GazeboSystemInterface virtual bool initSim( rclcpp::Node::SharedPtr & model_nh, gazebo::physics::ModelPtr parent_model, - std::vector transmissions, + const std::vector & control_hardware, sdf::ElementPtr sdf) = 0; // Methods used to control a joint. - enum ControlMethod {EFFORT, POSITION, VELOCITY}; + enum ControlMethod_ + { + NONE = 0, + POSITION = (1 << 0), + VELOCITY = (1 << 1), + EFFORT = (1 << 2), + }; + + typedef SafeEnum ControlMethod; protected: rclcpp::Node::SharedPtr nh_; diff --git a/gazebo_ros2_control/package.xml b/gazebo_ros2_control/package.xml index 7bd3b3e5..16dd00a5 100644 --- a/gazebo_ros2_control/package.xml +++ b/gazebo_ros2_control/package.xml @@ -25,7 +25,6 @@ pluginlib rclcpp std_msgs - transmission_interface urdf yaml_cpp_vendor diff --git a/gazebo_ros2_control/src/gazebo_ros2_control_plugin.cpp b/gazebo_ros2_control/src/gazebo_ros2_control_plugin.cpp index a08269f5..d1ebc762 100644 --- a/gazebo_ros2_control/src/gazebo_ros2_control_plugin.cpp +++ b/gazebo_ros2_control/src/gazebo_ros2_control_plugin.cpp @@ -47,6 +47,7 @@ #include "rclcpp/rclcpp.hpp" #include "hardware_interface/resource_manager.hpp" +#include "hardware_interface/component_parser.hpp" #include "hardware_interface/types/hardware_interface_type_values.hpp" #include "urdf/model.h" @@ -95,9 +96,6 @@ class GazeboRosControlPrivate // Name of the file with the controllers configuration std::string param_file_; - // Transmissions in this plugin's scope - std::vector transmissions_; - // Robot simulator interface std::string robot_hw_sim_type_str_; @@ -183,17 +181,6 @@ void GazeboRosControlPlugin::Load(gazebo::physics::ModelPtr parent, sdf::Element impl_->robot_description_node_ = "robot_state_publisher"; // default } - // Get the robot simulation interface type - if (sdf->HasElement("robot_sim_type")) { - impl_->robot_hw_sim_type_str_ = sdf->Get("robot_sim_type"); - } else { - impl_->robot_hw_sim_type_str_ = "gazebo_ros2_control/GazeboSystem"; - RCLCPP_DEBUG_STREAM( - impl_->model_nh_->get_logger(), - "Using default plugin for ros2_control system plugin (none specified in URDF/SDF)\"" << - impl_->robot_hw_sim_type_str_ << "\""); - } - if (sdf->HasElement("parameters")) { impl_->param_file_ = sdf->GetElement("parameters")->Get(); } else { @@ -237,9 +224,12 @@ void GazeboRosControlPlugin::Load(gazebo::physics::ModelPtr parent, sdf::Element // setup actuators and mechanism control node. // This call will block if ROS is not properly initialized. std::string urdf_string; + std::vector control_hardware; try { urdf_string = impl_->getURDF(impl_->robot_description_); - impl_->transmissions_ = transmission_interface::parse_transmissions_from_urdf(urdf_string); + control_hardware = hardware_interface::parse_control_resources_from_urdf(urdf_string); + const auto hardware_info = control_hardware.front(); + impl_->robot_hw_sim_type_str_ = hardware_info.hardware_class_type; } catch (const std::runtime_error & ex) { RCLCPP_ERROR_STREAM( impl_->model_nh_->get_logger(), @@ -251,7 +241,6 @@ void GazeboRosControlPlugin::Load(gazebo::physics::ModelPtr parent, sdf::Element std::make_unique(); try { - // We cannot use (for now) the tag in the URDF, we need to call it manually. impl_->robot_hw_sim_loader_.reset( new pluginlib::ClassLoader( "gazebo_ros2_control", @@ -264,7 +253,7 @@ void GazeboRosControlPlugin::Load(gazebo::physics::ModelPtr parent, sdf::Element if (!gazeboSystem->initSim( node_ros2, impl_->parent_model_, - impl_->transmissions_, + control_hardware, sdf)) { RCLCPP_FATAL( diff --git a/gazebo_ros2_control/src/gazebo_system.cpp b/gazebo_ros2_control/src/gazebo_system.cpp index 3559d85b..b922e351 100644 --- a/gazebo_ros2_control/src/gazebo_system.cpp +++ b/gazebo_ros2_control/src/gazebo_system.cpp @@ -100,7 +100,7 @@ namespace gazebo_ros2_control bool GazeboSystem::initSim( rclcpp::Node::SharedPtr & model_nh, gazebo::physics::ModelPtr parent_model, - std::vector transmissions, + const std::vector & control_hardware, sdf::ElementPtr sdf) { this->dataPtr = std::make_unique(); @@ -108,7 +108,8 @@ bool GazeboSystem::initSim( this->nh_ = model_nh; this->dataPtr->parent_model_ = parent_model; - this->dataPtr->n_dof_ = transmissions.size(); + const auto hardware_info = control_hardware.front(); + this->dataPtr->n_dof_ = hardware_info.joints.size(); this->dataPtr->joint_names_.resize(this->dataPtr->n_dof_); this->dataPtr->joint_control_methods_.resize(this->dataPtr->n_dof_); @@ -134,78 +135,55 @@ bool GazeboSystem::initSim( return false; } - for (unsigned int j = 0; j < this->dataPtr->n_dof_; j++) { - // - // Perform some validation on the URDF joint and actuator spec - // - // Check that this transmission has one joint - if (transmissions[j].joints.empty()) { - RCLCPP_WARN_STREAM( - this->nh_->get_logger(), "Transmission " << transmissions[j].name << - " has no associated joints."); - continue; - } else if (transmissions[j].joints.size() > 1) { - RCLCPP_WARN_STREAM( - this->nh_->get_logger(), "Transmission " << transmissions[j].name << - " has more than one joint. Currently the default robot hardware simulation " << - " interface only supports one."); - continue; - } - std::string joint_name = this->dataPtr->joint_names_[j] = transmissions[j].joints[0].name; - - std::vector joint_interfaces = transmissions[j].joints[0].interfaces; - if (joint_interfaces.empty() && - !(transmissions[j].actuators.empty()) && - !(transmissions[j].actuators[0].interfaces.empty())) - { - // TODO(anyone): Deprecate HW interface specification in actuators in ROS 2 - joint_interfaces = transmissions[j].actuators[0].interfaces; - RCLCPP_WARN_STREAM( - this->nh_->get_logger(), "The element of transmission " << - transmissions[j].name << " should be nested inside the element," << - " not . The transmission will be properly loaded, but please update " << - "your robot model to remain compatible with future versions of the plugin."); - } - if (joint_interfaces.empty()) { - RCLCPP_WARN_STREAM( - this->nh_->get_logger(), "Joint " << transmissions[j].name << - " of transmission " << transmissions[j].name << - " does not specify any hardware interface. " << - "Not adding it to the robot hardware simulation."); - continue; - } else if (joint_interfaces.size() > 1) { - // only a warning, allow joint to continue - RCLCPP_WARN_STREAM( - this->nh_->get_logger(), "Joint " << transmissions[j].name << - " of transmission " << transmissions[j].name << - " specifies multiple hardware interfaces. " << - "Currently the default robot hardware simulation interface only supports one." << - "Using the first entry"); - } - std::string hardware_interface = joint_interfaces.front(); - // Decide what kind of command interface this actuator/joint has - if (hardware_interface == "hardware_interface/EffortJointInterface") { - this->dataPtr->joint_control_methods_[j] = EFFORT; - } else if (hardware_interface == "hardware_interface/PositionJointInterface") { - this->dataPtr->joint_control_methods_[j] = POSITION; - } else if (hardware_interface == "hardware_interface/VelocityJointInterface") { - this->dataPtr->joint_control_methods_[j] = VELOCITY; - } else { - RCLCPP_WARN_STREAM( - this->nh_->get_logger(), "No matching joint interface '" << - hardware_interface << "' for joint " << joint_name); - RCLCPP_INFO( - this->nh_->get_logger(), - " Expecting one of 'hardware_interface/{EffortJointInterface |" - " PositionJointInterface | VelocityJointInterface}'"); - return false; - } + if (this->dataPtr->n_dof_ == 0) + { + RCLCPP_WARN_STREAM(this->nh_->get_logger(), "There is not joint available "); + return false; + } + for (unsigned int j = 0; j < this->dataPtr->n_dof_; j++) { + std::string joint_name = this->dataPtr->joint_names_[j] = hardware_info.joints[j].name; + // std::vector joint_interfaces = hardware_info.joints[j].interfaces; + + // if (joint_interfaces.empty()) { + // RCLCPP_WARN_STREAM( + // this->nh_->get_logger(), "Joint " << transmissions[j].name << + // " of transmission " << transmissions[j].name << + // " does not specify any hardware interface. " << + // "Not adding it to the robot hardware simulation."); + // continue; + // } else if (joint_interfaces.size() > 1) { + // // only a warning, allow joint to continue + // RCLCPP_WARN_STREAM( + // this->nh_->get_logger(), "Joint " << transmissions[j].name << + // " of transmission " << transmissions[j].name << + // " specifies multiple hardware interfaces. " << + // "Currently the default robot hardware simulation interface only supports one." << + // "Using the first entry"); + // } + // std::string hardware_interface = joint_interfaces.front(); + // // Decide what kind of command interface this actuator/joint has + // if (hardware_interface == "hardware_interface/EffortJointInterface") { + // this->dataPtr->joint_control_methods_[j] = EFFORT; + // } else if (hardware_interface == "hardware_interface/PositionJointInterface") { + // this->dataPtr->joint_control_methods_[j] = POSITION; + // } else if (hardware_interface == "hardware_interface/VelocityJointInterface") { + // this->dataPtr->joint_control_methods_[j] = VELOCITY; + // } else { + // RCLCPP_WARN_STREAM( + // this->nh_->get_logger(), "No matching joint interface '" << + // hardware_interface << "' for joint " << joint_name); + // RCLCPP_INFO( + // this->nh_->get_logger(), + // " Expecting one of 'hardware_interface/{EffortJointInterface |" + // " PositionJointInterface | VelocityJointInterface}'"); + // return false; + // } // - // Accept this URDF joint as valid and link with the gazebo joint of the same name + // // + // // Accept this URDF joint as valid and link with the gazebo joint of the same name + // // // - - // I think it's safe to only skip this joint and not abort if there is no match found gazebo::physics::JointPtr simjoint = parent_model->GetJoint(joint_name); if (!simjoint) { RCLCPP_WARN_STREAM( @@ -214,27 +192,53 @@ bool GazeboSystem::initSim( continue; } this->dataPtr->sim_joints_.push_back(simjoint); - + // // Accept this joint and continue configuration - RCLCPP_INFO_STREAM( - this->nh_->get_logger(), "Loading joint '" << joint_name << "' of type '" << - hardware_interface << "'"); - - // register the state handles - this->dataPtr->joint_pos_state_[j] = std::make_shared( - joint_name, hardware_interface::HW_IF_POSITION, &this->dataPtr->joint_position_[j]); - this->dataPtr->joint_vel_state_[j] = std::make_shared( - joint_name, hardware_interface::HW_IF_VELOCITY, &this->dataPtr->joint_velocity_[j]); - this->dataPtr->joint_eff_state_[j] = std::make_shared( - joint_name, hardware_interface::HW_IF_EFFORT, &this->dataPtr->joint_effort_[j]); + RCLCPP_INFO_STREAM(this->nh_->get_logger(), "Loading joint: " << joint_name); + + RCLCPP_INFO_STREAM(this->nh_->get_logger(), "\tCommand:"); + // register the command handles + for (unsigned int i = 0; i < hardware_info.joints[j].command_interfaces.size(); i++) { + if (hardware_info.joints[j].command_interfaces[i].name == "position") { + RCLCPP_INFO_STREAM(this->nh_->get_logger(), "\t\t position"); + this->dataPtr->joint_control_methods_[i] |= POSITION; + this->dataPtr->joint_pos_cmd_[j] = std::make_shared( + joint_name, hardware_interface::HW_IF_POSITION, &this->dataPtr->joint_position_cmd_[j]); + } + if (hardware_info.joints[j].command_interfaces[i].name == "velocity") { + RCLCPP_INFO_STREAM(this->nh_->get_logger(), "\t\t velocity"); + this->dataPtr->joint_control_methods_[i] |= VELOCITY; + this->dataPtr->joint_vel_cmd_[j] = std::make_shared( + joint_name, hardware_interface::HW_IF_VELOCITY, &this->dataPtr->joint_velocity_cmd_[j]); + } + if (hardware_info.joints[j].command_interfaces[i].name == "effort") { + this->dataPtr->joint_control_methods_[i] |= EFFORT; + RCLCPP_INFO_STREAM(this->nh_->get_logger(), "\t\t effort"); + this->dataPtr->joint_eff_cmd_[j] = std::make_shared( + joint_name, hardware_interface::HW_IF_EFFORT, &this->dataPtr->joint_effort_cmd_[j]); + } + } + RCLCPP_INFO_STREAM( + this->nh_->get_logger(), "\tState:"); // register the state handles - this->dataPtr->joint_pos_cmd_[j] = std::make_shared( - joint_name, hardware_interface::HW_IF_POSITION, &this->dataPtr->joint_position_cmd_[j]); - this->dataPtr->joint_vel_cmd_[j] = std::make_shared( - joint_name, hardware_interface::HW_IF_VELOCITY, &this->dataPtr->joint_velocity_cmd_[j]); - this->dataPtr->joint_eff_cmd_[j] = std::make_shared( - joint_name, hardware_interface::HW_IF_EFFORT, &this->dataPtr->joint_effort_cmd_[j]); + for (unsigned int i = 0; i < hardware_info.joints[j].state_interfaces.size(); i++) { + if (hardware_info.joints[j].state_interfaces[i].name == "position") { + RCLCPP_INFO_STREAM(this->nh_->get_logger(), "\t\t position"); + this->dataPtr->joint_pos_cmd_[j] = std::make_shared( + joint_name, hardware_interface::HW_IF_POSITION, &this->dataPtr->joint_position_cmd_[j]); + } + if (hardware_info.joints[j].state_interfaces[i].name == "velocity") { + RCLCPP_INFO_STREAM(this->nh_->get_logger(), "\t\t velocity"); + this->dataPtr->joint_vel_cmd_[j] = std::make_shared( + joint_name, hardware_interface::HW_IF_VELOCITY, &this->dataPtr->joint_velocity_cmd_[j]); + } + if (hardware_info.joints[j].state_interfaces[i].name == "effort") { + RCLCPP_INFO_STREAM(this->nh_->get_logger(), "\t\t effort"); + this->dataPtr->joint_eff_cmd_[j] = std::make_shared( + joint_name, hardware_interface::HW_IF_EFFORT, &this->dataPtr->joint_effort_cmd_[j]); + } + } } // Initialize the emergency stop code. @@ -348,33 +352,29 @@ hardware_interface::return_type GazeboSystem::write() rclcpp::Duration sim_period = sim_time_ros - this->dataPtr->last_update_sim_time_ros_; for (unsigned int j = 0; j < this->dataPtr->joint_names_.size(); j++) { - switch (this->dataPtr->joint_control_methods_[j]) { - case EFFORT: - { - const double effort = - this->dataPtr->e_stop_active_ ? 0 : this->dataPtr->joint_effort_cmd_[j]; - this->dataPtr->sim_joints_[j]->SetForce(0, effort); - } - break; - case POSITION: - if (this->dataPtr->e_stop_active_) { - // If the E-stop is active, joints controlled by position commands will maintain - // their positions. - this->dataPtr->sim_joints_[j]->SetPosition( - 0, this->dataPtr->last_joint_position_cmd_[j], - true); - } else { - this->dataPtr->sim_joints_[j]->SetPosition( - 0, this->dataPtr->joint_position_cmd_[j], - true); - this->dataPtr->last_joint_position_cmd_[j] = this->dataPtr->joint_position_cmd_[j]; - } - break; - case VELOCITY: - this->dataPtr->sim_joints_[j]->SetVelocity( - 0, - this->dataPtr->e_stop_active_ ? 0 : this->dataPtr->joint_velocity_cmd_[j]); - break; + if (this->dataPtr->joint_control_methods_[j] & POSITION) { + if (this->dataPtr->e_stop_active_) { + // If the E-stop is active, joints controlled by position commands will maintain + // their positions. + this->dataPtr->sim_joints_[j]->SetPosition( + 0, this->dataPtr->last_joint_position_cmd_[j], + true); + } else { + this->dataPtr->sim_joints_[j]->SetPosition( + 0, this->dataPtr->joint_position_cmd_[j], + true); + this->dataPtr->last_joint_position_cmd_[j] = this->dataPtr->joint_position_cmd_[j]; + } + } + if (this->dataPtr->joint_control_methods_[j] & VELOCITY) { + this->dataPtr->sim_joints_[j]->SetVelocity( + 0, + this->dataPtr->e_stop_active_ ? 0 : this->dataPtr->joint_velocity_cmd_[j]); + } + if (this->dataPtr->joint_control_methods_[j] & EFFORT) { + const double effort = + this->dataPtr->e_stop_active_ ? 0 : this->dataPtr->joint_effort_cmd_[j]; + this->dataPtr->sim_joints_[j]->SetForce(0, effort); } } diff --git a/gazebo_ros2_control_demos/config/cartpole_controller.yaml b/gazebo_ros2_control_demos/config/cartpole_controller.yaml index 1f39ba1e..710005b0 100644 --- a/gazebo_ros2_control_demos/config/cartpole_controller.yaml +++ b/gazebo_ros2_control_demos/config/cartpole_controller.yaml @@ -5,13 +5,7 @@ cart_pole_controller: - slider_to_cart write_op_modes: - slider_to_cart - state_publish_rate: 25 - action_monitor_rate: 20 - constraints: - stopped_velocity_tolerance: 0.05 - goal_time: 5 joint_state_controller: ros__parameters: type: joint_state_controller/JointStateController - publish_rate: 50 diff --git a/gazebo_ros2_control_demos/config/cartpole_controller_effort.yaml b/gazebo_ros2_control_demos/config/cartpole_controller_effort.yaml index 9b4fb4c2..5f4b9212 100644 --- a/gazebo_ros2_control_demos/config/cartpole_controller_effort.yaml +++ b/gazebo_ros2_control_demos/config/cartpole_controller_effort.yaml @@ -5,13 +5,7 @@ cart_pole_controller: - slider_to_cart write_op_modes: - slider_to_cart - state_publish_rate: 25 - action_monitor_rate: 20 - constraints: - stopped_velocity_tolerance: 0.05 - goal_time: 5 joint_state_controller: ros__parameters: type: joint_state_controller/JointStateController - publish_rate: 50 diff --git a/gazebo_ros2_control_demos/config/cartpole_controller_velocity.yaml b/gazebo_ros2_control_demos/config/cartpole_controller_velocity.yaml index 03f7ac24..1af0fb28 100644 --- a/gazebo_ros2_control_demos/config/cartpole_controller_velocity.yaml +++ b/gazebo_ros2_control_demos/config/cartpole_controller_velocity.yaml @@ -5,13 +5,7 @@ cart_pole_controller: - slider_to_cart write_op_modes: - slider_to_cart - state_publish_rate: 25 - action_monitor_rate: 20 - constraints: - stopped_velocity_tolerance: 0.05 - goal_time: 5 joint_state_controller: ros__parameters: type: joint_state_controller/JointStateController - publish_rate: 50 diff --git a/gazebo_ros2_control_demos/urdf/test_cart_effort.xacro.urdf b/gazebo_ros2_control_demos/urdf/test_cart_effort.xacro.urdf index 853d2626..0e63a61e 100644 --- a/gazebo_ros2_control_demos/urdf/test_cart_effort.xacro.urdf +++ b/gazebo_ros2_control_demos/urdf/test_cart_effort.xacro.urdf @@ -48,19 +48,24 @@ - - transmission_interface/SimpleTransmission + + + + gazebo_ros2_control/GazeboSystem + - hardware_interface/EffortJointInterface + + -1000 + 1000 + + + + - - hardware_interface/EffortJointInterface - 1 - - + + - gazebo_ros2_control/GazeboSystem $(find gazebo_ros2_control_demos)/config/cartpole_controller_effort.yaml 0.01 /cart_pole/estop diff --git a/gazebo_ros2_control_demos/urdf/test_cart_position.xacro.urdf b/gazebo_ros2_control_demos/urdf/test_cart_position.xacro.urdf index 23d2bc04..7dbdfa5c 100644 --- a/gazebo_ros2_control_demos/urdf/test_cart_position.xacro.urdf +++ b/gazebo_ros2_control_demos/urdf/test_cart_position.xacro.urdf @@ -48,19 +48,24 @@ - - transmission_interface/SimpleTransmission + + + + gazebo_ros2_control/GazeboSystem + - hardware_interface/PositionJointInterface + + -15 + 15 + + + + - - hardware_interface/PositionJointInterface - 1 - - + + - gazebo_ros2_control/GazeboSystem $(find gazebo_ros2_control_demos)/config/cartpole_controller.yaml 0.01 /cart_pole/estop diff --git a/gazebo_ros2_control_demos/urdf/test_cart_velocity.xacro.urdf b/gazebo_ros2_control_demos/urdf/test_cart_velocity.xacro.urdf index 87ba5819..50ef8255 100644 --- a/gazebo_ros2_control_demos/urdf/test_cart_velocity.xacro.urdf +++ b/gazebo_ros2_control_demos/urdf/test_cart_velocity.xacro.urdf @@ -48,19 +48,22 @@ - - transmission_interface/SimpleTransmission + + + gazebo_ros2_control/GazeboSystem + - hardware_interface/VelocityJointInterface + + -10 + 10 + + + + - - hardware_interface/VelocityJointInterface - 1 - - + - gazebo_ros2_control/GazeboSystem $(find gazebo_ros2_control_demos)/config/cartpole_controller_velocity.yaml 0.01 /cart_pole/estop From 970adeb3e0c8e5b44d94fa9169747d3984e7c234 Mon Sep 17 00:00:00 2001 From: ahcorde Date: Mon, 1 Feb 2021 09:46:56 +0100 Subject: [PATCH 24/33] Removed e-stop Signed-off-by: ahcorde --- gazebo_ros2_control/src/gazebo_system.cpp | 47 ++----------------- .../urdf/test_cart_effort.xacro.urdf | 1 - .../urdf/test_cart_position.xacro.urdf | 1 - .../urdf/test_cart_velocity.xacro.urdf | 1 - 4 files changed, 5 insertions(+), 45 deletions(-) diff --git a/gazebo_ros2_control/src/gazebo_system.cpp b/gazebo_ros2_control/src/gazebo_system.cpp index b922e351..7a270aad 100644 --- a/gazebo_ros2_control/src/gazebo_system.cpp +++ b/gazebo_ros2_control/src/gazebo_system.cpp @@ -27,12 +27,6 @@ class gazebo_ros2_control::GazeboSystemPrivate /// \brief Degrees od freedom. size_t n_dof_; - /// \brief e_stop_active_ is true if the emergency stop is active. - bool e_stop_active_; - - /// \brief Emergency stop subscriber. - rclcpp::Subscription::SharedPtr e_stop_sub_; - /// \brief Gazebo Model Ptr. gazebo::physics::ModelPtr parent_model_; @@ -60,9 +54,6 @@ class gazebo_ros2_control::GazeboSystemPrivate /// \brief vector with the current cmd joint position std::vector joint_position_cmd_; - /// \brief vector with the last cmd joint position - std::vector last_joint_position_cmd_; - /// \brief vector with the current cmd joint velocity std::vector joint_velocity_cmd_; @@ -86,12 +77,6 @@ class gazebo_ros2_control::GazeboSystemPrivate /// \brief The effort command interfaces of the joints std::vector> joint_eff_cmd_; - - /// \brief callback to get the e_stop signal from the ROS 2 topic - void eStopCB(const std::shared_ptr e_stop_active) - { - this->e_stop_active_ = e_stop_active->data; - } }; namespace gazebo_ros2_control @@ -120,7 +105,6 @@ bool GazeboSystem::initSim( this->dataPtr->joint_vel_state_.resize(this->dataPtr->n_dof_); this->dataPtr->joint_eff_state_.resize(this->dataPtr->n_dof_); this->dataPtr->joint_position_cmd_.resize(this->dataPtr->n_dof_); - this->dataPtr->last_joint_position_cmd_.resize(this->dataPtr->n_dof_); this->dataPtr->joint_velocity_cmd_.resize(this->dataPtr->n_dof_); this->dataPtr->joint_effort_cmd_.resize(this->dataPtr->n_dof_); this->dataPtr->joint_pos_cmd_.resize(this->dataPtr->n_dof_); @@ -240,18 +224,6 @@ bool GazeboSystem::initSim( } } } - - // Initialize the emergency stop code. - this->dataPtr->e_stop_active_ = false; - if (sdf->HasElement("e_stop_topic")) { - const std::string e_stop_topic = sdf->GetElement("e_stop_topic")->Get(); - rclcpp::QoS qos = rclcpp::SensorDataQoS().reliable(); - this->dataPtr->e_stop_sub_ = this->nh_->create_subscription( - e_stop_topic, - qos, - std::bind(&GazeboSystemPrivate::eStopCB, this->dataPtr.get(), std::placeholders::_1)); - } - return true; } @@ -353,27 +325,18 @@ hardware_interface::return_type GazeboSystem::write() for (unsigned int j = 0; j < this->dataPtr->joint_names_.size(); j++) { if (this->dataPtr->joint_control_methods_[j] & POSITION) { - if (this->dataPtr->e_stop_active_) { - // If the E-stop is active, joints controlled by position commands will maintain - // their positions. - this->dataPtr->sim_joints_[j]->SetPosition( - 0, this->dataPtr->last_joint_position_cmd_[j], - true); - } else { - this->dataPtr->sim_joints_[j]->SetPosition( - 0, this->dataPtr->joint_position_cmd_[j], - true); - this->dataPtr->last_joint_position_cmd_[j] = this->dataPtr->joint_position_cmd_[j]; - } + this->dataPtr->sim_joints_[j]->SetPosition( + 0, this->dataPtr->joint_position_cmd_[j], + true); } if (this->dataPtr->joint_control_methods_[j] & VELOCITY) { this->dataPtr->sim_joints_[j]->SetVelocity( 0, - this->dataPtr->e_stop_active_ ? 0 : this->dataPtr->joint_velocity_cmd_[j]); + this->dataPtr->joint_velocity_cmd_[j]); } if (this->dataPtr->joint_control_methods_[j] & EFFORT) { const double effort = - this->dataPtr->e_stop_active_ ? 0 : this->dataPtr->joint_effort_cmd_[j]; + this->dataPtr->joint_effort_cmd_[j]; this->dataPtr->sim_joints_[j]->SetForce(0, effort); } } diff --git a/gazebo_ros2_control_demos/urdf/test_cart_effort.xacro.urdf b/gazebo_ros2_control_demos/urdf/test_cart_effort.xacro.urdf index 0e63a61e..19fe31f4 100644 --- a/gazebo_ros2_control_demos/urdf/test_cart_effort.xacro.urdf +++ b/gazebo_ros2_control_demos/urdf/test_cart_effort.xacro.urdf @@ -68,7 +68,6 @@ $(find gazebo_ros2_control_demos)/config/cartpole_controller_effort.yaml 0.01 - /cart_pole/estop diff --git a/gazebo_ros2_control_demos/urdf/test_cart_position.xacro.urdf b/gazebo_ros2_control_demos/urdf/test_cart_position.xacro.urdf index 7dbdfa5c..b62336f4 100644 --- a/gazebo_ros2_control_demos/urdf/test_cart_position.xacro.urdf +++ b/gazebo_ros2_control_demos/urdf/test_cart_position.xacro.urdf @@ -68,7 +68,6 @@ $(find gazebo_ros2_control_demos)/config/cartpole_controller.yaml 0.01 - /cart_pole/estop diff --git a/gazebo_ros2_control_demos/urdf/test_cart_velocity.xacro.urdf b/gazebo_ros2_control_demos/urdf/test_cart_velocity.xacro.urdf index 50ef8255..71dff886 100644 --- a/gazebo_ros2_control_demos/urdf/test_cart_velocity.xacro.urdf +++ b/gazebo_ros2_control_demos/urdf/test_cart_velocity.xacro.urdf @@ -66,7 +66,6 @@ $(find gazebo_ros2_control_demos)/config/cartpole_controller_velocity.yaml 0.01 - /cart_pole/estop From 9af1bfa59c30d51175af5a9fc9a658abf970b374 Mon Sep 17 00:00:00 2001 From: ahcorde Date: Mon, 1 Feb 2021 09:49:15 +0100 Subject: [PATCH 25/33] make linters happy Signed-off-by: ahcorde --- .../gazebo_system_interface.hpp | 29 ++++++++++--------- .../src/gazebo_ros2_control_plugin.cpp | 2 +- gazebo_ros2_control/src/gazebo_system.cpp | 3 +- 3 files changed, 18 insertions(+), 16 deletions(-) diff --git a/gazebo_ros2_control/include/gazebo_ros2_control/gazebo_system_interface.hpp b/gazebo_ros2_control/include/gazebo_ros2_control/gazebo_system_interface.hpp index d2aef52e..66184e54 100644 --- a/gazebo_ros2_control/include/gazebo_ros2_control/gazebo_system_interface.hpp +++ b/gazebo_ros2_control/include/gazebo_ros2_control/gazebo_system_interface.hpp @@ -36,23 +36,26 @@ namespace gazebo_ros2_control { -template::type> +template::type> class SafeEnum { public: - SafeEnum() : mFlags(0) {} - SafeEnum( ENUM singleFlag ) : mFlags(singleFlag) {} - SafeEnum( const SafeEnum& original ) : mFlags(original.mFlags) {} - - SafeEnum& operator |=( ENUM addValue ) { mFlags |= addValue; return *this; } - SafeEnum operator |( ENUM addValue ) { SafeEnum result(*this); result |= addValue; return result; } - SafeEnum& operator &=( ENUM maskValue ) { mFlags &= maskValue; return *this; } - SafeEnum operator &( ENUM maskValue ) { SafeEnum result(*this); result &= maskValue; return result; } - SafeEnum operator ~() { SafeEnum result(*this); result.mFlags = ~result.mFlags; return result; } - explicit operator bool() { return mFlags != 0; } + SafeEnum() + : mFlags(0) {} + explicit SafeEnum(ENUM singleFlag) + : mFlags(singleFlag) {} + SafeEnum(const SafeEnum & original) + : mFlags(original.mFlags) {} + + SafeEnum & operator|=(ENUM addValue) {mFlags |= addValue; return *this;} + SafeEnum operator|(ENUM addValue) {SafeEnum result(*this); result |= addValue; return result;} + SafeEnum & operator&=(ENUM maskValue) {mFlags &= maskValue; return *this;} + SafeEnum operator&(ENUM maskValue) {SafeEnum result(*this); result &= maskValue; return result;} + SafeEnum operator~() {SafeEnum result(*this); result.mFlags = ~result.mFlags; return result;} + explicit operator bool() {return mFlags != 0;} protected: - UNDERLYING mFlags; + UNDERLYING mFlags; }; // SystemInterface provides API-level access to read and command joint properties. @@ -80,7 +83,7 @@ class GazeboSystemInterface EFFORT = (1 << 2), }; - typedef SafeEnum ControlMethod; + typedef SafeEnum ControlMethod; protected: rclcpp::Node::SharedPtr nh_; diff --git a/gazebo_ros2_control/src/gazebo_ros2_control_plugin.cpp b/gazebo_ros2_control/src/gazebo_ros2_control_plugin.cpp index d1ebc762..b35ef3ff 100644 --- a/gazebo_ros2_control/src/gazebo_ros2_control_plugin.cpp +++ b/gazebo_ros2_control/src/gazebo_ros2_control_plugin.cpp @@ -229,7 +229,7 @@ void GazeboRosControlPlugin::Load(gazebo::physics::ModelPtr parent, sdf::Element urdf_string = impl_->getURDF(impl_->robot_description_); control_hardware = hardware_interface::parse_control_resources_from_urdf(urdf_string); const auto hardware_info = control_hardware.front(); - impl_->robot_hw_sim_type_str_ = hardware_info.hardware_class_type; + impl_->robot_hw_sim_type_str_ = hardware_info.hardware_class_type; } catch (const std::runtime_error & ex) { RCLCPP_ERROR_STREAM( impl_->model_nh_->get_logger(), diff --git a/gazebo_ros2_control/src/gazebo_system.cpp b/gazebo_ros2_control/src/gazebo_system.cpp index 7a270aad..ea2b2aef 100644 --- a/gazebo_ros2_control/src/gazebo_system.cpp +++ b/gazebo_ros2_control/src/gazebo_system.cpp @@ -119,8 +119,7 @@ bool GazeboSystem::initSim( return false; } - if (this->dataPtr->n_dof_ == 0) - { + if (this->dataPtr->n_dof_ == 0) { RCLCPP_WARN_STREAM(this->nh_->get_logger(), "There is not joint available "); return false; } From 2822a9aca62972edf8694513f229ba7e06af2b99 Mon Sep 17 00:00:00 2001 From: ahcorde Date: Mon, 1 Feb 2021 09:54:49 +0100 Subject: [PATCH 26/33] clean code Signed-off-by: ahcorde --- README.md | 8 ++-- .../gazebo_system_interface.hpp | 2 +- gazebo_ros2_control/src/gazebo_system.cpp | 45 ++----------------- 3 files changed, 7 insertions(+), 48 deletions(-) diff --git a/README.md b/README.md index 592e372c..80206dc4 100644 --- a/README.md +++ b/README.md @@ -60,7 +60,7 @@ ros2 run gazebo_ros2_control_demos example_position ``` -## Add transmission elements to a URDF +## Add ros2_control tag to a URDF To use `ros2_control` with your robot, you need to add some additional elements to your URDF. You should include the tag `` to access and control the robot interfaces. We should @@ -88,8 +88,8 @@ include ## Add the gazebo_ros2_control plugin -In addition to the transmission tags, a Gazebo plugin needs to be added to your URDF that -actually parses the transmission tags and loads the appropriate hardware interfaces and +In addition to the `ros2_control` tags, a Gazebo plugin needs to be added to your URDF that +actually parses the `ros2_control` tags and loads the appropriate hardware interfaces and controller manager. By default the `gazebo_ros2_control` plugin is very simple, though it is also extensible via an additional plugin architecture to allow power users to create their own custom robot hardware interfaces between `ros2_control` and Gazebo. @@ -100,7 +100,6 @@ robot hardware interfaces between `ros2_control` and Gazebo. robot_description robot_state_publisher $(find gazebo_ros2_control_demos)/config/cartpole_controller.yaml - False 0.01 @@ -112,7 +111,6 @@ The `gazebo_ros2_control` `` tag also has the following optional child e - ``: The location of the `robot_description` (URDF) on the parameter server, defaults to `robot_description` - ``: Name of the node where the `robot_param` is located, defauls to `robot_state_publisher` - ``: YAML file with the configuration of the controllers - - ``: Topic to publish the emergency stop #### Default gazebo_ros2_control Behavior diff --git a/gazebo_ros2_control/include/gazebo_ros2_control/gazebo_system_interface.hpp b/gazebo_ros2_control/include/gazebo_ros2_control/gazebo_system_interface.hpp index 66184e54..8f9f69c9 100644 --- a/gazebo_ros2_control/include/gazebo_ros2_control/gazebo_system_interface.hpp +++ b/gazebo_ros2_control/include/gazebo_ros2_control/gazebo_system_interface.hpp @@ -66,7 +66,7 @@ class GazeboSystemInterface /// \brief Initilize the system interface /// param[in] model_nh pointer to the ros2 node /// param[in] parent_model pointer to the model - /// param[in] transmissions availables in the model + /// param[in] control_hardware vector filled with information about robot's control resources /// param[in] sdf pointer to the SDF virtual bool initSim( rclcpp::Node::SharedPtr & model_nh, diff --git a/gazebo_ros2_control/src/gazebo_system.cpp b/gazebo_ros2_control/src/gazebo_system.cpp index ea2b2aef..dca0230d 100644 --- a/gazebo_ros2_control/src/gazebo_system.cpp +++ b/gazebo_ros2_control/src/gazebo_system.cpp @@ -126,47 +126,7 @@ bool GazeboSystem::initSim( for (unsigned int j = 0; j < this->dataPtr->n_dof_; j++) { std::string joint_name = this->dataPtr->joint_names_[j] = hardware_info.joints[j].name; - // std::vector joint_interfaces = hardware_info.joints[j].interfaces; - - // if (joint_interfaces.empty()) { - // RCLCPP_WARN_STREAM( - // this->nh_->get_logger(), "Joint " << transmissions[j].name << - // " of transmission " << transmissions[j].name << - // " does not specify any hardware interface. " << - // "Not adding it to the robot hardware simulation."); - // continue; - // } else if (joint_interfaces.size() > 1) { - // // only a warning, allow joint to continue - // RCLCPP_WARN_STREAM( - // this->nh_->get_logger(), "Joint " << transmissions[j].name << - // " of transmission " << transmissions[j].name << - // " specifies multiple hardware interfaces. " << - // "Currently the default robot hardware simulation interface only supports one." << - // "Using the first entry"); - // } - // std::string hardware_interface = joint_interfaces.front(); - // // Decide what kind of command interface this actuator/joint has - // if (hardware_interface == "hardware_interface/EffortJointInterface") { - // this->dataPtr->joint_control_methods_[j] = EFFORT; - // } else if (hardware_interface == "hardware_interface/PositionJointInterface") { - // this->dataPtr->joint_control_methods_[j] = POSITION; - // } else if (hardware_interface == "hardware_interface/VelocityJointInterface") { - // this->dataPtr->joint_control_methods_[j] = VELOCITY; - // } else { - // RCLCPP_WARN_STREAM( - // this->nh_->get_logger(), "No matching joint interface '" << - // hardware_interface << "' for joint " << joint_name); - // RCLCPP_INFO( - // this->nh_->get_logger(), - // " Expecting one of 'hardware_interface/{EffortJointInterface |" - // " PositionJointInterface | VelocityJointInterface}'"); - // return false; - // } - // - // // - // // Accept this URDF joint as valid and link with the gazebo joint of the same name - // // - // + gazebo::physics::JointPtr simjoint = parent_model->GetJoint(joint_name); if (!simjoint) { RCLCPP_WARN_STREAM( @@ -175,11 +135,12 @@ bool GazeboSystem::initSim( continue; } this->dataPtr->sim_joints_.push_back(simjoint); - // + // Accept this joint and continue configuration RCLCPP_INFO_STREAM(this->nh_->get_logger(), "Loading joint: " << joint_name); RCLCPP_INFO_STREAM(this->nh_->get_logger(), "\tCommand:"); + // register the command handles for (unsigned int i = 0; i < hardware_info.joints[j].command_interfaces.size(); i++) { if (hardware_info.joints[j].command_interfaces[i].name == "position") { From 27ecc7514812163ca85fe05f66ff67c37ff64de4 Mon Sep 17 00:00:00 2001 From: ahcorde Date: Mon, 1 Feb 2021 09:59:23 +0100 Subject: [PATCH 27/33] Fix CI Signed-off-by: ahcorde --- gazebo_ros2_control_demos/package.xml | 1 - 1 file changed, 1 deletion(-) diff --git a/gazebo_ros2_control_demos/package.xml b/gazebo_ros2_control_demos/package.xml index 49a0e780..ec9f27e3 100644 --- a/gazebo_ros2_control_demos/package.xml +++ b/gazebo_ros2_control_demos/package.xml @@ -33,7 +33,6 @@ robot_state_publisher rclcpp std_msgs - transmission_interface velocity_controllers xacro From f8b0871aae87cd803dbb6fb142e7bcc8df15ee8e Mon Sep 17 00:00:00 2001 From: ahcorde Date: Mon, 1 Feb 2021 12:51:38 +0100 Subject: [PATCH 28/33] Changed log level of a trace Signed-off-by: ahcorde --- gazebo_ros2_control/src/gazebo_ros2_control_plugin.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/gazebo_ros2_control/src/gazebo_ros2_control_plugin.cpp b/gazebo_ros2_control/src/gazebo_ros2_control_plugin.cpp index b35ef3ff..e95a2916 100644 --- a/gazebo_ros2_control/src/gazebo_ros2_control_plugin.cpp +++ b/gazebo_ros2_control/src/gazebo_ros2_control_plugin.cpp @@ -489,7 +489,7 @@ std::string GazeboRosControlPrivate::getURDF(std::string param_name) const // search and wait for robot_description on param server while (urdf_string.empty()) { std::string search_param_name; - RCLCPP_ERROR(model_nh_->get_logger(), "param_name %s", param_name.c_str()); + RCLCPP_DEBUG(model_nh_->get_logger(), "param_name %s", param_name.c_str()); try { auto f = parameters_client->get_parameters({param_name}); From 595ba174d9f01403404160f659be5bd43f5fc7ce Mon Sep 17 00:00:00 2001 From: ahcorde Date: Mon, 1 Feb 2021 19:22:18 +0100 Subject: [PATCH 29/33] Added rclcpp dependency to gazebo_hardware_plugin Signed-off-by: ahcorde --- gazebo_ros2_control/CMakeLists.txt | 5 +++-- 1 file changed, 3 insertions(+), 2 deletions(-) diff --git a/gazebo_ros2_control/CMakeLists.txt b/gazebo_ros2_control/CMakeLists.txt index 91c4bddc..0a745663 100644 --- a/gazebo_ros2_control/CMakeLists.txt +++ b/gazebo_ros2_control/CMakeLists.txt @@ -45,9 +45,10 @@ add_library(gazebo_hardware_plugins SHARED src/gazebo_system.cpp ) ament_target_dependencies(gazebo_hardware_plugins - hardware_interface - gazebo_dev angles + gazebo_dev + hardware_interface + rclcpp ) ## Install From da262d9b76151fbe7dff208a1a2028d4aade8ff2 Mon Sep 17 00:00:00 2001 From: ahcorde Date: Tue, 2 Feb 2021 08:05:42 +0100 Subject: [PATCH 30/33] Fixed bug in control method Signed-off-by: ahcorde --- gazebo_ros2_control/src/gazebo_system.cpp | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/gazebo_ros2_control/src/gazebo_system.cpp b/gazebo_ros2_control/src/gazebo_system.cpp index dca0230d..6692ea25 100644 --- a/gazebo_ros2_control/src/gazebo_system.cpp +++ b/gazebo_ros2_control/src/gazebo_system.cpp @@ -145,18 +145,18 @@ bool GazeboSystem::initSim( for (unsigned int i = 0; i < hardware_info.joints[j].command_interfaces.size(); i++) { if (hardware_info.joints[j].command_interfaces[i].name == "position") { RCLCPP_INFO_STREAM(this->nh_->get_logger(), "\t\t position"); - this->dataPtr->joint_control_methods_[i] |= POSITION; + this->dataPtr->joint_control_methods_[j] |= POSITION; this->dataPtr->joint_pos_cmd_[j] = std::make_shared( joint_name, hardware_interface::HW_IF_POSITION, &this->dataPtr->joint_position_cmd_[j]); } if (hardware_info.joints[j].command_interfaces[i].name == "velocity") { RCLCPP_INFO_STREAM(this->nh_->get_logger(), "\t\t velocity"); - this->dataPtr->joint_control_methods_[i] |= VELOCITY; + this->dataPtr->joint_control_methods_[j] |= VELOCITY; this->dataPtr->joint_vel_cmd_[j] = std::make_shared( joint_name, hardware_interface::HW_IF_VELOCITY, &this->dataPtr->joint_velocity_cmd_[j]); } if (hardware_info.joints[j].command_interfaces[i].name == "effort") { - this->dataPtr->joint_control_methods_[i] |= EFFORT; + this->dataPtr->joint_control_methods_[j] |= EFFORT; RCLCPP_INFO_STREAM(this->nh_->get_logger(), "\t\t effort"); this->dataPtr->joint_eff_cmd_[j] = std::make_shared( joint_name, hardware_interface::HW_IF_EFFORT, &this->dataPtr->joint_effort_cmd_[j]); From 794da79c0b46a8adc4a7ff909429a69d518eea99 Mon Sep 17 00:00:00 2001 From: ahcorde Date: Tue, 2 Feb 2021 08:45:17 +0100 Subject: [PATCH 31/33] Support more than one ros2_control tag Signed-off-by: ahcorde --- .../gazebo_ros2_control/gazebo_system.hpp | 2 +- .../gazebo_system_interface.hpp | 2 +- .../src/gazebo_ros2_control_plugin.cpp | 37 +++++++++---------- gazebo_ros2_control/src/gazebo_system.cpp | 3 +- 4 files changed, 21 insertions(+), 23 deletions(-) diff --git a/gazebo_ros2_control/include/gazebo_ros2_control/gazebo_system.hpp b/gazebo_ros2_control/include/gazebo_ros2_control/gazebo_system.hpp index 8540fc0c..3c53af21 100644 --- a/gazebo_ros2_control/include/gazebo_ros2_control/gazebo_system.hpp +++ b/gazebo_ros2_control/include/gazebo_ros2_control/gazebo_system.hpp @@ -63,7 +63,7 @@ class GazeboSystem : public GazeboSystemInterface bool initSim( rclcpp::Node::SharedPtr & model_nh, gazebo::physics::ModelPtr parent_model, - const std::vector & control_hardware, + const hardware_interface::HardwareInfo & hardware_info, sdf::ElementPtr sdf) override; private: diff --git a/gazebo_ros2_control/include/gazebo_ros2_control/gazebo_system_interface.hpp b/gazebo_ros2_control/include/gazebo_ros2_control/gazebo_system_interface.hpp index 8f9f69c9..598f884c 100644 --- a/gazebo_ros2_control/include/gazebo_ros2_control/gazebo_system_interface.hpp +++ b/gazebo_ros2_control/include/gazebo_ros2_control/gazebo_system_interface.hpp @@ -71,7 +71,7 @@ class GazeboSystemInterface virtual bool initSim( rclcpp::Node::SharedPtr & model_nh, gazebo::physics::ModelPtr parent_model, - const std::vector & control_hardware, + const hardware_interface::HardwareInfo & hardware_info, sdf::ElementPtr sdf) = 0; // Methods used to control a joint. diff --git a/gazebo_ros2_control/src/gazebo_ros2_control_plugin.cpp b/gazebo_ros2_control/src/gazebo_ros2_control_plugin.cpp index e95a2916..fc89defa 100644 --- a/gazebo_ros2_control/src/gazebo_ros2_control_plugin.cpp +++ b/gazebo_ros2_control/src/gazebo_ros2_control_plugin.cpp @@ -96,9 +96,6 @@ class GazeboRosControlPrivate // Name of the file with the controllers configuration std::string param_file_; - // Robot simulator interface - std::string robot_hw_sim_type_str_; - // Executor to spin the controller rclcpp::executors::MultiThreadedExecutor::SharedPtr executor_; @@ -228,8 +225,6 @@ void GazeboRosControlPlugin::Load(gazebo::physics::ModelPtr parent, sdf::Element try { urdf_string = impl_->getURDF(impl_->robot_description_); control_hardware = hardware_interface::parse_control_resources_from_urdf(urdf_string); - const auto hardware_info = control_hardware.front(); - impl_->robot_hw_sim_type_str_ = hardware_info.hardware_class_type; } catch (const std::runtime_error & ex) { RCLCPP_ERROR_STREAM( impl_->model_nh_->get_logger(), @@ -246,22 +241,26 @@ void GazeboRosControlPlugin::Load(gazebo::physics::ModelPtr parent, sdf::Element "gazebo_ros2_control", "gazebo_ros2_control::GazeboSystemInterface")); - auto gazeboSystem = std::unique_ptr( - impl_->robot_hw_sim_loader_->createUnmanagedInstance(impl_->robot_hw_sim_type_str_)); - - rclcpp::Node::SharedPtr node_ros2 = std::dynamic_pointer_cast(impl_->model_nh_); - if (!gazeboSystem->initSim( - node_ros2, - impl_->parent_model_, - control_hardware, - sdf)) + for (unsigned int i = 0; i < control_hardware.size(); i++) { - RCLCPP_FATAL( - impl_->model_nh_->get_logger(), "Could not initialize robot simulation interface"); - return; - } + std::string robot_hw_sim_type_str_ = control_hardware[i].hardware_class_type; + auto gazeboSystem = std::unique_ptr( + impl_->robot_hw_sim_loader_->createUnmanagedInstance(robot_hw_sim_type_str_)); + + rclcpp::Node::SharedPtr node_ros2 = std::dynamic_pointer_cast(impl_->model_nh_); + if (!gazeboSystem->initSim( + node_ros2, + impl_->parent_model_, + control_hardware[i], + sdf)) + { + RCLCPP_FATAL( + impl_->model_nh_->get_logger(), "Could not initialize robot simulation interface"); + return; + } - resource_manager_->import_component(std::move(gazeboSystem)); + resource_manager_->import_component(std::move(gazeboSystem)); + } impl_->executor_ = std::make_shared(); diff --git a/gazebo_ros2_control/src/gazebo_system.cpp b/gazebo_ros2_control/src/gazebo_system.cpp index 6692ea25..1602af1f 100644 --- a/gazebo_ros2_control/src/gazebo_system.cpp +++ b/gazebo_ros2_control/src/gazebo_system.cpp @@ -85,7 +85,7 @@ namespace gazebo_ros2_control bool GazeboSystem::initSim( rclcpp::Node::SharedPtr & model_nh, gazebo::physics::ModelPtr parent_model, - const std::vector & control_hardware, + const hardware_interface::HardwareInfo & hardware_info, sdf::ElementPtr sdf) { this->dataPtr = std::make_unique(); @@ -93,7 +93,6 @@ bool GazeboSystem::initSim( this->nh_ = model_nh; this->dataPtr->parent_model_ = parent_model; - const auto hardware_info = control_hardware.front(); this->dataPtr->n_dof_ = hardware_info.joints.size(); this->dataPtr->joint_names_.resize(this->dataPtr->n_dof_); From f84047fba75834bb33e7f5577f9b73ab9b04698c Mon Sep 17 00:00:00 2001 From: ahcorde Date: Tue, 2 Feb 2021 09:03:37 +0100 Subject: [PATCH 32/33] make linters happy Signed-off-by: ahcorde --- gazebo_ros2_control/src/gazebo_ros2_control_plugin.cpp | 3 +-- 1 file changed, 1 insertion(+), 2 deletions(-) diff --git a/gazebo_ros2_control/src/gazebo_ros2_control_plugin.cpp b/gazebo_ros2_control/src/gazebo_ros2_control_plugin.cpp index fc89defa..a1449f42 100644 --- a/gazebo_ros2_control/src/gazebo_ros2_control_plugin.cpp +++ b/gazebo_ros2_control/src/gazebo_ros2_control_plugin.cpp @@ -241,8 +241,7 @@ void GazeboRosControlPlugin::Load(gazebo::physics::ModelPtr parent, sdf::Element "gazebo_ros2_control", "gazebo_ros2_control::GazeboSystemInterface")); - for (unsigned int i = 0; i < control_hardware.size(); i++) - { + for (unsigned int i = 0; i < control_hardware.size(); i++) { std::string robot_hw_sim_type_str_ = control_hardware[i].hardware_class_type; auto gazeboSystem = std::unique_ptr( impl_->robot_hw_sim_loader_->createUnmanagedInstance(robot_hw_sim_type_str_)); From 4889311276802a32225b2c97ec773ec25fa04357 Mon Sep 17 00:00:00 2001 From: ahcorde Date: Wed, 3 Feb 2021 09:56:35 +0100 Subject: [PATCH 33/33] unify yaml files Signed-off-by: ahcorde --- Docker/Dockerfile | 4 +- README.md | 2 - .../src/gazebo_ros2_control_plugin.cpp | 91 +++++++++---------- .../config/cartpole_controller.yaml | 20 ++-- .../config/cartpole_controller_effort.yaml | 20 ++-- .../config/cartpole_controller_velocity.yaml | 20 ++-- .../examples/example_effort.cpp | 2 +- .../examples/example_position.cpp | 2 +- .../examples/example_velocity.cpp | 2 +- .../urdf/test_cart_effort.xacro.urdf | 1 - .../urdf/test_cart_position.xacro.urdf | 1 - .../urdf/test_cart_velocity.xacro.urdf | 1 - 12 files changed, 84 insertions(+), 82 deletions(-) diff --git a/Docker/Dockerfile b/Docker/Dockerfile index 7b75a59f..785b3f87 100644 --- a/Docker/Dockerfile +++ b/Docker/Dockerfile @@ -14,7 +14,7 @@ RUN apt-get update && apt-get install -q -y --no-install-recommends \ RUN mkdir -p /home/ros2_ws/src \ && cd /home/ros2_ws/src/ \ - && git clone https://github.com/ros-simulation/gazebo_ros2_control -b ahcorde/update/foxy \ + && git clone https://github.com/ros-simulation/gazebo_ros2_control \ && rosdep update \ && rosdep install --from-paths ./ -i -y --rosdistro foxy \ --ignore-src @@ -26,4 +26,4 @@ RUN cd /home/ros2_ws/ \ COPY entrypoint.sh /entrypoint.sh ENTRYPOINT ["/entrypoint.sh"] -CMD ros2 launch rrbot_moveit_demo_nodes rrbot_demo.launch.py +CMD ros2 launch gazebo_ros2_control_demos cart_example_position.launch.py diff --git a/README.md b/README.md index 80206dc4..c86c5636 100644 --- a/README.md +++ b/README.md @@ -100,14 +100,12 @@ robot hardware interfaces between `ros2_control` and Gazebo. robot_description robot_state_publisher $(find gazebo_ros2_control_demos)/config/cartpole_controller.yaml - 0.01 ``` The `gazebo_ros2_control` `` tag also has the following optional child elements: - - ``: The period of the controller update (in seconds), defaults to Gazebo's period - ``: The location of the `robot_description` (URDF) on the parameter server, defaults to `robot_description` - ``: Name of the node where the `robot_param` is located, defauls to `robot_state_publisher` - ``: YAML file with the configuration of the controllers diff --git a/gazebo_ros2_control/src/gazebo_ros2_control_plugin.cpp b/gazebo_ros2_control/src/gazebo_ros2_control_plugin.cpp index a1449f42..91e84dbf 100644 --- a/gazebo_ros2_control/src/gazebo_ros2_control_plugin.cpp +++ b/gazebo_ros2_control/src/gazebo_ros2_control_plugin.cpp @@ -191,32 +191,6 @@ void GazeboRosControlPlugin::Load(gazebo::physics::ModelPtr parent, sdf::Element std::chrono::duration( impl_->parent_model_->GetWorld()->Physics()->GetMaxStepSize()))); - // Decide the plugin control period - if (sdf->HasElement("control_period")) { - impl_->control_period_ = rclcpp::Duration( - std::chrono::duration_cast( - std::chrono::duration(sdf->Get("control_period")))); - - // Check the period against the simulation period - if (impl_->control_period_ < gazebo_period) { - RCLCPP_ERROR_STREAM( - impl_->model_nh_->get_logger(), - "Desired controller update period (" << impl_->control_period_.seconds() << - " s) is faster than the gazebo simulation period (" << gazebo_period.seconds() << " s)."); - } else if (impl_->control_period_ > gazebo_period) { - RCLCPP_WARN_STREAM( - impl_->model_nh_->get_logger(), - " Desired controller update period (" << impl_->control_period_.seconds() << - " s) is slower than the gazebo simulation period (" << gazebo_period.seconds() << " s)."); - } - } else { - impl_->control_period_ = gazebo_period; - RCLCPP_DEBUG_STREAM( - impl_->model_nh_->get_logger(), - "Control period not found in URDF/SDF, defaulting to Gazebo period of " << - impl_->control_period_.seconds()); - } - // Read urdf from ros parameter server then // setup actuators and mechanism control node. // This call will block if ROS is not properly initialized. @@ -342,12 +316,6 @@ void GazeboRosControlPlugin::Load(gazebo::physics::ModelPtr parent, sdf::Element node->declare_parameter(key); } node->set_parameter({rclcpp::Parameter(key, val)}); - if (key == "joints") { - if (!node->has_parameter("write_op_modes")) { - node->declare_parameter("write_op_modes"); - } - node->set_parameter(rclcpp::Parameter("write_op_modes", val)); - } } else { size_t index = 0; for (auto yaml_node_it : yaml_node) { @@ -388,24 +356,51 @@ void GazeboRosControlPlugin::Load(gazebo::physics::ModelPtr parent, sdf::Element YAML::Node root_node = YAML::LoadFile(impl_->param_file_); for (auto yaml : root_node) { - auto controller_name = yaml.first.as(); - for (auto yaml_node_it : yaml.second) { // ros__parameters - for (auto yaml_node_it2 : yaml_node_it.second) { - auto param_name = yaml_node_it2.first.as(); - if (param_name == "type") { - auto controller_type = yaml_node_it2.second.as(); - auto controller = impl_->controller_manager_->load_controller( - controller_name, - controller_type); - impl_->controllers_.push_back(controller); - load_params_from_yaml( - controller->get_node(), - impl_->param_file_, - controller_name); - controller->configure(); - start_controllers.push_back(controller_name); + auto controller_manager_node_name = yaml.first.as(); + if (controller_manager_node_name == "controller_manager") { + for (auto yaml_node_it : yaml.second) { // ros__parameters + for (auto controller_manager_params_it : yaml_node_it.second) { + auto controller_name = controller_manager_params_it.first.as(); + + if (controller_name == "update_rate") { + float udpate_rate = controller_manager_params_it.second.as(); + // Decide the plugin control period + impl_->control_period_ = rclcpp::Duration( + std::chrono::duration_cast( + std::chrono::duration(1.0 / udpate_rate))); + + // Check the period against the simulation period + if (impl_->control_period_ < gazebo_period) { + RCLCPP_ERROR_STREAM( + impl_->model_nh_->get_logger(), + "Desired controller update period (" << impl_->control_period_.seconds() << + " s) is faster than the gazebo simulation period (" << + gazebo_period.seconds() << " s)."); + } else if (impl_->control_period_ > gazebo_period) { + RCLCPP_WARN_STREAM( + impl_->model_nh_->get_logger(), + " Desired controller update period (" << impl_->control_period_.seconds() << + " s) is slower than the gazebo simulation period (" << + gazebo_period.seconds() << " s)."); + } + } else { + for (auto controller_type_it : controller_manager_params_it.second) { + auto controller_type = controller_type_it.second.as(); + auto controller = impl_->controller_manager_->load_controller( + controller_name, + controller_type); + impl_->controllers_.push_back(controller); + load_params_from_yaml( + controller->get_node(), + impl_->param_file_, + controller_name); + controller->configure(); + start_controllers.push_back(controller_name); + } + } } } + break; } } diff --git a/gazebo_ros2_control_demos/config/cartpole_controller.yaml b/gazebo_ros2_control_demos/config/cartpole_controller.yaml index 710005b0..c55ae298 100644 --- a/gazebo_ros2_control_demos/config/cartpole_controller.yaml +++ b/gazebo_ros2_control_demos/config/cartpole_controller.yaml @@ -1,11 +1,15 @@ -cart_pole_controller: +controller_manager: ros__parameters: - type: joint_trajectory_controller/JointTrajectoryController - joints: - - slider_to_cart - write_op_modes: - - slider_to_cart + update_rate: 100 # Hz + + joint_trajectory_controller: + type: joint_trajectory_controller/JointTrajectoryController -joint_state_controller: + joint_state_controller: + type: joint_state_controller/JointStateController + +joint_trajectory_controller: ros__parameters: - type: joint_state_controller/JointStateController + joints: + - slider_to_cart + interface_name: position diff --git a/gazebo_ros2_control_demos/config/cartpole_controller_effort.yaml b/gazebo_ros2_control_demos/config/cartpole_controller_effort.yaml index 5f4b9212..a52b1246 100644 --- a/gazebo_ros2_control_demos/config/cartpole_controller_effort.yaml +++ b/gazebo_ros2_control_demos/config/cartpole_controller_effort.yaml @@ -1,11 +1,15 @@ -cart_pole_controller: +controller_manager: ros__parameters: - type: effort_controllers/JointGroupEffortController - joints: - - slider_to_cart - write_op_modes: - - slider_to_cart + update_rate: 100 # Hz + + effort_controllers: + type: effort_controllers/JointGroupEffortController -joint_state_controller: + joint_state_controller: + type: joint_state_controller/JointStateController + +effort_controllers: ros__parameters: - type: joint_state_controller/JointStateController + joints: + - slider_to_cart + interface_name: position diff --git a/gazebo_ros2_control_demos/config/cartpole_controller_velocity.yaml b/gazebo_ros2_control_demos/config/cartpole_controller_velocity.yaml index 1af0fb28..c6cb3c59 100644 --- a/gazebo_ros2_control_demos/config/cartpole_controller_velocity.yaml +++ b/gazebo_ros2_control_demos/config/cartpole_controller_velocity.yaml @@ -1,11 +1,15 @@ -cart_pole_controller: +controller_manager: ros__parameters: - type: velocity_controllers/JointGroupVelocityController - joints: - - slider_to_cart - write_op_modes: - - slider_to_cart + update_rate: 100 # Hz + + velocity_controller: + type: velocity_controllers/JointGroupVelocityController -joint_state_controller: + joint_state_controller: + type: joint_state_controller/JointStateController + +velocity_controller: ros__parameters: - type: joint_state_controller/JointStateController + joints: + - slider_to_cart + interface_name: position diff --git a/gazebo_ros2_control_demos/examples/example_effort.cpp b/gazebo_ros2_control_demos/examples/example_effort.cpp index 6d139d1e..dd4bff8b 100644 --- a/gazebo_ros2_control_demos/examples/example_effort.cpp +++ b/gazebo_ros2_control_demos/examples/example_effort.cpp @@ -29,7 +29,7 @@ int main(int argc, char * argv[]) node = std::make_shared("effort_test_node"); auto publisher = node->create_publisher( - "/cart_pole_controller/commands", 10); + "/effort_controllers/commands", 10); RCLCPP_INFO(node->get_logger(), "node created"); diff --git a/gazebo_ros2_control_demos/examples/example_position.cpp b/gazebo_ros2_control_demos/examples/example_position.cpp index 2cafb297..160fd869 100644 --- a/gazebo_ros2_control_demos/examples/example_position.cpp +++ b/gazebo_ros2_control_demos/examples/example_position.cpp @@ -96,7 +96,7 @@ int main(int argc, char * argv[]) node->get_node_graph_interface(), node->get_node_logging_interface(), node->get_node_waitables_interface(), - "/cart_pole_controller/follow_joint_trajectory"); + "/joint_trajectory_controller/follow_joint_trajectory"); bool response = action_client->wait_for_action_server(std::chrono::seconds(1)); diff --git a/gazebo_ros2_control_demos/examples/example_velocity.cpp b/gazebo_ros2_control_demos/examples/example_velocity.cpp index e59e8c9f..66076916 100644 --- a/gazebo_ros2_control_demos/examples/example_velocity.cpp +++ b/gazebo_ros2_control_demos/examples/example_velocity.cpp @@ -29,7 +29,7 @@ int main(int argc, char * argv[]) node = std::make_shared("velocity_test_node"); auto publisher = node->create_publisher( - "/cart_pole_controller/commands", 10); + "/velocity_controller/commands", 10); RCLCPP_INFO(node->get_logger(), "node created"); diff --git a/gazebo_ros2_control_demos/urdf/test_cart_effort.xacro.urdf b/gazebo_ros2_control_demos/urdf/test_cart_effort.xacro.urdf index 19fe31f4..a1aa22f9 100644 --- a/gazebo_ros2_control_demos/urdf/test_cart_effort.xacro.urdf +++ b/gazebo_ros2_control_demos/urdf/test_cart_effort.xacro.urdf @@ -67,7 +67,6 @@ $(find gazebo_ros2_control_demos)/config/cartpole_controller_effort.yaml - 0.01 diff --git a/gazebo_ros2_control_demos/urdf/test_cart_position.xacro.urdf b/gazebo_ros2_control_demos/urdf/test_cart_position.xacro.urdf index b62336f4..187ca60e 100644 --- a/gazebo_ros2_control_demos/urdf/test_cart_position.xacro.urdf +++ b/gazebo_ros2_control_demos/urdf/test_cart_position.xacro.urdf @@ -67,7 +67,6 @@ $(find gazebo_ros2_control_demos)/config/cartpole_controller.yaml - 0.01 diff --git a/gazebo_ros2_control_demos/urdf/test_cart_velocity.xacro.urdf b/gazebo_ros2_control_demos/urdf/test_cart_velocity.xacro.urdf index 71dff886..f94ba88f 100644 --- a/gazebo_ros2_control_demos/urdf/test_cart_velocity.xacro.urdf +++ b/gazebo_ros2_control_demos/urdf/test_cart_velocity.xacro.urdf @@ -65,7 +65,6 @@ $(find gazebo_ros2_control_demos)/config/cartpole_controller_velocity.yaml - 0.01